From a194a19e3d0698121b37e5dd6339c0061c845ba1 Mon Sep 17 00:00:00 2001 From: Geoff Schmit Date: Mon, 26 Dec 2022 10:28:59 -0600 Subject: [PATCH] public release of our 2022 season software --- .gitattributes | 4 + .gitignore | 152 ++++ .vscode/extensions.json | 6 + .vscode/launch.json | 20 + .vscode/settings.json | 47 ++ .wpilib/wpilib_preferences.json | 6 + BSD_License_for_WPILib_code.txt | 24 + README.md | 4 +- build.gradle | 165 ++++ config.json | 42 + gradle/wrapper/gradle-wrapper.jar | Bin 0 -> 59536 bytes gradle/wrapper/gradle-wrapper.properties | 5 + gradlew | 234 ++++++ gradlew.bat | 89 ++ settings.gradle | 27 + simgui-ds.json | 92 ++ simgui-window.json | 60 ++ simgui.json | 47 ++ src/main/deploy/example.txt | 3 + src/main/deploy/pathplanner/Blue0(1).path | 1 + src/main/deploy/pathplanner/Blue0(2).path | 1 + src/main/deploy/pathplanner/Blue1(1).path | 1 + src/main/deploy/pathplanner/Blue1(2).path | 1 + src/main/deploy/pathplanner/Blue2(1).path | 1 + src/main/deploy/pathplanner/Blue3(1).path | 1 + src/main/deploy/pathplanner/Blue3(2).path | 1 + src/main/deploy/pathplanner/Blue3(23).path | 1 + src/main/deploy/pathplanner/Blue3(3).path | 1 + src/main/deploy/pathplanner/Blue4(1).path | 1 + src/main/deploy/pathplanner/Blue4(2).path | 1 + src/main/deploy/pathplanner/Blue4(3).path | 1 + src/main/deploy/pathplanner/Blue4(4).path | 1 + .../generatedJSON/Blue0(1).wpilib.json | 1 + .../generatedJSON/Blue0(2).wpilib.json | 1 + .../generatedJSON/Blue1(1).wpilib.json | 1 + .../generatedJSON/Blue1(2).wpilib.json | 1 + .../generatedJSON/Blue3(1).wpilib.json | 1 + .../generatedJSON/Blue3(2).wpilib.json | 1 + .../generatedJSON/Blue3(23).wpilib.json | 1 + .../generatedJSON/Blue3(3).wpilib.json | 1 + .../generatedJSON/Blue4(1).wpilib.json | 1 + .../generatedJSON/Blue4(2).wpilib.json | 1 + .../generatedJSON/Blue4(3).wpilib.json | 1 + .../generatedJSON/Blue4(4).wpilib.json | 1 + .../generatedJSON/New Path.wpilib.json | 1 + src/main/java/frc/robot/Constants.java | 393 +++++++++ src/main/java/frc/robot/FieldConstants.java | 148 ++++ src/main/java/frc/robot/GVersion.java | 19 + src/main/java/frc/robot/Main.java | 21 + src/main/java/frc/robot/Robot.java | 209 +++++ src/main/java/frc/robot/RobotContainer.java | 716 ++++++++++++++++ .../robot/commands/DefaultDriveCommand.java | 66 ++ .../ExtendClimberToLowRungCommand.java | 60 ++ .../ExtendClimberToMidRungCommand.java | 60 ++ .../java/frc/robot/commands/FollowPath.java | 94 +++ .../commands/IndexSingleBallCommand.java | 74 ++ .../commands/LimelightAlignOnMoveCommand.java | 171 ++++ .../LimelightAlignToTargetCommand.java | 63 ++ .../LimelightAlignWithGyroCommand.java | 88 ++ .../LimelightSetFlywheelVelocityCommand.java | 53 ++ .../ReachToNextRungWithPitchCommand.java | 100 +++ .../commands/RetractClimberFullCommand.java | 59 ++ .../RetractClimberMinimumCommand.java | 62 ++ .../commands/SetFlywheelVelocityCommand.java | 52 ++ .../robot/commands/SortStorageCommand.java | 102 +++ .../commands/VisionBoxCollectBallCommand.java | 261 ++++++ .../robot/commands/WaitForShotCommand.java | 90 ++ .../java/frc/robot/subsystems/VisionBox.java | 169 ++++ .../robot/subsystems/collector/Collector.java | 99 +++ .../subsystems/collector/CollectorIO.java | 45 + .../collector/CollectorIOTalonSRX.java | 71 ++ .../subsystems/drivetrain/Drivetrain.java | 791 ++++++++++++++++++ .../subsystems/drivetrain/DrivetrainIO.java | 74 ++ .../drivetrain/DrivetrainIOTalonFX.java | 185 ++++ .../robot/subsystems/elevator/Elevator.java | 382 +++++++++ .../robot/subsystems/elevator/ElevatorIO.java | 99 +++ .../elevator/ElevatorIOTalonFX.java | 196 +++++ .../robot/subsystems/flywheel/Flywheel.java | 176 ++++ .../robot/subsystems/flywheel/FlywheelIO.java | 75 ++ .../flywheel/FlywheelIOTalonFX.java | 157 ++++ .../subsystems/pneumatics/Pneumatics.java | 127 +++ .../subsystems/pneumatics/PneumaticsIO.java | 44 + .../pneumatics/PneumaticsIORev.java | 48 ++ .../secondary_arm/SecondaryArm.java | 68 ++ .../secondary_arm/SecondaryArmIO.java | 30 + .../secondary_arm/SecondaryArmSolenoid.java | 29 + .../frc/robot/subsystems/storage/Storage.java | 131 +++ .../robot/subsystems/storage/StorageIO.java | 52 ++ .../subsystems/storage/StorageIOTalonSRX.java | 65 ++ src/main/java/frc/robot/util/Alert.java | 133 +++ .../java/frc/robot/util/CANDeviceFinder.java | 309 +++++++ src/main/java/frc/robot/util/CANDeviceId.java | 67 ++ src/main/java/frc/robot/util/GeomUtil.java | 125 +++ src/main/java/frc/robot/util/TalonUtil.java | 22 + sysid_data20220216-170203.json | 7 + vendordeps/AdvantageKit.json | 41 + vendordeps/PathplannerLib.json | 33 + vendordeps/Phoenix.json | 257 ++++++ vendordeps/REVLib.json | 73 ++ vendordeps/SdsSwerveLib.json | 19 + vendordeps/WPILibNewCommands.json | 37 + 101 files changed, 8249 insertions(+), 1 deletion(-) create mode 100644 .gitattributes create mode 100644 .gitignore create mode 100644 .vscode/extensions.json create mode 100644 .vscode/launch.json create mode 100644 .vscode/settings.json create mode 100644 .wpilib/wpilib_preferences.json create mode 100644 BSD_License_for_WPILib_code.txt create mode 100644 build.gradle create mode 100644 config.json create mode 100644 gradle/wrapper/gradle-wrapper.jar create mode 100644 gradle/wrapper/gradle-wrapper.properties create mode 100755 gradlew create mode 100644 gradlew.bat create mode 100644 settings.gradle create mode 100644 simgui-ds.json create mode 100644 simgui-window.json create mode 100644 simgui.json create mode 100644 src/main/deploy/example.txt create mode 100644 src/main/deploy/pathplanner/Blue0(1).path create mode 100644 src/main/deploy/pathplanner/Blue0(2).path create mode 100644 src/main/deploy/pathplanner/Blue1(1).path create mode 100644 src/main/deploy/pathplanner/Blue1(2).path create mode 100644 src/main/deploy/pathplanner/Blue2(1).path create mode 100644 src/main/deploy/pathplanner/Blue3(1).path create mode 100644 src/main/deploy/pathplanner/Blue3(2).path create mode 100644 src/main/deploy/pathplanner/Blue3(23).path create mode 100644 src/main/deploy/pathplanner/Blue3(3).path create mode 100644 src/main/deploy/pathplanner/Blue4(1).path create mode 100644 src/main/deploy/pathplanner/Blue4(2).path create mode 100644 src/main/deploy/pathplanner/Blue4(3).path create mode 100644 src/main/deploy/pathplanner/Blue4(4).path create mode 100644 src/main/deploy/pathplanner/generatedJSON/Blue0(1).wpilib.json create mode 100644 src/main/deploy/pathplanner/generatedJSON/Blue0(2).wpilib.json create mode 100644 src/main/deploy/pathplanner/generatedJSON/Blue1(1).wpilib.json create mode 100644 src/main/deploy/pathplanner/generatedJSON/Blue1(2).wpilib.json create mode 100644 src/main/deploy/pathplanner/generatedJSON/Blue3(1).wpilib.json create mode 100644 src/main/deploy/pathplanner/generatedJSON/Blue3(2).wpilib.json create mode 100644 src/main/deploy/pathplanner/generatedJSON/Blue3(23).wpilib.json create mode 100644 src/main/deploy/pathplanner/generatedJSON/Blue3(3).wpilib.json create mode 100644 src/main/deploy/pathplanner/generatedJSON/Blue4(1).wpilib.json create mode 100644 src/main/deploy/pathplanner/generatedJSON/Blue4(2).wpilib.json create mode 100644 src/main/deploy/pathplanner/generatedJSON/Blue4(3).wpilib.json create mode 100644 src/main/deploy/pathplanner/generatedJSON/Blue4(4).wpilib.json create mode 100644 src/main/deploy/pathplanner/generatedJSON/New Path.wpilib.json create mode 100644 src/main/java/frc/robot/Constants.java create mode 100644 src/main/java/frc/robot/FieldConstants.java create mode 100644 src/main/java/frc/robot/GVersion.java create mode 100644 src/main/java/frc/robot/Main.java create mode 100644 src/main/java/frc/robot/Robot.java create mode 100644 src/main/java/frc/robot/RobotContainer.java create mode 100644 src/main/java/frc/robot/commands/DefaultDriveCommand.java create mode 100644 src/main/java/frc/robot/commands/ExtendClimberToLowRungCommand.java create mode 100644 src/main/java/frc/robot/commands/ExtendClimberToMidRungCommand.java create mode 100644 src/main/java/frc/robot/commands/FollowPath.java create mode 100644 src/main/java/frc/robot/commands/IndexSingleBallCommand.java create mode 100644 src/main/java/frc/robot/commands/LimelightAlignOnMoveCommand.java create mode 100644 src/main/java/frc/robot/commands/LimelightAlignToTargetCommand.java create mode 100644 src/main/java/frc/robot/commands/LimelightAlignWithGyroCommand.java create mode 100644 src/main/java/frc/robot/commands/LimelightSetFlywheelVelocityCommand.java create mode 100644 src/main/java/frc/robot/commands/ReachToNextRungWithPitchCommand.java create mode 100644 src/main/java/frc/robot/commands/RetractClimberFullCommand.java create mode 100644 src/main/java/frc/robot/commands/RetractClimberMinimumCommand.java create mode 100644 src/main/java/frc/robot/commands/SetFlywheelVelocityCommand.java create mode 100644 src/main/java/frc/robot/commands/SortStorageCommand.java create mode 100644 src/main/java/frc/robot/commands/VisionBoxCollectBallCommand.java create mode 100644 src/main/java/frc/robot/commands/WaitForShotCommand.java create mode 100644 src/main/java/frc/robot/subsystems/VisionBox.java create mode 100644 src/main/java/frc/robot/subsystems/collector/Collector.java create mode 100644 src/main/java/frc/robot/subsystems/collector/CollectorIO.java create mode 100644 src/main/java/frc/robot/subsystems/collector/CollectorIOTalonSRX.java create mode 100644 src/main/java/frc/robot/subsystems/drivetrain/Drivetrain.java create mode 100644 src/main/java/frc/robot/subsystems/drivetrain/DrivetrainIO.java create mode 100644 src/main/java/frc/robot/subsystems/drivetrain/DrivetrainIOTalonFX.java create mode 100644 src/main/java/frc/robot/subsystems/elevator/Elevator.java create mode 100644 src/main/java/frc/robot/subsystems/elevator/ElevatorIO.java create mode 100644 src/main/java/frc/robot/subsystems/elevator/ElevatorIOTalonFX.java create mode 100644 src/main/java/frc/robot/subsystems/flywheel/Flywheel.java create mode 100644 src/main/java/frc/robot/subsystems/flywheel/FlywheelIO.java create mode 100644 src/main/java/frc/robot/subsystems/flywheel/FlywheelIOTalonFX.java create mode 100644 src/main/java/frc/robot/subsystems/pneumatics/Pneumatics.java create mode 100644 src/main/java/frc/robot/subsystems/pneumatics/PneumaticsIO.java create mode 100644 src/main/java/frc/robot/subsystems/pneumatics/PneumaticsIORev.java create mode 100644 src/main/java/frc/robot/subsystems/secondary_arm/SecondaryArm.java create mode 100644 src/main/java/frc/robot/subsystems/secondary_arm/SecondaryArmIO.java create mode 100644 src/main/java/frc/robot/subsystems/secondary_arm/SecondaryArmSolenoid.java create mode 100644 src/main/java/frc/robot/subsystems/storage/Storage.java create mode 100644 src/main/java/frc/robot/subsystems/storage/StorageIO.java create mode 100644 src/main/java/frc/robot/subsystems/storage/StorageIOTalonSRX.java create mode 100644 src/main/java/frc/robot/util/Alert.java create mode 100644 src/main/java/frc/robot/util/CANDeviceFinder.java create mode 100644 src/main/java/frc/robot/util/CANDeviceId.java create mode 100644 src/main/java/frc/robot/util/GeomUtil.java create mode 100644 src/main/java/frc/robot/util/TalonUtil.java create mode 100644 sysid_data20220216-170203.json create mode 100644 vendordeps/AdvantageKit.json create mode 100644 vendordeps/PathplannerLib.json create mode 100644 vendordeps/Phoenix.json create mode 100644 vendordeps/REVLib.json create mode 100644 vendordeps/SdsSwerveLib.json create mode 100644 vendordeps/WPILibNewCommands.json diff --git a/.gitattributes b/.gitattributes new file mode 100644 index 0000000..286213b --- /dev/null +++ b/.gitattributes @@ -0,0 +1,4 @@ +*.gradle text eol=lf +*.java text eol=lf +*.md text eol=lf +*.xml text eol=lf \ No newline at end of file diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..1a851da --- /dev/null +++ b/.gitignore @@ -0,0 +1,152 @@ +# This gitignore has been specially created by the WPILib team. +# If you remove items from this file, intellisense might break. + +# Prerequisites +*.d + +# Compiled Object files +*.slo +*.lo +*.o +*.obj + +# Precompiled Headers +*.gch +*.pch + +# Compiled Dynamic libraries +*.so +*.dylib +*.dll + +# Fortran module files +*.mod +*.smod + +# Compiled Static libraries +*.lai +*.la +*.a +*.lib + +# Executables +*.exe +*.out +*.app + +# Compiled class file +*.class + +# Log file +*.log + +# BlueJ files +*.ctxt + +# Mobile Tools for Java (J2ME) +.mtj.tmp/ + +# Package Files # +*.jar +*.war +*.nar +*.ear +*.zip +*.tar.gz +*.rar + +# virtual machine crash logs, see http://www.java.com/en/download/help/error_hotspot.xml +hs_err_pid* + +*~ + +# temporary files which can be created if a process still has a handle open of a deleted file +.fuse_hidden* + +# KDE directory preferences +.directory + +# Linux trash folder which might appear on any partition or disk +.Trash-* + +# .nfs files are created when an open file is removed but is still being accessed +.nfs* + +# General +.DS_Store +.AppleDouble +.LSOverride + +# Icon must end with two \r +Icon + +# Thumbnails +._* + +# Files that might appear in the root of a volume +.DocumentRevisions-V100 +.fseventsd +.Spotlight-V100 +.TemporaryItems +.Trashes +.VolumeIcon.icns +.com.apple.timemachine.donotpresent + +# Directories potentially created on remote AFP share +.AppleDB +.AppleDesktop +Network Trash Folder +Temporary Items +.apdisk + +.vscode/* +!.vscode/settings.json +!.vscode/tasks.json +!.vscode/launch.json +!.vscode/extensions.json + +# Windows thumbnail cache files +Thumbs.db +ehthumbs.db +ehthumbs_vista.db + +# Dump file +*.stackdump + +# Folder config file +[Dd]esktop.ini + +# Recycle Bin used on file shares +$RECYCLE.BIN/ + +# Windows Installer files +*.cab +*.msi +*.msix +*.msm +*.msp + +# Windows shortcuts +*.lnk + +.gradle +/build/ + +# Ignore Gradle GUI config +gradle-app.setting + +# Avoid ignoring Gradle wrapper jar file (.jar files are usually ignored) +!gradle-wrapper.jar + +# Cache of project +.gradletasknamecache + +# # Work around https://youtrack.jetbrains.com/issue/IDEA-116898 +# gradle/wrapper/gradle-wrapper.properties + +# # VS Code Specific Java Settings +# DO NOT REMOVE .classpath and .project +.classpath +.project +.settings/ +bin/ diff --git a/.vscode/extensions.json b/.vscode/extensions.json new file mode 100644 index 0000000..bf3ea9a --- /dev/null +++ b/.vscode/extensions.json @@ -0,0 +1,6 @@ +{ + "recommendations": [ + "richardwillis.vscode-spotless-gradle", + "sonarsource.sonarlint-vscode" + ] +} \ No newline at end of file diff --git a/.vscode/launch.json b/.vscode/launch.json new file mode 100644 index 0000000..4dbe5d3 --- /dev/null +++ b/.vscode/launch.json @@ -0,0 +1,20 @@ +{ + // Use IntelliSense to learn about possible attributes. + // Hover to view descriptions of existing attributes. + // For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387 + "version": "0.2.0", + "configurations": [ + { + "type": "wpilib", + "name": "WPILib Desktop Debug", + "request": "launch", + "desktop": true, + }, + { + "type": "wpilib", + "name": "WPILib roboRIO Debug", + "request": "launch", + "desktop": false, + } + ] +} diff --git a/.vscode/settings.json b/.vscode/settings.json new file mode 100644 index 0000000..8edda5e --- /dev/null +++ b/.vscode/settings.json @@ -0,0 +1,47 @@ +{ + "java.configuration.updateBuildConfiguration": "automatic", + "java.server.launchMode": "Standard", + "files.exclude": { + "**/.git": true, + "**/.svn": true, + "**/.hg": true, + "**/CVS": true, + "**/.DS_Store": true, + "bin/": true, + "**/.classpath": true, + "**/.project": true, + "**/.settings": true, + "**/.factorypath": true, + "**/*~": true + }, + "java.test.config": [ + { + "name": "WPIlibUnitTests", + "workingDirectory": "${workspaceFolder}/build/jni/release", + "vmargs": [ "-Djava.library.path=${workspaceFolder}/build/jni/release" ], + "env": { + "LD_LIBRARY_PATH": "${workspaceFolder}/build/jni/release" , + "DYLD_LIBRARY_PATH": "${workspaceFolder}/build/jni/release" + } + }, + ], + "java.test.defaultConfig": "WPIlibUnitTests", + + "sonarlint.rules": { + "java:S106": { + "level": "off" + }, + "java:S1612": { + "level": "off" + }, + "java:S1134": { + "level": "off" + } + }, + + "spotlessGradle.format.enable": true, + "editor.defaultFormatter": "richardwillis.vscode-spotless-gradle", + "editor.codeActionsOnSave": { + "source.fixAll.spotlessGradle": true + } +} diff --git a/.wpilib/wpilib_preferences.json b/.wpilib/wpilib_preferences.json new file mode 100644 index 0000000..6eb254a --- /dev/null +++ b/.wpilib/wpilib_preferences.json @@ -0,0 +1,6 @@ +{ + "enableCppIntellisense": false, + "currentLanguage": "java", + "projectYear": "2022", + "teamNumber": 3061 +} diff --git a/BSD_License_for_WPILib_code.txt b/BSD_License_for_WPILib_code.txt new file mode 100644 index 0000000..91fd148 --- /dev/null +++ b/BSD_License_for_WPILib_code.txt @@ -0,0 +1,24 @@ +Copyright (c) 2009-2022 FIRST and other WPILib contributors +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + * Neither the name of FIRST, WPILib, nor the names of other WPILib + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY FIRST AND OTHER WPILIB CONTRIBUTORS "AS IS" AND +ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY NONINFRINGEMENT AND FITNESS FOR A PARTICULAR +PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL FIRST OR CONTRIBUTORS BE LIABLE FOR +ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/README.md b/README.md index 8f8a0cf..d621b22 100644 --- a/README.md +++ b/README.md @@ -1 +1,3 @@ -# 2022-release \ No newline at end of file +# 2022-release + +public release of our 2022 season (Rapid React) software diff --git a/build.gradle b/build.gradle new file mode 100644 index 0000000..706230a --- /dev/null +++ b/build.gradle @@ -0,0 +1,165 @@ +import edu.wpi.first.gradlerio.deploy.roborio.RoboRIO + +plugins { + id "java" + id "edu.wpi.first.GradleRIO" version "2022.4.1" + id 'com.diffplug.spotless' version '6.1.0' + id "com.peterabeles.gversion" version "1.10" +} + +sourceCompatibility = JavaVersion.VERSION_11 +targetCompatibility = JavaVersion.VERSION_11 + +def ROBOT_MAIN_CLASS = "frc.robot.Main" + +// Define my targets (RoboRIO) and artifacts (deployable files) +// This is added by GradleRIO's backing project DeployTools. +deploy { + targets { + roborio(getTargetTypeClass('RoboRIO')) { + // Team number is loaded either from the .wpilib/wpilib_preferences.json + // or from command line. If not found an exception will be thrown. + // You can use getTeamOrDefault(team) instead of getTeamNumber if you + // want to store a team number in this file. + team = project.frc.getTeamNumber() + debug = project.frc.getDebugOrDefault(false) + + artifacts { + // First part is artifact name, 2nd is artifact type + // getTargetTypeClass is a shortcut to get the class type using a string + + frcJava(getArtifactTypeClass('FRCJavaArtifact')) { + } + + // Static files artifact + frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { + files = project.fileTree('src/main/deploy') + directory = '/home/lvuser/deploy' + } + } + } + } +} + +def deployArtifact = deploy.targets.roborio.artifacts.frcJava + +// Set to true to use debug for JNI. +wpi.java.debugJni = false + +// BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DESKTOP +// Set this to true to enable desktop support. +def includeDesktopSupport = true + +// END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DESKTOP + +// Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries. +// Also defines JUnit 4. +dependencies { + implementation wpi.java.deps.wpilib() + implementation wpi.java.vendor.java() + + roborioDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.roborio) + roborioDebug wpi.java.vendor.jniDebug(wpi.platforms.roborio) + + roborioRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.roborio) + roborioRelease wpi.java.vendor.jniRelease(wpi.platforms.roborio) + + nativeDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.desktop) + nativeDebug wpi.java.vendor.jniDebug(wpi.platforms.desktop) + simulationDebug wpi.sim.enableDebug() + + nativeRelease wpi.java.deps.wpilibJniRelease(wpi.platforms.desktop) + nativeRelease wpi.java.vendor.jniRelease(wpi.platforms.desktop) + simulationRelease wpi.sim.enableRelease() + + testImplementation 'junit:junit:4.12' +} + +wpi.sim.addGui().defaultEnabled = true +wpi.sim.addDriverstation() + +// Setting up my Jar File. In this case, adding all libraries into the main jar ('fat jar') +// in order to make them all available at runtime. Also adding the manifest so WPILib +// knows where to look for our Robot Class. +jar { + from { configurations.runtimeClasspath.collect { it.isDirectory() ? it : zipTree(it) } } + manifest edu.wpi.first.gradlerio.GradleRIOPlugin.javaManifest(ROBOT_MAIN_CLASS) + duplicatesStrategy = DuplicatesStrategy.INCLUDE +} + +// Configure jar and deploy tasks +deployArtifact.jarTask = jar +wpi.java.configureExecutableTasks(jar) +wpi.java.configureTestTasks(test) + +// from https://docs.wpilib.org/en/stable/docs/software/advanced-gradlerio/code-formatting.html +spotless { + java { + target fileTree('.') { + include '**/*.java' + exclude '**/build/**', '**/build-*/**', '**/GVersion.java' + } + toggleOffOn() + googleJavaFormat() + removeUnusedImports() + trimTrailingWhitespace() + endWithNewline() + } + groovyGradle { + target fileTree('.') { + include '**/*.gradle' + exclude '**/build/**', '**/build-*/**', '**/GVersion.java' + } + greclipse() + indentWithSpaces(4) + trimTrailingWhitespace() + endWithNewline() + } + format 'xml', { + target fileTree('.') { + include '**/*.xml' + exclude '**/build/**', '**/build-*/**' + } + eclipseWtp('xml') + trimTrailingWhitespace() + indentWithSpaces(2) + endWithNewline() + } + format 'misc', { + target fileTree('.') { + include '**/*.md', '**/.gitignore' + exclude '**/build/**', '**/build-*/**' + } + trimTrailingWhitespace() + indentWithSpaces(2) + endWithNewline() + } +} + +// from https://github.com/Mechanical-Advantage/AdvantageKit/blob/main/docs/START-LOGGING.md#installation-with-gradle +repositories { + maven { + url = uri("https://maven.pkg.github.com/Mechanical-Advantage/AdvantageKit") + credentials { + username = "Mechanical-Advantage-Bot" + password = "\u0067\u0068\u0070\u005f\u006e\u0056\u0051\u006a\u0055\u004f\u004c\u0061\u0079\u0066\u006e\u0078\u006e\u0037\u0051\u0049\u0054\u0042\u0032\u004c\u004a\u006d\u0055\u0070\u0073\u0031\u006d\u0037\u004c\u005a\u0030\u0076\u0062\u0070\u0063\u0051" + } + } +} + +configurations.all { + exclude group: "edu.wpi.first.wpilibj" +} + +// from https://github.com/lessthanoptimal/gversion-plugin +gversion { + srcDir = "src/main/java/" // path is relative to the sub-project by default + // Gradle variables can also be used + // E.g. "${project.rootDir}/module/src/main/java" + classPackage = "frc.robot" + timeZone = "CDT" // optional. UTC is default + language = "java" // optional. Can be Java, Kotlin, YAML, or Properties. Case insensitive. + indent = " " +} + +project.compileJava.dependsOn(createVersionFile) diff --git a/config.json b/config.json new file mode 100644 index 0000000..2d33a87 --- /dev/null +++ b/config.json @@ -0,0 +1,42 @@ +{ + "counts per rotation": 2048.0, + "encoder type": "Built-in", + "encoding": false, + "gearing denominator": 1.0, + "gearing numerator": 6.75, + "gyro": "None", + "gyro ctor": "1", + "is drivetrain": true, + "motor controllers": [ + "TalonFX", + "TalonFX" + ], + "number of samples per average": 1, + "primary encoder inverted": false, + "primary encoder ports": [ + 0, + 1 + ], + "primary motor ports": [ + 16, + 13 + ], + "primary motors inverted": [ + false, + false + ], + "secondary encoder inverted": false, + "secondary encoder ports": [ + 2, + 3 + ], + "secondary motor ports": [ + 10, + 7 + ], + "secondary motors inverted": [ + false, + false + ], + "velocity measurement period": 100 +} \ No newline at end of file diff --git a/gradle/wrapper/gradle-wrapper.jar b/gradle/wrapper/gradle-wrapper.jar new file mode 100644 index 0000000000000000000000000000000000000000..7454180f2ae8848c63b8b4dea2cb829da983f2fa GIT binary patch literal 59536 zcma&NbC71ylI~qywr$(CZQJHswz}-9F59+k+g;UV+cs{`J?GrGXYR~=-ydruB3JCa zB64N^cILAcWk5iofq)<(fq;O7{th4@;QxID0)qN`mJ?GIqLY#rX8-|G{5M0pdVW5^ zzXk$-2kQTAC?_N@B`&6-N-rmVFE=$QD?>*=4<|!MJu@}isLc4AW#{m2if&A5T5g&~ ziuMQeS*U5sL6J698wOd)K@oK@1{peP5&Esut<#VH^u)gp`9H4)`uE!2$>RTctN+^u z=ASkePDZA-X8)rp%D;p*~P?*a_=*Kwc<^>QSH|^<0>o37lt^+Mj1;4YvJ(JR-Y+?%Nu}JAYj5 z_Qc5%Ao#F?q32i?ZaN2OSNhWL;2oDEw_({7ZbgUjna!Fqn3NzLM@-EWFPZVmc>(fZ z0&bF-Ch#p9C{YJT9Rcr3+Y_uR^At1^BxZ#eo>$PLJF3=;t_$2|t+_6gg5(j{TmjYU zK12c&lE?Eh+2u2&6Gf*IdKS&6?rYbSEKBN!rv{YCm|Rt=UlPcW9j`0o6{66#y5t9C zruFA2iKd=H%jHf%ypOkxLnO8#H}#Zt{8p!oi6)7#NqoF({t6|J^?1e*oxqng9Q2Cc zg%5Vu!em)}Yuj?kaP!D?b?(C*w!1;>R=j90+RTkyEXz+9CufZ$C^umX^+4|JYaO<5 zmIM3#dv`DGM;@F6;(t!WngZSYzHx?9&$xEF70D1BvfVj<%+b#)vz)2iLCrTeYzUcL z(OBnNoG6Le%M+@2oo)&jdOg=iCszzv59e zDRCeaX8l1hC=8LbBt|k5?CXgep=3r9BXx1uR8!p%Z|0+4Xro=xi0G!e{c4U~1j6!) zH6adq0}#l{%*1U(Cb%4AJ}VLWKBPi0MoKFaQH6x?^hQ!6em@993xdtS%_dmevzeNl z(o?YlOI=jl(`L9^ z0O+H9k$_@`6L13eTT8ci-V0ljDMD|0ifUw|Q-Hep$xYj0hTO@0%IS^TD4b4n6EKDG z??uM;MEx`s98KYN(K0>c!C3HZdZ{+_53DO%9k5W%pr6yJusQAv_;IA}925Y%;+!tY z%2k!YQmLLOr{rF~!s<3-WEUs)`ix_mSU|cNRBIWxOox_Yb7Z=~Q45ZNe*u|m^|)d* zog=i>`=bTe!|;8F+#H>EjIMcgWcG2ORD`w0WD;YZAy5#s{65~qfI6o$+Ty&-hyMyJ z3Ra~t>R!p=5ZpxA;QkDAoPi4sYOP6>LT+}{xp}tk+<0k^CKCFdNYG(Es>p0gqD)jP zWOeX5G;9(m@?GOG7g;e74i_|SmE?`B2i;sLYwRWKLy0RLW!Hx`=!LH3&k=FuCsM=9M4|GqzA)anEHfxkB z?2iK-u(DC_T1};KaUT@3nP~LEcENT^UgPvp!QC@Dw&PVAhaEYrPey{nkcn(ro|r7XUz z%#(=$7D8uP_uU-oPHhd>>^adbCSQetgSG`e$U|7mr!`|bU0aHl_cmL)na-5x1#OsVE#m*+k84Y^+UMeSAa zbrVZHU=mFwXEaGHtXQq`2ZtjfS!B2H{5A<3(nb-6ARVV8kEmOkx6D2x7~-6hl;*-*}2Xz;J#a8Wn;_B5=m zl3dY;%krf?i-Ok^Pal-}4F`{F@TYPTwTEhxpZK5WCpfD^UmM_iYPe}wpE!Djai6_{ z*pGO=WB47#Xjb7!n2Ma)s^yeR*1rTxp`Mt4sfA+`HwZf%!7ZqGosPkw69`Ix5Ku6G z@Pa;pjzV&dn{M=QDx89t?p?d9gna*}jBly*#1!6}5K<*xDPJ{wv4& zM$17DFd~L*Te3A%yD;Dp9UGWTjRxAvMu!j^Tbc}2v~q^59d4bz zvu#!IJCy(BcWTc`;v$9tH;J%oiSJ_i7s;2`JXZF+qd4C)vY!hyCtl)sJIC{ebI*0> z@x>;EzyBv>AI-~{D6l6{ST=em*U( z(r$nuXY-#CCi^8Z2#v#UXOt`dbYN1z5jzNF2 z411?w)whZrfA20;nl&C1Gi+gk<`JSm+{|*2o<< zqM#@z_D`Cn|0H^9$|Tah)0M_X4c37|KQ*PmoT@%xHc3L1ZY6(p(sNXHa&49Frzto& zR`c~ClHpE~4Z=uKa5S(-?M8EJ$zt0&fJk~p$M#fGN1-y$7!37hld`Uw>Urri(DxLa;=#rK0g4J)pXMC zxzraOVw1+kNWpi#P=6(qxf`zSdUC?D$i`8ZI@F>k6k zz21?d+dw7b&i*>Kv5L(LH-?J%@WnqT7j#qZ9B>|Zl+=> z^U-pV@1y_ptHo4hl^cPRWewbLQ#g6XYQ@EkiP z;(=SU!yhjHp%1&MsU`FV1Z_#K1&(|5n(7IHbx&gG28HNT)*~-BQi372@|->2Aw5It z0CBpUcMA*QvsPy)#lr!lIdCi@1k4V2m!NH)%Px(vu-r(Q)HYc!p zJ^$|)j^E#q#QOgcb^pd74^JUi7fUmMiNP_o*lvx*q%_odv49Dsv$NV;6J z9GOXKomA{2Pb{w}&+yHtH?IkJJu~}Z?{Uk++2mB8zyvh*xhHKE``99>y#TdD z&(MH^^JHf;g(Tbb^&8P*;_i*2&fS$7${3WJtV7K&&(MBV2~)2KB3%cWg#1!VE~k#C z!;A;?p$s{ihyojEZz+$I1)L}&G~ml=udD9qh>Tu(ylv)?YcJT3ihapi!zgPtWb*CP zlLLJSRCj-^w?@;RU9aL2zDZY1`I3d<&OMuW=c3$o0#STpv_p3b9Wtbql>w^bBi~u4 z3D8KyF?YE?=HcKk!xcp@Cigvzy=lnFgc^9c%(^F22BWYNAYRSho@~*~S)4%AhEttv zvq>7X!!EWKG?mOd9&n>vvH1p4VzE?HCuxT-u+F&mnsfDI^}*-d00-KAauEaXqg3k@ zy#)MGX!X;&3&0s}F3q40ZmVM$(H3CLfpdL?hB6nVqMxX)q=1b}o_PG%r~hZ4gUfSp zOH4qlEOW4OMUc)_m)fMR_rl^pCfXc{$fQbI*E&mV77}kRF z&{<06AJyJ!e863o-V>FA1a9Eemx6>^F$~9ppt()ZbPGfg_NdRXBWoZnDy2;#ODgf! zgl?iOcF7Meo|{AF>KDwTgYrJLb$L2%%BEtO>T$C?|9bAB&}s;gI?lY#^tttY&hfr# zKhC+&b-rpg_?~uVK%S@mQleU#_xCsvIPK*<`E0fHE1&!J7!xD#IB|SSPW6-PyuqGn3^M^Rz%WT{e?OI^svARX&SAdU77V(C~ zM$H{Kg59op{<|8ry9ecfP%=kFm(-!W&?U0@<%z*+!*<e0XesMxRFu9QnGqun6R_%T+B%&9Dtk?*d$Q zb~>84jEAPi@&F@3wAa^Lzc(AJz5gsfZ7J53;@D<;Klpl?sK&u@gie`~vTsbOE~Cd4 z%kr56mI|#b(Jk&;p6plVwmNB0H@0SmgdmjIn5Ne@)}7Vty(yb2t3ev@22AE^s!KaN zyQ>j+F3w=wnx7w@FVCRe+`vUH)3gW%_72fxzqX!S&!dchdkRiHbXW1FMrIIBwjsai8`CB2r4mAbwp%rrO>3B$Zw;9=%fXI9B{d(UzVap7u z6piC-FQ)>}VOEuPpuqznpY`hN4dGa_1Xz9rVg(;H$5Te^F0dDv*gz9JS<|>>U0J^# z6)(4ICh+N_Q`Ft0hF|3fSHs*?a=XC;e`sJaU9&d>X4l?1W=|fr!5ShD|nv$GK;j46@BV6+{oRbWfqOBRb!ir88XD*SbC(LF}I1h#6@dvK%Toe%@ zhDyG$93H8Eu&gCYddP58iF3oQH*zLbNI;rN@E{T9%A8!=v#JLxKyUe}e}BJpB{~uN zqgxRgo0*-@-iaHPV8bTOH(rS(huwK1Xg0u+e!`(Irzu@Bld&s5&bWgVc@m7;JgELd zimVs`>vQ}B_1(2#rv#N9O`fJpVfPc7V2nv34PC);Dzbb;p!6pqHzvy?2pD&1NE)?A zt(t-ucqy@wn9`^MN5apa7K|L=9>ISC>xoc#>{@e}m#YAAa1*8-RUMKwbm|;5p>T`Z zNf*ph@tnF{gmDa3uwwN(g=`Rh)4!&)^oOy@VJaK4lMT&5#YbXkl`q?<*XtsqD z9PRK6bqb)fJw0g-^a@nu`^?71k|m3RPRjt;pIkCo1{*pdqbVs-Yl>4E>3fZx3Sv44grW=*qdSoiZ9?X0wWyO4`yDHh2E!9I!ZFi zVL8|VtW38}BOJHW(Ax#KL_KQzarbuE{(%TA)AY)@tY4%A%P%SqIU~8~-Lp3qY;U-} z`h_Gel7;K1h}7$_5ZZT0&%$Lxxr-<89V&&TCsu}LL#!xpQ1O31jaa{U34~^le*Y%L za?7$>Jk^k^pS^_M&cDs}NgXlR>16AHkSK-4TRaJSh#h&p!-!vQY%f+bmn6x`4fwTp z$727L^y`~!exvmE^W&#@uY!NxJi`g!i#(++!)?iJ(1)2Wk;RN zFK&O4eTkP$Xn~4bB|q8y(btx$R#D`O@epi4ofcETrx!IM(kWNEe42Qh(8*KqfP(c0 zouBl6>Fc_zM+V;F3znbo{x#%!?mH3`_ANJ?y7ppxS@glg#S9^MXu|FM&ynpz3o&Qh z2ujAHLF3($pH}0jXQsa#?t--TnF1P73b?4`KeJ9^qK-USHE)4!IYgMn-7z|=ALF5SNGkrtPG@Y~niUQV2?g$vzJN3nZ{7;HZHzWAeQ;5P|@Tl3YHpyznGG4-f4=XflwSJY+58-+wf?~Fg@1p1wkzuu-RF3j2JX37SQUc? zQ4v%`V8z9ZVZVqS8h|@@RpD?n0W<=hk=3Cf8R?d^9YK&e9ZybFY%jdnA)PeHvtBe- zhMLD+SSteHBq*q)d6x{)s1UrsO!byyLS$58WK;sqip$Mk{l)Y(_6hEIBsIjCr5t>( z7CdKUrJTrW%qZ#1z^n*Lb8#VdfzPw~OIL76aC+Rhr<~;4Tl!sw?Rj6hXj4XWa#6Tp z@)kJ~qOV)^Rh*-?aG>ic2*NlC2M7&LUzc9RT6WM%Cpe78`iAowe!>(T0jo&ivn8-7 zs{Qa@cGy$rE-3AY0V(l8wjI^uB8Lchj@?L}fYal^>T9z;8juH@?rG&g-t+R2dVDBe zq!K%{e-rT5jX19`(bP23LUN4+_zh2KD~EAYzhpEO3MUG8@}uBHH@4J zd`>_(K4q&>*k82(dDuC)X6JuPrBBubOg7qZ{?x!r@{%0);*`h*^F|%o?&1wX?Wr4b z1~&cy#PUuES{C#xJ84!z<1tp9sfrR(i%Tu^jnXy;4`Xk;AQCdFC@?V%|; zySdC7qS|uQRcH}EFZH%mMB~7gi}a0utE}ZE_}8PQH8f;H%PN41Cb9R%w5Oi5el^fd z$n{3SqLCnrF##x?4sa^r!O$7NX!}&}V;0ZGQ&K&i%6$3C_dR%I7%gdQ;KT6YZiQrW zk%q<74oVBV>@}CvJ4Wj!d^?#Zwq(b$E1ze4$99DuNg?6t9H}k_|D7KWD7i0-g*EO7 z;5{hSIYE4DMOK3H%|f5Edx+S0VI0Yw!tsaRS2&Il2)ea^8R5TG72BrJue|f_{2UHa z@w;^c|K3da#$TB0P3;MPlF7RuQeXT$ zS<<|C0OF(k)>fr&wOB=gP8!Qm>F41u;3esv7_0l%QHt(~+n; zf!G6%hp;Gfa9L9=AceiZs~tK+Tf*Wof=4!u{nIO90jH@iS0l+#%8=~%ASzFv7zqSB^?!@N7)kp0t&tCGLmzXSRMRyxCmCYUD2!B`? zhs$4%KO~m=VFk3Buv9osha{v+mAEq=ik3RdK@;WWTV_g&-$U4IM{1IhGX{pAu%Z&H zFfwCpUsX%RKg);B@7OUzZ{Hn{q6Vv!3#8fAg!P$IEx<0vAx;GU%}0{VIsmFBPq_mb zpe^BChDK>sc-WLKl<6 zwbW|e&d&dv9Wu0goueyu>(JyPx1mz0v4E?cJjFuKF71Q1)AL8jHO$!fYT3(;U3Re* zPPOe%*O+@JYt1bW`!W_1!mN&=w3G9ru1XsmwfS~BJ))PhD(+_J_^N6j)sx5VwbWK| zwRyC?W<`pOCY)b#AS?rluxuuGf-AJ=D!M36l{ua?@SJ5>e!IBr3CXIxWw5xUZ@Xrw z_R@%?{>d%Ld4p}nEsiA@v*nc6Ah!MUs?GA7e5Q5lPpp0@`%5xY$C;{%rz24$;vR#* zBP=a{)K#CwIY%p} zXVdxTQ^HS@O&~eIftU+Qt^~(DGxrdi3k}DdT^I7Iy5SMOp$QuD8s;+93YQ!OY{eB24%xY7ml@|M7I(Nb@K_-?F;2?et|CKkuZK_>+>Lvg!>JE~wN`BI|_h6$qi!P)+K-1Hh(1;a`os z55)4Q{oJiA(lQM#;w#Ta%T0jDNXIPM_bgESMCDEg6rM33anEr}=|Fn6)|jBP6Y}u{ zv9@%7*#RI9;fv;Yii5CI+KrRdr0DKh=L>)eO4q$1zmcSmglsV`*N(x=&Wx`*v!!hn6X-l0 zP_m;X??O(skcj+oS$cIdKhfT%ABAzz3w^la-Ucw?yBPEC+=Pe_vU8nd-HV5YX6X8r zZih&j^eLU=%*;VzhUyoLF;#8QsEfmByk+Y~caBqSvQaaWf2a{JKB9B>V&r?l^rXaC z8)6AdR@Qy_BxQrE2Fk?ewD!SwLuMj@&d_n5RZFf7=>O>hzVE*seW3U?_p|R^CfoY`?|#x9)-*yjv#lo&zP=uI`M?J zbzC<^3x7GfXA4{FZ72{PE*-mNHyy59Q;kYG@BB~NhTd6pm2Oj=_ zizmD?MKVRkT^KmXuhsk?eRQllPo2Ubk=uCKiZ&u3Xjj~<(!M94c)Tez@9M1Gfs5JV z->@II)CDJOXTtPrQudNjE}Eltbjq>6KiwAwqvAKd^|g!exgLG3;wP+#mZYr`cy3#39e653d=jrR-ulW|h#ddHu(m9mFoW~2yE zz5?dB%6vF}+`-&-W8vy^OCxm3_{02royjvmwjlp+eQDzFVEUiyO#gLv%QdDSI#3W* z?3!lL8clTaNo-DVJw@ynq?q!%6hTQi35&^>P85G$TqNt78%9_sSJt2RThO|JzM$iL zg|wjxdMC2|Icc5rX*qPL(coL!u>-xxz-rFiC!6hD1IR%|HSRsV3>Kq~&vJ=s3M5y8SG%YBQ|{^l#LGlg!D?E>2yR*eV%9m$_J6VGQ~AIh&P$_aFbh zULr0Z$QE!QpkP=aAeR4ny<#3Fwyw@rZf4?Ewq`;mCVv}xaz+3ni+}a=k~P+yaWt^L z@w67!DqVf7D%7XtXX5xBW;Co|HvQ8WR1k?r2cZD%U;2$bsM%u8{JUJ5Z0k= zZJARv^vFkmWx15CB=rb=D4${+#DVqy5$C%bf`!T0+epLJLnh1jwCdb*zuCL}eEFvE z{rO1%gxg>1!W(I!owu*mJZ0@6FM(?C+d*CeceZRW_4id*D9p5nzMY&{mWqrJomjIZ z97ZNnZ3_%Hx8dn;H>p8m7F#^2;T%yZ3H;a&N7tm=Lvs&lgJLW{V1@h&6Vy~!+Ffbb zv(n3+v)_D$}dqd!2>Y2B)#<+o}LH#%ogGi2-?xRIH)1!SD)u-L65B&bsJTC=LiaF+YOCif2dUX6uAA|#+vNR z>U+KQekVGon)Yi<93(d!(yw1h3&X0N(PxN2{%vn}cnV?rYw z$N^}_o!XUB!mckL`yO1rnUaI4wrOeQ(+&k?2mi47hzxSD`N#-byqd1IhEoh!PGq>t z_MRy{5B0eKY>;Ao3z$RUU7U+i?iX^&r739F)itdrTpAi-NN0=?^m%?{A9Ly2pVv>Lqs6moTP?T2-AHqFD-o_ znVr|7OAS#AEH}h8SRPQ@NGG47dO}l=t07__+iK8nHw^(AHx&Wb<%jPc$$jl6_p(b$ z)!pi(0fQodCHfM)KMEMUR&UID>}m^(!{C^U7sBDOA)$VThRCI0_+2=( zV8mMq0R(#z;C|7$m>$>`tX+T|xGt(+Y48@ZYu#z;0pCgYgmMVbFb!$?%yhZqP_nhn zy4<#3P1oQ#2b51NU1mGnHP$cf0j-YOgAA}A$QoL6JVLcmExs(kU{4z;PBHJD%_=0F z>+sQV`mzijSIT7xn%PiDKHOujX;n|M&qr1T@rOxTdxtZ!&u&3HHFLYD5$RLQ=heur zb>+AFokUVQeJy-#LP*^)spt{mb@Mqe=A~-4p0b+Bt|pZ+@CY+%x}9f}izU5;4&QFE zO1bhg&A4uC1)Zb67kuowWY4xbo&J=%yoXlFB)&$d*-}kjBu|w!^zbD1YPc0-#XTJr z)pm2RDy%J3jlqSMq|o%xGS$bPwn4AqitC6&e?pqWcjWPt{3I{>CBy;hg0Umh#c;hU3RhCUX=8aR>rmd` z7Orw(5tcM{|-^J?ZAA9KP|)X6n9$-kvr#j5YDecTM6n z&07(nD^qb8hpF0B^z^pQ*%5ePYkv&FabrlI61ntiVp!!C8y^}|<2xgAd#FY=8b*y( zuQOuvy2`Ii^`VBNJB&R!0{hABYX55ooCAJSSevl4RPqEGb)iy_0H}v@vFwFzD%>#I>)3PsouQ+_Kkbqy*kKdHdfkN7NBcq%V{x^fSxgXpg7$bF& zj!6AQbDY(1u#1_A#1UO9AxiZaCVN2F0wGXdY*g@x$ByvUA?ePdide0dmr#}udE%K| z3*k}Vv2Ew2u1FXBaVA6aerI36R&rzEZeDDCl5!t0J=ug6kuNZzH>3i_VN`%BsaVB3 zQYw|Xub_SGf{)F{$ZX5`Jc!X!;eybjP+o$I{Z^Hsj@D=E{MnnL+TbC@HEU2DjG{3-LDGIbq()U87x4eS;JXnSh;lRlJ z>EL3D>wHt-+wTjQF$fGyDO$>d+(fq@bPpLBS~xA~R=3JPbS{tzN(u~m#Po!?H;IYv zE;?8%^vle|%#oux(Lj!YzBKv+Fd}*Ur-dCBoX*t{KeNM*n~ZPYJ4NNKkI^MFbz9!v z4(Bvm*Kc!-$%VFEewYJKz-CQN{`2}KX4*CeJEs+Q(!kI%hN1!1P6iOq?ovz}X0IOi z)YfWpwW@pK08^69#wSyCZkX9?uZD?C^@rw^Y?gLS_xmFKkooyx$*^5#cPqntNTtSG zlP>XLMj2!VF^0k#ole7`-c~*~+_T5ls?x4)ah(j8vo_ zwb%S8qoaZqY0-$ZI+ViIA_1~~rAH7K_+yFS{0rT@eQtTAdz#8E5VpwnW!zJ_^{Utv zlW5Iar3V5t&H4D6A=>?mq;G92;1cg9a2sf;gY9pJDVKn$DYdQlvfXq}zz8#LyPGq@ z+`YUMD;^-6w&r-82JL7mA8&M~Pj@aK!m{0+^v<|t%APYf7`}jGEhdYLqsHW-Le9TL z_hZZ1gbrz7$f9^fAzVIP30^KIz!!#+DRLL+qMszvI_BpOSmjtl$hh;&UeM{ER@INV zcI}VbiVTPoN|iSna@=7XkP&-4#06C};8ajbxJ4Gcq8(vWv4*&X8bM^T$mBk75Q92j z1v&%a;OSKc8EIrodmIiw$lOES2hzGDcjjB`kEDfJe{r}yE6`eZL zEB`9u>Cl0IsQ+t}`-cx}{6jqcANucqIB>Qmga_&<+80E2Q|VHHQ$YlAt{6`Qu`HA3 z03s0-sSlwbvgi&_R8s={6<~M^pGvBNjKOa>tWenzS8s zR>L7R5aZ=mSU{f?ib4Grx$AeFvtO5N|D>9#)ChH#Fny2maHWHOf2G=#<9Myot#+4u zWVa6d^Vseq_0=#AYS(-m$Lp;*8nC_6jXIjEM`omUmtH@QDs3|G)i4j*#_?#UYVZvJ z?YjT-?!4Q{BNun;dKBWLEw2C-VeAz`%?A>p;)PL}TAZn5j~HK>v1W&anteARlE+~+ zj>c(F;?qO3pXBb|#OZdQnm<4xWmn~;DR5SDMxt0UK_F^&eD|KZ=O;tO3vy4@4h^;2 zUL~-z`-P1aOe?|ZC1BgVsL)2^J-&vIFI%q@40w0{jjEfeVl)i9(~bt2z#2Vm)p`V_ z1;6$Ae7=YXk#=Qkd24Y23t&GvRxaOoad~NbJ+6pxqzJ>FY#Td7@`N5xp!n(c!=RE& z&<<@^a$_Ys8jqz4|5Nk#FY$~|FPC0`*a5HH!|Gssa9=~66&xG9)|=pOOJ2KE5|YrR zw!w6K2aC=J$t?L-;}5hn6mHd%hC;p8P|Dgh6D>hGnXPgi;6r+eA=?f72y9(Cf_ho{ zH6#)uD&R=73^$$NE;5piWX2bzR67fQ)`b=85o0eOLGI4c-Tb@-KNi2pz=Ke@SDcPn za$AxXib84`!Sf;Z3B@TSo`Dz7GM5Kf(@PR>Ghzi=BBxK8wRp>YQoXm+iL>H*Jo9M3 z6w&E?BC8AFTFT&Tv8zf+m9<&S&%dIaZ)Aoqkak_$r-2{$d~0g2oLETx9Y`eOAf14QXEQw3tJne;fdzl@wV#TFXSLXM2428F-Q}t+n2g%vPRMUzYPvzQ9f# zu(liiJem9P*?0%V@RwA7F53r~|I!Ty)<*AsMX3J{_4&}{6pT%Tpw>)^|DJ)>gpS~1rNEh z0$D?uO8mG?H;2BwM5a*26^7YO$XjUm40XmBsb63MoR;bJh63J;OngS5sSI+o2HA;W zdZV#8pDpC9Oez&L8loZO)MClRz!_!WD&QRtQxnazhT%Vj6Wl4G11nUk8*vSeVab@N#oJ}`KyJv+8Mo@T1-pqZ1t|?cnaVOd;1(h9 z!$DrN=jcGsVYE-0-n?oCJ^4x)F}E;UaD-LZUIzcD?W^ficqJWM%QLy6QikrM1aKZC zi{?;oKwq^Vsr|&`i{jIphA8S6G4)$KGvpULjH%9u(Dq247;R#l&I0{IhcC|oBF*Al zvLo7Xte=C{aIt*otJD}BUq)|_pdR>{zBMT< z(^1RpZv*l*m*OV^8>9&asGBo8h*_4q*)-eCv*|Pq=XNGrZE)^(SF7^{QE_~4VDB(o zVcPA_!G+2CAtLbl+`=Q~9iW`4ZRLku!uB?;tWqVjB0lEOf}2RD7dJ=BExy=<9wkb- z9&7{XFA%n#JsHYN8t5d~=T~5DcW4$B%3M+nNvC2`0!#@sckqlzo5;hhGi(D9=*A4` z5ynobawSPRtWn&CDLEs3Xf`(8^zDP=NdF~F^s&={l7(aw&EG}KWpMjtmz7j_VLO;@ zM2NVLDxZ@GIv7*gzl1 zjq78tv*8#WSY`}Su0&C;2F$Ze(q>F(@Wm^Gw!)(j;dk9Ad{STaxn)IV9FZhm*n+U} zi;4y*3v%A`_c7a__DJ8D1b@dl0Std3F||4Wtvi)fCcBRh!X9$1x!_VzUh>*S5s!oq z;qd{J_r79EL2wIeiGAqFstWtkfIJpjVh%zFo*=55B9Zq~y0=^iqHWfQl@O!Ak;(o*m!pZqe9 z%U2oDOhR)BvW8&F70L;2TpkzIutIvNQaTjjs5V#8mV4!NQ}zN=i`i@WI1z0eN-iCS z;vL-Wxc^Vc_qK<5RPh(}*8dLT{~GzE{w2o$2kMFaEl&q zP{V=>&3kW7tWaK-Exy{~`v4J0U#OZBk{a9{&)&QG18L@6=bsZ1zC_d{{pKZ-Ey>I> z;8H0t4bwyQqgu4hmO`3|4K{R*5>qnQ&gOfdy?z`XD%e5+pTDzUt3`k^u~SaL&XMe= z9*h#kT(*Q9jO#w2Hd|Mr-%DV8i_1{J1MU~XJ3!WUplhXDYBpJH><0OU`**nIvPIof z|N8@I=wA)sf45SAvx||f?Z5uB$kz1qL3Ky_{%RPdP5iN-D2!p5scq}buuC00C@jom zhfGKm3|f?Z0iQ|K$Z~!`8{nmAS1r+fp6r#YDOS8V*;K&Gs7Lc&f^$RC66O|)28oh`NHy&vq zJh+hAw8+ybTB0@VhWN^0iiTnLsCWbS_y`^gs!LX!Lw{yE``!UVzrV24tP8o;I6-65 z1MUiHw^{bB15tmrVT*7-#sj6cs~z`wk52YQJ*TG{SE;KTm#Hf#a~|<(|ImHH17nNM z`Ub{+J3dMD!)mzC8b(2tZtokKW5pAwHa?NFiso~# z1*iaNh4lQ4TS)|@G)H4dZV@l*Vd;Rw;-;odDhW2&lJ%m@jz+Panv7LQm~2Js6rOW3 z0_&2cW^b^MYW3)@o;neZ<{B4c#m48dAl$GCc=$>ErDe|?y@z`$uq3xd(%aAsX)D%l z>y*SQ%My`yDP*zof|3@_w#cjaW_YW4BdA;#Glg1RQcJGY*CJ9`H{@|D+*e~*457kd z73p<%fB^PV!Ybw@)Dr%(ZJbX}xmCStCYv#K3O32ej{$9IzM^I{6FJ8!(=azt7RWf4 z7ib0UOPqN40X!wOnFOoddd8`!_IN~9O)#HRTyjfc#&MCZ zZAMzOVB=;qwt8gV?{Y2?b=iSZG~RF~uyx18K)IDFLl})G1v@$(s{O4@RJ%OTJyF+Cpcx4jmy|F3euCnMK!P2WTDu5j z{{gD$=M*pH!GGzL%P)V2*ROm>!$Y=z|D`!_yY6e7SU$~a5q8?hZGgaYqaiLnkK%?0 zs#oI%;zOxF@g*@(V4p!$7dS1rOr6GVs6uYCTt2h)eB4?(&w8{#o)s#%gN@BBosRUe z)@P@8_Zm89pr~)b>e{tbPC~&_MR--iB{=)y;INU5#)@Gix-YpgP<-c2Ms{9zuCX|3 z!p(?VaXww&(w&uBHzoT%!A2=3HAP>SDxcljrego7rY|%hxy3XlODWffO_%g|l+7Y_ zqV(xbu)s4lV=l7M;f>vJl{`6qBm>#ZeMA}kXb97Z)?R97EkoI?x6Lp0yu1Z>PS?2{ z0QQ(8D)|lc9CO3B~e(pQM&5(1y&y=e>C^X$`)_&XuaI!IgDTVqt31wX#n+@!a_A0ZQkA zCJ2@M_4Gb5MfCrm5UPggeyh)8 zO9?`B0J#rkoCx(R0I!ko_2?iO@|oRf1;3r+i)w-2&j?=;NVIdPFsB)`|IC0zk6r9c zRrkfxWsiJ(#8QndNJj@{@WP2Ackr|r1VxV{7S&rSU(^)-M8gV>@UzOLXu9K<{6e{T zXJ6b92r$!|lwjhmgqkdswY&}c)KW4A)-ac%sU;2^fvq7gfUW4Bw$b!i@duy1CAxSn z(pyh$^Z=&O-q<{bZUP+$U}=*#M9uVc>CQVgDs4swy5&8RAHZ~$)hrTF4W zPsSa~qYv_0mJnF89RnnJTH`3}w4?~epFl=D(35$ zWa07ON$`OMBOHgCmfO(9RFc<)?$x)N}Jd2A(<*Ll7+4jrRt9w zwGxExUXd9VB#I|DwfxvJ;HZ8Q{37^wDhaZ%O!oO(HpcqfLH%#a#!~;Jl7F5>EX_=8 z{()l2NqPz>La3qJR;_v+wlK>GsHl;uRA8%j`A|yH@k5r%55S9{*Cp%uw6t`qc1!*T za2OeqtQj7sAp#Q~=5Fs&aCR9v>5V+s&RdNvo&H~6FJOjvaj--2sYYBvMq;55%z8^o z|BJDA4vzfow#DO#ZQHh;Oq_{r+qP{R9ox2TOgwQiv7Ow!zjN+A@BN;0tA2lUb#+zO z(^b89eV)D7UVE+h{mcNc6&GtpOqDn_?VAQ)Vob$hlFwW%xh>D#wml{t&Ofmm_d_+; zKDxzdr}`n2Rw`DtyIjrG)eD0vut$}dJAZ0AohZ+ZQdWXn_Z@dI_y=7t3q8x#pDI-K z2VVc&EGq445Rq-j0=U=Zx`oBaBjsefY;%)Co>J3v4l8V(T8H?49_@;K6q#r~Wwppc z4XW0(4k}cP=5ex>-Xt3oATZ~bBWKv)aw|I|Lx=9C1s~&b77idz({&q3T(Y(KbWO?+ zmcZ6?WeUsGk6>km*~234YC+2e6Zxdl~<_g2J|IE`GH%n<%PRv-50; zH{tnVts*S5*_RxFT9eM0z-pksIb^drUq4>QSww=u;UFCv2AhOuXE*V4z?MM`|ABOC4P;OfhS(M{1|c%QZ=!%rQTDFx`+}?Kdx$&FU?Y<$x;j7z=(;Lyz+?EE>ov!8vvMtSzG!nMie zsBa9t8as#2nH}n8xzN%W%U$#MHNXmDUVr@GX{?(=yI=4vks|V)!-W5jHsU|h_&+kY zS_8^kd3jlYqOoiI`ZqBVY!(UfnAGny!FowZWY_@YR0z!nG7m{{)4OS$q&YDyw6vC$ zm4!$h>*|!2LbMbxS+VM6&DIrL*X4DeMO!@#EzMVfr)e4Tagn~AQHIU8?e61TuhcKD zr!F4(kEebk(Wdk-?4oXM(rJwanS>Jc%<>R(siF+>+5*CqJLecP_we33iTFTXr6W^G z7M?LPC-qFHK;E!fxCP)`8rkxZyFk{EV;G-|kwf4b$c1k0atD?85+|4V%YATWMG|?K zLyLrws36p%Qz6{}>7b>)$pe>mR+=IWuGrX{3ZPZXF3plvuv5Huax86}KX*lbPVr}L z{C#lDjdDeHr~?l|)Vp_}T|%$qF&q#U;ClHEPVuS+Jg~NjC1RP=17=aQKGOcJ6B3mp z8?4*-fAD~}sX*=E6!}^u8)+m2j<&FSW%pYr_d|p_{28DZ#Cz0@NF=gC-o$MY?8Ca8 zr5Y8DSR^*urS~rhpX^05r30Ik#2>*dIOGxRm0#0YX@YQ%Mg5b6dXlS!4{7O_kdaW8PFSdj1=ryI-=5$fiieGK{LZ+SX(1b=MNL!q#lN zv98?fqqTUH8r8C7v(cx#BQ5P9W>- zmW93;eH6T`vuJ~rqtIBg%A6>q>gnWb3X!r0wh_q;211+Om&?nvYzL1hhtjB zK_7G3!n7PL>d!kj){HQE zE8(%J%dWLh1_k%gVXTZt zEdT09XSKAx27Ncaq|(vzL3gm83q>6CAw<$fTnMU05*xAe&rDfCiu`u^1)CD<>sx0i z*hr^N_TeN89G(nunZoLBf^81#pmM}>JgD@Nn1l*lN#a=B=9pN%tmvYFjFIoKe_(GF z-26x{(KXdfsQL7Uv6UtDuYwV`;8V3w>oT_I<`Ccz3QqK9tYT5ZQzbop{=I=!pMOCb zCU68`n?^DT%^&m>A%+-~#lvF!7`L7a{z<3JqIlk1$<||_J}vW1U9Y&eX<}l8##6i( zZcTT@2`9(Mecptm@{3A_Y(X`w9K0EwtPq~O!16bq{7c0f7#(3wn-^)h zxV&M~iiF!{-6A@>o;$RzQ5A50kxXYj!tcgme=Qjrbje~;5X2xryU;vH|6bE(8z^<7 zQ>BG7_c*JG8~K7Oe68i#0~C$v?-t@~@r3t2inUnLT(c=URpA9kA8uq9PKU(Ps(LVH zqgcqW>Gm?6oV#AldDPKVRcEyQIdTT`Qa1j~vS{<;SwyTdr&3*t?J)y=M7q*CzucZ&B0M=joT zBbj@*SY;o2^_h*>R0e({!QHF0=)0hOj^B^d*m>SnRrwq>MolNSgl^~r8GR#mDWGYEIJA8B<|{{j?-7p zVnV$zancW3&JVDtVpIlI|5djKq0(w$KxEFzEiiL=h5Jw~4Le23@s(mYyXWL9SX6Ot zmb)sZaly_P%BeX_9 zw&{yBef8tFm+%=--m*J|o~+Xg3N+$IH)t)=fqD+|fEk4AAZ&!wcN5=mi~Vvo^i`}> z#_3ahR}Ju)(Px7kev#JGcSwPXJ2id9%Qd2A#Uc@t8~egZ8;iC{e! z%=CGJOD1}j!HW_sgbi_8suYnn4#Ou}%9u)dXd3huFIb!ytlX>Denx@pCS-Nj$`VO&j@(z!kKSP0hE4;YIP#w9ta=3DO$7f*x zc9M4&NK%IrVmZAe=r@skWD`AEWH=g+r|*13Ss$+{c_R!b?>?UaGXlw*8qDmY#xlR= z<0XFbs2t?8i^G~m?b|!Hal^ZjRjt<@a? z%({Gn14b4-a|#uY^=@iiKH+k?~~wTj5K1A&hU z2^9-HTC)7zpoWK|$JXaBL6C z#qSNYtY>65T@Zs&-0cHeu|RX(Pxz6vTITdzJdYippF zC-EB+n4}#lM7`2Ry~SO>FxhKboIAF#Z{1wqxaCb{#yEFhLuX;Rx(Lz%T`Xo1+a2M}7D+@wol2)OJs$TwtRNJ={( zD@#zTUEE}#Fz#&(EoD|SV#bayvr&E0vzmb%H?o~46|FAcx?r4$N z&67W3mdip-T1RIxwSm_&(%U|+WvtGBj*}t69XVd&ebn>KOuL(7Y8cV?THd-(+9>G7*Nt%T zcH;`p={`SOjaf7hNd(=37Lz3-51;58JffzIPgGs_7xIOsB5p2t&@v1mKS$2D$*GQ6 zM(IR*j4{nri7NMK9xlDy-hJW6sW|ZiDRaFiayj%;(%51DN!ZCCCXz+0Vm#};70nOx zJ#yA0P3p^1DED;jGdPbQWo0WATN=&2(QybbVdhd=Vq*liDk`c7iZ?*AKEYC#SY&2g z&Q(Ci)MJ{mEat$ZdSwTjf6h~roanYh2?9j$CF@4hjj_f35kTKuGHvIs9}Re@iKMxS-OI*`0S z6s)fOtz}O$T?PLFVSeOjSO26$@u`e<>k(OSP!&YstH3ANh>)mzmKGNOwOawq-MPXe zy4xbeUAl6tamnx))-`Gi2uV5>9n(73yS)Ukma4*7fI8PaEwa)dWHs6QA6>$}7?(L8 ztN8M}?{Tf!Zu22J5?2@95&rQ|F7=FK-hihT-vDp!5JCcWrVogEnp;CHenAZ)+E+K5 z$Cffk5sNwD_?4+ymgcHR(5xgt20Z8M`2*;MzOM#>yhk{r3x=EyM226wb&!+j`W<%* zSc&|`8!>dn9D@!pYow~(DsY_naSx7(Z4i>cu#hA5=;IuI88}7f%)bRkuY2B;+9Uep zpXcvFWkJ!mQai63BgNXG26$5kyhZ2&*3Q_tk)Ii4M>@p~_~q_cE!|^A;_MHB;7s#9 zKzMzK{lIxotjc};k67^Xsl-gS!^*m*m6kn|sbdun`O?dUkJ{0cmI0-_2y=lTAfn*Y zKg*A-2sJq)CCJgY0LF-VQvl&6HIXZyxo2#!O&6fOhbHXC?%1cMc6y^*dOS{f$=137Ds1m01qs`>iUQ49JijsaQ( zksqV9@&?il$|4Ua%4!O15>Zy&%gBY&wgqB>XA3!EldQ%1CRSM(pp#k~-pkcCg4LAT zXE=puHbgsw)!xtc@P4r~Z}nTF=D2~j(6D%gTBw$(`Fc=OOQ0kiW$_RDd=hcO0t97h zb86S5r=>(@VGy1&#S$Kg_H@7G^;8Ue)X5Y+IWUi`o;mpvoV)`fcVk4FpcT|;EG!;? zHG^zrVVZOm>1KFaHlaogcWj(v!S)O(Aa|Vo?S|P z5|6b{qkH(USa*Z7-y_Uvty_Z1|B{rTS^qmEMLEYUSk03_Fg&!O3BMo{b^*`3SHvl0 zhnLTe^_vVIdcSHe)SQE}r~2dq)VZJ!aSKR?RS<(9lzkYo&dQ?mubnWmgMM37Nudwo z3Vz@R{=m2gENUE3V4NbIzAA$H1z0pagz94-PTJyX{b$yndsdKptmlKQKaaHj@3=ED zc7L?p@%ui|RegVYutK$64q4pe9+5sv34QUpo)u{1ci?)_7gXQd{PL>b0l(LI#rJmN zGuO+%GO`xneFOOr4EU(Wg}_%bhzUf;d@TU+V*2#}!2OLwg~%D;1FAu=Un>OgjPb3S z7l(riiCwgghC=Lm5hWGf5NdGp#01xQ59`HJcLXbUR3&n%P(+W2q$h2Qd z*6+-QXJ*&Kvk9ht0f0*rO_|FMBALen{j7T1l%=Q>gf#kma zQlg#I9+HB+z*5BMxdesMND`_W;q5|FaEURFk|~&{@qY32N$G$2B=&Po{=!)x5b!#n zxLzblkq{yj05#O7(GRuT39(06FJlalyv<#K4m}+vs>9@q-&31@1(QBv82{}Zkns~K ze{eHC_RDX0#^A*JQTwF`a=IkE6Ze@j#-8Q`tTT?k9`^ZhA~3eCZJ-Jr{~7Cx;H4A3 zcZ+Zj{mzFZbVvQ6U~n>$U2ZotGsERZ@}VKrgGh0xM;Jzt29%TX6_&CWzg+YYMozrM z`nutuS)_0dCM8UVaKRj804J4i%z2BA_8A4OJRQ$N(P9Mfn-gF;4#q788C@9XR0O3< zsoS4wIoyt046d+LnSCJOy@B@Uz*#GGd#+Ln1ek5Dv>(ZtD@tgZlPnZZJGBLr^JK+!$$?A_fA3LOrkoDRH&l7 zcMcD$Hsjko3`-{bn)jPL6E9Ds{WskMrivsUu5apD z?grQO@W7i5+%X&E&p|RBaEZ(sGLR@~(y^BI@lDMot^Ll?!`90KT!JXUhYS`ZgX3jnu@Ja^seA*M5R@f`=`ynQV4rc$uT1mvE?@tz)TN<=&H1%Z?5yjxcpO+6y_R z6EPuPKM5uxKpmZfT(WKjRRNHs@ib)F5WAP7QCADvmCSD#hPz$V10wiD&{NXyEwx5S z6NE`3z!IS^$s7m}PCwQutVQ#~w+V z=+~->DI*bR2j0^@dMr9`p>q^Ny~NrAVxrJtX2DUveic5vM%#N*XO|?YAWwNI$Q)_) zvE|L(L1jP@F%gOGtnlXtIv2&1i8q<)Xfz8O3G^Ea~e*HJsQgBxWL(yuLY+jqUK zRE~`-zklrGog(X}$9@ZVUw!8*=l`6mzYLtsg`AvBYz(cxmAhr^j0~(rzXdiOEeu_p zE$sf2(w(BPAvO5DlaN&uQ$4@p-b?fRs}d7&2UQ4Fh?1Hzu*YVjcndqJLw0#q@fR4u zJCJ}>_7-|QbvOfylj+e^_L`5Ep9gqd>XI3-O?Wp z-gt*P29f$Tx(mtS`0d05nHH=gm~Po_^OxxUwV294BDKT>PHVlC5bndncxGR!n(OOm znsNt@Q&N{TLrmsoKFw0&_M9$&+C24`sIXGWgQaz=kY;S{?w`z^Q0JXXBKFLj0w0U6P*+jPKyZHX9F#b0D1$&(- zrm8PJd?+SrVf^JlfTM^qGDK&-p2Kdfg?f>^%>1n8bu&byH(huaocL>l@f%c*QkX2i znl}VZ4R1en4S&Bcqw?$=Zi7ohqB$Jw9x`aM#>pHc0x z0$!q7iFu zZ`tryM70qBI6JWWTF9EjgG@>6SRzsd}3h+4D8d~@CR07P$LJ}MFsYi-*O%XVvD@yT|rJ+Mk zDllJ7$n0V&A!0flbOf)HE6P_afPWZmbhpliqJuw=-h+r;WGk|ntkWN(8tKlYpq5Ow z(@%s>IN8nHRaYb*^d;M(D$zGCv5C|uqmsDjwy4g=Lz>*OhO3z=)VD}C<65;`89Ye} zSCxrv#ILzIpEx1KdLPlM&%Cctf@FqTKvNPXC&`*H9=l=D3r!GLM?UV zOxa(8ZsB`&+76S-_xuj?G#wXBfDY@Z_tMpXJS7^mp z@YX&u0jYw2A+Z+bD#6sgVK5ZgdPSJV3>{K^4~%HV?rn~4D)*2H!67Y>0aOmzup`{D zzDp3c9yEbGCY$U<8biJ_gB*`jluz1ShUd!QUIQJ$*1;MXCMApJ^m*Fiv88RZ zFopLViw}{$Tyhh_{MLGIE2~sZ)t0VvoW%=8qKZ>h=adTe3QM$&$PO2lfqH@brt!9j ziePM8$!CgE9iz6B<6_wyTQj?qYa;eC^{x_0wuwV~W+^fZmFco-o%wsKSnjXFEx02V zF5C2t)T6Gw$Kf^_c;Ei3G~uC8SM-xyycmXyC2hAVi-IfXqhu$$-C=*|X?R0~hu z8`J6TdgflslhrmDZq1f?GXF7*ALeMmOEpRDg(s*H`4>_NAr`2uqF;k;JQ+8>A|_6ZNsNLECC%NNEb1Y1dP zbIEmNpK)#XagtL4R6BC{C5T(+=yA-(Z|Ap}U-AfZM#gwVpus3(gPn}Q$CExObJ5AC z)ff9Yk?wZ}dZ-^)?cbb9Fw#EjqQ8jxF4G3=L?Ra zg_)0QDMV1y^A^>HRI$x?Op@t;oj&H@1xt4SZ9(kifQ zb59B*`M99Td7@aZ3UWvj1rD0sE)d=BsBuW*KwkCds7ay(7*01_+L}b~7)VHI>F_!{ zyxg-&nCO?v#KOUec0{OOKy+sjWA;8rTE|Lv6I9H?CI?H(mUm8VXGwU$49LGpz&{nQp2}dinE1@lZ1iox6{ghN&v^GZv9J${7WaXj)<0S4g_uiJ&JCZ zr8-hsu`U%N;+9N^@&Q0^kVPB3)wY(rr}p7{p0qFHb3NUUHJb672+wRZs`gd1UjKPX z4o6zljKKA+Kkj?H>Ew63o%QjyBk&1!P22;MkD>sM0=z_s-G{mTixJCT9@_|*(p^bz zJ8?ZZ&;pzV+7#6Mn`_U-)k8Pjg?a;|Oe^us^PoPY$Va~yi8|?+&=y$f+lABT<*pZr zP}D{~Pq1Qyni+@|aP;ixO~mbEW9#c0OU#YbDZIaw=_&$K%Ep2f%hO^&P67hApZe`x zv8b`Mz@?M_7-)b!lkQKk)JXXUuT|B8kJlvqRmRpxtQDgvrHMXC1B$M@Y%Me!BSx3P z#2Eawl$HleZhhTS6Txm>lN_+I`>eV$&v9fOg)%zVn3O5mI*lAl>QcHuW6!Kixmq`X zBCZ*Ck6OYtDiK!N47>jxI&O2a9x7M|i^IagRr-fmrmikEQGgw%J7bO|)*$2FW95O4 zeBs>KR)izRG1gRVL;F*sr8A}aRHO0gc$$j&ds8CIO1=Gwq1%_~E)CWNn9pCtBE}+`Jelk4{>S)M)`Ll=!~gnn1yq^EX(+y*ik@3Ou0qU`IgYi3*doM+5&dU!cho$pZ zn%lhKeZkS72P?Cf68<#kll_6OAO26bIbueZx**j6o;I0cS^XiL`y+>{cD}gd%lux} z)3N>MaE24WBZ}s0ApfdM;5J_Ny}rfUyxfkC``Awo2#sgLnGPewK};dORuT?@I6(5~ z?kE)Qh$L&fwJXzK){iYx!l5$Tt|^D~MkGZPA}(o6f7w~O2G6Vvzdo*a;iXzk$B66$ zwF#;wM7A+(;uFG4+UAY(2`*3XXx|V$K8AYu#ECJYSl@S=uZW$ksfC$~qrrbQj4??z-)uz0QL}>k^?fPnJTPw% zGz)~?B4}u0CzOf@l^um}HZzbaIwPmb<)< zi_3@E9lc)Qe2_`*Z^HH;1CXOceL=CHpHS{HySy3T%<^NrWQ}G0i4e1xm_K3(+~oi$ zoHl9wzb?Z4j#90DtURtjtgvi7uw8DzHYmtPb;?%8vb9n@bszT=1qr)V_>R%s!92_` zfnHQPANx z<#hIjIMm#*(v*!OXtF+w8kLu`o?VZ5k7{`vw{Yc^qYclpUGIM_PBN1+c{#Vxv&E*@ zxg=W2W~JuV{IuRYw3>LSI1)a!thID@R=bU+cU@DbR^_SXY`MC7HOsCN z!dO4OKV7(E_Z8T#8MA1H`99?Z!r0)qKW_#|29X3#Jb+5+>qUidbeP1NJ@)(qi2S-X zao|f0_tl(O+$R|Qwd$H{_ig|~I1fbp_$NkI!0E;Y z6JrnU{1Ra6^on{9gUUB0mwzP3S%B#h0fjo>JvV~#+X0P~JV=IG=yHG$O+p5O3NUgG zEQ}z6BTp^Fie)Sg<){Z&I8NwPR(=mO4joTLHkJ>|Tnk23E(Bo`FSbPc05lF2-+)X? z6vV3*m~IBHTy*^E!<0nA(tCOJW2G4DsH7)BxLV8kICn5lu6@U*R`w)o9;Ro$i8=Q^V%uH8n3q=+Yf;SFRZu z!+F&PKcH#8cG?aSK_Tl@K9P#8o+jry@gdexz&d(Q=47<7nw@e@FFfIRNL9^)1i@;A z28+$Z#rjv-wj#heI|<&J_DiJ*s}xd-f!{J8jfqOHE`TiHHZVIA8CjkNQ_u;Ery^^t zl1I75&u^`1_q)crO+JT4rx|z2ToSC>)Or@-D zy3S>jW*sNIZR-EBsfyaJ+Jq4BQE4?SePtD2+jY8*%FsSLZ9MY>+wk?}}}AFAw)vr{ml)8LUG-y9>^t!{~|sgpxYc0Gnkg`&~R z-pilJZjr@y5$>B=VMdZ73svct%##v%wdX~9fz6i3Q-zOKJ9wso+h?VME7}SjL=!NUG{J?M&i!>ma`eoEa@IX`5G>B1(7;%}M*%-# zfhJ(W{y;>MRz!Ic8=S}VaBKqh;~7KdnGEHxcL$kA-6E~=!hrN*zw9N+_=odt<$_H_8dbo;0=42wcAETPCVGUr~v(`Uai zb{=D!Qc!dOEU6v)2eHSZq%5iqK?B(JlCq%T6av$Cb4Rko6onlG&?CqaX7Y_C_cOC3 zYZ;_oI(}=>_07}Oep&Ws7x7-R)cc8zfe!SYxJYP``pi$FDS)4Fvw5HH=FiU6xfVqIM!hJ;Rx8c0cB7~aPtNH(Nmm5Vh{ibAoU#J6 zImRCr?(iyu_4W_6AWo3*vxTPUw@vPwy@E0`(>1Qi=%>5eSIrp^`` zK*Y?fK_6F1W>-7UsB)RPC4>>Ps9)f+^MqM}8AUm@tZ->j%&h1M8s*s!LX5&WxQcAh z8mciQej@RPm?660%>{_D+7er>%zX_{s|$Z+;G7_sfNfBgY(zLB4Ey}J9F>zX#K0f6 z?dVNIeEh?EIShmP6>M+d|0wMM85Sa4diw1hrg|ITJ}JDg@o8y>(rF9mXk5M z2@D|NA)-7>wD&wF;S_$KS=eE84`BGw3g0?6wGxu8ys4rwI?9U=*^VF22t3%mbGeOh z`!O-OpF7#Vceu~F`${bW0nYVU9ecmk31V{tF%iv&5hWofC>I~cqAt@u6|R+|HLMMX zVxuSlMFOK_EQ86#E8&KwxIr8S9tj_goWtLv4f@!&h8;Ov41{J~496vp9vX=(LK#j! zAwi*21RAV-LD>9Cw3bV_9X(X3)Kr0-UaB*7Y>t82EQ%!)(&(XuAYtTsYy-dz+w=$ir)VJpe!_$ z6SGpX^i(af3{o=VlFPC);|J8#(=_8#vdxDe|Cok+ANhYwbE*FO`Su2m1~w+&9<_9~ z-|tTU_ACGN`~CNW5WYYBn^B#SwZ(t4%3aPp z;o)|L6Rk569KGxFLUPx@!6OOa+5OjQLK5w&nAmwxkC5rZ|m&HT8G%GVZxB_@ME z>>{rnXUqyiJrT(8GMj_ap#yN_!9-lO5e8mR3cJiK3NE{_UM&=*vIU`YkiL$1%kf+1 z4=jk@7EEj`u(jy$HnzE33ZVW_J4bj}K;vT?T91YlO(|Y0FU4r+VdbmQ97%(J5 zkK*Bed8+C}FcZ@HIgdCMioV%A<*4pw_n}l*{Cr4}a(lq|injK#O?$tyvyE`S%(1`H z_wwRvk#13ElkZvij2MFGOj`fhy?nC^8`Zyo%yVcUAfEr8x&J#A{|moUBAV_^f$hpaUuyQeY3da^ zS9iRgf87YBwfe}>BO+T&Fl%rfpZh#+AM?Dq-k$Bq`vG6G_b4z%Kbd&v>qFjow*mBl z-OylnqOpLg}or7_VNwRg2za3VBK6FUfFX{|TD z`Wt0Vm2H$vdlRWYQJqDmM?JUbVqL*ZQY|5&sY*?!&%P8qhA~5+Af<{MaGo(dl&C5t zE%t!J0 zh6jqANt4ABdPxSTrVV}fLsRQal*)l&_*rFq(Ez}ClEH6LHv{J#v?+H-BZ2)Wy{K@9 z+ovXHq~DiDvm>O~r$LJo!cOuwL+Oa--6;UFE2q@g3N8Qkw5E>ytz^(&($!O47+i~$ zKM+tkAd-RbmP{s_rh+ugTD;lriL~`Xwkad#;_aM?nQ7L_muEFI}U_4$phjvYgleK~`Fo`;GiC07&Hq1F<%p;9Q;tv5b?*QnR%8DYJH3P>Svmv47Y>*LPZJy8_{9H`g6kQpyZU{oJ`m%&p~D=K#KpfoJ@ zn-3cqmHsdtN!f?~w+(t+I`*7GQA#EQC^lUA9(i6=i1PqSAc|ha91I%X&nXzjYaM{8$s&wEx@aVkQ6M{E2 zfzId#&r(XwUNtPcq4Ngze^+XaJA1EK-%&C9j>^9(secqe{}z>hR5CFNveMsVA)m#S zk)_%SidkY-XmMWlVnQ(mNJ>)ooszQ#vaK;!rPmGKXV7am^_F!Lz>;~{VrIO$;!#30XRhE1QqO_~#+Ux;B_D{Nk=grn z8Y0oR^4RqtcYM)7a%@B(XdbZCOqnX#fD{BQTeLvRHd(irHKq=4*jq34`6@VAQR8WG z^%)@5CXnD_T#f%@-l${>y$tfb>2LPmc{~5A82|16mH)R?&r#KKLs7xpN-D`=&Cm^R zvMA6#Ahr<3X>Q7|-qfTY)}32HkAz$_mibYV!I)u>bmjK`qwBe(>za^0Kt*HnFbSdO z1>+ryKCNxmm^)*$XfiDOF2|{-v3KKB?&!(S_Y=Ht@|ir^hLd978xuI&N{k>?(*f8H z=ClxVJK_%_z1TH0eUwm2J+2To7FK4o+n_na)&#VLn1m;!+CX+~WC+qg1?PA~KdOlC zW)C@pw75_xoe=w7i|r9KGIvQ$+3K?L{7TGHwrQM{dCp=Z*D}3kX7E-@sZnup!BImw z*T#a=+WcTwL78exTgBn|iNE3#EsOorO z*kt)gDzHiPt07fmisA2LWN?AymkdqTgr?=loT7z@d`wnlr6oN}@o|&JX!yPzC*Y8d zu6kWlTzE1)ckyBn+0Y^HMN+GA$wUO_LN6W>mxCo!0?oiQvT`z$jbSEu&{UHRU0E8# z%B^wOc@S!yhMT49Y)ww(Xta^8pmPCe@eI5C*ed96)AX9<>))nKx0(sci8gwob_1}4 z0DIL&vsJ1_s%<@y%U*-eX z5rN&(zef-5G~?@r79oZGW1d!WaTqQn0F6RIOa9tJ=0(kdd{d1{<*tHT#cCvl*i>YY zH+L7jq8xZNcTUBqj(S)ztTU!TM!RQ}In*n&Gn<>(60G7}4%WQL!o>hbJqNDSGwl#H z`4k+twp0cj%PsS+NKaxslAEu9!#U3xT1|_KB6`h=PI0SW`P9GTa7caD1}vKEglV8# zjKZR`pluCW19c2fM&ZG)c3T3Um;ir3y(tSCJ7Agl6|b524dy5El{^EQBG?E61H0XY z`bqg!;zhGhyMFl&(o=JWEJ8n~z)xI}A@C0d2hQGvw7nGv)?POU@(kS1m=%`|+^ika zXl8zjS?xqW$WlO?Ewa;vF~XbybHBor$f<%I&*t$F5fynwZlTGj|IjZtVfGa7l&tK} zW>I<69w(cZLu)QIVG|M2xzW@S+70NinQzk&Y0+3WT*cC)rx~04O-^<{JohU_&HL5XdUKW!uFy|i$FB|EMu0eUyW;gsf`XfIc!Z0V zeK&*hPL}f_cX=@iv>K%S5kL;cl_$v?n(Q9f_cChk8Lq$glT|=e+T*8O4H2n<=NGmn z+2*h+v;kBvF>}&0RDS>)B{1!_*XuE8A$Y=G8w^qGMtfudDBsD5>T5SB;Qo}fSkkiV ze^K^M(UthkwrD!&*tTsu>Dacdj_q`~V%r_twr$(Ct&_dKeeXE?fA&4&yASJWJ*}~- zel=@W)tusynfC_YqH4ll>4Eg`Xjs5F7Tj>tTLz<0N3)X<1px_d2yUY>X~y>>93*$) z5PuNMQLf9Bu?AAGO~a_|J2akO1M*@VYN^VxvP0F$2>;Zb9;d5Yfd8P%oFCCoZE$ z4#N$^J8rxYjUE_6{T%Y>MmWfHgScpuGv59#4u6fpTF%~KB^Ae`t1TD_^Ud#DhL+Dm zbY^VAM#MrAmFj{3-BpVSWph2b_Y6gCnCAombVa|1S@DU)2r9W<> zT5L8BB^er3zxKt1v(y&OYk!^aoQisqU zH(g@_o)D~BufUXcPt!Ydom)e|aW{XiMnes2z&rE?og>7|G+tp7&^;q?Qz5S5^yd$i z8lWr4g5nctBHtigX%0%XzIAB8U|T6&JsC4&^hZBw^*aIcuNO47de?|pGXJ4t}BB`L^d8tD`H`i zqrP8?#J@8T#;{^B!KO6J=@OWKhAerih(phML`(Rg7N1XWf1TN>=Z3Do{l_!d~DND&)O)D>ta20}@Lt77qSnVsA7>)uZAaT9bsB>u&aUQl+7GiY2|dAEg@%Al3i316y;&IhQL^8fw_nwS>f60M_-m+!5)S_6EPM7Y)(Nq^8gL7(3 zOiot`6Wy6%vw~a_H?1hLVzIT^i1;HedHgW9-P#)}Y6vF%C=P70X0Tk^z9Te@kPILI z_(gk!k+0%CG)%!WnBjjw*kAKs_lf#=5HXC00s-}oM-Q1aXYLj)(1d!_a7 z*Gg4Fe6F$*ujVjI|79Z5+Pr`us%zW@ln++2l+0hsngv<{mJ%?OfSo_3HJXOCys{Ug z00*YR-(fv<=&%Q!j%b-_ppA$JsTm^_L4x`$k{VpfLI(FMCap%LFAyq;#ns5bR7V+x zO!o;c5y~DyBPqdVQX)8G^G&jWkBy2|oWTw>)?5u}SAsI$RjT#)lTV&Rf8;>u*qXnb z8F%Xb=7#$m)83z%`E;49)t3fHInhtc#kx4wSLLms!*~Z$V?bTyUGiS&m>1P(952(H zuHdv=;o*{;5#X-uAyon`hP}d#U{uDlV?W?_5UjJvf%11hKwe&(&9_~{W)*y1nR5f_ z!N(R74nNK`y8>B!0Bt_Vr!;nc3W>~RiKtGSBkNlsR#-t^&;$W#)f9tTlZz>n*+Fjz z3zXZ;jf(sTM(oDzJt4FJS*8c&;PLTW(IQDFs_5QPy+7yhi1syPCarvqrHFcf&yTy)^O<1EBx;Ir`5W{TIM>{8w&PB>ro4;YD<5LF^TjTb0!zAP|QijA+1Vg>{Afv^% zmrkc4o6rvBI;Q8rj4*=AZacy*n8B{&G3VJc)so4$XUoie0)vr;qzPZVbb<#Fc=j+8CGBWe$n|3K& z_@%?{l|TzKSlUEO{U{{%Fz_pVDxs7i9H#bnbCw7@4DR=}r_qV!Zo~CvD4ZI*+j3kO zW6_=|S`)(*gM0Z;;}nj`73OigF4p6_NPZQ-Od~e$c_);;4-7sR>+2u$6m$Gf%T{aq zle>e3(*Rt(TPD}03n5)!Ca8Pu!V}m6v0o1;5<1h$*|7z|^(3$Y&;KHKTT}hV056wuF0Xo@mK-52~r=6^SI1NC%c~CC?n>yX6wPTgiWYVz!Sx^atLby9YNn1Rk{g?|pJaxD4|9cUf|V1_I*w zzxK)hRh9%zOl=*$?XUjly5z8?jPMy%vEN)f%T*|WO|bp5NWv@B(K3D6LMl!-6dQg0 zXNE&O>Oyf%K@`ngCvbGPR>HRg5!1IV$_}m@3dWB7x3t&KFyOJn9pxRXCAzFr&%37wXG;z^xaO$ekR=LJG ztIHpY8F5xBP{mtQidqNRoz= z@){+N3(VO5bD+VrmS^YjG@+JO{EOIW)9=F4v_$Ed8rZtHvjpiEp{r^c4F6Ic#ChlC zJX^DtSK+v(YdCW)^EFcs=XP7S>Y!4=xgmv>{S$~@h=xW-G4FF9?I@zYN$e5oF9g$# zb!eVU#J+NjLyX;yb)%SY)xJdvGhsnE*JEkuOVo^k5PyS=o#vq!KD46UTW_%R=Y&0G zFj6bV{`Y6)YoKgqnir2&+sl+i6foAn-**Zd1{_;Zb7Ki=u394C5J{l^H@XN`_6XTKY%X1AgQM6KycJ+= zYO=&t#5oSKB^pYhNdzPgH~aEGW2=ec1O#s-KG z71}LOg@4UEFtp3GY1PBemXpNs6UK-ax*)#$J^pC_me;Z$Je(OqLoh|ZrW*mAMBFn< zHttjwC&fkVfMnQeen8`Rvy^$pNRFVaiEN4Pih*Y3@jo!T0nsClN)pdrr9AYLcZxZ| zJ5Wlj+4q~($hbtuY zVQ7hl>4-+@6g1i`1a)rvtp-;b0>^`Dloy(#{z~ytgv=j4q^Kl}wD>K_Y!l~ zp(_&7sh`vfO(1*MO!B%<6E_bx1)&s+Ae`O)a|X=J9y~XDa@UB`m)`tSG4AUhoM=5& znWoHlA-(z@3n0=l{E)R-p8sB9XkV zZ#D8wietfHL?J5X0%&fGg@MH~(rNS2`GHS4xTo7L$>TPme+Is~!|79=^}QbPF>m%J zFMkGzSndiPO|E~hrhCeo@&Ea{M(ieIgRWMf)E}qeTxT8Q#g-!Lu*x$v8W^M^>?-g= zwMJ$dThI|~M06rG$Sv@C@tWR>_YgaG&!BAbkGggVQa#KdtDB)lMLNVLN|51C@F^y8 zCRvMB^{GO@j=cHfmy}_pCGbP%xb{pNN>? z?7tBz$1^zVaP|uaatYaIN+#xEN4jBzwZ|YI_)p(4CUAz1ZEbDk>J~Y|63SZaak~#0 zoYKruYsWHoOlC1(MhTnsdUOwQfz5p6-D0}4;DO$B;7#M{3lSE^jnTT;ns`>!G%i*F?@pR1JO{QTuD0U+~SlZxcc8~>IB{)@8p`P&+nDxNj`*gh|u?yrv$phpQcW)Us)bi`kT%qLj(fi{dWRZ%Es2!=3mI~UxiW0$-v3vUl?#g{p6eF zMEUAqo5-L0Ar(s{VlR9g=j7+lt!gP!UN2ICMokAZ5(Agd>})#gkA2w|5+<%-CuEP# zqgcM}u@3(QIC^Gx<2dbLj?cFSws_f3e%f4jeR?4M^M3cx1f+Qr6ydQ>n)kz1s##2w zk}UyQc+Z5G-d-1}{WzjkLXgS-2P7auWSJ%pSnD|Uivj5u!xk0 z_^-N9r9o;(rFDt~q1PvE#iJZ_f>J3gcP$)SOqhE~pD2|$=GvpL^d!r z6u=sp-CrMoF7;)}Zd7XO4XihC4ji?>V&(t^?@3Q&t9Mx=qex6C9d%{FE6dvU6%d94 zIE;hJ1J)cCqjv?F``7I*6bc#X)JW2b4f$L^>j{*$R`%5VHFi*+Q$2;nyieduE}qdS{L8y8F08yLs?w}{>8>$3236T-VMh@B zq-nujsb_1aUv_7g#)*rf9h%sFj*^mIcImRV*k~Vmw;%;YH(&ylYpy!&UjUVqqtfG` zox3esju?`unJJA_zKXRJP)rA3nXc$m^{S&-p|v|-0x9LHJm;XIww7C#R$?00l&Yyj z=e}gKUOpsImwW?N)+E(awoF@HyP^EhL+GlNB#k?R<2>95hz!h9sF@U20DHSB3~WMa zk90+858r@-+vWwkawJ)8ougd(i#1m3GLN{iSTylYz$brAsP%=&m$mQQrH$g%3-^VR zE%B`Vi&m8f3T~&myTEK28BDWCVzfWir1I?03;pX))|kY5ClO^+bae z*7E?g=3g7EiisYOrE+lA)2?Ln6q2*HLNpZEWMB|O-JI_oaHZB%CvYB(%=tU= zE*OY%QY58fW#RG5=gm0NR#iMB=EuNF@)%oZJ}nmm=tsJ?eGjia{e{yuU0l3{d^D@)kVDt=1PE)&tf_hHC%0MB znL|CRCPC}SeuVTdf>-QV70`0(EHizc21s^sU>y%hW0t!0&y<7}Wi-wGy>m%(-jsDj zP?mF|>p_K>liZ6ZP(w5(|9Ga%>tLgb$|doDDfkdW>Z z`)>V2XC?NJT26mL^@ zf+IKr27TfM!UbZ@?zRddC7#6ss1sw%CXJ4FWC+t3lHZupzM77m^=9 z&(a?-LxIq}*nvv)y?27lZ{j zifdl9hyJudyP2LpU$-kXctshbJDKS{WfulP5Dk~xU4Le4c#h^(YjJit4#R8_khheS z|8(>2ibaHES4+J|DBM7I#QF5u-*EdN{n=Kt@4Zt?@Tv{JZA{`4 zU#kYOv{#A&gGPwT+$Ud}AXlK3K7hYzo$(fBSFjrP{QQ zeaKg--L&jh$9N}`pu{Bs>?eDFPaWY4|9|foN%}i;3%;@4{dc+iw>m}{3rELqH21G! z`8@;w-zsJ1H(N3%|1B@#ioLOjib)j`EiJqPQVSbPSPVHCj6t5J&(NcWzBrzCiDt{4 zdlPAUKldz%6x5II1H_+jv)(xVL+a;P+-1hv_pM>gMRr%04@k;DTokASSKKhU1Qms| zrWh3a!b(J3n0>-tipg{a?UaKsP7?+|@A+1WPDiQIW1Sf@qDU~M_P65_s}7(gjTn0X zucyEm)o;f8UyshMy&>^SC3I|C6jR*R_GFwGranWZe*I>K+0k}pBuET&M~ z;Odo*ZcT?ZpduHyrf8E%IBFtv;JQ!N_m>!sV6ly$_1D{(&nO~w)G~Y`7sD3#hQk%^ zp}ucDF_$!6DAz*PM8yE(&~;%|=+h(Rn-=1Wykas_-@d&z#=S}rDf`4w(rVlcF&lF! z=1)M3YVz7orwk^BXhslJ8jR);sh^knJW(Qmm(QdSgIAIdlN4Te5KJisifjr?eB{FjAX1a0AB>d?qY4Wx>BZ8&}5K0fA+d{l8 z?^s&l8#j7pR&ijD?0b%;lL9l$P_mi2^*_OL+b}4kuLR$GAf85sOo02?Y#90}CCDiS zZ%rbCw>=H~CBO=C_JVV=xgDe%b4FaEFtuS7Q1##y686r%F6I)s-~2(}PWK|Z8M+Gu zl$y~5@#0Ka%$M<&Cv%L`a8X^@tY&T7<0|(6dNT=EsRe0%kp1Qyq!^43VAKYnr*A5~ zsI%lK1ewqO;0TpLrT9v}!@vJK{QoVa_+N4FYT#h?Y8rS1S&-G+m$FNMP?(8N`MZP zels(*?kK{{^g9DOzkuZXJ2;SrOQsp9T$hwRB1(phw1c7`!Q!by?Q#YsSM#I12RhU{$Q+{xj83axHcftEc$mNJ8_T7A-BQc*k(sZ+~NsO~xAA zxnbb%dam_fZlHvW7fKXrB~F&jS<4FD2FqY?VG?ix*r~MDXCE^WQ|W|WM;gsIA4lQP zJ2hAK@CF*3*VqPr2eeg6GzWFlICi8S>nO>5HvWzyZTE)hlkdC_>pBej*>o0EOHR|) z$?};&I4+_?wvL*g#PJ9)!bc#9BJu1(*RdNEn>#Oxta(VWeM40ola<0aOe2kSS~{^P zDJBd}0L-P#O-CzX*%+$#v;(x%<*SPgAje=F{Zh-@ucd2DA(yC|N_|ocs*|-!H%wEw z@Q!>siv2W;C^^j^59OAX03&}&D*W4EjCvfi(ygcL#~t8XGa#|NPO+*M@Y-)ctFA@I z-p7npT1#5zOLo>7q?aZpCZ=iecn3QYklP;gF0bq@>oyBq94f6C=;Csw3PkZ|5q=(c zfs`aw?II0e(h=|7o&T+hq&m$; zBrE09Twxd9BJ2P+QPN}*OdZ-JZV7%av@OM7v!!NL8R;%WFq*?{9T3{ct@2EKgc8h) zMxoM$SaF#p<`65BwIDfmXG6+OiK0e)`I=!A3E`+K@61f}0e z!2a*FOaDrOe>U`q%K!QN`&=&0C~)CaL3R4VY(NDt{Xz(Xpqru5=r#uQN1L$Je1*dkdqQ*=lofQaN%lO!<5z9ZlHgxt|`THd>2 zsWfU$9=p;yLyJyM^t zS2w9w?Bpto`@H^xJpZDKR1@~^30Il6oFGfk5%g6w*C+VM)+%R@gfIwNprOV5{F^M2 zO?n3DEzpT+EoSV-%OdvZvNF+pDd-ZVZ&d8 zKeIyrrfPN=EcFRCPEDCVflX#3-)Ik_HCkL(ejmY8vzcf-MTA{oHk!R2*36`O68$7J zf}zJC+bbQk--9Xm!u#lgLvx8TXx2J258E5^*IZ(FXMpq$2LUUvhWQPs((z1+2{Op% z?J}9k5^N=z;7ja~zi8a_-exIqWUBJwohe#4QJ`|FF*$C{lM18z^#hX6!5B8KAkLUX ziP=oti-gpV(BsLD{0(3*dw}4JxK23Y7M{BeFPucw!sHpY&l%Ws4pSm`+~V7;bZ%Dx zeI)MK=4vC&5#;2MT7fS?^ch9?2;%<8Jlu-IB&N~gg8t;6S-#C@!NU{`p7M8@2iGc& zg|JPg%@gCoCQ&s6JvDU&`X2S<57f(k8nJ1wvBu{8r?;q3_kpZZ${?|( z+^)UvR33sjSd)aT!UPkA;ylO6{aE3MQa{g%Mcf$1KONcjO@&g5zPHWtzM1rYC{_K> zgQNcs<{&X{OA=cEWw5JGqpr0O>x*Tfak2PE9?FuWtz^DDNI}rwAaT0(bdo-<+SJ6A z&}S%boGMWIS0L}=S>|-#kRX;e^sUsotry(MjE|3_9duvfc|nwF#NHuM-w7ZU!5ei8 z6Mkf>2)WunY2eU@C-Uj-A zG(z0Tz2YoBk>zCz_9-)4a>T46$(~kF+Y{#sA9MWH%5z#zNoz)sdXq7ZR_+`RZ%0(q zC7&GyS_|BGHNFl8Xa%@>iWh%Gr?=J5<(!OEjauj5jyrA-QXBjn0OAhJJ9+v=!LK`` z@g(`^*84Q4jcDL`OA&ZV60djgwG`|bcD*i50O}Q{9_noRg|~?dj%VtKOnyRs$Uzqg z191aWoR^rDX#@iSq0n z?9Sg$WSRPqSeI<}&n1T3!6%Wj@5iw5`*`Btni~G=&;J+4`7g#OQTa>u`{4ZZ(c@s$ zK0y;ySOGD-UTjREKbru{QaS>HjN<2)R%Nn-TZiQ(Twe4p@-saNa3~p{?^V9Nixz@a zykPv~<@lu6-Ng9i$Lrk(xi2Tri3q=RW`BJYOPC;S0Yly%77c727Yj-d1vF!Fuk{Xh z)lMbA69y7*5ufET>P*gXQrxsW+ zz)*MbHZv*eJPEXYE<6g6_M7N%#%mR{#awV3i^PafNv(zyI)&bH?F}2s8_rR(6%!V4SOWlup`TKAb@ee>!9JKPM=&8g#BeYRH9FpFybxBXQI2|g}FGJfJ+ zY-*2hB?o{TVL;Wt_ek;AP5PBqfDR4@Z->_182W z{P@Mc27j6jE*9xG{R$>6_;i=y{qf(c`5w9fa*`rEzX6t!KJ(p1H|>J1pC-2zqWENF zmm=Z5B4u{cY2XYl(PfrInB*~WGWik3@1oRhiMOS|D;acnf-Bs(QCm#wR;@Vf!hOPJ zgjhDCfDj$HcyVLJ=AaTbQ{@vIv14LWWF$=i-BDoC11}V;2V8A`S>_x)vIq44-VB-v z*w-d}$G+Ql?En8j!~ZkCpQ$|cA0|+rrY>tiCeWxkRGPoarxlGU2?7%k#F693RHT24 z-?JsiXlT2PTqZqNb&sSc>$d;O4V@|b6VKSWQb~bUaWn1Cf0+K%`Q&Wc<>mQ>*iEGB zbZ;aYOotBZ{vH3y<0A*L0QVM|#rf*LIsGx(O*-7)r@yyBIzJnBFSKBUSl1e|8lxU* zzFL+YDVVkIuzFWeJ8AbgN&w(4-7zbiaMn{5!JQXu)SELk*CNL+Fro|2v|YO)1l15t zs(0^&EB6DPMyaqvY>=KL>)tEpsn;N5Q#yJj<9}ImL((SqErWN3Q=;tBO~ExTCs9hB z2E$7eN#5wX4<3m^5pdjm#5o>s#eS_Q^P)tm$@SawTqF*1dj_i#)3};JslbLKHXl_N z)Fxzf>FN)EK&Rz&*|6&%Hs-^f{V|+_vL1S;-1K-l$5xiC@}%uDuwHYhmsV?YcOUlk zOYkG5v2+`+UWqpn0aaaqrD3lYdh0*!L`3FAsNKu=Q!vJu?Yc8n|CoYyDo_`r0mPoo z8>XCo$W4>l(==h?2~PoRR*kEe)&IH{1sM41mO#-36`02m#nTX{r*r`Q5rZ2-sE|nA zhnn5T#s#v`52T5|?GNS`%HgS2;R(*|^egNPDzzH_z^W)-Q98~$#YAe)cEZ%vge965AS_am#DK#pjPRr-!^za8>`kksCAUj(Xr*1NW5~e zpypt_eJpD&4_bl_y?G%>^L}=>xAaV>KR6;^aBytqpiHe%!j;&MzI_>Sx7O%F%D*8s zSN}cS^<{iiK)=Ji`FpO#^zY!_|D)qeRNAtgmH)m;qC|mq^j(|hL`7uBz+ULUj37gj zksdbnU+LSVo35riSX_4z{UX=%n&}7s0{WuZYoSfwAP`8aKN9P@%e=~1`~1ASL-z%# zw>DO&ixr}c9%4InGc*_y42bdEk)ZdG7-mTu0bD@_vGAr*NcFoMW;@r?@LUhRI zCUJgHb`O?M3!w)|CPu~ej%fddw20lod?Ufp8Dmt0PbnA0J%KE^2~AIcnKP()025V> zG>noSM3$5Btmc$GZoyP^v1@Poz0FD(6YSTH@aD0}BXva?LphAiSz9f&Y(aDAzBnUh z?d2m``~{z;{}kZJ>a^wYI?ry(V9hIoh;|EFc0*-#*`$T0DRQ1;WsqInG;YPS+I4{g zJGpKk%%Sdc5xBa$Q^_I~(F97eqDO7AN3EN0u)PNBAb+n+ zWBTxQx^;O9o0`=g+Zrt_{lP!sgWZHW?8bLYS$;1a@&7w9rD9|Ge;Gb?sEjFoF9-6v z#!2)t{DMHZ2@0W*fCx;62d#;jouz`R5Y(t{BT=$N4yr^^o$ON8d{PQ=!O zX17^CrdM~7D-;ZrC!||<+FEOxI_WI3CA<35va%4v>gc zEX-@h8esj=a4szW7x{0g$hwoWRQG$yK{@3mqd-jYiVofJE!Wok1* znV7Gm&Ssq#hFuvj1sRyHg(6PFA5U*Q8Rx>-blOs=lb`qa{zFy&n4xY;sd$fE+<3EI z##W$P9M{B3c3Si9gw^jlPU-JqD~Cye;wr=XkV7BSv#6}DrsXWFJ3eUNrc%7{=^sP> zrp)BWKA9<}^R9g!0q7yWlh;gr_TEOD|#BmGq<@IV;ueg+D2}cjpp+dPf&Q(36sFU&K8}hA85U61faW&{ zlB`9HUl-WWCG|<1XANN3JVAkRYvr5U4q6;!G*MTdSUt*Mi=z_y3B1A9j-@aK{lNvx zK%p23>M&=KTCgR!Ee8c?DAO2_R?B zkaqr6^BSP!8dHXxj%N1l+V$_%vzHjqvu7p@%Nl6;>y*S}M!B=pz=aqUV#`;h%M0rU zHfcog>kv3UZAEB*g7Er@t6CF8kHDmKTjO@rejA^ULqn!`LwrEwOVmHx^;g|5PHm#B zZ+jjWgjJ!043F+&#_;D*mz%Q60=L9Ove|$gU&~As5^uz@2-BfQ!bW)Khn}G+Wyjw- z19qI#oB(RSNydn0t~;tAmK!P-d{b-@@E5|cdgOS#!>%#Rj6ynkMvaW@37E>@hJP^8 z2zk8VXx|>#R^JCcWdBCy{0nPmYFOxN55#^-rlqobe0#L6)bi?E?SPymF*a5oDDeSd zO0gx?#KMoOd&G(2O@*W)HgX6y_aa6iMCl^~`{@UR`nMQE`>n_{_aY5nA}vqU8mt8H z`oa=g0SyiLd~BxAj2~l$zRSDHxvDs;I4>+M$W`HbJ|g&P+$!U7-PHX4RAcR0szJ*( ze-417=bO2q{492SWrqDK+L3#ChUHtz*@MP)e^%@>_&#Yk^1|tv@j4%3T)diEX zATx4K*hcO`sY$jk#jN5WD<=C3nvuVsRh||qDHnc~;Kf59zr0;c7VkVSUPD%NnnJC_ zl3F^#f_rDu8l}l8qcAz0FFa)EAt32IUy_JLIhU_J^l~FRH&6-ivSpG2PRqzDdMWft>Zc(c)#tb%wgmWN%>IOPm zZi-noqS!^Ftb81pRcQi`X#UhWK70hy4tGW1mz|+vI8c*h@ zfFGJtW3r>qV>1Z0r|L>7I3un^gcep$AAWfZHRvB|E*kktY$qQP_$YG60C@X~tTQjB3%@`uz!qxtxF+LE!+=nrS^07hn` zEgAp!h|r03h7B!$#OZW#ACD+M;-5J!W+{h|6I;5cNnE(Y863%1(oH}_FTW})8zYb$7czP zg~Szk1+_NTm6SJ0MS_|oSz%e(S~P-&SFp;!k?uFayytV$8HPwuyELSXOs^27XvK-D zOx-Dl!P|28DK6iX>p#Yb%3`A&CG0X2S43FjN%IB}q(!hC$fG}yl1y9W&W&I@KTg6@ zK^kpH8=yFuP+vI^+59|3%Zqnb5lTDAykf z9S#X`3N(X^SpdMyWQGOQRjhiwlj!0W-yD<3aEj^&X%=?`6lCy~?`&WSWt z?U~EKFcCG_RJ(Qp7j=$I%H8t)Z@6VjA#>1f@EYiS8MRHZphp zMA_5`znM=pzUpBPO)pXGYpQ6gkine{6u_o!P@Q+NKJ}k!_X7u|qfpAyIJb$_#3@wJ z<1SE2Edkfk9C!0t%}8Yio09^F`YGzpaJHGk*-ffsn85@)%4@`;Fv^8q(-Wk7r=Q8p zT&hD`5(f?M{gfzGbbwh8(}G#|#fDuk7v1W)5H9wkorE0ZZjL0Q1=NRGY>zwgfm81DdoaVwNH;or{{eSyybt)m<=zXoA^RALYG-2t zouH|L*BLvmm9cdMmn+KGopyR@4*=&0&4g|FLoreZOhRmh=)R0bg~ zT2(8V_q7~42-zvb)+y959OAv!V$u(O3)%Es0M@CRFmG{5sovIq4%8Ahjk#*5w{+)+ zMWQoJI_r$HxL5km1#6(e@{lK3Udc~n0@g`g$s?VrnQJ$!oPnb?IHh-1qA`Rz$)Ai< z6w$-MJW-gKNvOhL+XMbE7&mFt`x1KY>k4(!KbbpZ`>`K@1J<(#vVbjx@Z@(6Q}MF# zMnbr-f55(cTa^q4+#)=s+ThMaV~E`B8V=|W_fZWDwiso8tNMTNse)RNBGi=gVwgg% zbOg8>mbRN%7^Um-7oj4=6`$|(K7!+t^90a{$18Z>}<#!bm%ZEFQ{X(yBZMc>lCz0f1I2w9Sq zuGh<9<=AO&g6BZte6hn>Qmvv;Rt)*cJfTr2=~EnGD8P$v3R|&1RCl&7)b+`=QGapi zPbLg_pxm`+HZurtFZ;wZ=`Vk*do~$wB zxoW&=j0OTbQ=Q%S8XJ%~qoa3Ea|au5o}_(P;=!y-AjFrERh%8la!z6Fn@lR?^E~H12D?8#ht=1F;7@o4$Q8GDj;sSC%Jfn01xgL&%F2 zwG1|5ikb^qHv&9hT8w83+yv&BQXOQyMVJSBL(Ky~p)gU3#%|blG?IR9rP^zUbs7rOA0X52Ao=GRt@C&zlyjNLv-} z9?*x{y(`509qhCV*B47f2hLrGl^<@SuRGR!KwHei?!CM10Tq*YDIoBNyRuO*>3FU? zHjipIE#B~y3FSfOsMfj~F9PNr*H?0oHyYB^G(YyNh{SxcE(Y-`x5jFMKb~HO*m+R% zrq|ic4fzJ#USpTm;X7K+E%xsT_3VHKe?*uc4-FsILUH;kL>_okY(w`VU*8+l>o>Jm ziU#?2^`>arnsl#)*R&nf_%>A+qwl%o{l(u)M?DK1^mf260_oteV3#E_>6Y4!_hhVD zM8AI6MM2V*^_M^sQ0dmHu11fy^kOqXqzpr?K$`}BKWG`=Es(9&S@K@)ZjA{lj3ea7_MBP zk(|hBFRjHVMN!sNUkrB;(cTP)T97M$0Dtc&UXSec<+q?y>5=)}S~{Z@ua;1xt@=T5 zI7{`Z=z_X*no8s>mY;>BvEXK%b`a6(DTS6t&b!vf_z#HM{Uoy_5fiB(zpkF{})ruka$iX*~pq1ZxD?q68dIo zIZSVls9kFGsTwvr4{T_LidcWtt$u{kJlW7moRaH6+A5hW&;;2O#$oKyEN8kx`LmG)Wfq4ykh+q{I3|RfVpkR&QH_x;t41Uw z`P+tft^E2B$domKT@|nNW`EHwyj>&}K;eDpe z1bNOh=fvIfk`&B61+S8ND<(KC%>y&?>opCnY*r5M+!UrWKxv0_QvTlJc>X#AaI^xo zaRXL}t5Ej_Z$y*|w*$6D+A?Lw-CO-$itm^{2Ct82-<0IW)0KMNvJHgBrdsIR0v~=H z?n6^}l{D``Me90`^o|q!olsF?UX3YSq^6Vu>Ijm>>PaZI8G@<^NGw{Cx&%|PwYrfw zR!gX_%AR=L3BFsf8LxI|K^J}deh0ZdV?$3r--FEX`#INxsOG6_=!v)DI>0q|BxT)z z-G6kzA01M?rba+G_mwNMQD1mbVbNTWmBi*{s_v_Ft9m2Avg!^78(QFu&n6mbRJ2bA zv!b;%yo{g*9l2)>tsZJOOp}U~8VUH`}$ z8p_}t*XIOehezolNa-a2x0BS})Y9}&*TPgua{Ewn-=wVrmJUeU39EKx+%w%=ixQWK zDLpwaNJs65#6o7Ln7~~X+p_o2BR1g~VCfxLzxA{HlWAI6^H;`juI=&r1jQrUv_q0Z z1Ja-tjdktrrP>GOC*#p?*xfQU5MqjMsBe!9lh(u8)w$e@Z|>aUHI5o;MGw*|Myiz3 z-f0;pHg~Q#%*Kx8MxH%AluVXjG2C$)WL-K63@Q`#y9_k_+}eR(x4~dp7oV-ek0H>I zgy8p#i4GN{>#v=pFYUQT(g&b$OeTy-X_#FDgNF8XyfGY6R!>inYn8IR2RDa&O!(6< znXs{W!bkP|s_YI*Yx%4stI`=ZO45IK6rBs`g7sP40ic}GZ58s?Mc$&i`kq_tfci>N zIHrC0H+Qpam1bNa=(`SRKjixBTtm&e`j9porEci!zdlg1RI0Jw#b(_Tb@RQK1Zxr_ z%7SUeH6=TrXt3J@js`4iDD0=IoHhK~I7^W8^Rcp~Yaf>2wVe|Hh1bUpX9ATD#moByY57-f2Ef1TP^lBi&p5_s7WGG9|0T}dlfxOx zXvScJO1Cnq`c`~{Dp;{;l<-KkCDE+pmexJkd}zCgE{eF=)K``-qC~IT6GcRog_)!X z?fK^F8UDz$(zFUrwuR$qro5>qqn>+Z%<5>;_*3pZ8QM|yv9CAtrAx;($>4l^_$_-L z*&?(77!-=zvnCVW&kUcZMb6;2!83si518Y%R*A3JZ8Is|kUCMu`!vxDgaWjs7^0j( ziTaS4HhQ)ldR=r)_7vYFUr%THE}cPF{0H45FJ5MQW^+W>P+eEX2kLp3zzFe*-pFVA zdDZRybv?H|>`9f$AKVjFWJ=wegO7hOOIYCtd?Vj{EYLT*^gl35|HQ`R=ti+ADm{jyQE7K@kdjuqJhWVSks>b^ zxha88-h3s;%3_5b1TqFCPTxVjvuB5U>v=HyZ$?JSk+&I%)M7KE*wOg<)1-Iy)8-K! z^XpIt|0ibmk9RtMmlUd7#Ap3Q!q9N4atQy)TmrhrFhfx1DAN`^vq@Q_SRl|V z#lU<~n67$mT)NvHh`%als+G-)x1`Y%4Bp*6Un5Ri9h=_Db zA-AdP!f>f0m@~>7X#uBM?diI@)Egjuz@jXKvm zJo+==juc9_<;CqeRaU9_Mz@;3e=E4=6TK+c`|uu#pIqhSyNm`G(X)&)B`8q0RBv#> z`gGlw(Q=1Xmf55VHj%C#^1lpc>LY8kfA@|rlC1EA<1#`iuyNO z(=;irt{_&K=i4)^x%;U(Xv<)+o=dczC5H3W~+e|f~{*ucxj@{Yi-cw^MqYr3fN zF5D+~!wd$#al?UfMnz(@K#wn`_5na@rRr8XqN@&M&FGEC@`+OEv}sI1hw>Up0qAWf zL#e4~&oM;TVfjRE+10B_gFlLEP9?Q-dARr3xi6nQqnw>k-S;~b z;!0s2VS4}W8b&pGuK=7im+t(`nz@FnT#VD|!)eQNp-W6)@>aA+j~K*H{$G`y2|QHY z|Hmy+CR@#jWY4~)lr1qBJB_RfHJFfP<}pK5(#ZZGSqcpyS&}01LnTWk5fzmXMGHkJ zTP6L^B+uj;lmB_W<~4=${+v0>z31M!-_O@o-O9GyW)j_mjx}!0@br_LE-7SIuPP84 z;5=O(U*g_um0tyG|61N@d9lEuOeiRd+#NY^{nd5;-CVlw&Ap7J?qwM^?E29wvS}2d zbzar4Fz&RSR(-|s!Z6+za&Z zY#D<5q_JUktIzvL0)yq_kLWG6DO{ri=?c!y!f(Dk%G{8)k`Gym%j#!OgXVDD3;$&v@qy#ISJfp=Vm>pls@9-mapVQChAHHd-x+OGx)(*Yr zC1qDUTZ6mM(b_hi!TuFF2k#8uI2;kD70AQ&di$L*4P*Y-@p`jdm%_c3f)XhYD^6M8&#Y$ZpzQMcR|6nsH>b=*R_Von!$BTRj7yGCXokoAQ z&ANvx0-Epw`QIEPgI(^cS2f(Y85yV@ygI{ewyv5Frng)e}KCZF7JbR(&W618_dcEh(#+^zZFY;o<815<5sOHQdeax9_!PyM&;{P zkBa5xymca0#)c#tke@3KNEM8a_mT&1gm;p&&JlMGH(cL(b)BckgMQ^9&vRwj!~3@l zY?L5}=Jzr080OGKb|y`ee(+`flQg|!lo6>=H)X4`$Gz~hLmu2a%kYW_Uu8x09Pa0J zKZ`E$BKJ=2GPj_3l*TEcZ*uYRr<*J^#5pILTT;k_cgto1ZL-%slyc16J~OH-(RgDA z%;EjEnoUkZ&acS{Q8`{i6T5^nywgqQI5bDIymoa7CSZG|WWVk>GM9)zy*bNih|QIm z%0+(Nnc*a_xo;$=!HQYaapLms>J1ToyjtFByY`C2H1wT#178#4+|{H0BBqtCdd$L% z_3Hc60j@{t9~MjM@LBalR&6@>B;9?r<7J~F+WXyYu*y3?px*=8MAK@EA+jRX8{CG?GI-< z54?Dc9CAh>QTAvyOEm0^+x;r2BWX|{3$Y7)L5l*qVE*y0`7J>l2wCmW zL1?|a`pJ-l{fb_N;R(Z9UMiSj6pQjOvQ^%DvhIJF!+Th7jO2~1f1N+(-TyCFYQZYw z4)>7caf^Ki_KJ^Zx2JUb z&$3zJy!*+rCV4%jqwyuNY3j1ZEiltS0xTzd+=itTb;IPYpaf?8Y+RSdVdpacB(bVQ zC(JupLfFp8y43%PMj2}T|VS@%LVp>hv4Y!RPMF?pp8U_$xCJ)S zQx!69>bphNTIb9yn*_yfj{N%bY)t{L1cs8<8|!f$;UQ*}IN=2<6lA;x^(`8t?;+ST zh)z4qeYYgZkIy{$4x28O-pugO&gauRh3;lti9)9Pvw+^)0!h~%m&8Q!AKX%urEMnl z?yEz?g#ODn$UM`+Q#$Q!6|zsq_`dLO5YK-6bJM6ya>}H+vnW^h?o$z;V&wvuM$dR& zeEq;uUUh$XR`TWeC$$c&Jjau2it3#%J-y}Qm>nW*s?En?R&6w@sDXMEr#8~$=b(gk zwDC3)NtAP;M2BW_lL^5ShpK$D%@|BnD{=!Tq)o(5@z3i7Z){} zGr}Exom_qDO{kAVkZ*MbLNHE666Kina#D{&>Jy%~w7yX$oj;cYCd^p9zy z8*+wgSEcj$4{WxKmCF(5o7U4jqwEvO&dm1H#7z}%VXAbW&W24v-tS6N3}qrm1OnE)fUkoE8yMMn9S$?IswS88tQWm4#Oid#ckgr6 zRtHm!mfNl-`d>O*1~d7%;~n+{Rph6BBy^95zqI{K((E!iFQ+h*C3EsbxNo_aRm5gj zKYug($r*Q#W9`p%Bf{bi6;IY0v`pB^^qu)gbg9QHQ7 zWBj(a1YSu)~2RK8Pi#C>{DMlrqFb9e_RehEHyI{n?e3vL_}L>kYJC z_ly$$)zFi*SFyNrnOt(B*7E$??s67EO%DgoZL2XNk8iVx~X_)o++4oaK1M|ou73vA0K^503j@uuVmLcHH4ya-kOIDfM%5%(E z+Xpt~#7y2!KB&)PoyCA+$~DXqxPxxALy!g-O?<9+9KTk4Pgq4AIdUkl`1<1#j^cJg zgU3`0hkHj_jxV>`Y~%LAZl^3o0}`Sm@iw7kwff{M%VwtN)|~!p{AsfA6vB5UolF~d zHWS%*uBDt<9y!9v2Xe|au&1j&iR1HXCdyCjxSgG*L{wmTD4(NQ=mFjpa~xooc6kju z`~+d{j7$h-;HAB04H!Zscu^hZffL#9!p$)9>sRI|Yovm)g@F>ZnosF2EgkU3ln0bR zTA}|+E(tt)!SG)-bEJi_0m{l+(cAz^pi}`9=~n?y&;2eG;d9{M6nj>BHGn(KA2n|O zt}$=FPq!j`p&kQ8>cirSzkU0c08%8{^Qyqi-w2LoO8)^E7;;I1;HQ6B$u0nNaX2CY zSmfi)F`m94zL8>#zu;8|{aBui@RzRKBlP1&mfFxEC@%cjl?NBs`cr^nm){>;$g?rhKr$AO&6qV_Wbn^}5tfFBry^e1`%du2~o zs$~dN;S_#%iwwA_QvmMjh%Qo?0?rR~6liyN5Xmej8(*V9ym*T`xAhHih-v$7U}8=dfXi2i*aAB!xM(Xekg*ix@r|ymDw*{*s0?dlVys2e)z62u1 z+k3esbJE=-P5S$&KdFp+2H7_2e=}OKDrf( z9-207?6$@f4m4B+9E*e((Y89!q?zH|mz_vM>kp*HGXldO0Hg#!EtFhRuOm$u8e~a9 z5(roy7m$Kh+zjW6@zw{&20u?1f2uP&boD}$#Zy)4o&T;vyBoqFiF2t;*g=|1=)PxB z8eM3Mp=l_obbc?I^xyLz?4Y1YDWPa+nm;O<$Cn;@ane616`J9OO2r=rZr{I_Kizyc zP#^^WCdIEp*()rRT+*YZK>V@^Zs=ht32x>Kwe zab)@ZEffz;VM4{XA6e421^h~`ji5r%)B{wZu#hD}f3$y@L0JV9f3g{-RK!A?vBUA}${YF(vO4)@`6f1 z-A|}e#LN{)(eXloDnX4Vs7eH|<@{r#LodP@Nz--$Dg_Par%DCpu2>2jUnqy~|J?eZ zBG4FVsz_A+ibdwv>mLp>P!(t}E>$JGaK$R~;fb{O3($y1ssQQo|5M;^JqC?7qe|hg zu0ZOqeFcp?qVn&Qu7FQJ4hcFi&|nR!*j)MF#b}QO^lN%5)4p*D^H+B){n8%VPUzi! zDihoGcP71a6!ab`l^hK&*dYrVYzJ0)#}xVrp!e;lI!+x+bfCN0KXwUAPU9@#l7@0& QuEJmfE|#`Dqx|px0L@K;Y5)KL literal 0 HcmV?d00001 diff --git a/gradle/wrapper/gradle-wrapper.properties b/gradle/wrapper/gradle-wrapper.properties new file mode 100644 index 0000000..f959987 --- /dev/null +++ b/gradle/wrapper/gradle-wrapper.properties @@ -0,0 +1,5 @@ +distributionBase=GRADLE_USER_HOME +distributionPath=permwrapper/dists +distributionUrl=https\://services.gradle.org/distributions/gradle-7.3.3-bin.zip +zipStoreBase=GRADLE_USER_HOME +zipStorePath=permwrapper/dists diff --git a/gradlew b/gradlew new file mode 100755 index 0000000..c53aefa --- /dev/null +++ b/gradlew @@ -0,0 +1,234 @@ +#!/bin/sh + +# +# Copyright © 2015-2021 the original authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# https://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# + +############################################################################## +# +# Gradle start up script for POSIX generated by Gradle. +# +# Important for running: +# +# (1) You need a POSIX-compliant shell to run this script. If your /bin/sh is +# noncompliant, but you have some other compliant shell such as ksh or +# bash, then to run this script, type that shell name before the whole +# command line, like: +# +# ksh Gradle +# +# Busybox and similar reduced shells will NOT work, because this script +# requires all of these POSIX shell features: +# * functions; +# * expansions «$var», «${var}», «${var:-default}», «${var+SET}», +# «${var#prefix}», «${var%suffix}», and «$( cmd )»; +# * compound commands having a testable exit status, especially «case»; +# * various built-in commands including «command», «set», and «ulimit». +# +# Important for patching: +# +# (2) This script targets any POSIX shell, so it avoids extensions provided +# by Bash, Ksh, etc; in particular arrays are avoided. +# +# The "traditional" practice of packing multiple parameters into a +# space-separated string is a well documented source of bugs and security +# problems, so this is (mostly) avoided, by progressively accumulating +# options in "$@", and eventually passing that to Java. +# +# Where the inherited environment variables (DEFAULT_JVM_OPTS, JAVA_OPTS, +# and GRADLE_OPTS) rely on word-splitting, this is performed explicitly; +# see the in-line comments for details. +# +# There are tweaks for specific operating systems such as AIX, CygWin, +# Darwin, MinGW, and NonStop. +# +# (3) This script is generated from the Groovy template +# https://github.com/gradle/gradle/blob/master/subprojects/plugins/src/main/resources/org/gradle/api/internal/plugins/unixStartScript.txt +# within the Gradle project. +# +# You can find Gradle at https://github.com/gradle/gradle/. +# +############################################################################## + +# Attempt to set APP_HOME + +# Resolve links: $0 may be a link +app_path=$0 + +# Need this for daisy-chained symlinks. +while + APP_HOME=${app_path%"${app_path##*/}"} # leaves a trailing /; empty if no leading path + [ -h "$app_path" ] +do + ls=$( ls -ld "$app_path" ) + link=${ls#*' -> '} + case $link in #( + /*) app_path=$link ;; #( + *) app_path=$APP_HOME$link ;; + esac +done + +APP_HOME=$( cd "${APP_HOME:-./}" && pwd -P ) || exit + +APP_NAME="Gradle" +APP_BASE_NAME=${0##*/} + +# Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. +DEFAULT_JVM_OPTS='"-Xmx64m" "-Xms64m"' + +# Use the maximum available, or set MAX_FD != -1 to use that value. +MAX_FD=maximum + +warn () { + echo "$*" +} >&2 + +die () { + echo + echo "$*" + echo + exit 1 +} >&2 + +# OS specific support (must be 'true' or 'false'). +cygwin=false +msys=false +darwin=false +nonstop=false +case "$( uname )" in #( + CYGWIN* ) cygwin=true ;; #( + Darwin* ) darwin=true ;; #( + MSYS* | MINGW* ) msys=true ;; #( + NONSTOP* ) nonstop=true ;; +esac + +CLASSPATH=$APP_HOME/gradle/wrapper/gradle-wrapper.jar + + +# Determine the Java command to use to start the JVM. +if [ -n "$JAVA_HOME" ] ; then + if [ -x "$JAVA_HOME/jre/sh/java" ] ; then + # IBM's JDK on AIX uses strange locations for the executables + JAVACMD=$JAVA_HOME/jre/sh/java + else + JAVACMD=$JAVA_HOME/bin/java + fi + if [ ! -x "$JAVACMD" ] ; then + die "ERROR: JAVA_HOME is set to an invalid directory: $JAVA_HOME + +Please set the JAVA_HOME variable in your environment to match the +location of your Java installation." + fi +else + JAVACMD=java + which java >/dev/null 2>&1 || die "ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. + +Please set the JAVA_HOME variable in your environment to match the +location of your Java installation." +fi + +# Increase the maximum file descriptors if we can. +if ! "$cygwin" && ! "$darwin" && ! "$nonstop" ; then + case $MAX_FD in #( + max*) + MAX_FD=$( ulimit -H -n ) || + warn "Could not query maximum file descriptor limit" + esac + case $MAX_FD in #( + '' | soft) :;; #( + *) + ulimit -n "$MAX_FD" || + warn "Could not set maximum file descriptor limit to $MAX_FD" + esac +fi + +# Collect all arguments for the java command, stacking in reverse order: +# * args from the command line +# * the main class name +# * -classpath +# * -D...appname settings +# * --module-path (only if needed) +# * DEFAULT_JVM_OPTS, JAVA_OPTS, and GRADLE_OPTS environment variables. + +# For Cygwin or MSYS, switch paths to Windows format before running java +if "$cygwin" || "$msys" ; then + APP_HOME=$( cygpath --path --mixed "$APP_HOME" ) + CLASSPATH=$( cygpath --path --mixed "$CLASSPATH" ) + + JAVACMD=$( cygpath --unix "$JAVACMD" ) + + # Now convert the arguments - kludge to limit ourselves to /bin/sh + for arg do + if + case $arg in #( + -*) false ;; # don't mess with options #( + /?*) t=${arg#/} t=/${t%%/*} # looks like a POSIX filepath + [ -e "$t" ] ;; #( + *) false ;; + esac + then + arg=$( cygpath --path --ignore --mixed "$arg" ) + fi + # Roll the args list around exactly as many times as the number of + # args, so each arg winds up back in the position where it started, but + # possibly modified. + # + # NB: a `for` loop captures its iteration list before it begins, so + # changing the positional parameters here affects neither the number of + # iterations, nor the values presented in `arg`. + shift # remove old arg + set -- "$@" "$arg" # push replacement arg + done +fi + +# Collect all arguments for the java command; +# * $DEFAULT_JVM_OPTS, $JAVA_OPTS, and $GRADLE_OPTS can contain fragments of +# shell script including quotes and variable substitutions, so put them in +# double quotes to make sure that they get re-expanded; and +# * put everything else in single quotes, so that it's not re-expanded. + +set -- \ + "-Dorg.gradle.appname=$APP_BASE_NAME" \ + -classpath "$CLASSPATH" \ + org.gradle.wrapper.GradleWrapperMain \ + "$@" + +# Use "xargs" to parse quoted args. +# +# With -n1 it outputs one arg per line, with the quotes and backslashes removed. +# +# In Bash we could simply go: +# +# readarray ARGS < <( xargs -n1 <<<"$var" ) && +# set -- "${ARGS[@]}" "$@" +# +# but POSIX shell has neither arrays nor command substitution, so instead we +# post-process each arg (as a line of input to sed) to backslash-escape any +# character that might be a shell metacharacter, then use eval to reverse +# that process (while maintaining the separation between arguments), and wrap +# the whole thing up as a single "set" statement. +# +# This will of course break if any of these variables contains a newline or +# an unmatched quote. +# + +eval "set -- $( + printf '%s\n' "$DEFAULT_JVM_OPTS $JAVA_OPTS $GRADLE_OPTS" | + xargs -n1 | + sed ' s~[^-[:alnum:]+,./:=@_]~\\&~g; ' | + tr '\n' ' ' + )" '"$@"' + +exec "$JAVACMD" "$@" diff --git a/gradlew.bat b/gradlew.bat new file mode 100644 index 0000000..107acd3 --- /dev/null +++ b/gradlew.bat @@ -0,0 +1,89 @@ +@rem +@rem Copyright 2015 the original author or authors. +@rem +@rem Licensed under the Apache License, Version 2.0 (the "License"); +@rem you may not use this file except in compliance with the License. +@rem You may obtain a copy of the License at +@rem +@rem https://www.apache.org/licenses/LICENSE-2.0 +@rem +@rem Unless required by applicable law or agreed to in writing, software +@rem distributed under the License is distributed on an "AS IS" BASIS, +@rem WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +@rem See the License for the specific language governing permissions and +@rem limitations under the License. +@rem + +@if "%DEBUG%" == "" @echo off +@rem ########################################################################## +@rem +@rem Gradle startup script for Windows +@rem +@rem ########################################################################## + +@rem Set local scope for the variables with windows NT shell +if "%OS%"=="Windows_NT" setlocal + +set DIRNAME=%~dp0 +if "%DIRNAME%" == "" set DIRNAME=. +set APP_BASE_NAME=%~n0 +set APP_HOME=%DIRNAME% + +@rem Resolve any "." and ".." in APP_HOME to make it shorter. +for %%i in ("%APP_HOME%") do set APP_HOME=%%~fi + +@rem Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script. +set DEFAULT_JVM_OPTS="-Xmx64m" "-Xms64m" + +@rem Find java.exe +if defined JAVA_HOME goto findJavaFromJavaHome + +set JAVA_EXE=java.exe +%JAVA_EXE% -version >NUL 2>&1 +if "%ERRORLEVEL%" == "0" goto execute + +echo. +echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH. +echo. +echo Please set the JAVA_HOME variable in your environment to match the +echo location of your Java installation. + +goto fail + +:findJavaFromJavaHome +set JAVA_HOME=%JAVA_HOME:"=% +set JAVA_EXE=%JAVA_HOME%/bin/java.exe + +if exist "%JAVA_EXE%" goto execute + +echo. +echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME% +echo. +echo Please set the JAVA_HOME variable in your environment to match the +echo location of your Java installation. + +goto fail + +:execute +@rem Setup the command line + +set CLASSPATH=%APP_HOME%\gradle\wrapper\gradle-wrapper.jar + + +@rem Execute Gradle +"%JAVA_EXE%" %DEFAULT_JVM_OPTS% %JAVA_OPTS% %GRADLE_OPTS% "-Dorg.gradle.appname=%APP_BASE_NAME%" -classpath "%CLASSPATH%" org.gradle.wrapper.GradleWrapperMain %* + +:end +@rem End local scope for the variables with windows NT shell +if "%ERRORLEVEL%"=="0" goto mainEnd + +:fail +rem Set variable GRADLE_EXIT_CONSOLE if you need the _script_ return code instead of +rem the _cmd.exe /c_ return code! +if not "" == "%GRADLE_EXIT_CONSOLE%" exit 1 +exit /b 1 + +:mainEnd +if "%OS%"=="Windows_NT" endlocal + +:omega diff --git a/settings.gradle b/settings.gradle new file mode 100644 index 0000000..c363694 --- /dev/null +++ b/settings.gradle @@ -0,0 +1,27 @@ +import org.gradle.internal.os.OperatingSystem + +pluginManagement { + repositories { + mavenLocal() + gradlePluginPortal() + String frcYear = '2022' + File frcHome + if (OperatingSystem.current().isWindows()) { + String publicFolder = System.getenv('PUBLIC') + if (publicFolder == null) { + publicFolder = "C:\\Users\\Public" + } + def homeRoot = new File(publicFolder, "wpilib") + frcHome = new File(homeRoot, frcYear) + } else { + def userFolder = System.getProperty("user.home") + def homeRoot = new File(userFolder, "wpilib") + frcHome = new File(homeRoot, frcYear) + } + def frcHomeMaven = new File(frcHome, 'maven') + maven { + name 'frcHome' + url frcHomeMaven + } + } +} diff --git a/simgui-ds.json b/simgui-ds.json new file mode 100644 index 0000000..73cc713 --- /dev/null +++ b/simgui-ds.json @@ -0,0 +1,92 @@ +{ + "keyboardJoysticks": [ + { + "axisConfig": [ + { + "decKey": 65, + "incKey": 68 + }, + { + "decKey": 87, + "incKey": 83 + }, + { + "decKey": 69, + "decayRate": 0.0, + "incKey": 82, + "keyRate": 0.009999999776482582 + } + ], + "axisCount": 3, + "buttonCount": 4, + "buttonKeys": [ + 90, + 88, + 67, + 86 + ], + "povConfig": [ + { + "key0": 328, + "key135": 323, + "key180": 322, + "key225": 321, + "key270": 324, + "key315": 327, + "key45": 329, + "key90": 326 + } + ], + "povCount": 1 + }, + { + "axisConfig": [ + { + "decKey": 74, + "incKey": 76 + }, + { + "decKey": 73, + "incKey": 75 + } + ], + "axisCount": 2, + "buttonCount": 4, + "buttonKeys": [ + 77, + 44, + 46, + 47 + ], + "povCount": 0 + }, + { + "axisConfig": [ + { + "decKey": 263, + "incKey": 262 + }, + { + "decKey": 265, + "incKey": 264 + } + ], + "axisCount": 2, + "buttonCount": 6, + "buttonKeys": [ + 260, + 268, + 266, + 261, + 269, + 267 + ], + "povCount": 0 + }, + { + "axisCount": 0, + "buttonCount": 0, + "povCount": 0 + } + ] +} diff --git a/simgui-window.json b/simgui-window.json new file mode 100644 index 0000000..86f3cc3 --- /dev/null +++ b/simgui-window.json @@ -0,0 +1,60 @@ +{ + "MainWindow": { + "GLOBAL": { + "height": "720", + "maximized": "0", + "style": "1", + "userScale": "4", + "width": "1280", + "xpos": "497", + "ypos": "249" + } + }, + "Window": { + "###/FMSInfo": { + "Collapsed": "0", + "Pos": "60,60", + "Size": "169,167" + }, + "###FMS": { + "Collapsed": "0", + "Pos": "318,244", + "Size": "235,244" + }, + "###Joysticks": { + "Collapsed": "0", + "Pos": "5,569", + "Size": "1156,114" + }, + "###NetworkTables": { + "Collapsed": "0", + "Pos": "115,41", + "Size": "750,185" + }, + "###Other Devices": { + "Collapsed": "0", + "Pos": "905,32", + "Size": "250,512" + }, + "###System Joysticks": { + "Collapsed": "0", + "Pos": "571,243", + "Size": "273,290" + }, + "###Timing": { + "Collapsed": "0", + "Pos": "116,244", + "Size": "188,157" + }, + "Debug##Default": { + "Collapsed": "0", + "Pos": "60,60", + "Size": "400,400" + }, + "Robot State": { + "Collapsed": "0", + "Pos": "5,20", + "Size": "126,129" + } + } +} diff --git a/simgui.json b/simgui.json new file mode 100644 index 0000000..e17e95c --- /dev/null +++ b/simgui.json @@ -0,0 +1,47 @@ +{ + "NTProvider": { + "types": { + "/FMSInfo": "FMSInfo", + "/Shuffleboard/MAIN/Auto Mode": "String Chooser", + "/SmartDashboard/Field": "Field2d" + } + }, + "NetworkTables": { + "CameraPublisher": { + "USB Camera 0": { + "open": true + } + }, + "LiveWindow": { + "open": true + }, + "Shuffleboard": { + ".metadata": { + "Collector": { + "open": true + }, + "Drivetrain": { + "open": true + } + }, + "open": true + }, + "Usage": { + "Client": { + "Dashboard": { + "open": true + }, + "open": true + } + }, + "VisionBox": { + "config": { + "open": true + }, + "open": true, + "output": { + "open": true + } + } + } +} diff --git a/src/main/deploy/example.txt b/src/main/deploy/example.txt new file mode 100644 index 0000000..bb82515 --- /dev/null +++ b/src/main/deploy/example.txt @@ -0,0 +1,3 @@ +Files placed in this directory will be deployed to the RoboRIO into the +'deploy' directory in the home folder. Use the 'Filesystem.getDeployDirectory' wpilib function +to get a proper path relative to the deploy directory. \ No newline at end of file diff --git a/src/main/deploy/pathplanner/Blue0(1).path b/src/main/deploy/pathplanner/Blue0(1).path new file mode 100644 index 0000000..114080e --- /dev/null +++ b/src/main/deploy/pathplanner/Blue0(1).path @@ -0,0 +1 @@ +{"waypoints":[{"anchorPoint":{"x":6.087618268986538,"y":4.109629000508001},"prevControl":null,"nextControl":{"x":5.087618268986538,"y":4.109629000508001},"holonomicAngle":-178.07368468360667,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":4.368828581407163,"y":4.113260414020828},"prevControl":{"x":5.2790036830073666,"y":4.093495999491999},"nextControl":null,"holonomicAngle":180.0,"isReversal":false,"velOverride":null,"isLocked":false}]} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/Blue0(2).path b/src/main/deploy/pathplanner/Blue0(2).path new file mode 100644 index 0000000..3d5b816 --- /dev/null +++ b/src/main/deploy/pathplanner/Blue0(2).path @@ -0,0 +1 @@ +{"waypoints":[{"anchorPoint":{"x":4.37,"y":4.11},"prevControl":null,"nextControl":{"x":3.1287945064741036,"y":4.111516419333393},"holonomicAngle":180.0,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":2.3701819278590945,"y":4.168148336292042},"prevControl":{"x":3.199215773426786,"y":4.116653702052774},"nextControl":{"x":1.7244526502670792,"y":4.208257184857106},"holonomicAngle":0.7588401242685351,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":0.7521193167342504,"y":4.5421839281146426},"prevControl":{"x":1.4305387985732136,"y":4.371388430273647},"nextControl":null,"holonomicAngle":0.0,"isReversal":false,"velOverride":null,"isLocked":false}]} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/Blue1(1).path b/src/main/deploy/pathplanner/Blue1(1).path new file mode 100644 index 0000000..d5a625b --- /dev/null +++ b/src/main/deploy/pathplanner/Blue1(1).path @@ -0,0 +1 @@ +{"waypoints":[{"anchorPoint":{"x":6.219218062337707,"y":5.134470725883456},"prevControl":null,"nextControl":{"x":5.75622979458902,"y":5.585884286938426},"holonomicAngle":135.0,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":5.062154236786506,"y":6.190291466698926},"prevControl":{"x":5.727465936478446,"y":5.611759553923325},"nextControl":null,"holonomicAngle":147.1,"isReversal":false,"velOverride":null,"isLocked":false}]} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/Blue1(2).path b/src/main/deploy/pathplanner/Blue1(2).path new file mode 100644 index 0000000..fce4c1f --- /dev/null +++ b/src/main/deploy/pathplanner/Blue1(2).path @@ -0,0 +1 @@ +{"waypoints":[{"anchorPoint":{"x":5.06,"y":6.19},"prevControl":null,"nextControl":{"x":4.630556951331294,"y":7.015440539033253},"holonomicAngle":147.1,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":4.213019458644182,"y":7.246059886138997},"prevControl":{"x":4.00753669920478,"y":7.237318201620873},"nextControl":{"x":4.663123198525575,"y":7.265208280414046},"holonomicAngle":0.0,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":5.619797476007996,"y":7.246712142880808},"prevControl":{"x":5.162146193854174,"y":7.258126635815974},"nextControl":null,"holonomicAngle":0.0,"isReversal":false,"velOverride":null,"isLocked":false}]} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/Blue2(1).path b/src/main/deploy/pathplanner/Blue2(1).path new file mode 100644 index 0000000..46b6760 --- /dev/null +++ b/src/main/deploy/pathplanner/Blue2(1).path @@ -0,0 +1 @@ +{"waypoints":[{"anchorPoint":{"x":6.823783178816358,"y":2.648074358648717},"prevControl":null,"nextControl":{"x":5.904466458328888,"y":2.179659093414595},"holonomicAngle":-153.0,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":5.186968186436373,"y":1.9522121856743715},"prevControl":{"x":5.973643102869047,"y":2.3530430760757217},"nextControl":null,"holonomicAngle":-153.0,"isReversal":false,"velOverride":null,"isLocked":false}]} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/Blue3(1).path b/src/main/deploy/pathplanner/Blue3(1).path new file mode 100644 index 0000000..45a3742 --- /dev/null +++ b/src/main/deploy/pathplanner/Blue3(1).path @@ -0,0 +1 @@ +{"waypoints":[{"anchorPoint":{"x":7.64757694377755,"y":1.8956170898115021},"prevControl":null,"nextControl":{"x":7.64757694377755,"y":0.9707673938606185},"holonomicAngle":-90.0,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":7.644623634676634,"y":0.96},"prevControl":{"x":7.644623634676634,"y":1.8726793005347007},"nextControl":null,"holonomicAngle":-101.4,"isReversal":false,"velOverride":null,"isLocked":false}],"maxVelocity":3.0,"maxAcceleration":3.0,"isReversed":null} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/Blue3(2).path b/src/main/deploy/pathplanner/Blue3(2).path new file mode 100644 index 0000000..3a9103c --- /dev/null +++ b/src/main/deploy/pathplanner/Blue3(2).path @@ -0,0 +1 @@ +{"waypoints":[{"anchorPoint":{"x":7.64,"y":0.96},"prevControl":null,"nextControl":{"x":7.231648909695007,"y":1.416160101564492},"holonomicAngle":-101.4,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":6.9134563576684265,"y":2.2562744598248425},"prevControl":{"x":7.337456314650316,"y":2.351823745905268},"nextControl":{"x":5.886562212491737,"y":2.0248616947146028},"holonomicAngle":178.09084756700352,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":5.177860619341625,"y":1.923618609978872},"prevControl":{"x":5.65124556878986,"y":2.0007043682517893},"nextControl":{"x":4.608021633580698,"y":1.830826326738666},"holonomicAngle":-168.6900675259797,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":3.3636880045442963,"y":1.852828447499948},"prevControl":{"x":3.9944666264829287,"y":1.454994895039021},"nextControl":{"x":2.2950198013072085,"y":2.526839983257431},"holonomicAngle":-139.96082725906072,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":1.2660948398819876,"y":1.5566029024576493},"prevControl":{"x":1.9598079106483597,"y":2.0916058246602693},"nextControl":null,"holonomicAngle":-137.49,"isReversal":false,"velOverride":null,"isLocked":false}],"maxVelocity":null,"maxAcceleration":3.0,"isReversed":null} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/Blue3(23).path b/src/main/deploy/pathplanner/Blue3(23).path new file mode 100644 index 0000000..2885afc --- /dev/null +++ b/src/main/deploy/pathplanner/Blue3(23).path @@ -0,0 +1 @@ +{"waypoints":[{"anchorPoint":{"x":7.64,"y":0.86},"prevControl":null,"nextControl":{"x":7.231648909695007,"y":1.316160101564492},"holonomicAngle":-90.0,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":6.9134563576684265,"y":2.2562744598248425},"prevControl":{"x":7.337456314650316,"y":2.351823745905268},"nextControl":{"x":5.886562212491737,"y":2.0248616947146028},"holonomicAngle":178.09084756700352,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":5.177860619341625,"y":1.923618609978872},"prevControl":{"x":5.65124556878986,"y":2.0007043682517893},"nextControl":{"x":4.608021633580698,"y":1.830826326738666},"holonomicAngle":-168.6900675259797,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":3.3636880045442963,"y":1.852828447499948},"prevControl":{"x":4.108844739428609,"y":1.8229178170312865},"nextControl":{"x":2.5478988628415786,"y":1.8855742664874187},"holonomicAngle":-139.96082725906072,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":1.4174031863002212,"y":1.359549995022662},"prevControl":{"x":1.9798321525934617,"y":1.793240135388542},"nextControl":{"x":1.9798321525934617,"y":1.793240135388542},"holonomicAngle":-137.4919052551881,"isReversal":true,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":4.214789869791505,"y":2.2100321917987413},"prevControl":{"x":3.3552086669334473,"y":2.0409579270197766},"nextControl":null,"holonomicAngle":-156.484042453676,"isReversal":false,"velOverride":null,"isLocked":false}],"maxVelocity":null,"maxAcceleration":3.0,"isReversed":null} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/Blue3(3).path b/src/main/deploy/pathplanner/Blue3(3).path new file mode 100644 index 0000000..6b10179 --- /dev/null +++ b/src/main/deploy/pathplanner/Blue3(3).path @@ -0,0 +1 @@ +{"waypoints":[{"anchorPoint":{"x":1.27,"y":1.56},"prevControl":null,"nextControl":{"x":1.8324289662932405,"y":1.9936901403658802},"holonomicAngle":-137.4919052551881,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":3.55,"y":2.352988354600895},"prevControl":{"x":2.690418797141942,"y":2.1839140898219305},"nextControl":null,"holonomicAngle":-156.484042453676,"isReversal":false,"velOverride":null,"isLocked":false}],"maxVelocity":null,"maxAcceleration":3.0,"isReversed":null} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/Blue4(1).path b/src/main/deploy/pathplanner/Blue4(1).path new file mode 100644 index 0000000..ce93795 --- /dev/null +++ b/src/main/deploy/pathplanner/Blue4(1).path @@ -0,0 +1 @@ +{"waypoints":[{"anchorPoint":{"x":7.65,"y":1.9},"prevControl":null,"nextControl":{"x":7.65364093005766,"y":1.3569592975484872},"holonomicAngle":-90.0,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":7.64,"y":0.86},"prevControl":{"x":7.65364093005766,"y":1.3569592975484872},"nextControl":null,"holonomicAngle":-90.0,"isReversal":false,"velOverride":null,"isLocked":false}],"maxVelocity":3.0,"maxAcceleration":3.0,"isReversed":null} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/Blue4(2).path b/src/main/deploy/pathplanner/Blue4(2).path new file mode 100644 index 0000000..81a6b13 --- /dev/null +++ b/src/main/deploy/pathplanner/Blue4(2).path @@ -0,0 +1 @@ +{"waypoints":[{"anchorPoint":{"x":7.64,"y":0.86},"prevControl":null,"nextControl":{"x":7.250959366783599,"y":1.7960581867109686},"holonomicAngle":-90.0,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":6.91,"y":2.26},"prevControl":{"x":7.251070219727081,"y":2.3068285265465254},"nextControl":{"x":5.960911381282222,"y":2.1296912864096003},"holonomicAngle":178.09,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":5.18,"y":1.92},"prevControl":{"x":6.0053957945753735,"y":2.1185701830863115},"nextControl":null,"holonomicAngle":-141.81209331635426,"isReversal":false,"velOverride":null,"isLocked":false}],"maxVelocity":null,"maxAcceleration":3.0,"isReversed":null} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/Blue4(3).path b/src/main/deploy/pathplanner/Blue4(3).path new file mode 100644 index 0000000..e32f89f --- /dev/null +++ b/src/main/deploy/pathplanner/Blue4(3).path @@ -0,0 +1 @@ +{"waypoints":[{"anchorPoint":{"x":5.18,"y":1.92},"prevControl":null,"nextControl":{"x":4.207752444593786,"y":1.6860455364677942},"holonomicAngle":-141.81,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":3.36,"y":1.85},"prevControl":{"x":4.1743219194578955,"y":1.8172934531196434},"nextControl":{"x":2.4064110392953277,"y":1.8883000890712125},"holonomicAngle":-139.93,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":1.42,"y":1.36},"prevControl":{"x":2.159497424068187,"y":1.930312567991141},"nextControl":null,"holonomicAngle":-137.49,"isReversal":false,"velOverride":null,"isLocked":false}],"maxVelocity":null,"maxAcceleration":3.0,"isReversed":null} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/Blue4(4).path b/src/main/deploy/pathplanner/Blue4(4).path new file mode 100644 index 0000000..31a0f63 --- /dev/null +++ b/src/main/deploy/pathplanner/Blue4(4).path @@ -0,0 +1 @@ +{"waypoints":[{"anchorPoint":{"x":1.42,"y":1.36},"prevControl":null,"nextControl":{"x":2.499860981193719,"y":2.192806537540064},"holonomicAngle":-137.49,"isReversal":false,"velOverride":null,"isLocked":false},{"anchorPoint":{"x":3.55,"y":2.35},"prevControl":{"x":2.568808274782572,"y":2.1569642562506943},"nextControl":null,"holonomicAngle":-156.48,"isReversal":false,"velOverride":null,"isLocked":false}],"maxVelocity":null,"maxAcceleration":3.0,"isReversed":null} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/generatedJSON/Blue0(1).wpilib.json b/src/main/deploy/pathplanner/generatedJSON/Blue0(1).wpilib.json new file mode 100644 index 0000000..c8d56d9 --- /dev/null +++ b/src/main/deploy/pathplanner/generatedJSON/Blue0(1).wpilib.json @@ -0,0 +1 @@ +[{"acceleration":0.0,"curvature":0.01092484114707641,"pose":{"rotation":{"radians":-3.141528092200964},"translation":{"x":6.087618268986538,"y":4.109629000508001}},"time":0.0,"velocity":0,"position":0.0,"holonomicRotation":-178.07368468360667,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":91.53451171851678},{"acceleration":2.4999999999999996,"curvature":0.01092484114707641,"pose":{"rotation":{"radians":-3.141528092200964},"translation":{"x":6.075675308737872,"y":4.109628229453899}},"time":0.06911717665980281,"velocity":0.172792941649507,"position":0.011942960273555975,"holonomicRotation":-178.08138994487226,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":91.53451171851678},{"acceleration":8.584948914774735,"curvature":0.011096512197602281,"pose":{"rotation":{"radians":-3.14139823719318},"translation":{"x":6.063845840997714,"y":4.109625929611378}},"time":0.09751395435993307,"velocity":0.41657782754933964,"position":0.023772428237277772,"holonomicRotation":-178.0890952061378,"angularVelocity":0.004572878273556952,"angularAcceleration":0.16103511186538522,"curveRadius":90.1184067743447},{"acceleration":5.781830557290776,"curvature":0.01127007286535344,"pose":{"rotation":{"radians":-3.1412675961501066},"translation":{"x":6.0521289852748295,"y":4.109622120960122}},"time":0.11914576715801092,"velocity":0.5416493037948599,"position":0.03548928457917738,"holonomicRotation":-178.0968004674034,"angularVelocity":0.0060393016661489645,"angularAcceleration":0.06779012957815143,"curveRadius":88.73057095080627},{"acceleration":5.486999774858369,"curvature":0.011445484227743923,"pose":{"rotation":{"radians":-3.1411361759289727},"translation":{"x":6.040523861077978,"y":4.109616823479807}},"time":0.13725073403828406,"velocity":0.6409912529907368,"position":0.04709440998511945,"holonomicRotation":-178.10450572866895,"angularVelocity":0.007258793788636337,"angularAcceleration":0.0673567717937176,"curveRadius":87.37070272448534},{"acceleration":5.358241272622224,"curvature":0.011622702932557067,"pose":{"rotation":{"radians":-3.141003984013561},"translation":{"x":6.029029587915926,"y":4.109610057150114}},"time":0.15308649207390929,"velocity":0.7258430652804829,"position":0.0585886851387377,"holonomicRotation":-178.11221098993454,"angularVelocity":0.00834768472178076,"angularAcceleration":0.06876152885733522,"curveRadius":86.03850634423759},{"acceleration":5.2853908690403575,"curvature":0.011801680934758271,"pose":{"rotation":{"radians":-3.140871028538229},"translation":{"x":6.0176452852974345,"y":4.109601841950724}},"time":0.1672997199296835,"velocity":0.8009655300089821,"position":0.06997299072137633,"holonomicRotation":-178.11991625120012,"angularVelocity":0.009354347702093022,"angularAcceleration":0.07082578218875864,"curveRadius":84.733692219623},{"acceleration":5.2383990704661185,"curvature":0.011982364399012074,"pose":{"rotation":{"radians":-3.1407373183134517},"translation":{"x":6.006370072731268,"y":4.109592197861316}},"time":0.18027557506440894,"velocity":0.8689382374852308,"position":0.08124820741200833,"holonomicRotation":-178.12762151246568,"angularVelocity":0.010304540501482697,"angularAcceleration":0.07322775952135974,"curveRadius":83.45598303473798},{"acceleration":5.205537245948035,"curvature":0.012164695011723438,"pose":{"rotation":{"radians":-3.1406028628525595},"translation":{"x":5.9952030697261876,"y":4.109581144861569}},"time":0.19226566608437118,"velocity":0.9313531028719513,"position":0.09241521588716728,"holonomicRotation":-178.13532677373126,"angularVelocity":0.011213881585080292,"angularAcceleration":0.07584104925339084,"curveRadius":82.20510247369734},{"acceleration":5.181253648487343,"curvature":0.012348609727331145,"pose":{"rotation":{"radians":-3.140467672398822},"translation":{"x":5.984143395790958,"y":4.109568702931165}},"time":0.20344522291847175,"velocity":0.9892772225071065,"position":0.10347489682086664,"holonomicRotation":-178.14303203499682,"angularVelocity":0.012092648728711455,"angularAcceleration":0.07860482814047634,"curveRadius":80.98077614249179},{"acceleration":5.162573252548821,"curvature":0.012534037081839445,"pose":{"rotation":{"radians":-3.140331757952858},"translation":{"x":5.973190170434341,"y":4.1095548920497835}},"time":0.21394217058310364,"velocity":1.0434684837539399,"position":0.11442813088452453,"holonomicRotation":-178.1507372962624,"angularVelocity":0.012947996913617515,"angularAcceleration":0.08148541959374014,"curveRadius":79.78275422919397},{"acceleration":5.1477561005841075,"curvature":0.012720900134806791,"pose":{"rotation":{"radians":-3.140195131301497},"translation":{"x":5.962342513165101,"y":4.1095397321971046}},"time":0.22385334372922128,"velocity":1.0944887857808123,"position":0.12527579874688222,"holonomicRotation":-178.158442557528,"angularVelocity":0.01378511396649921,"angularAcceleration":0.08446195425509312,"curveRadius":78.61078928399183},{"acceleration":5.1357158532217175,"curvature":0.012909117920994705,"pose":{"rotation":{"radians":-3.1400578050468146},"translation":{"x":5.951599543491999,"y":4.109523243352807}},"time":0.23325417987588246,"velocity":1.14276880901276,"position":0.13601878107392631,"holonomicRotation":-178.16614781879355,"angularVelocity":0.01460787663352776,"angularAcceleration":0.08752015822770871,"curveRadius":77.464626639877},{"acceleration":5.125738889215808,"curvature":0.013098599006372207,"pose":{"rotation":{"radians":-3.1399197926367255},"translation":{"x":5.9409603809238,"y":4.109505445496571}},"time":0.2422048377128734,"velocity":1.1886475439718887,"position":0.14665795852879834,"holonomicRotation":-178.17385308005913,"angularVelocity":0.015419247680184732,"angularAcceleration":0.09064932002022993,"curveRadius":76.34404255856064},{"acceleration":5.1173369318938,"curvature":0.013289248069242395,"pose":{"rotation":{"radians":-3.1397811083950042},"translation":{"x":5.930424144969266,"y":4.109486358608077}},"time":0.25075423168649974,"velocity":1.232397673498437,"position":0.157194211771717,"holonomicRotation":-178.1815583413247,"angularVelocity":0.016221528935159067,"angularAcceleration":0.09384071636530716,"curveRadius":75.24880224897547},{"acceleration":5.1101645316887,"curvature":0.013480959297162405,"pose":{"rotation":{"radians":-3.139641767553097},"translation":{"x":5.91998995513716,"y":4.109466002667005}},"time":0.2589427901756605,"velocity":1.2742425546554048,"position":0.16762842145989043,"holonomicRotation":-178.18926360259027,"angularVelocity":0.017016528866647018,"angularAcceleration":0.09708667679913312,"curveRadius":74.17869737285604},{"acceleration":5.103970359122336,"curvature":0.013673621328869161,"pose":{"rotation":{"radians":-3.139501786282601},"translation":{"x":5.9096569309362454,"y":4.109444397653035}},"time":0.2668043989498086,"velocity":1.3143679728136728,"position":0.17796146824742165,"holonomicRotation":-178.19696886385586,"angularVelocity":0.017805677504153333,"angularAcceleration":0.10038004436208146,"curveRadius":73.13351569044089},{"acceleration":5.098567169407576,"curvature":0.013867112242918067,"pose":{"rotation":{"radians":-3.139361181727609},"translation":{"x":5.899424191875286,"y":4.109421563545847}},"time":0.27436780626394586,"velocity":1.35293051303439,"position":0.1881942327852254,"holonomicRotation":-178.20467412512141,"angularVelocity":0.018590107494153015,"angularAcceleration":0.10371383655795655,"curveRadius":72.11306741320277},{"acceleration":5.093812585036241,"curvature":0.014061304680861317,"pose":{"rotation":{"radians":-3.139219972038966},"translation":{"x":5.889290857463043,"y":4.10939752032512}},"time":0.28165766151193916,"velocity":1.3900636694397108,"position":0.1983275957209353,"holonomicRotation":-178.212379386387,"angularVelocity":0.019370712289785673,"angularAcceleration":0.10708097336329643,"curveRadius":71.11715610295315},{"acceleration":5.089596405814524,"curvature":0.014256057785554409,"pose":{"rotation":{"radians":-3.139078176408194},"translation":{"x":5.879256047208281,"y":4.109372287970535}},"time":0.28869529798651306,"velocity":1.4258823987461313,"position":0.208362437698804,"holonomicRotation":-178.22008464765256,"angularVelocity":0.02014818913770146,"angularAcceleration":0.11047414152815595,"curveRadius":70.14561914958671},{"acceleration":5.085831997090479,"curvature":0.014451226262310187,"pose":{"rotation":{"radians":-3.1389358151030677},"translation":{"x":5.869318880619761,"y":4.109345886461773}},"time":0.2954993328991567,"velocity":1.460486577214175,"position":0.21829963935961666,"holonomicRotation":-178.22778990891814,"angularVelocity":0.0209230709356859,"angularAcceleration":0.1138856293262852,"curveRadius":69.19827991400773},{"acceleration":5.082450304298839,"curvature":0.014646650155757971,"pose":{"rotation":{"radians":-3.1387929095023543},"translation":{"x":5.859478477206248,"y":4.109318335778512}},"time":0.3020861342998622,"velocity":1.4939636679975468,"position":0.22814008134058603,"holonomicRotation":-178.23549517018373,"angularVelocity":0.02169575064128821,"angularAcceleration":0.1173072723157481,"curveRadius":68.27499731103187},{"acceleration":5.079395604186291,"curvature":0.014842165179325486,"pose":{"rotation":{"radians":-3.138649482133244},"translation":{"x":5.849733956476505,"y":4.109289655900431}},"time":0.3084701893378088,"velocity":1.526390809094176,"position":0.23788464427525907,"holonomicRotation":-178.24320043144928,"angularVelocity":0.022466499467470147,"angularAcceleration":0.12073029157810108,"curveRadius":67.37561453587365},{"acceleration":5.076622431792776,"curvature":0.015037591159839152,"pose":{"rotation":{"radians":-3.138505556708086},"translation":{"x":5.840084437939294,"y":4.109259866807213}},"time":0.31466439823622555,"velocity":1.557836468935089,"position":0.24753420879341495,"holonomicRotation":-178.25090569271487,"angularVelocity":0.0232354813210497,"angularAcceleration":0.12414528896113013,"curveRadius":66.50001249340366},{"acceleration":5.074093320189488,"curvature":0.01523273629876407,"pose":{"rotation":{"radians":-3.1383611581611577},"translation":{"x":5.830529041103378,"y":4.109228988478536}},"time":0.32068031153843113,"velocity":1.5883617744366494,"position":0.25708965552096325,"holonomicRotation":-178.25861095398042,"angularVelocity":0.024002763948668036,"angularAcceleration":0.12754216842470664,"curveRadius":65.64808714512681},{"acceleration":5.07177711271851,"curvature":0.015427401894273817,"pose":{"rotation":{"radians":-3.138216312688195},"translation":{"x":5.821066885477522,"y":4.109197040894082}},"time":0.3265283234758288,"velocity":1.6180215875356474,"position":0.2665518650798388,"holonomicRotation":-178.266316215246,"angularVelocity":0.02476832717057544,"angularAcceleration":0.13090999644027346,"curveRadius":64.81972835433616},{"acceleration":5.069647685362038,"curvature":0.015621375517871707,"pose":{"rotation":{"radians":-3.1380710477835194},"translation":{"x":5.811697090570484,"y":4.109164044033528}},"time":0.3322178310012297,"velocity":1.646865386192646,"position":0.27592171808790417,"holonomicRotation":-178.2740214765116,"angularVelocity":0.025532070047685183,"angularAcceleration":0.13423708004603166,"curveRadius":64.01484932334834},{"acceleration":5.067682967442714,"curvature":0.015814430193905774,"pose":{"rotation":{"radians":-3.1379253922808976},"translation":{"x":5.8024187758910335,"y":4.109130017876555}},"time":0.33775736566880615,"velocity":1.6749379916750817,"position":0.28520009515882916,"holonomicRotation":-178.28172673777715,"angularVelocity":0.02629381552106509,"angularAcceleration":0.1375107331376572,"curveRadius":63.233387971534924},{"acceleration":5.065864182454783,"curvature":0.016006328060929977,"pose":{"rotation":{"radians":-3.1377793763919777},"translation":{"x":5.793231060947929,"y":4.109094982402844}},"time":0.3431547038302119,"velocity":1.7022801737475435,"position":0.2943878769020012,"holonomicRotation":-178.28943199904273,"angularVelocity":0.02705331490326831,"angularAcceleration":0.14071739800075952,"curveRadius":62.47529078458107},{"acceleration":5.0641752533175115,"curvature":0.016196816373399398,"pose":{"rotation":{"radians":-3.1376330317464936},"translation":{"x":5.784133065249937,"y":4.109058957592075}},"time":0.3484169593589843,"velocity":1.728929157972986,"position":0.30348594392240036,"holonomicRotation":-178.2971372603083,"angularVelocity":0.02781025069648617,"angularAcceleration":0.14384246243443818,"curveRadius":61.74052832026516},{"acceleration":5.062602331995369,"curvature":0.016385632503574183,"pose":{"rotation":{"radians":-3.137486391433049},"translation":{"x":5.775123908305816,"y":4.109021963423927}},"time":0.3535506621804032,"velocity":1.7549190538484725,"position":0.31249517682050404,"holonomicRotation":-178.30484252157387,"angularVelocity":0.02856423882439276,"angularAcceleration":0.14687023268288807,"curveRadius":61.02907530617881},{"acceleration":5.061133424108672,"curvature":0.016572493967152064,"pose":{"rotation":{"radians":-3.1373394900397966},"translation":{"x":5.766202709624333,"y":4.10898401987808}},"time":0.3585618251806299,"velocity":1.7802812184025765,"position":0.3214164561921615,"holonomicRotation":-178.31254778283946,"angularVelocity":0.02931483035890426,"angularAcceleration":0.14978389936179376,"curveRadius":60.34094819899018},{"acceleration":5.05975808694397,"curvature":0.016757108093780906,"pose":{"rotation":{"radians":-3.137192363694656},"translation":{"x":5.757368588714249,"y":4.1089451469342135}},"time":0.363456001534433,"velocity":1.8050445667876618,"position":0.3302506626284945,"holonomicRotation":-178.32025304410502,"angularVelocity":0.03006151280722925,"angularAcceleration":0.15256549710244185,"curveRadius":59.67616813136937},{"acceleration":5.058467184557847,"curvature":0.01693916544378366,"pose":{"rotation":{"radians":-3.137045050107557},"translation":{"x":5.748620665084328,"y":4.108905364572009}},"time":0.368238334080403,"velocity":1.829235839037094,"position":0.3389986767157763,"holonomicRotation":-178.3279583053706,"angularVelocity":0.030803710466185175,"angularAcceleration":0.15519574429874491,"curveRadius":59.034785587207324},{"acceleration":5.057252687885328,"curvature":0.017118338832169542,"pose":{"rotation":{"radians":-3.13689758861018},"translation":{"x":5.7399580582433325,"y":4.108864692771146}},"time":0.3729135980547349,"velocity":1.8528798303378573,"position":0.34766137903532107,"holonomicRotation":-178.33566356663616,"angularVelocity":0.03154078533029793,"angularAcceleration":0.1576541705793386,"curveRadius":58.41688319200433},{"acceleration":5.056107510353323,"curvature":0.01729428873088277,"pose":{"rotation":{"radians":-3.136750020197981},"translation":{"x":5.731379887700026,"y":4.108823151511302}},"time":0.3774862382463075,"velocity":1.875999590752611,"position":0.3562396501633702,"holonomicRotation":-178.34336882790174,"angularVelocity":0.03227203672633833,"angularAcceleration":0.1599188576849095,"curveRadius":57.82255723615157},{"acceleration":5.05502537198963,"curvature":0.01746665751305989,"pose":{"rotation":{"radians":-3.1366023875716564},"translation":{"x":5.72288527296317,"y":4.108780760772161}},"time":0.38196040144024246,"velocity":1.8986165992163744,"position":0.3647343706709781,"holonomicRotation":-178.35107408916733,"angularVelocity":0.03299670126581546,"angularAcceleration":0.16196649698863702,"curveRadius":57.251938400480796},{"acceleration":5.054000686303519,"curvature":0.017635071095847308,"pose":{"rotation":{"radians":-3.136454735176324},"translation":{"x":5.714473333541529,"y":4.108737540533401}},"time":0.3863399648619817,"velocity":1.9207509157555542,"position":0.37314642112389323,"holonomicRotation":-178.35877935043288,"angularVelocity":0.033713952993494105,"angularAcceleration":0.1637724262921631,"curveRadius":56.70518675909842},{"acceleration":5.0530284657053155,"curvature":0.017799138091606628,"pose":{"rotation":{"radians":-3.1363071092438353},"translation":{"x":5.706143188943866,"y":4.108693510774701}},"time":0.39062856120998046,"velocity":1.942421315179912,"position":0.3814766820824488,"holonomicRotation":-178.36648461169847,"angularVelocity":0.034422902159471,"angularAcceleration":0.1653103039897228,"curveRadius":56.182495739586436},{"acceleration":5.05210424194314,"curvature":0.017958448899277207,"pose":{"rotation":{"radians":-3.1361595578319785},"translation":{"x":5.697893958678943,"y":4.108648691475743}},"time":0.394829600765415,"velocity":1.9636454049384937,"position":0.3897260341014427,"holonomicRotation":-178.37418987296402,"angularVelocity":0.035122595231426336,"angularAcceleration":0.16655236465226844,"curveRadius":55.68409641660355},{"acceleration":5.05122399892801,"curvature":0.01811257330265785,"pose":{"rotation":{"radians":-3.13601213086419},"translation":{"x":5.6897247622555245,"y":4.108603102616205}},"time":0.39894629098665624,"velocity":1.9844397293801797,"position":0.39789535773002466,"holonomicRotation":-178.3818951342296,"angularVelocity":0.03581201398824338,"angularAcceleration":0.16746918513804923,"curveRadius":55.21026655297287},{"acceleration":5.05038411565069,"curvature":0.0182610694617867,"pose":{"rotation":{"radians":-3.1358648801689433},"translation":{"x":5.681634719182372,"y":4.108556764175768}},"time":0.40298165393058943,"velocity":2.0048198622931053,"position":0.4059855335115835,"holonomicRotation":-178.3896003954952,"angularVelocity":0.03649007469533351,"angularAcceleration":0.16802967081549225,"curveRadius":54.76130530539902},{"acceleration":5.0495813175760675,"curvature":0.01840347478204957,"pose":{"rotation":{"radians":-3.1357178595171495},"translation":{"x":5.67362294896825,"y":4.108509696134112}},"time":0.40693854178911565,"velocity":2.024800489299263,"position":0.4139974419836297,"holonomicRotation":-178.39730565676075,"angularVelocity":0.037155627617025073,"angularAcceleration":0.16820110791298884,"curveRadius":54.337564609015175},{"acceleration":5.048812634973404,"curvature":0.01853930018057766,"pose":{"rotation":{"radians":-3.1355711246602636},"translation":{"x":5.66568857112192,"y":4.108461918470917}},"time":0.4108196507849568,"velocity":2.0443954814351746,"position":0.42193196367768476,"holonomicRotation":-178.40501091802633,"angularVelocity":0.037807455818227136,"angularAcceleration":0.16794895528585668,"curveRadius":53.93946860236023},{"acceleration":5.048075367200555,"curvature":0.01866804695421194,"pose":{"rotation":{"radians":-3.1354247333654213},"translation":{"x":5.657830705152146,"y":4.1084134511658625}},"time":0.41462753363430543,"velocity":2.063617961048157,"position":0.42978997911916783,"holonomicRotation":-178.4127161792919,"angularVelocity":0.038444274846146216,"angularAcceleration":0.1672370325226821,"curveRadius":53.56746757991077},{"acceleration":5.047367051784323,"curvature":0.01878919421838614,"pose":{"rotation":{"radians":-3.135278745451441},"translation":{"x":5.650048470567691,"y":4.108364314198628}},"time":0.41836461075348447,"velocity":2.082480360969478,"position":0.43757236882728656,"holonomicRotation":-178.42042144055748,"angularVelocity":0.039064731426337214,"angularAcceleration":0.16602723476236442,"curveRadius":53.222080115679006},{"acceleration":5.046685437768008,"curvature":0.01890219846168516,"pose":{"rotation":{"radians":-3.1351332228217332},"translation":{"x":5.6423409868773176,"y":4.108314527548895}},"time":0.4220331803614156,"velocity":2.1009944777872627,"position":0.4452800133149281,"holonomicRotation":-178.42812670182306,"angularVelocity":0.03966740317348386,"angularAcceleration":0.1642797633834506,"curveRadius":52.90389909020394},{"acceleration":5.0460284624798035,"curvature":0.019006500586787316,"pose":{"rotation":{"radians":-3.1349882294953386},"translation":{"x":5.634707373589789,"y":4.108264111196342}},"time":0.42563542760843975,"velocity":2.119171519924636,"position":0.45291379308854857,"holonomicRotation":-178.43583196308862,"angularVelocity":0.04025079803014549,"angularAcceleration":0.16195303005466277,"curveRadius":52.6135779405477},{"acceleration":5.045394231381752,"curvature":0.019101520383411178,"pose":{"rotation":{"radians":-3.1348438316389524},"translation":{"x":5.627146750213869,"y":4.10821308512065}},"time":0.4291734328441462,"velocity":2.1370221511314678,"position":0.4604745886480724,"holonomicRotation":-178.4435372243542,"angularVelocity":0.040813352939363105,"angularAcceleration":0.15900341343200056,"curveRadius":52.35185367068768},{"acceleration":5.0447810003475775,"curvature":0.019186657218900012,"pose":{"rotation":{"radians":-3.1347000975927863},"translation":{"x":5.619658236258318,"y":4.108161469301498}},"time":0.4326491791217401,"velocity":2.1545565299147023,"position":0.46796328048678903,"holonomicRotation":-178.45124248561976,"angularVelocity":0.0413534345394101,"angularAcceleration":0.15538579542718253,"curveRadius":52.119553113970255},{"acceleration":5.044187160299235,"curvature":0.019261290884423923,"pose":{"rotation":{"radians":-3.134557097898413},"translation":{"x":5.612240951231902,"y":4.1081092837185675}},"time":0.4360645590236609,"velocity":2.1717843453635153,"position":0.47538074909124983,"holonomicRotation":-178.45894774688534,"angularVelocity":0.04186933766663732,"angularAcceleration":0.1510529258947374,"curveRadius":51.917600227338475},{"acceleration":5.04361122348529,"curvature":0.019324784456572694,"pose":{"rotation":{"radians":-3.134414905320321},"translation":{"x":5.604894014643383,"y":4.108056548351537}},"time":0.43942138088225785,"velocity":2.1887148497647755,"position":0.4827278749411759,"holonomicRotation":-178.46665300815093,"angularVelocity":0.042359286277835834,"angularAcceleration":0.14595609532979498,"curveRadius":51.74701959792792},{"acceleration":5.043051811712994,"curvature":0.01937647917143741,"pose":{"rotation":{"radians":-3.1342735948683655},"translation":{"x":5.5976165460015235,"y":4.108003283180087}},"time":0.44272137445999354,"velocity":2.2053568883556167,"position":0.4900055385093646,"holonomicRotation":-178.47435826941648,"angularVelocity":0.04282143241393335,"angularAcceleration":0.14004455621232528,"curveRadius":51.608963173974644},{"acceleration":5.04250764557537,"curvature":0.019415695287025334,"pose":{"rotation":{"radians":-3.1341332438147145},"translation":{"x":5.590407664815088,"y":4.107949508183896}},"time":0.4459661961456702,"velocity":2.22171892651417,"position":0.497214620261596,"holonomicRotation":-178.48206353068207,"angularVelocity":0.04325385714432548,"angularAcceleration":0.13326609973698966,"curveRadius":51.504722608015825},{"acceleration":5.041977535245205,"curvature":0.019441742074995626,"pose":{"rotation":{"radians":-3.133993931708871},"translation":{"x":5.583266490592837,"y":4.1078952433426466}},"time":0.4491574337163119,"velocity":2.237809074654976,"position":0.504356000656558,"holonomicRotation":-178.48976879194763,"angularVelocity":0.0436545706044904,"angularAcceleration":0.12556679071822882,"curveRadius":51.43571991350086},{"acceleration":5.041460372162969,"curvature":0.019453903982930322,"pose":{"rotation":{"radians":-3.133855740389041},"translation":{"x":5.576192142843535,"y":4.107840508636017}},"time":0.45229661070839466,"velocity":2.253635111061767,"position":0.5114305601457529,"holonomicRotation":-178.4974740532132,"angularVelocity":0.04402151270187139,"angularAcceleration":0.11689117826310796,"curveRadius":51.403564080373904},{"acceleration":5.040955121688502,"curvature":0.019451449655865885,"pose":{"rotation":{"radians":-3.133718753989894},"translation":{"x":5.569183741075946,"y":4.107785324043689}},"time":0.4553851904370338,"velocity":2.2692045028635937,"position":0.5184391791734341,"holonomicRotation":-178.5051793144788,"angularVelocity":0.04435255398347103,"angularAcceleration":0.10718236558053756,"curveRadius":51.41005003184606},{"acceleration":5.04046081645329,"curvature":0.019433631761913043,"pose":{"rotation":{"radians":-3.1335830589461224},"translation":{"x":5.562240404798832,"y":4.107729709545339}},"time":0.458424579697264,"velocity":2.284524425335733,"position":0.5253827381765331,"holonomicRotation":-178.51288457574435,"angularVelocity":0.04464549689215046,"angularAcceleration":0.09638216220361248,"curveRadius":51.45718578242527},{"acceleration":5.039976550722347,"curvature":0.019399690137882408,"pose":{"rotation":{"radians":-3.133448743993092},"translation":{"x":5.555361253520954,"y":4.10767368512065}},"time":0.46141613217771077,"velocity":2.29960177968744,"position":0.5322621175845968,"holonomicRotation":-178.52058983700994,"angularVelocity":0.044898076804035555,"angularAcceleration":0.08443104827209273,"curveRadius":51.547215078825786},{"acceleration":5.0395014749448634,"curvature":0.01934884288729166,"pose":{"rotation":{"radians":-3.1333159001603375},"translation":{"x":5.54854540675108,"y":4.1076172707493015}},"time":0.4643611516135795,"velocity":2.3144432094782417,"position":0.5390781978197247,"holonomicRotation":-178.5282950982755,"angularVelocity":0.04510796470020402,"angularAcceleration":0.07126876434571029,"curveRadius":51.68267714121557},{"acceleration":5.039034791254333,"curvature":0.019280299467467545,"pose":{"rotation":{"radians":-3.1331846207632505},"translation":{"x":5.5417919839979675,"y":4.107560486410972}},"time":0.4672608947029629,"velocity":2.329055115791344,"position":0.5458318592965337,"holonomicRotation":-178.53600035954108,"angularVelocity":0.04527276832473399,"angularAcceleration":0.056833870949930004,"curveRadius":51.866414299598496},{"acceleration":5.038575749302215,"curvature":0.019193255531907948,"pose":{"rotation":{"radians":-3.133055001388398},"translation":{"x":5.535100104770383,"y":4.107503352085344}},"time":0.47011657380785865,"velocity":2.3434436712770608,"position":0.5525239824220998,"holonomicRotation":-178.54370562080666,"angularVelocity":0.04539003511646126,"angularAcceleration":0.0410644149499257,"curveRadius":52.10163530296065},{"acceleration":5.038123642352814,"curvature":0.019086894276525608,"pose":{"rotation":{"radians":-3.132927139872084},"translation":{"x":5.5284688885770885,"y":4.107445887752095}},"time":0.4729293594590788,"velocity":2.357614833167344,"position":0.5591554475959367,"holonomicRotation":-178.55141088207222,"angularVelocity":0.04545725560650744,"angularAcceleration":0.023898191466180167,"curveRadius":52.391970401903976},{"acceleration":5.037677804152289,"curvature":0.018960391938145464,"pose":{"rotation":{"radians":-3.1328011362770365},"translation":{"x":5.521897454926847,"y":4.107388113390907}},"time":0.4757003826821928,"velocity":2.3715743553532156,"position":0.565727135209962,"holonomicRotation":-178.5591161433378,"angularVelocity":0.04547186540936531,"angularAcceleration":0.005272349483037304,"curveRadius":52.74152576920892},{"acceleration":5.037237605681785,"curvature":0.01881291356971456,"pose":{"rotation":{"radians":-3.1326770928584042},"translation":{"x":5.515384923328423,"y":4.107330048981458}},"time":0.47843073715993006,"velocity":2.3853277996053155,"position":0.5722399256484856,"holonomicRotation":-178.56682140460336,"angularVelocity":0.04543125064663988,"angularAcceleration":-0.01487527097913354,"curveRadius":53.15497763248229},{"acceleration":5.036802452702476,"curvature":0.0186436190164682,"pose":{"rotation":{"radians":-3.132555114027334},"translation":{"x":5.508930413290576,"y":4.107271714503429}},"time":0.481121481244894,"velocity":2.3988805460120566,"position":0.5786946992882026,"holonomicRotation":-178.57452666586894,"angularVelocity":0.045332750799913966,"angularAcceleration":-0.03660691749777953,"curveRadius":53.637654744858516},{"acceleration":5.036371783082739,"curvature":0.018451662863419926,"pose":{"rotation":{"radians":-3.1324353063064123},"translation":{"x":5.502533044322072,"y":4.1072131299365}},"time":0.4837736398350756,"velocity":2.4122378026999076,"position":0.5850923364981939,"holonomicRotation":-178.58223192713453,"angularVelocity":0.04517366396015638,"angularAcceleration":-0.059983909086934885,"curveRadius":54.19565745385914},{"acceleration":5.035945064773318,"curvature":0.018236197255053575,"pose":{"rotation":{"radians":-3.1323177782775518},"translation":{"x":5.496191935931674,"y":4.10715431526035}},"time":0.48638820612343825,"velocity":2.42540461489631,"position":0.591433717639941,"holonomicRotation":-178.58993718840009,"angularVelocity":0.04495125229131571,"angularAcceleration":-0.08506637212856911,"curveRadius":54.83599382118343},{"acceleration":5.035521793677692,"curvature":0.017996376806858134,"pose":{"rotation":{"radians":-3.132202640524677},"translation":{"x":5.489906207628143,"y":4.1070952904546605}},"time":0.4889661432317606,"velocity":2.4383858733879977,"position":0.5977197230673569,"holonomicRotation":-178.59764244966567,"angularVelocity":0.044662747009333176,"angularAcceleration":-0.11191323521863956,"curveRadius":55.56674050183901},{"acceleration":5.035101492123738,"curvature":0.017731354720123098,"pose":{"rotation":{"radians":-3.132090005566722},"translation":{"x":5.483674978920244,"y":4.107036075499111}},"time":0.49150838573794947,"velocity":2.45118632242425,"position":0.6039512331268126,"holonomicRotation":-178.60534771093123,"angularVelocity":0.04430535548067116,"angularAcceleration":-0.14058121040458293,"curveRadius":56.39727002162515},{"acceleration":5.034683707039741,"curvature":0.01744029303030462,"pose":{"rotation":{"radians":-3.1319799877849417},"translation":{"x":5.477497369316739,"y":4.10697669037338}},"time":0.4940158411052016,"velocity":2.4638105671078834,"position":0.6101291281571998,"holonomicRotation":-178.6130529721968,"angularVelocity":0.04387626723776628,"angularAcceleration":-0.17112497734111637,"curveRadius":57.338486128781156},{"acceleration":5.034268008544551,"curvature":0.017122357503183142,"pose":{"rotation":{"radians":-3.1318727033415},"translation":{"x":5.4713724983263905,"y":4.10691715505715}},"time":0.49648939102058626,"velocity":2.4762630803144425,"position":0.6162542884899818,"holonomicRotation":-178.6207582334624,"angularVelocity":0.043372661604389774,"angularAcceleration":-0.20359630919281027,"curveRadius":58.40317256628326},{"acceleration":5.033853988870062,"curvature":0.016776729464883167,"pose":{"rotation":{"radians":-3.1317682700881484},"translation":{"x":5.465299485457962,"y":4.106857489530099}},"time":0.4989298926499704,"velocity":2.4885482091763618,"position":0.6223275944492777,"holonomicRotation":-178.62846349472795,"angularVelocity":0.04279171629895493,"angularAcceleration":-0.23804339994702028,"curveRadius":59.60637334548352},{"acceleration":5.03344126091626,"curvature":0.01640259721946609,"pose":{"rotation":{"radians":-3.1316668074705936},"translation":{"x":5.459277450220219,"y":4.106797713771908}},"time":0.5013381798155593,"velocity":2.500670181163772,"position":0.6283499263519452,"holonomicRotation":-178.63616875599354,"angularVelocity":0.04213061424094212,"angularAcceleration":-0.27451130723073797,"curveRadius":60.96595475826422},{"acceleration":5.033029457460024,"curvature":0.015999173257643322,"pose":{"rotation":{"radians":-3.1315684364188687},"translation":{"x":5.45330551212192,"y":4.106737847762255}},"time":0.5037150641017983,"velocity":2.512633109793387,"position":0.6343221645076971,"holonomicRotation":-178.6438740172591,"angularVelocity":0.04138655478280987,"angularAcceleration":-0.3130398322038516,"curveRadius":62.50322962921023},{"acceleration":5.032618230010397,"curvature":0.015565686142468158,"pose":{"rotation":{"radians":-3.1314732792340156},"translation":{"x":5.447382790671831,"y":4.106677911480823}},"time":0.5060613358948531,"velocity":2.5244409999916737,"position":0.6402451892192086,"holonomicRotation":-178.65157927852468,"angularVelocity":0.0405567612135834,"angularAcceleration":-0.3536647253241275,"curveRadius":64.2438753324006},{"acceleration":5.032207248103462,"curvature":0.015101389726877686,"pose":{"rotation":{"radians":-3.1313814594610747},"translation":{"x":5.441508405378714,"y":4.10661792490729}},"time":0.5083777653604691,"velocity":2.5360977531382667,"position":0.6461198807822605,"holonomicRotation":-178.65928453979026,"angularVelocity":0.03963849290637106,"angularAcceleration":-0.39641539742207055,"curveRadius":66.21907109781986},{"acceleration":5.031796198771005,"curvature":0.014605567765412905,"pose":{"rotation":{"radians":-3.1312931017563734},"translation":{"x":5.435681475751333,"y":4.106557908021336}},"time":0.5106651033645779,"velocity":2.547607171812646,"position":0.6519471194858878,"holonomicRotation":-178.66698980105582,"angularVelocity":0.038629054622692234,"angularAcceleration":-0.44131574864122564,"curveRadius":68.46704051916942},{"acceleration":5.03138478524828,"curvature":0.01407752922757964,"pose":{"rotation":{"radians":-3.131208331744661},"translation":{"x":5.4299011212984505,"y":4.1064978808026416}},"time":0.5129240823406717,"velocity":2.55897296426316,"position":0.6577277856125505,"holonomicRotation":-178.6746950623214,"angularVelocity":0.037525808167967585,"angularAcceleration":-0.4883827899241474,"curveRadius":71.03519259905886},{"acceleration":5.03097272710059,"curvature":0.013516628482663145,"pose":{"rotation":{"radians":-3.131127275864371},"translation":{"x":5.424166461528829,"y":4.1064378632308856}},"time":0.515155417107621,"velocity":2.5701987486207134,"position":0.6634627594383177,"holonomicRotation":-178.68240032358696,"angularVelocity":0.03632618533559017,"angularAcceleration":-0.5376256625165722,"curveRadius":73.98294635993226},{"acceleration":5.0305597593895754,"curvature":0.012922251922749579,"pose":{"rotation":{"radians":-3.1310500612080086},"translation":{"x":5.418476615951231,"y":4.106377875285751}},"time":0.5173598056413237,"velocity":2.5812880568724177,"position":0.6691529212330708,"holonomicRotation":-178.69010558485255,"angularVelocity":0.03502769824014308,"angularAcceleration":-0.5890463843350076,"curveRadius":77.38589264302327},{"acceleration":5.030145631916803,"curvature":0.012293835511158136,"pose":{"rotation":{"radians":-3.1309768153472106},"translation":{"x":5.412830704074422,"y":4.106317936946914}},"time":0.5195379298032906,"velocity":2.592244338611508,"position":0.6747991512607225,"holonomicRotation":-178.69781084611813,"angularVelocity":0.033627954768101105,"angularAcceleration":-0.6426371354229623,"curveRadius":81.34157961462715},{"acceleration":5.029730109569959,"curvature":0.011630858956374444,"pose":{"rotation":{"radians":-3.130907666155503},"translation":{"x":5.407227845407163,"y":4.106258068194056}},"time":0.5216904560290369,"velocity":2.603070964580783,"position":0.6804023297794612,"holonomicRotation":-178.7055161073837,"angularVelocity":0.03212466862455,"angularAcceleration":-0.6983822661811915,"curveRadius":85.97817269995669},{"acceleration":5.029312971127395,"curvature":0.010932861618580772,"pose":{"rotation":{"radians":-3.1308427416143165},"translation":{"x":5.401667159458217,"y":4.106198289006858}},"time":0.523818035978908,"velocity":2.6137712300197804,"position":0.6859633370420013,"holonomicRotation":-178.71322136864927,"angularVelocity":0.030515676362842525,"angularAcceleration":-0.756254664744768,"curveRadius":91.46736096068992},{"acceleration":5.028894009655842,"curvature":0.010199429363143182,"pose":{"rotation":{"radians":-3.1307821696152556},"translation":{"x":5.396147765736347,"y":4.106138619364998}},"time":0.5259213071537854,"velocity":2.624348357831803,"position":0.6914830532958658,"holonomicRotation":-178.72092662991483,"angularVelocity":0.0287989488870758,"angularAcceleration":-0.8162178497343727,"curveRadius":98.04470077645871},{"acceleration":5.028473031431119,"curvature":0.009430216616856217,"pose":{"rotation":{"radians":-3.130726077750391},"translation":{"x":5.390668783750317,"y":4.106079079248158}},"time":0.5280008934779096,"velocity":2.6348055015791947,"position":0.6969623587836771,"holonomicRotation":-178.7286318911804,"angularVelocity":0.026972607106396963,"angularAcceleration":-0.8782235964395417,"curveRadius":106.04210280944463},{"acceleration":5.0280498569437935,"curvature":0.008624951871674101,"pose":{"rotation":{"radians":-3.130674593094644},"translation":{"x":5.38522933300889,"y":4.1060196886360165}},"time":0.5300574058509033,"velocity":2.645145748322029,"position":0.7024021337434732,"holonomicRotation":-178.736337152446,"angularVelocity":0.025034936051546962,"angularAcceleration":-0.9422122036782336,"curveRadius":115.94267595674133},{"acceleration":5.027624319243985,"curvature":0.0077834167416448025,"pose":{"rotation":{"radians":-3.130627841979375},"translation":{"x":5.379828533020828,"y":4.105960467508255}},"time":0.5320914426709161,"velocity":2.655372121304563,"position":0.7078032584090421,"holonomicRotation":-178.74404241371155,"angularVelocity":0.02298439969664238,"angularAcceleration":-1.0081117188880007,"curveRadius":128.4782805794719},{"acceleration":5.02719626483304,"curvature":0.006905489026565997,"pose":{"rotation":{"radians":-3.130585949757519},"translation":{"x":5.3744655032948945,"y":4.105901435844552}},"time":0.534103590330668,"velocity":2.6654875825039603,"position":0.7131666130102752,"holonomicRotation":-178.75174767497714,"angularVelocity":0.020819655880284716,"angularAcceleration":-1.0758374545059952,"curveRadius":144.81233641135566},{"acceleration":5.026765553097067,"curvature":0.0059910971159118824,"pose":{"rotation":{"radians":-3.130549040561292},"translation":{"x":5.369139363339852,"y":4.105842613624587}},"time":0.5360944236880425,"velocity":2.675495035046767,"position":0.7184930777735361,"holonomicRotation":-178.7594529362427,"angularVelocity":0.01853957092399403,"angularAcceleration":-1.1452917180861706,"curveRadius":166.91433649841508},{"acceleration":5.02633205618873,"curvature":0.005040281272452715,"pose":{"rotation":{"radians":-3.1305172370524637},"translation":{"x":5.363849232664466,"y":4.105784020828041}},"time":0.5380645065127613,"velocity":2.685397325501998,"position":0.7237835329220533,"holonomicRotation":-178.76715819750828,"angularVelocity":0.01614323440071311,"angularAcceleration":-1.216363339253509,"curveRadius":198.4016260095297},{"acceleration":5.02589565896055,"curvature":0.004053183125060032,"pose":{"rotation":{"radians":-3.130490660163644},"translation":{"x":5.358594230777496,"y":4.105725677434594}},"time":0.5400143919105619,"velocity":2.6951972460582745,"position":0.7290388586763348,"holonomicRotation":-178.77486345877386,"angularVelocity":0.01362997479207777,"angularAcceleration":-1.2889268320436649,"curveRadius":246.7196692439572},{"acceleration":5.025456258915085,"curvature":0.00302995666646718,"pose":{"rotation":{"radians":-3.130469428837164},"translation":{"x":5.353373477187706,"y":4.105667603423926}},"time":0.5419446227261939,"velocity":2.7048975365918433,"position":0.7342599352545915,"holonomicRotation":-178.78256872003942,"angularVelocity":0.010999371840961981,"angularAcceleration":-1.362843723046882,"curveRadius":330.0377233335036},{"acceleration":5.025013766083859,"curvature":0.0019709523421208943,"pose":{"rotation":{"radians":-3.130453659753848},"translation":{"x":5.348186091403861,"y":4.105609818775717}},"time":0.5438557319264676,"velocity":2.714500886631708,"position":0.7394476428731845,"holonomicRotation":-178.790273981305,"angularVelocity":0.008251272775915221,"angularAcceleration":-1.4379602508601697,"curveRadius":507.3689396892895},{"acceleration":5.024568102666026,"curvature":0.0008765669228281146,"pose":{"rotation":{"radians":-3.1304434670602586},"translation":{"x":5.343031192934721,"y":4.105552343469647}},"time":0.5457482429644999,"velocity":2.7240099372273483,"position":0.7446028617470968,"holonomicRotation":-178.79797924257056,"angularVelocity":0.005385804037472168,"angularAcceleration":-1.5141093926841627,"curveRadius":1140.8142081994683},{"acceleration":5.024119203883876,"curvature":-0.00025262980921307213,"pose":{"rotation":{"radians":-3.1304389620884887},"translation":{"x":5.337907901289053,"y":4.105495197485395}},"time":0.5476226701262135,"velocity":2.733427282726795,"position":0.7497264720904089,"holonomicRotation":-178.80568450383615,"angularVelocity":0.0024033858780242515,"angularAcceleration":-1.5911091240917539,"curveRadius":-3958.3610624373455},{"acceleration":5.0236670164419275,"curvature":-0.0014162707559019086,"pose":{"rotation":{"radians":-3.1304402530759394},"translation":{"x":5.332815335975615,"y":4.105438400802641}},"time":0.5494795188600958,"velocity":2.742755472465722,"position":0.7548193541168058,"holonomicRotation":-178.81338976510173,"angularVelocity":-0.0006952571995566837,"angularAcceleration":-1.6687644076974333,"curveRadius":-706.0796785027031},{"acceleration":5.023211500030587,"curvature":-0.0026133823099186966,"pose":{"rotation":{"radians":-3.1304474448787594},"translation":{"x":5.327752616503175,"y":4.105381973401067}},"time":0.5513192860911308,"velocity":2.751997012378036,"position":0.759882388040085,"holonomicRotation":-178.8210950263673,"angularVelocity":-0.003909083007144003,"angularAcceleration":-1.7468654476356673,"curveRadius":-382.64589004243714},{"acceleration":5.022752626064457,"curvature":-0.003843220075967555,"pose":{"rotation":{"radians":-3.1304606386858724},"translation":{"x":5.322718862380493,"y":4.10532593526035}},"time":0.5531424605197821,"velocity":2.761154366527318,"position":0.7649164540746966,"holonomicRotation":-178.82880028763287,"angularVelocity":-0.007236722337547005,"angularAcceleration":-1.825189777845118,"curveRadius":-260.1984742568362},{"acceleration":5.02229037815282,"curvature":-0.005104838603966961,"pose":{"rotation":{"radians":-3.1304799317331087},"translation":{"x":5.317713193116332,"y":4.105270306360173}},"time":0.5549495229068266,"velocity":2.770229958566494,"position":0.769922432436286,"holonomicRotation":-178.83650554889843,"angularVelocity":-0.010676469929629935,"angularAcceleration":-1.9035024007713797,"curveRadius":-195.89257909601722},{"acceleration":5.021824752228316,"curvature":-0.006397206590113899,"pose":{"rotation":{"radians":-3.130505417013074},"translation":{"x":5.312734728219456,"y":4.105215106680213}},"time":0.5567409463447978,"velocity":2.779226173129019,"position":0.7749012033422521,"holonomicRotation":-178.84421081016401,"angularVelocity":-0.014226273601929885,"angularAcceleration":-1.9815547776467028,"curveRadius":-156.31822826315752},{"acceleration":5.0213557559384725,"curvature":-0.007719128208871541,"pose":{"rotation":{"radians":-3.1305371829933053},"translation":{"x":5.307782587198628,"y":4.105160356200153}},"time":0.5585171965167498,"velocity":2.788145357153937,"position":0.7798536470123241,"holonomicRotation":-178.8519160714296,"angularVelocity":-0.017883730981557405,"angularAcceleration":-2.059089106580122,"curveRadius":-129.54830816914102},{"acceleration":5.020883408652711,"curvature":-0.009069350572421357,"pose":{"rotation":{"radians":-3.1305753133303496},"translation":{"x":5.302855889562611,"y":4.10510607489967}},"time":0.5602787319430015,"velocity":2.7969898211493582,"position":0.784780643669144,"holonomicRotation":-178.85962133269516,"angularVelocity":-0.021646080161661783,"angularAcceleration":-2.1358350925193528,"curveRadius":-110.26147815267632},{"acceleration":5.020407742152182,"curvature":-0.010446474229970457,"pose":{"rotation":{"radians":-3.1306198865921675},"translation":{"x":5.297953754820168,"y":4.105052282758446}},"time":0.5620260042164827,"velocity":2.8057618403987914,"position":0.7896830735388646,"holonomicRotation":-178.86732659396074,"angularVelocity":-0.025510198092447714,"angularAcceleration":-2.2115144785575263,"curveRadius":-95.72607733344574},{"acceleration":5.019928799032439,"curvature":-0.011848996964950606,"pose":{"rotation":{"radians":-3.130670975982158},"translation":{"x":5.2930753024800605,"y":4.10499899975616}},"time":0.5637594582272659,"velocity":2.81446365610932,"position":0.7945618168517508,"holonomicRotation":-178.8750318552263,"angularVelocity":-0.029472596142000797,"angularAcceleration":-2.2858397309097747,"curveRadius":-84.39532923824736},{"acceleration":5.0194466343744555,"curvature":-0.013275295570207506,"pose":{"rotation":{"radians":-3.1307286490718105},"translation":{"x":5.288219652051054,"y":4.104946245872491}},"time":0.5654795323768285,"velocity":2.8230974765102164,"position":0.7994177538427912,"holonomicRotation":-178.88273711649188,"angularVelocity":-0.03352942061660544,"angularAcceleration":-2.3585172044102785,"curveRadius":-75.32788966629155},{"acceleration":5.018961313859999,"curvature":-0.014723655139822201,"pose":{"rotation":{"radians":-3.1307929675398136},"translation":{"x":5.28338592304191,"y":4.104894041087122}},"time":0.567186658782564,"velocity":2.831665477898472,"position":0.8042517647523215,"holonomicRotation":-178.89044237775747,"angularVelocity":-0.037676453124413256,"angularAcceleration":-2.4292474733415905,"curveRadius":-67.91791783382368},{"acceleration":5.01847291489479,"curvature":-0.016192242230996648,"pose":{"rotation":{"radians":-3.1308639869178796},"translation":{"x":5.278573234961392,"y":4.104842405379731}},"time":0.5688812634730177,"velocity":2.8401698056389675,"position":0.8090647298266422,"holonomicRotation":-178.89814763902302,"angularVelocity":-0.0419091121758665,"angularAcceleration":-2.4977265053598248,"curveRadius":-61.757969386457795},{"acceleration":5.017981525746498,"curvature":-0.017679119062060086,"pose":{"rotation":{"radians":-3.1309417563495767},"translation":{"x":5.273780707318263,"y":4.104791358729997}},"time":0.5705637665743075,"velocity":2.848612575118251,"position":0.8138575293186519,"holonomicRotation":-178.9058529002886,"angularVelocity":-0.046222459642130544,"angularAcceleration":-2.5636490434742254,"curveRadius":-56.563904371571866},{"acceleration":5.01748724589907,"curvature":-0.01918225920925914,"pose":{"rotation":{"radians":-3.13102631835932},"translation":{"x":5.269007459621285,"y":4.104740921117602}},"time":0.5722345824881504,"velocity":2.856995872656203,"position":0.8186310434884693,"holonomicRotation":-178.91355816155416,"angularVelocity":-0.05061120680188525,"angularAcceleration":-2.626708976969566,"curveRadius":-52.131502816795795},{"acceleration":5.016990184902247,"curvature":-0.020699536176810734,"pose":{"rotation":{"radians":-3.1311177086309763},"translation":{"x":5.264252611379223,"y":4.104691112522225}},"time":0.573894120061903,"velocity":2.865321756375196,"position":0.8233861526040647,"holonomicRotation":-178.92126342281975,"angularVelocity":-0.055069721289595426,"angularAcceleration":-2.686600507410305,"curveRadius":-48.31026122799213},{"acceleration":5.016490463308672,"curvature":-0.022228728683368535,"pose":{"rotation":{"radians":-3.1312159558040906},"translation":{"x":5.259515282100838,"y":4.104641952923545}},"time":0.5755427827509915,"velocity":2.873592257032221,"position":0.8281237369418872,"holonomicRotation":-178.92896868408533,"angularVelocity":-0.059592040121118725,"angularAcceleration":-2.743022488137722,"curveRadius":-44.98682827273864},{"acceleration":5.015988211701676,"curvature":-0.023767539019033376,"pose":{"rotation":{"radians":-3.131321081283045},"translation":{"x":5.254794591294894,"y":4.104593462301245}},"time":0.5771809687740882,"velocity":2.881809378812649,"position":0.8328446767874872,"holonomicRotation":-178.9366739453509,"angularVelocity":-0.06417188125902619,"angularAcceleration":-2.7956783132906944,"curveRadius":-42.07419199771529},{"acceleration":5.015483570414064,"curvature":-0.025313588122898606,"pose":{"rotation":{"radians":-3.1314330990602537},"translation":{"x":5.250089658470155,"y":4.104545660635002}},"time":0.578809071261373,"velocity":2.8899751000885763,"position":0.8375498524361327,"holonomicRotation":-178.94437920661647,"angularVelocity":-0.0688026571321785,"angularAcceleration":-2.844277869063982,"curveRadius":-39.50447463808588},{"acceleration":5.014976689581557,"curvature":-0.026864435796345166,"pose":{"rotation":{"radians":-3.131552015560529},"translation":{"x":5.245399603135382,"y":4.104498567904495}},"time":0.5804274783961982,"velocity":2.898091374143977,"position":0.8422401441934226,"holonomicRotation":-178.95208446788203,"angularVelocity":-0.07347749383725644,"angularAcceleration":-2.8885418288661175,"curveRadius":-37.223934557227786},{"acceleration":5.014467728160916,"curvature":-0.02841756516113428,"pose":{"rotation":{"radians":-3.1316778295006933},"translation":{"x":5.24072354479934,"y":4.104452204089408}},"time":0.5820365735504541,"velocity":2.9061601298665334,"position":0.8469164323758825,"holonomicRotation":-178.95978972914762,"angularVelocity":-0.07818924805754651,"angularAcceleration":-2.9282011121765996,"curveRadius":-35.18950319387903},{"acceleration":5.0139568549102025,"curvature":-0.02997042049871554,"pose":{"rotation":{"radians":-3.1318105317673384},"translation":{"x":5.23606060297079,"y":4.104406589169418}},"time":0.5836367354139266,"velocity":2.914183272410857,"position":0.8515795973115637,"holonomicRotation":-178.9674949904132,"angularVelocity":-0.08293052701375311,"angularAcceleration":-2.962999596751879,"curveRadius":-33.36623188329499},{"acceleration":2.626508729954992,"curvature":-0.03152038611590766,"pose":{"rotation":{"radians":-3.1319501053178964},"translation":{"x":5.231409897158496,"y":4.1043617431242065}},"time":0.5852304070591565,"velocity":2.918369064899735,"position":0.8562305193406107,"holonomicRotation":-178.97520025167876,"angularVelocity":-0.08757986689153216,"angularAcceleration":-2.9173762937271897,"curveRadius":-31.725499691620893},{"acceleration":-2.38353922256907,"curvature":-0.03306481785495075,"pose":{"rotation":{"radians":-3.1320965250993553},"translation":{"x":5.226770546871222,"y":4.104317685933451}},"time":0.5868222548382007,"velocity":2.914574833282024,"position":0.8608700788158288,"holonomicRotation":-178.98290551294434,"angularVelocity":-0.09198101940803788,"angularAcceleration":-2.764807398323179,"curveRadius":-30.243626454765764},{"acceleration":-4.998816876274329,"curvature":-0.03460104006748758,"pose":{"rotation":{"radians":-3.1322497579915116},"translation":{"x":5.222141671617729,"y":4.1042744375768345}},"time":0.58841485631505,"velocity":2.9066137101423704,"position":0.8654991561032318,"holonomicRotation":-178.9906107742099,"angularVelocity":-0.09621546531493048,"angularAcceleration":-2.6588232953732307,"curveRadius":-28.900865351144088},{"acceleration":-4.998330803018391,"curvature":-0.03612636394310206,"pose":{"rotation":{"radians":-3.13240976276836},"translation":{"x":5.217522390906781,"y":4.104232018034036}},"time":0.5900085218485729,"velocity":2.898648042616454,"position":0.8701186315825633,"holonomicRotation":-178.99831603547548,"angularVelocity":-0.10040047518296265,"angularAcceleration":-2.6260277203717224,"curveRadius":-27.680615784499373},{"acceleration":-4.9978404157476275,"curvature":-0.037638087993767416,"pose":{"rotation":{"radians":-3.1325764900856576},"translation":{"x":5.212911824247142,"y":4.104190447284735}},"time":0.5916035652342986,"velocity":2.8906762703184032,"position":0.8747293856478089,"holonomicRotation":-179.00602129674107,"angularVelocity":-0.1045283901301248,"angularAcceleration":-2.58796405420915,"curveRadius":-26.56883102472135},{"acceleration":-4.997345935588762,"curvature":-0.03913351411415916,"pose":{"rotation":{"radians":-3.1327498824913746},"translation":{"x":5.208309091147574,"y":4.104149745308611}},"time":0.5932003037588122,"velocity":2.8826968155427273,"position":0.8793322987076786,"holonomicRotation":-179.01372655800662,"angularVelocity":-0.10859160911761084,"angularAcceleration":-2.5446990381370194,"curveRadius":-25.553544644184743},{"acceleration":-4.996847587396283,"curvature":-0.04060995803596201,"pose":{"rotation":{"radians":-3.132929874456695},"translation":{"x":5.203713311116839,"y":4.104109932085344}},"time":0.5947990582569102,"velocity":2.8747080829860674,"position":0.8839282511860712,"holonomicRotation":-179.0214318192722,"angularVelocity":-0.11258261698990821,"angularAcceleration":-2.4963231547091205,"curveRadius":-24.62450217541356},{"acceleration":-4.996345599782122,"curvature":-0.042064757137330225,"pose":{"rotation":{"radians":-3.1331163924340473},"translation":{"x":5.199123603663703,"y":4.104071027594615}},"time":0.5964001531716366,"velocity":2.86670845945404,"position":0.8885181235225065,"holonomicRotation":-179.02913708053777,"angularVelocity":-0.11649401646136985,"angularAcceleration":-2.4429529039693594,"curveRadius":-23.772869928507287},{"acceleration":-4.99584020484273,"curvature":-0.04349528279062394,"pose":{"rotation":{"radians":-3.133309354936702},"translation":{"x":5.194539088296926,"y":4.104033051816104}},"time":0.5980039166173368,"velocity":2.8586963135529544,"position":0.8931027961725404,"holonomicRotation":-179.03684234180335,"angularVelocity":-0.120318556437992,"angularAcceleration":-2.3847282383671873,"curveRadius":-22.9909989277174},{"acceleration":-4.995331636731697,"curvature":-0.0448989530914348,"pose":{"rotation":{"radians":-3.133508672641887},"translation":{"x":5.189958884525273,"y":4.10399602472949}},"time":0.5996106804458551,"velocity":2.8506699953676007,"position":0.8976831496081396,"holonomicRotation":-179.04454760306893,"angularVelocity":-0.12404916120679058,"angularAcceleration":-2.3218127658740992,"curveRadius":-22.2722342314651},{"acceleration":-4.9948201324750245,"curvature":-0.04627323492799021,"pose":{"rotation":{"radians":-3.1337142485188982},"translation":{"x":5.185382111857505,"y":4.103959966314453}},"time":0.6012207803160332,"velocity":2.8426278361207395,"position":0.9022600643180423,"holonomicRotation":-179.0522528643345,"angularVelocity":-0.1276789600563449,"angularAcceleration":-2.254393604263047,"curveRadius":-21.610764874255857},{"acceleration":-4.994305929579723,"curvature":-0.04761566327523496,"pose":{"rotation":{"radians":-3.1339259779790267},"translation":{"x":5.180807889802387,"y":4.103924896550673}},"time":0.6028345557666421,"velocity":2.834568147818753,"position":0.9068344208080702,"holonomicRotation":-179.05995812560008,"angularVelocity":-0.13120131431457407,"angularAcceleration":-2.1826792921531197,"curveRadius":-21.001492601702406},{"acceleration":-4.993789267413196,"curvature":-0.04892384187645899,"pose":{"rotation":{"radians":-3.134143749048157},"translation":{"x":5.176235337868682,"y":4.103890835417831}},"time":0.6044523502929209,"velocity":2.8264892228765426,"position":0.9114070996014257,"holonomicRotation":-179.06766338686563,"angularVelocity":-0.1346098442002854,"angularAcceleration":-2.1068991335702147,"curveRadius":-20.439931976829822},{"acceleration":-4.9932703854182385,"curvature":-0.05019546474745508,"pose":{"rotation":{"radians":-3.134367442560946},"translation":{"x":5.171663575565151,"y":4.103857802895606}},"time":0.6060745114268753,"velocity":2.8183893337259915,"position":0.9159789812389477,"holonomicRotation":-179.07536864813122,"angularVelocity":-0.1378984541710148,"angularAcceleration":-2.027301666828001,"curveRadius":-19.922118562528105},{"acceleration":-4.992749522929591,"curvature":-0.05142831395267366,"pose":{"rotation":{"radians":-3.1345969323780847},"translation":{"x":5.167091722400559,"y":4.103825818963678}},"time":0.6077013908215125,"velocity":2.8102667324045525,"position":0.9205509462793312,"holonomicRotation":-179.0830739093968,"angularVelocity":-0.1410613582637793,"angularAcceleration":-1.9441540062468976,"curveRadius":-19.44454179307218},{"acceleration":-4.992226918616682,"curvature":-0.05262027339765301,"pose":{"rotation":{"radians":-3.134832085622143},"translation":{"x":5.162518897883667,"y":4.103794903601727}},"time":0.6093333443391972,"velocity":2.802119650123636,"position":0.9251238752993237,"holonomicRotation":-179.09077917066236,"angularVelocity":-0.1440931016172231,"angularAcceleration":-1.8577387901005573,"curveRadius":-19.004082180321824},{"acceleration":-4.99170280944238,"curvature":-0.05376933713295701,"pose":{"rotation":{"radians":-3.135072762933727},"translation":{"x":5.157944221523241,"y":4.103765076789434}},"time":0.6109707321443101,"velocity":2.7939462968167073,"position":0.9296986488938718,"holonomicRotation":-179.09848443192794,"angularVelocity":-0.14698858195499456,"angularAcceleration":-1.7683534277768662,"curveRadius":-18.597960349172073},{"acceleration":-4.991177431132151,"curvature":-0.054873612988653835,"pose":{"rotation":{"radians":-3.1353188187469945},"translation":{"x":5.153366812828041,"y":4.103736358506477}},"time":0.6126139188004229,"velocity":2.7857448606635793,"position":0.9342761476762491,"holonomicRotation":-179.1061896931935,"angularVelocity":-0.14974306926859152,"angularAcceleration":-1.6763082291046694,"curveRadius":-18.223695243226814},{"acceleration":-4.990651016183046,"curvature":-0.05593133507523582,"pose":{"rotation":{"radians":-3.1355701015802016},"translation":{"x":5.148785791306833,"y":4.103708768732537}},"time":0.6142632733721861,"velocity":2.777513507593963,"position":0.9388572522781332,"holonomicRotation":-179.11389495445908,"angularVelocity":-0.1523522215956592,"angularAcceleration":-1.5819232393908242,"curveRadius":-17.87906544077401},{"acceleration":-4.990123794593598,"curvature":-0.05694086486297185,"pose":{"rotation":{"radians":-3.135826454346346},"translation":{"x":5.144200276468377,"y":4.103682327447295}},"time":0.6159191695321644,"velocity":2.7692503807646793,"position":0.9434428433496599,"holonomicRotation":-179.12160021572467,"angularVelocity":-0.15481210255835826,"angularAcceleration":-1.4855285145001456,"curveRadius":-17.562079578638283},{"acceleration":-4.989595992392532,"curvature":-0.05790069973185608,"pose":{"rotation":{"radians":-3.136087714673415},"translation":{"x":5.139609387821437,"y":4.103657054630429}},"time":0.617581985672845,"velocity":2.760953600013054,"position":0.9480338015594316,"holonomicRotation":-179.12930547699023,"angularVelocity":-0.15711919115839976,"angularAcceleration":-1.3874586273244187,"curveRadius":-17.27094844502916},{"acceleration":-4.989067831464491,"curvature":-0.05880947698439072,"pose":{"rotation":{"radians":-3.1363537152439553},"translation":{"x":5.135012244874778,"y":4.1036329702616205}},"time":0.619252105024071,"velocity":2.7526212612831458,"position":0.9526310075944969,"holonomicRotation":-179.1370107382558,"angularVelocity":-0.15927039606187662,"angularAcceleration":-1.2880545943603472,"curveRadius":-17.004062121916526},{"acceleration":-4.988539528513088,"curvature":-0.05966597864198362,"pose":{"rotation":{"radians":-3.1366242841416505},"translation":{"x":5.13040796713716,"y":4.103610094320549}},"time":0.6209299157761601,"velocity":2.7442514360249852,"position":0.9572353421602955,"holonomicRotation":-179.14471599952137,"angularVelocity":-0.16126306102060609,"angularAcceleration":-1.187657759522863,"curveRadius":-16.759969797869967},{"acceleration":-4.98801129571068,"curvature":-0.06046913220423911,"pose":{"rotation":{"radians":-3.1368992452111457},"translation":{"x":5.125795674117348,"y":4.103588446786894}},"time":0.6226158112089782,"velocity":2.735842170562701,"position":0.9618476859805585,"holonomicRotation":-179.15242126078695,"angularVelocity":-0.1630949726434558,"angularAcceleration":-1.0866104665741116,"curveRadius":-16.53736317270808},{"acceleration":-4.9874833385101915,"curvature":-0.061218015853236614,"pose":{"rotation":{"radians":-3.1371784184272995},"translation":{"x":5.121174485324105,"y":4.1035680476403344}},"time":0.6243101898272696,"velocity":2.727391485434845,"position":0.9664689197971892,"holonomicRotation":-179.16012652205254,"angularVelocity":-0.16476436443426448,"angularAcceleration":-0.9852531026932649,"curveRadius":-16.335060620020563},{"acceleration":-4.986955856134553,"curvature":-0.0619118596252361,"pose":{"rotation":{"radians":-3.1374616202701144},"translation":{"x":5.116543520266193,"y":4.103548916860553}},"time":0.6260134555025407,"velocity":2.718897374700999,"position":0.9710999243701022,"holonomicRotation":-179.1678317833181,"angularVelocity":-0.1662699172105723,"angularAcceleration":-0.8839212802595595,"curveRadius":-16.151994239119684},{"acceleration":-4.986429041199652,"curvature":-0.06255004410741234,"pose":{"rotation":{"radians":-3.137748664105547},"translation":{"x":5.111901898452374,"y":4.103531074427229}},"time":0.6277260176218276,"velocity":2.7103578052145285,"position":0.975741580477026,"holonomicRotation":-179.17553704458368,"angularVelocity":-0.16761075829021613,"angularAcceleration":-0.7829444926658778,"curveRadius":-15.987198958369676},{"acceleration":-4.98590307821263,"curvature":-0.0631321012560561,"pose":{"rotation":{"radians":-3.1380393605719403},"translation":{"x":5.107248739391415,"y":4.103514540320041}},"time":0.6294482912436918,"velocity":2.701770715861751,"position":0.98039476891328,"holonomicRotation":-179.18324230584923,"angularVelocity":-0.1687864591913453,"angularAcceleration":-0.6826446658670491,"curveRadius":-15.839802257557087},{"acceleration":-4.985378144446486,"curvature":-0.0636577181185003,"pose":{"rotation":{"radians":-3.1383335179700693},"translation":{"x":5.102583162592075,"y":4.103499334518669}},"time":0.6311806972618136,"velocity":2.6931340167616993,"position":0.9850603704915264,"holonomicRotation":-179.19094756711482,"angularVelocity":-0.1697970308645737,"angularAcceleration":-0.5833341968668841,"curveRadius":-15.709014233568302},{"acceleration":-4.984854408049162,"curvature":-0.06412672732838161,"pose":{"rotation":{"radians":-3.1386309426504506},"translation":{"x":5.097904287563119,"y":4.103485477002794}},"time":0.6329236625765573,"velocity":2.6844455884294223,"position":0.9897392660414757,"holonomicRotation":-179.1986528283804,"angularVelocity":-0.17064291404159723,"angularAcceleration":-0.48531268515111226,"curveRadius":-15.594121853110906},{"acceleration":-4.984332028473389,"curvature":-0.06453911478971198,"pose":{"rotation":{"radians":-3.138931439403656},"translation":{"x":5.093211233813309,"y":4.103472987752095}},"time":0.6346776202749356,"velocity":2.675703280896808,"position":0.9944323364095806,"holonomicRotation":-179.20635808964596,"angularVelocity":-0.17132497179565298,"angularAcceleration":-0.38886784709026107,"curveRadius":-15.494479638561875},{"acceleration":-4.98381115648633,"curvature":-0.06489500494982417,"pose":{"rotation":{"radians":-3.139234811847296},"translation":{"x":5.08850312085141,"y":4.103461886746254}},"time":0.6364430098193975,"velocity":2.6669049127895743,"position":0.9991404624586935,"holonomicRotation":-179.21406335091154,"angularVelocity":-0.17184447737995306,"angularAcceleration":-0.2942724940961539,"curveRadius":-15.40950649087992},{"acceleration":-4.983291931888928,"curvature":-0.06519466818020783,"pose":{"rotation":{"radians":-3.139540862809367},"translation":{"x":5.083779068186183,"y":4.103452193964947}},"time":0.6382202772459091,"velocity":2.65804827036223,"position":1.0038645250677039,"holonomicRotation":-179.2217686121771,"angularVelocity":-0.17220310095448665,"angularAcceleration":-0.20178368724029663,"curveRadius":-15.33867765437275},{"acceleration":-4.982774485460732,"curvature":-0.06543851134980677,"pose":{"rotation":{"radians":-3.1398493947087807},"translation":{"x":5.07903819532639,"y":4.103443929387859}},"time":0.640009875371817,"velocity":2.649131106481228,"position":1.0086054051311468,"holonomicRotation":-179.22947387344269,"angularVelocity":-0.17240289590564206,"angularAcceleration":-0.11164235604798359,"curveRadius":-15.281521223097824},{"acceleration":-4.982258936819636,"curvature":-0.06562707571579128,"pose":{"rotation":{"radians":-3.1401602099245824},"translation":{"x":5.074279621780797,"y":4.103437112994666}},"time":0.6418122640140198,"velocity":2.6401511395609907,"position":1.0133639835587904,"holonomicRotation":-179.23717913470827,"angularVelocity":-0.17244627963362805,"angularAcceleration":-0.02407012947716009,"curveRadius":-15.237613273074402},{"acceleration":-4.981745395023556,"curvature":-0.06576102600534828,"pose":{"rotation":{"radians":-3.1404731111651283},"translation":{"x":5.069502467058165,"y":4.10343176476505}},"time":0.6436279102180097,"velocity":2.631106052445272,"position":1.0181411412752075,"holonomicRotation":-179.24488439597383,"angularVelocity":-0.172336020012179,"angularAcceleration":0.0607274816022883,"curveRadius":-15.206575394956142},{"acceleration":-4.9812339571906445,"curvature":-0.06584115145312727,"pose":{"rotation":{"radians":-3.1407879018204428},"translation":{"x":5.064705850667259,"y":4.103427904678689}},"time":0.6454572884983705,"velocity":2.621993491234592,"position":1.0229377592193194,"holonomicRotation":-179.2525896572394,"angularVelocity":-0.17207521194162032,"angularAcceleration":0.1425665065331571,"curveRadius":-15.188069739513992},{"acceleration":-4.980724710212144,"curvature":-0.06586835613077364,"pose":{"rotation":{"radians":-3.1411043863123203},"translation":{"x":5.05988889211684,"y":4.103425552715265}},"time":0.6473008810913781,"velocity":2.612811064051035,"position":1.0277547183439322,"holonomicRotation":-179.26029491850497,"angularVelocity":-0.17166726156193965,"angularAcceleration":0.22128011428769392,"curveRadius":-15.181796825392471},{"acceleration":-4.980217727607207,"curvature":-0.06584365434519954,"pose":{"rotation":{"radians":-3.141422370426389},"translation":{"x":5.055050710915672,"y":4.103424728854457}},"time":0.6491591782203677,"velocity":2.603556339746079,"position":1.0325928996152451,"holonomicRotation":-179.26800017977055,"angularVelocity":-0.17111586145628302,"angularAcceleration":0.2967233264555604,"curveRadius":-15.187492400669086},{"acceleration":-4.979713071775646,"curvature":-0.06576816243712383,"pose":{"rotation":{"radians":3.141443645541599},"translation":{"x":5.050190426572517,"y":4.103425453075946}},"time":0.6510326783746039,"velocity":2.5942268465380556,"position":1.0374531840123578,"holonomicRotation":-179.27570544103614,"angularVelocity":3353.5444348706696,"angularAcceleration":1790080.2106416028,"curveRadius":-15.204925345998946},{"acceleration":-4.979210792220165,"curvature":-0.06564309000605219,"pose":{"rotation":{"radians":3.1411232377586127},"translation":{"x":5.045307158596139,"y":4.103427745359411}},"time":0.6529218886024142,"velocity":2.58482007058297,"position":1.0423364525267524,"holonomicRotation":-179.2834107023017,"angularVelocity":-0.16959879756618476,"angularAcceleration":-1775193.6678616102,"curveRadius":-15.2338959044707},{"acceleration":-4.978710925813391,"curvature":-0.06546973862617773,"pose":{"rotation":{"radians":3.140801901632792},"translation":{"x":5.040400026495301,"y":4.103431625684531}},"time":0.6548273248194239,"velocity":2.5753334544709032,"position":1.047243586161778,"holonomicRotation":-179.29111596356728,"angularVelocity":-0.16864176452194263,"angularAcceleration":0.5022645395835239,"curveRadius":-15.274232355040366},{"acceleration":-4.978213496419661,"curvature":-0.06524948720416057,"pose":{"rotation":{"radians":3.140479822814172},"translation":{"x":5.035468149778765,"y":4.103437114030989}},"time":0.6567495121327671,"velocity":2.565764395644971,"position":1.0521754659321145,"holonomicRotation":-179.29882122483284,"angularVelocity":-0.1675584977512098,"angularAcceleration":0.5635594217135439,"curveRadius":-15.325790942556802},{"acceleration":-4.977718514640906,"curvature":-0.0649837911730755,"pose":{"rotation":{"radians":3.140157184105832},"translation":{"x":5.030510647955295,"y":4.103444230378461}},"time":0.6586889851822282,"velocity":2.5561102447380217,"position":1.0571329728632353,"holonomicRotation":-179.30652648609842,"angularVelocity":-0.16635379822875257,"angularAcceleration":0.6211478539451601,"curveRadius":-15.388452750265614},{"acceleration":-4.977225977888635,"curvature":-0.06467416691122525,"pose":{"rotation":{"radians":3.13983416521014},"translation":{"x":5.025526640533655,"y":4.10345299470663}},"time":0.6606462884993277,"velocity":2.5463683038215463,"position":1.0621169879908623,"holonomicRotation":-179.314231747364,"angularVelocity":-0.16503262058056728,"angularAcceleration":0.6749989317665394,"curveRadius":-15.46212417969985},{"acceleration":-4.976735869439986,"curvature":-0.06432219316462776,"pose":{"rotation":{"radians":3.1395109424945424},"translation":{"x":5.0205152470226055,"y":4.103463426995174}},"time":0.6626219768854442,"velocity":2.5365358245635243,"position":1.067128392360421,"holonomicRotation":-179.32193700862956,"angularVelocity":-0.1636000484027298,"angularAcceleration":0.7251002677873774,"curveRadius":-15.546733573598404},{"acceleration":-4.976248159032934,"curvature":-0.06392949790621537,"pose":{"rotation":{"radians":3.1391876887682453},"translation":{"x":5.015475586930911,"y":4.103475547223774}},"time":0.6646166158101392,"velocity":2.5266100062865755,"position":1.072168067026484,"holonomicRotation":-179.32964226989515,"angularVelocity":-0.16206127449688107,"angularAcceleration":0.7714548667418749,"curveRadius":-15.6422314072762},{"acceleration":-4.975762802208417,"curvature":-0.06349775088441106,"pose":{"rotation":{"radians":3.1388645730798483},"translation":{"x":5.010406779767336,"y":4.103489375372111}},"time":0.6666307818309495,"velocity":2.5165879939227556,"position":1.0772368930522223,"holonomicRotation":-179.3373475311607,"angularVelocity":-0.16042157650288869,"angularAcceleration":0.8140828397714441,"curveRadius":-15.748589297601464},{"acceleration":-4.975279739841933,"curvature":-0.06302865980051654,"pose":{"rotation":{"radians":3.138541760528733},"translation":{"x":5.00530794504064,"y":4.103504931419863}},"time":0.6686650630359975,"velocity":2.506466875858139,"position":1.0823357515088559,"holonomicRotation":-179.3450527924263,"angularVelocity":-0.15868629681795587,"angularAcceleration":0.8530185898718273,"curveRadius":-15.865798244242608},{"acceleration":-4.974798898587529,"curvature":-0.06252395927976462,"pose":{"rotation":{"radians":3.1382194120932967},"translation":{"x":5.000178202259589,"y":4.103522235346711}},"time":0.6707200595108741,"velocity":2.4962436816583216,"position":1.0874655234750967,"holonomicRotation":-179.35275805369187,"angularVelocity":-0.1568608216009565,"angularAcceleration":0.8883106318267476,"curveRadius":-15.993868774776105},{"acceleration":-4.974320190005758,"curvature":-0.06198540606677124,"pose":{"rotation":{"radians":3.1378976844765143},"translation":{"x":4.9950166709329435,"y":4.103541307132335}},"time":0.6727963838313745,"velocity":2.4859153796698563,"position":1.0926270900366113,"holonomicRotation":-179.36046331495743,"angularVelocity":-0.15495056027897228,"angularAcceleration":0.9200206842078577,"curveRadius":-16.13282970063616},{"acceleration":-4.973843510630097,"curvature":-0.06141477283635308,"pose":{"rotation":{"radians":3.13757672996728},"translation":{"x":4.989822470569469,"y":4.103562166756413}},"time":0.6748946615837689,"velocity":2.47547887448761,"position":1.0978213322854709,"holonomicRotation":-179.368168576223,"angularVelocity":-0.15296092658274277,"angularAcceleration":0.9482222713170991,"curveRadius":-16.2827273279121},{"acceleration":-4.973368741628186,"curvature":-0.06081383914958889,"pose":{"rotation":{"radians":3.1372566963172352},"translation":{"x":4.9845947206779275,"y":4.103584834198628}},"time":0.6770155319144482,"velocity":2.464931004279963,"position":1.1030491313196198,"holonomicRotation":-179.37587383748857,"angularVelocity":-0.1508973205082,"angularAcceleration":0.9729996429728847,"curveRadius":-16.443625562599596},{"acceleration":-4.972895748609591,"curvature":-0.06018438837429219,"pose":{"rotation":{"radians":3.1369377266351877},"translation":{"x":4.979332540767081,"y":4.103609329438659}},"time":0.679159648110916,"velocity":2.4542685379620233,"position":1.1083113682423456,"holonomicRotation":-179.38357909875415,"angularVelocity":-0.14876511010599758,"angularAcceleration":0.994447225255331,"curveRadius":-16.615604594681745},{"acceleration":-4.972424380943002,"curvature":-0.05952820010121746,"pose":{"rotation":{"radians":3.1366199592955706},"translation":{"x":4.9740350503456945,"y":4.1036356724561855}},"time":0.6813276782162642,"velocity":2.4434881722075716,"position":1.1136089241617537,"holonomicRotation":-179.39128436001974,"angularVelocity":-0.14656961581539066,"angularAcceleration":1.0126678062223435,"curveRadius":-16.798760894830888},{"acceleration":-4.971954472188008,"curvature":-0.058847042973857566,"pose":{"rotation":{"radians":3.1363035278624714},"translation":{"x":4.968701368922529,"y":4.103663883230887}},"time":0.6835203056794542,"velocity":2.4325865282861217,"position":1.11894268019026,"holonomicRotation":-179.3989896212853,"angularVelocity":-0.14431609491876668,"angularAcceleration":1.0277719012719746,"curveRadius":-16.993207295806585},{"acceleration":-4.971485838631107,"curvature":-0.05814267477265814,"pose":{"rotation":{"radians":3.1359885610284435},"translation":{"x":4.963330616006349,"y":4.103693981742444}},"time":0.6857382300439052,"velocity":2.4215601487170986,"position":1.1243135174440833,"holonomicRotation":-179.40669488255088,"angularVelocity":-0.14200972723695054,"angularAcceleration":1.0398766156243655,"curveRadius":-17.19907114542062},{"acceleration":-4.971018280123774,"curvature":-0.057416829672448155,"pose":{"rotation":{"radians":3.1356751825686477},"translation":{"x":4.957921911105918,"y":4.103725987970536}},"time":0.6879821676771195,"velocity":2.4104054937229327,"position":1.1297223170427546,"holonomicRotation":-179.41440014381644,"angularVelocity":-0.13965560145574946,"angularAcceleration":1.0491048175117788,"curveRadius":-17.416496273040597},{"acceleration":-4.970551578595003,"curvature":-0.056671221176384526,"pose":{"rotation":{"radians":3.135363511307628},"translation":{"x":4.952474373729997,"y":4.103759921894843}},"time":0.6902528525443001,"velocity":2.399118937471876,"position":1.1351699601086385,"holonomicRotation":-179.42210540508202,"angularVelocity":-0.13725870354110015,"angularAcceleration":1.0555836916398675,"curveRadius":-17.64564057809134},{"acceleration":-4.970085498058505,"curvature":-0.05590753454224315,"pose":{"rotation":{"radians":3.135053661098401},"translation":{"x":4.94698712338735,"y":4.103795803495047}},"time":0.6925510370291751,"velocity":2.387696764091736,"position":1.1406573277664602,"holonomicRotation":-179.4298106663476,"angularVelocity":-0.13482390611648185,"angularAcceleration":1.0594438525899195,"curveRadius":-17.88667678136317},{"acceleration":-4.969619784122091,"curvature":-0.05512742037697888,"pose":{"rotation":{"radians":3.134745740818488},"translation":{"x":4.9414592795867405,"y":4.103833652750826}},"time":0.6948774928055343,"velocity":2.376135163438656,"position":1.1461853011428524,"holonomicRotation":-179.43751592761316,"angularVelocity":-0.132355956662487,"angularAcceleration":1.060819414266712,"curveRadius":-18.13979310407926},{"acceleration":-4.96915416310831,"curvature":-0.05433249737197261,"pose":{"rotation":{"radians":3.1344398543717},"translation":{"x":4.935889961836931,"y":4.10387348964186}},"time":0.6972330117632913,"velocity":2.3644302266034374,"position":1.1517547613659105,"holonomicRotation":-179.44522118887875,"angularVelocity":-0.12985947142588466,"angularAcceleration":1.0598451047830195,"curveRadius":-18.405191153901374},{"acceleration":-4.9686883416354926,"curvature":-0.05352434337069797,"pose":{"rotation":{"radians":3.134136100707424},"translation":{"x":4.930278289646685,"y":4.103915334147828}},"time":0.6996184069932363,"velocity":2.352577941134217,"position":1.1573665895647658,"holonomicRotation":-179.4529264501443,"angularVelocity":-0.12733892499778704,"angularAcceleration":1.0566577800005825,"curveRadius":-18.68308767609193},{"acceleration":-4.968222005670085,"curvature":-0.05270449556155615,"pose":{"rotation":{"radians":3.133834573846553},"translation":{"x":4.924623382524764,"y":4.103959206248413}},"time":0.7020345138350259,"velocity":2.3405741859547877,"position":1.1630216668691673,"holonomicRotation":-179.4606317114099,"angularVelocity":-0.12479864534776715,"angularAcceleration":1.05139375713133,"curveRadius":-18.973713519979547},{"acceleration":-4.967754819620563,"curvature":-0.051874445735790496,"pose":{"rotation":{"radians":3.133535362920684},"translation":{"x":4.9189243599799335,"y":4.104005125923291}},"time":0.7044821909933893,"velocity":2.328414725954453,"position":1.168720874409083,"holonomicRotation":-179.46833697267547,"angularVelocity":-0.12224280675533691,"angularAcceleration":1.044189420037403,"curveRadius":-19.27731440434563},{"acceleration":-4.96728642591218,"curvature":-0.0510356422149275,"pose":{"rotation":{"radians":3.1332385522173976},"translation":{"x":4.913180341520955,"y":4.104053113152147}},"time":0.7069623217279981,"velocity":2.316095206221943,"position":1.1744650933143141,"holonomicRotation":-179.47604223394103,"angularVelocity":-0.11967542643802048,"angularAcceleration":1.0351794288462575,"curveRadius":-19.59414943361893},{"acceleration":-4.966816443147326,"curvature":-0.05018948403145367,"pose":{"rotation":{"radians":3.13294422123962},"translation":{"x":4.907390446656591,"y":4.104103187914656}},"time":0.7094758151229758,"velocity":2.3036111458980257,"position":1.1802552047141257,"holonomicRotation":-179.48374749520661,"angularVelocity":-0.11710035855496741,"angularAcceleration":1.0244975730584658,"curveRadius":-19.924492536589966},{"acceleration":-4.9663444657684614,"curvature":-0.04933731893506144,"pose":{"rotation":{"radians":3.1326524447662427},"translation":{"x":4.901553794895605,"y":4.1041553701905}},"time":0.7120236074426084,"velocity":2.2909579316114907,"position":1.186092089736887,"holonomicRotation":-179.49145275647217,"angularVelocity":-0.11452129403525478,"angularAcceleration":1.0122742343789184,"curveRadius":-20.26863278315175},{"acceleration":-4.9658700620835114,"curvature":-0.048480447110649756,"pose":{"rotation":{"radians":3.132363292927503},"translation":{"x":4.895669505746761,"y":4.10420967995936}},"time":0.7146066635804766,"velocity":2.2781308104677698,"position":1.1919766295097325,"holonomicRotation":-179.49915801773776,"angularVelocity":-0.11194175554326889,"angularAcceleration":0.9986381845013794,"curveRadius":-20.62687247330128},{"acceleration":-4.965392773321579,"curvature":-0.047620116551542316,"pose":{"rotation":{"radians":3.1320768312826925},"translation":{"x":4.889736698718821,"y":4.104266137200915}},"time":0.7172259786099547,"velocity":2.2651248825493466,"position":1.1979097051582388,"holonomicRotation":-179.50686327900334,"angularVelocity":-0.10936509796893934,"angularAcceleration":0.983714270842387,"curveRadius":-20.999528611351373},{"acceleration":-4.964912111621193,"curvature":-0.046757520068837106,"pose":{"rotation":{"radians":3.1317931209054737},"translation":{"x":4.883754493320548,"y":4.104324761894844}},"time":0.7198825794448395,"velocity":2.2519350928884845,"position":1.2038921978061126,"holonomicRotation":-179.5145685402689,"angularVelocity":-0.106794507286666,"angularAcceleration":0.9676239834445767,"curveRadius":-21.38693409162388},{"acceleration":-4.964427558676655,"curvature":-0.04589380065185718,"pose":{"rotation":{"radians":3.131512218475681},"translation":{"x":4.877722009060705,"y":4.104385574020828}},"time":0.7225775266197935,"velocity":2.238556222863965,"position":1.2099249885748955,"holonomicRotation":-179.52227380153448,"angularVelocity":-0.1042330003360914,"angularAcceleration":0.9504850315362192,"curveRadius":-21.789435300550405},{"acceleration":-4.9639385634734445,"curvature":-0.045030045205093995,"pose":{"rotation":{"radians":3.131234176374786},"translation":{"x":4.871638365448057,"y":4.104448593558548}},"time":0.7253119162013125,"velocity":2.2249828809727026,"position":1.2160089585836855,"holonomicRotation":-179.52997906280004,"angularVelocity":-0.10168342608317349,"angularAcceleration":0.9324107545427089,"curveRadius":-22.20739498362475},{"acceleration":-4.963444539911153,"curvature":-0.04416729067827442,"pose":{"rotation":{"radians":3.1309590427885605},"translation":{"x":4.865502681991363,"y":4.104513840487681}},"time":0.7280868818410837,"velocity":2.211209492919539,"position":1.2221449889488731,"holonomicRotation":-179.53768432406562,"angularVelocity":-0.09914846594213157,"angularAcceleration":0.9135104610704042,"curveRadius":-22.641189546450786},{"acceleration":-4.962944864959356,"curvature":-0.043306519355451864,"pose":{"rotation":{"radians":3.1306868618093513},"translation":{"x":4.8593140781993895,"y":4.10458133478791}},"time":0.7309035969849061,"velocity":2.1972302909604524,"position":1.2283339607838868,"holonomicRotation":-179.5453895853312,"angularVelocity":-0.09663063721802596,"angularAcceleration":0.89388830447682,"curveRadius":-23.091211551595404},{"acceleration":-4.962438875047353,"curvature":-0.042448660348402854,"pose":{"rotation":{"radians":3.1304176735470852},"translation":{"x":4.8530716735808985,"y":4.104651096438913}},"time":0.7337632772518243,"velocity":2.183039302433692,"position":1.2345767551989633,"holonomicRotation":-179.55309484659676,"angularVelocity":-0.0941322935225104,"angularAcceleration":0.8736444155723647,"curveRadius":-23.557869477914522},{"acceleration":-4.961925863941953,"curvature":-0.04159459109143274,"pose":{"rotation":{"radians":3.130151514238972},"translation":{"x":4.846774587644653,"y":4.104723145420371}},"time":0.7366671829997816,"velocity":2.168630337396453,"position":1.2408742533009234,"holonomicRotation":-179.56080010786235,"angularVelocity":-0.0916556290783442,"angularAcceleration":0.852873563788487,"curveRadius":-24.041587469914344},{"acceleration":-4.96140507843147,"curvature":-0.04074514014647207,"pose":{"rotation":{"radians":3.1298884163634244},"translation":{"x":4.840421939899415,"y":4.104797501711963}},"time":0.7396166220959993,"velocity":2.153996975285954,"position":1.2472273361929664,"holonomicRotation":-179.5685053691279,"angularVelocity":-0.08920268124368468,"angularAcceleration":0.8316658709125847,"curveRadius":-24.54280428058818},{"acceleration":-4.96087571508915,"curvature":-0.0399010808377677,"pose":{"rotation":{"radians":3.129628408756494},"translation":{"x":4.834012849853949,"y":4.104874185293371}},"time":0.7426129529124315,"velocity":2.1391325505043426,"position":1.2536368849744757,"holonomicRotation":-179.5762106303935,"angularVelocity":-0.08677533385321269,"angularAcceleration":0.8101066067739259,"curveRadius":-25.06197774606313},{"acceleration":-4.960336915838093,"curvature":-0.03906314069846614,"pose":{"rotation":{"radians":3.129371516728569},"translation":{"x":4.827546437017017,"y":4.104953216144273}},"time":0.7456575875690953,"velocity":2.124030136821653,"position":1.2601037807408413,"holonomicRotation":-179.58391589165907,"angularVelocity":-0.08437532147327062,"angularAcceleration":0.7882759840131024,"curveRadius":-25.59958011874007},{"acceleration":-4.959787763111838,"curvature":-0.038231997106735006,"pose":{"rotation":{"radians":3.129117762183275},"translation":{"x":4.821021820897383,"y":4.105034614244349}},"time":0.7487519954508624,"velocity":2.108682530475588,"position":1.2666289045832895,"holonomicRotation":-179.59162115292463,"angularVelocity":-0.08200423311653905,"angularAcceleration":0.766249456221509,"curveRadius":-26.15610158183022},{"acceleration":-4.959227274477057,"curvature":-0.03740828079352194,"pose":{"rotation":{"radians":3.128867163735049},"translation":{"x":4.81443812100381,"y":4.1051183995732785}},"time":0.7518977070265042,"velocity":2.093082231832027,"position":1.2732131375887337,"holonomicRotation":-179.59932641419022,"angularVelocity":-0.07966351720431282,"angularAcceleration":0.7440974342184137,"curveRadius":-26.732049128896936},{"acceleration":-4.958654396618056,"curvature":-0.03659257544212077,"pose":{"rotation":{"radians":3.1286197368304474},"translation":{"x":4.807794456845059,"y":4.105204592110744}},"time":0.7550963180024377,"velocity":2.077221425453143,"position":1.2798573608396324,"holonomicRotation":-179.60703167545577,"angularVelocity":-0.07735448495094449,"angularAcceleration":0.7218859282174552,"curveRadius":-27.327948030925576},{"acceleration":-4.958067998750321,"curvature":-0.03578542176765838,"pose":{"rotation":{"radians":3.1283754938669426},"translation":{"x":4.801089947929896,"y":4.105293211836424}},"time":0.7583494938478423,"velocity":2.061091958399735,"position":1.2865624554138562,"holonomicRotation":-179.61473693672136,"angularVelocity":-0.07507831580939409,"angularAcceleration":0.6996760242043705,"curveRadius":-27.944340197878155},{"acceleration":-4.957466864587204,"curvature":-0.034987314550512426,"pose":{"rotation":{"radians":3.12813444431104},"translation":{"x":4.794323713767081,"y":4.105384278729997}},"time":0.7616589747326846,"velocity":2.0446853165741445,"position":1.293329302384576,"holonomicRotation":-179.62244219798694,"angularVelocity":-0.07283606229800467,"angularAcceleration":0.677524237006213,"curveRadius":-28.581787795009664},{"acceleration":-4.956849684227654,"curvature":-0.034198708571151,"pose":{"rotation":{"radians":3.1278965948174493},"translation":{"x":4.787494873865379,"y":4.105477812771146}},"time":0.7650265809257999,"velocity":2.027992598879198,"position":1.3001587828201535,"holonomicRotation":-179.6301474592525,"angularVelocity":-0.07062865428775679,"angularAcceleration":0.6554828218218338,"curveRadius":-29.240870248637687},{"acceleration":-4.956215043949283,"curvature":-0.03342001813315507,"pose":{"rotation":{"radians":3.1276619493470528},"translation":{"x":4.780602547733553,"y":4.105573833939547}},"time":0.7684542187067133,"velocity":2.0110044889442262,"position":1.3070517777840451,"holonomicRotation":-179.63785272051808,"angularVelocity":-0.06845690396550774,"angularAcceleration":0.6335997153323284,"curveRadius":-29.922186038789956},{"acceleration":-4.955561415691711,"curvature":-0.032651615989859654,"pose":{"rotation":{"radians":3.127430509281246},"translation":{"x":4.773645854880365,"y":4.105672362214884}},"time":0.7719438868524703,"velocity":1.9937112241275443,"position":1.3140091683347213,"holonomicRotation":-179.64555798178364,"angularVelocity":-0.06632151142743388,"angularAcceleration":0.6119185116986616,"curveRadius":-30.626355532006805},{"acceleration":-4.954887144051264,"curvature":-0.03189384159785953,"pose":{"rotation":{"radians":3.1272022735393703},"translation":{"x":4.766623914814579,"y":4.1057734175768354}},"time":0.7754976837695904,"velocity":1.976102561470337,"position":1.3210318355255877,"holonomicRotation":-179.65326324304922,"angularVelocity":-0.06422306822772784,"angularAcceleration":0.5904792110086459,"curveRadius":-31.354015380421036},{"acceleration":-4.954190432434919,"curvature":-0.031146995583266484,"pose":{"rotation":{"radians":3.126977238690278},"translation":{"x":4.759535847044957,"y":4.10587702000508}},"time":0.7791178153516429,"velocity":1.9581677402223767,"position":1.3281206604049232,"holonomicRotation":-179.6609685043148,"angularVelocity":-0.06216206344765788,"angularAcceleration":0.5693176431176614,"curveRadius":-32.10582533800606},{"acceleration":-4.953469326670474,"curvature":-0.030411344795216295,"pose":{"rotation":{"radians":3.126755399063638},"translation":{"x":4.752380771080263,"y":4.105983189479298}},"time":0.7828066036551113,"velocity":1.939895440508565,"position":1.3352765240158229,"holonomicRotation":-179.66867376558037,"angularVelocity":-0.06013888800054816,"angularAcceleration":0.5484661305197186,"curveRadius":-32.8824656303032},{"acceleration":-4.9527216965210785,"curvature":-0.02968712355575897,"pose":{"rotation":{"radians":3.12653674686026},"translation":{"x":4.74515780642926,"y":4.106091945979172}},"time":0.7865664965005815,"velocity":1.9212737376362106,"position":1.342500307396151,"holonomicRotation":-179.67637902684595,"angularVelocity":-0.05815383904922366,"angularAcceleration":0.527953596793599,"curveRadius":-33.6846376551699},{"acceleration":-4.951945214355451,"curvature":-0.028974535482668574,"pose":{"rotation":{"radians":3.1263212722592586},"translation":{"x":4.737866072600711,"y":4.106203309484379}},"time":0.790400078123286,"velocity":1.9022900514658179,"position":1.349792891578504,"holonomicRotation":-179.6840842881115,"angularVelocity":-0.05620712487907073,"angularAcceleration":0.5078055880233361,"curveRadius":-34.51306408684828},{"acceleration":-4.951137330765992,"curvature":-0.028273752229153983,"pose":{"rotation":{"radians":3.126108963522707},"translation":{"x":4.730504689103377,"y":4.1063172999746}},"time":0.7943100810172289,"velocity":1.8829310901742145,"position":1.3571551575901801,"holonomicRotation":-179.6917895493771,"angularVelocity":-0.05429886941532851,"angularAcceleration":0.4880445144167004,"curveRadius":-35.3684927241057},{"acceleration":-4.95029524622226,"curvature":-0.02758492069832814,"pose":{"rotation":{"radians":3.1258998070977944},"translation":{"x":4.723072775446024,"y":4.1064339374295145}},"time":0.7982993991412062,"velocity":1.8631827876294214,"position":1.3645879864531527,"holonomicRotation":-179.69949481064268,"angularVelocity":-0.05242911655888608,"angularAcceleration":0.4686898357903605,"curveRadius":-36.251690223659324},{"acceleration":-4.949415878491183,"curvature":-0.026908157443776688,"pose":{"rotation":{"radians":3.1256937877184607},"translation":{"x":4.715569451137413,"y":4.106553241828803}},"time":0.8023711026839154,"velocity":1.8430302334626274,"position":1.3720922591840627,"holonomicRotation":-179.70720007190823,"angularVelocity":-0.05059783384832082,"angularAcceleration":0.4497583606852565,"curveRadius":-37.16345134702933},{"acceleration":-4.948495824519507,"curvature":-0.026243556370889428,"pose":{"rotation":{"radians":3.1254908885014956},"translation":{"x":4.707993835686309,"y":4.1066752331521466}},"time":0.8065284546200602,"velocity":1.822457594765557,"position":1.379668856794203,"holonomicRotation":-179.71490533317382,"angularVelocity":-0.048804917188055505,"angularAcceleration":0.43126410460403425,"curveRadius":-38.10459168976223},{"acceleration":-4.947531316425637,"curvature":-0.02559118609913508,"pose":{"rotation":{"radians":3.1252910910427047},"translation":{"x":4.700345048601472,"y":4.106799931379223}},"time":0.8107749293314007,"velocity":1.8014480281467902,"position":1.3873186602895227,"holonomicRotation":-179.72261059443937,"angularVelocity":-0.04705019395435595,"angularAcceleration":0.41321881159763585,"curveRadius":-39.07595357738411},{"acceleration":-4.946518169241975,"curvature":-0.02495109450627949,"pose":{"rotation":{"radians":3.1250943755079392},"translation":{"x":4.6926222093916685,"y":4.106927356489713}},"time":0.8151142336177181,"velocity":1.7799835806526518,"position":1.3950425506706232,"holonomicRotation":-179.73031585570496,"angularVelocity":-0.04533342715462595,"angularAcceleration":0.39563180787834856,"curveRadius":-40.0784021618101},{"acceleration":-4.945451720316481,"curvature":-0.024323306044702692,"pose":{"rotation":{"radians":3.124900720723358},"translation":{"x":4.684824437565658,"y":4.107057528463297}},"time":0.8195503304850731,"velocity":1.7580450777685004,"position":1.402841408932781,"holonomicRotation":-179.73802111697054,"angularVelocity":-0.043654318282859,"angularAcceleration":0.3785104162452854,"curveRadius":-41.11283220143453},{"acceleration":-4.944326757126777,"curvature":-0.023707826185001953,"pose":{"rotation":{"radians":3.12471010426243},"translation":{"x":4.676950852632206,"y":4.107190467279654}},"time":0.8240874661753184,"velocity":1.7356119963745058,"position":1.4107161160659496,"holonomicRotation":-179.7457263782361,"angularVelocity":-0.04201251052240189,"angularAcceleration":0.36185996464398307,"curveRadius":-42.1801641448097},{"acceleration":-4.943137431887708,"curvature":-0.023104642216194744,"pose":{"rotation":{"radians":3.1245225025285586},"translation":{"x":4.669000574100075,"y":4.107326192918467}},"time":0.8287302009955628,"velocity":1.712662320098227,"position":1.4186675530547903,"holonomicRotation":-179.75343163950168,"angularVelocity":-0.040407591890350106,"angularAcceleration":0.3456838898171822,"curveRadius":-43.281345395561665},{"acceleration":-4.94187715966908,"curvature":-0.022513723424557278,"pose":{"rotation":{"radians":3.124337890838428},"translation":{"x":4.660972721478028,"y":4.107464725359411}},"time":0.8334834446239795,"velocity":1.689172373976612,"position":1.426696600878692,"holonomicRotation":-179.76113690076724,"angularVelocity":-0.03883909695409503,"angularAcceleration":0.32998412428894386,"curveRadius":-44.41735296922191},{"acceleration":-4.94053849641811,"curvature":-0.021935027098703357,"pose":{"rotation":{"radians":3.1241562434975494},"translation":{"x":4.652866414274827,"y":4.107606084582169}},"time":0.8383524967157515,"velocity":1.6651166346761472,"position":1.4348041405118064,"holonomicRotation":-179.76884216203283,"angularVelocity":-0.037306510067046286,"angularAcceleration":0.31476083191604964,"curveRadius":-45.58918461783495},{"acceleration":-4.939112991568715,"curvature":-0.02136848749029674,"pose":{"rotation":{"radians":3.1239775338782154},"translation":{"x":4.644680771999237,"y":4.107750290566421}},"time":0.8433430938186711,"velocity":1.6404675116894318,"position":1.4429910529230774,"holonomicRotation":-179.7765474232984,"angularVelocity":-0.03580926603540552,"angularAcceleration":0.3000130046091778,"curveRadius":-46.79788405492397},{"acceleration":-4.937591009646602,"curvature":-0.02081403286487812,"pose":{"rotation":{"radians":3.123801734490701},"translation":{"x":4.63641491416002,"y":4.107897363291847}},"time":0.8484614638438063,"velocity":1.6151950938692798,"position":1.4512582190762833,"holonomicRotation":-179.78425268456397,"angularVelocity":-0.0343467523158995,"angularAcceleration":0.2857381768656706,"curveRadius":-48.04450951393535},{"acceleration":-4.935961512280473,"curvature":-0.020271574397665283,"pose":{"rotation":{"radians":3.123628817054215},"translation":{"x":4.628067960265938,"y":4.108047322738126}},"time":0.8537143896385551,"velocity":1.5892668543195345,"position":1.4596065199300776,"holonomicRotation":-179.79195794582955,"angularVelocity":-0.03291830938461271,"angularAcceleration":0.27193282126977125,"curveRadius":-49.33015958124949},{"acceleration":-4.934211790385972,"curvature":-0.01974101143184556,"pose":{"rotation":{"radians":3.1234587525634807},"translation":{"x":4.619639029825754,"y":4.108200188884938}},"time":0.8591092835991769,"velocity":1.562647304931152,"position":1.4680368364380327,"holonomicRotation":-179.7996632070951,"angularVelocity":-0.03152323140651841,"angularAcceleration":0.25859228898235664,"curveRadius":-50.65596580258459},{"acceleration":-4.932327132624793,"curvature":-0.01922223662449154,"pose":{"rotation":{"radians":3.1232915113532917},"translation":{"x":4.611127242348234,"y":4.108355981711964}},"time":0.8646542757676502,"velocity":1.5352975896083993,"position":1.4765500495486872,"holonomicRotation":-179.8073684683607,"angularVelocity":-0.03016076580591629,"angularAcceleration":0.24571100539123994,"curveRadius":-52.02308240893647},{"acceleration":-4.93029041142061,"curvature":-0.018715127189552573,"pose":{"rotation":{"radians":3.123127063160933},"translation":{"x":4.602531717342138,"y":4.108514721198883}},"time":0.8703583185256865,"velocity":1.50717500229212,"position":1.4851470402056048,"holonomicRotation":-179.81507372962628,"angularVelocity":-0.02883011213878548,"angularAcceleration":0.2332825547732947,"curveRadius":-53.43271193787208},{"acceleration":-4.928081562211905,"curvature":-0.01821955575943042,"pose":{"rotation":{"radians":3.1229653771851877},"translation":{"x":4.593851574316229,"y":4.108676427325375}},"time":0.8762313118867929,"velocity":1.4782324119942583,"position":1.4938286893474195,"holonomicRotation":-179.82277899089183,"angularVelocity":-0.027530420316180006,"angularAcceleration":0.221299726169044,"curveRadius":-54.886080275717},{"acceleration":-4.925676921664934,"curvature":-0.017735385038941377,"pose":{"rotation":{"radians":3.1228064221424434},"translation":{"x":4.585085932779273,"y":4.10884112007112}},"time":0.8822842545815217,"velocity":1.4484175718546723,"position":1.502595877907894,"holonomicRotation":-179.83048425215742,"angularVelocity":-0.026260787646767356,"angularAcceleration":0.20975461580336993,"curveRadius":-56.384453892842565},{"acceleration":-4.923048378639618,"curvature":-0.017262471652843794,"pose":{"rotation":{"radians":3.122650166321799},"translation":{"x":4.57623391224003,"y":4.1090088194157985}},"time":0.88852942775686,"velocity":1.4176722821794998,"position":1.511449486815982,"holonomicRotation":-179.83818951342298,"angularVelocity":-0.02502025424391951,"angularAcceleration":0.19863875156362826,"curveRadius":-57.92913205654773},{"acceleration":-4.92016227278458,"curvature":-0.01680066194638993,"pose":{"rotation":{"radians":3.1224965776362525},"translation":{"x":4.567294632207263,"y":4.1091795453390905}},"time":0.8949806203541039,"velocity":1.3859313677480731,"position":1.5203903969958865,"holonomicRotation":-179.84589477468856,"angularVelocity":-0.02380779727646297,"angularAcceleration":0.18794307396349105,"curveRadius":-59.52146428461866},{"acceleration":-4.916977948764344,"curvature":-0.01634980032325784,"pose":{"rotation":{"radians":3.1223456236722007},"translation":{"x":4.558267212189737,"y":4.109353317820675}},"time":0.9016534083707901,"velocity":1.3531214162132479,"position":1.5294194893671158,"holonomicRotation":-179.85360003595414,"angularVelocity":-0.022622322734420136,"angularAcceleration":0.17765805523544081,"curveRadius":-61.162826470576825},{"acceleration":-4.9134458333288755,"curvature":-0.015909724980698106,"pose":{"rotation":{"radians":3.122197271736046},"translation":{"x":4.549150771696214,"y":4.109530156840234}},"time":0.9085655046819555,"velocity":1.3191592053935843,"position":1.5385376448445567,"holonomicRotation":-179.8613052972197,"angularVelocity":-0.02146265466745032,"angularAcceleration":0.16777371361225915,"curveRadius":-62.854637727126864},{"acceleration":-4.90950484093352,"curvature":-0.015480269341341573,"pose":{"rotation":{"radians":3.122051488899531},"translation":{"x":4.539944430235457,"y":4.109710082377445}},"time":0.915737202569563,"velocity":1.2839497198966625,"position":1.5477457443385338,"holonomicRotation":-179.8690105584853,"angularVelocity":-0.02032752059549462,"angularAcceleration":0.15827968352057545,"curveRadius":-64.59835923716147},{"acceleration":-4.905078817074163,"curvature":-0.015061263449013262,"pose":{"rotation":{"radians":3.121908242041723},"translation":{"x":4.530647307316229,"y":4.109893114411988}},"time":0.9231919456705994,"velocity":1.2473836174250394,"position":1.557044668754879,"holonomicRotation":-179.87671581975084,"angularVelocity":-0.019215532429020042,"angularAcceleration":0.14916518938392306,"curveRadius":-66.39549220988594},{"acceleration":-4.900071575005303,"curvature":-0.014652533077134438,"pose":{"rotation":{"radians":3.1217674978887384},"translation":{"x":4.521258522447294,"y":4.110079272923546}},"time":0.9309570714887866,"velocity":1.2093339451270004,"position":1.5664352989949948,"holonomicRotation":-179.88442108101643,"angularVelocity":-0.018125160658047427,"angularAcceleration":0.14041907323881117,"curveRadius":-68.24758522883114},{"acceleration":-4.894359830640376,"curvature":-0.014253901081052322,"pose":{"rotation":{"radians":3.1216292230539655},"translation":{"x":4.511777195137412,"y":4.110268577891795}},"time":0.9390647979453748,"velocity":1.169651814440055,"position":1.5759185159559268,"holonomicRotation":-179.892126342282,"angularVelocity":-0.017054699059383237,"angularAcceleration":0.1320298118585823,"curveRadius":-70.15623262106804},{"acceleration":-4.887782916595988,"curvature":-0.013865189842169999,"pose":{"rotation":{"radians":3.1214933840715644},"translation":{"x":4.50220244489535,"y":4.110461049296418}},"time":0.9475535579581006,"velocity":1.1281605982667706,"position":1.5854952005304266,"holonomicRotation":-179.89983160354757,"angularVelocity":-0.016002217308236193,"angularAcceleration":0.12398533467423177,"curveRadius":-72.12306584930921},{"acceleration":-4.8801274191954445,"curvature":-0.013486219187897868,"pose":{"rotation":{"radians":3.1213599474328952},"translation":{"x":4.492533391229868,"y":4.110656707117094}},"time":0.9564698453218208,"velocity":1.0846479798256539,"position":1.5951662336070307,"holonomicRotation":-179.90753686481315,"angularVelocity":-0.01496549328503085,"angularAcceleration":0.11627306085083215,"curveRadius":-74.14976622190527},{"acceleration":-4.871103546962634,"curvature":-0.013116805438514928,"pose":{"rotation":{"radians":3.1212288796175702},"translation":{"x":4.482769153649732,"y":4.110855571333503}},"time":0.9658708343414071,"velocity":1.0388547888673902,"position":1.6049324960701177,"holonomicRotation":-179.9152421260787,"angularVelocity":-0.013941917712268763,"angularAcceleration":0.10887956263213779,"curveRadius":-76.23807524534107},{"acceleration":-4.8603075153292306,"curvature":-0.012756766035797238,"pose":{"rotation":{"radians":3.1211001471245616},"translation":{"x":4.472908851663702,"y":4.111057661925324}},"time":0.9758282116731003,"velocity":0.9904588729891928,"position":1.6147948687999947,"holonomicRotation":-179.9229473873443,"angularVelocity":-0.012928353392700863,"angularAcceleration":0.1017902893306893,"curveRadius":-78.38977348913217},{"acceleration":-4.847159209346279,"curvature":-0.012405916304392485,"pose":{"rotation":{"radians":3.120973716500494},"translation":{"x":4.4629516047805415,"y":4.111262998872237}},"time":0.9864339870419426,"velocity":0.9390509912378507,"position":1.624754232672952,"holonomicRotation":-179.93065264860988,"angularVelocity":-0.011920922296660771,"angularAcceleration":0.09498891509617727,"curveRadius":-80.60670211404991},{"acceleration":-4.83079376526127,"curvature":-0.012064074030280246,"pose":{"rotation":{"radians":3.1208495543669006},"translation":{"x":4.4528965325090155,"y":4.111471602153924}},"time":0.9978096989634693,"velocity":0.8840972730119315,"position":1.634811468561343,"holonomicRotation":-179.93835790987544,"angularVelocity":-0.010914669292765283,"angularAcceleration":0.08845626637145425,"curveRadius":-82.89073802846767},{"acceleration":-4.809861544594809,"curvature":-0.011731053973791638,"pose":{"rotation":{"radians":3.1207276274458513},"translation":{"x":4.4427427543578855,"y":4.111683491750063}},"time":1.010121813458112,"velocity":0.824877706971501,"position":1.6449674573336546,"holonomicRotation":-179.94606317114102,"angularVelocity":-0.009903004159223797,"angularAcceleration":0.08216826882024861,"curveRadius":-85.24383250082228},{"acceleration":-4.78213075082643,"curvature":-0.011406673530102308,"pose":{"rotation":{"radians":3.120607902583131},"translation":{"x":4.432489389835914,"y":4.111898687640336}},"time":1.0236093343748904,"velocity":0.7603786184429603,"position":1.655223079854575,"holonomicRotation":-179.95376843240658,"angularVelocity":-0.008876713775571218,"angularAcceleration":0.07609184741844437,"curveRadius":-87.66797764142119},{"acceleration":-4.74361833811732,"curvature":-0.011090750564754946,"pose":{"rotation":{"radians":3.120490346771412},"translation":{"x":4.422135558451865,"y":4.11211720980442}},"time":1.0386380947121903,"velocity":0.6890879153077746,"position":1.6655792169850652,"holonomicRotation":-179.96147369367216,"angularVelocity":-0.007822056449158845,"angularAcceleration":0.0701759361878187,"curveRadius":-90.16522318858006},{"acceleration":-4.686422887908876,"curvature":-0.010783099037646215,"pose":{"rotation":{"radians":3.1203749271698773},"translation":{"x":4.411680379714502,"y":4.1123390782219955}},"time":1.055822282204483,"velocity":0.6085555457337768,"position":1.6760367495824289,"holonomicRotation":-179.96917895493775,"angularVelocity":-0.006716616749337818,"angularAcceleration":0.06432888958624494,"curveRadius":-92.73771821150635},{"acceleration":-4.592164344069684,"curvature":-0.010483542370451796,"pose":{"rotation":{"radians":3.1202616111246266},"translation":{"x":4.401122973132587,"y":4.112564312872745}},"time":1.076356265996195,"velocity":0.5142601175237721,"position":1.686596558500386,"holonomicRotation":-179.9768842162033,"angularVelocity":-0.005518463752581879,"angularAcceleration":0.058349758571424486,"curveRadius":-95.38760513035483},{"acceleration":-4.404200123916094,"curvature":-0.01019190015995739,"pose":{"rotation":{"radians":3.1201503661869245},"translation":{"x":4.390462458214882,"y":4.112792933736348}},"time":1.1033150708164086,"velocity":0.39552814599395747,"position":1.697259524589138,"holonomicRotation":-179.9845894774689,"angularVelocity":-0.0041264788422178825,"angularAcceleration":0.051633776780797454,"curveRadius":-98.11713069255389},{"acceleration":-3.5269828900502094,"curvature":-0.01019190015995739,"pose":{"rotation":{"radians":3.1200411601291878},"translation":{"x":4.379697954470153,"y":4.113024960792481}},"time":1.168941297605093,"velocity":0.16406556697171268,"position":1.7080265286954377,"holonomicRotation":-179.99229473873444,"angularVelocity":-0.0016640612005384698,"angularAcceleration":0.03752185310925102,"curveRadius":-98.11713069255389}] \ No newline at end of file diff --git a/src/main/deploy/pathplanner/generatedJSON/Blue0(2).wpilib.json b/src/main/deploy/pathplanner/generatedJSON/Blue0(2).wpilib.json new file mode 100644 index 0000000..086d788 --- /dev/null +++ b/src/main/deploy/pathplanner/generatedJSON/Blue0(2).wpilib.json @@ -0,0 +1 @@ +[{"acceleration":0.0,"curvature":-0.0023892214861392608,"pose":{"rotation":{"radians":3.140353846040498},"translation":{"x":4.37,"y":4.11}},"time":0.0,"velocity":0,"position":0.0,"holonomicRotation":180.0,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-418.546378308316},{"acceleration":2.500000000000001,"curvature":-0.0023892214861392608,"pose":{"rotation":{"radians":3.140353846040498},"translation":{"x":4.355168350652953,"y":4.110018373568579}},"time":0.0770237904227167,"velocity":0.19255947605679183,"position":0.014831660727706468,"holonomicRotation":179.28303536049708,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-418.546378308316},{"acceleration":8.579336190246808,"curvature":-0.002522529243088163,"pose":{"rotation":{"radians":3.1403185593210154},"translation":{"x":4.3404617684194715,"y":4.110037111150855}},"time":0.1086982150689007,"velocity":0.4643050137290437,"position":0.02953825489791249,"holonomicRotation":178.56607072099416,"angularVelocity":-0.0011140445288762967,"angularAcceleration":-0.03517173686090971,"curveRadius":-396.4275152567775},{"acceleration":5.779128118120659,"curvature":-0.0026604588341321254,"pose":{"rotation":{"radians":3.140281618177572},"translation":{"x":4.325879404244118,"y":4.110056229157636}},"time":0.13284672612520035,"velocity":0.6038623529852526,"position":0.04412063160545998,"holonomicRotation":177.84910608149121,"angularVelocity":-0.0015297482878841287,"angularAcceleration":-0.017214467510591587,"curveRadius":-375.87501342647624},{"acceleration":5.4845477389397415,"curvature":-0.002803149409640228,"pose":{"rotation":{"radians":3.140242986478026},"translation":{"x":4.311420409071453,"y":4.110075743999739}},"time":0.1530746745185458,"velocity":0.7148035016093652,"position":0.05857963994739685,"holonomicRotation":177.1321414419883,"angularVelocity":-0.001909817980289926,"angularAcceleration":-0.018789334687586583,"curveRadius":-356.74159806142677},{"acceleration":5.355891747883767,"curvature":-0.0029507435163729895,"pose":{"rotation":{"radians":3.1402026274442623},"translation":{"x":4.297083933846037,"y":4.110095672087972}},"time":0.1707818831411545,"velocity":0.8096413941492514,"position":0.0729161290230974,"holonomicRotation":176.41517680248538,"angularVelocity":-0.002279243138997058,"angularAcceleration":-0.020862981093216888,"curveRadius":-338.8976352743749},{"acceleration":5.28309576337803,"curvature":-0.0031033886866959092,"pose":{"rotation":{"radians":3.140160503643941},"translation":{"x":4.28286912951243,"y":4.110116029833147}},"time":0.18668791919605132,"velocity":0.893674505843015,"position":0.08713094793437849,"holonomicRotation":175.69821216298246,"angularVelocity":-0.0026482902575990963,"angularAcceleration":-0.023201702632154143,"curveRadius":-322.22840931493886},{"acceleration":5.236136677267774,"curvature":-0.0032612388104823428,"pose":{"rotation":{"radians":3.1401165769858186},"translation":{"x":4.2687751470151944,"y":4.110136833646077}},"time":0.2012212173560507,"velocity":0.969772841380256,"position":0.10122494578562753,"holonomicRotation":174.9812475234795,"angularVelocity":-0.00302248379128243,"angularAcceleration":-0.0257473238052215,"curveRadius":-306.63194513256093},{"acceleration":5.203295993447498,"curvature":-0.0034244448024053826,"pose":{"rotation":{"radians":3.140070808714399},"translation":{"x":4.254801137298889,"y":4.11015809993757}},"time":0.2146615677609145,"velocity":1.0397069627924143,"position":0.11519897168393427,"holonomicRotation":174.2642828839766,"angularVelocity":-0.003405288555786568,"angularAcceleration":-0.028481754788596023,"curveRadius":-292.0181394944911},{"acceleration":5.179026719246737,"curvature":-0.0035931641796848775,"pose":{"rotation":{"radians":3.1400231594033796},"translation":{"x":4.240946251308078,"y":4.1101798451184415}},"time":0.2272037629435013,"velocity":1.104663326761039,"position":0.1290538747392169,"holonomicRotation":173.54731824447367,"angularVelocity":-0.0037991205148586115,"angularAcceleration":-0.03140056053495542,"curveRadius":-278.30623650703893},{"acceleration":5.160356365713319,"curvature":-0.003767560754985008,"pose":{"rotation":{"radians":3.1399735889525444},"translation":{"x":4.2272096399873185,"y":4.1102020855995}},"time":0.23898996134931533,"velocity":1.1654843107320416,"position":0.14279050406436813,"holonomicRotation":172.83035360497075,"angularVelocity":-0.004205804885377516,"angularAcceleration":-0.03450513528758269,"curveRadius":-265.4237224116056},{"acceleration":5.145546458143414,"curvature":-0.003947797336910775,"pose":{"rotation":{"radians":3.13992205658173},"translation":{"x":4.213590454281172,"y":4.110224837791559}},"time":0.25012773438816516,"velocity":1.2227942393437006,"position":0.1564097087753913,"holonomicRotation":172.1133889654678,"angularVelocity":-0.004626811000261515,"angularAcceleration":-0.03779984682893807,"curveRadius":-253.30580945741218},{"acceleration":5.133511586171033,"curvature":-0.004134045901671687,"pose":{"rotation":{"radians":3.13986852082788},"translation":{"x":4.2000878451342,"y":4.110248118105429}},"time":0.26070085384712033,"velocity":1.2770714705882174,"position":0.16991233799154407,"holonomicRotation":171.3964243259649,"angularVelocity":-0.005063383049615309,"angularAcceleration":-0.04129075161295256,"curveRadius":-241.89378245549455},{"acceleration":5.123538743552778,"curvature":-0.004326480313045907,"pose":{"rotation":{"radians":3.139812939540471},"translation":{"x":4.1867009634909635,"y":4.11027194295192}},"time":0.27077610000551594,"velocity":1.3286923846315886,"position":0.18329924083549298,"holonomicRotation":170.67945968646197,"angularVelocity":-0.005516618307404515,"angularAcceleration":-0.04498503070433962,"curveRadius":-231.13476258857284},{"acceleration":5.115140079773982,"curvature":-0.004525275205782359,"pose":{"rotation":{"radians":3.13975526987876},"translation":{"x":4.1734289602960235,"y":4.110296328741845}},"time":0.28040775055869327,"velocity":1.3779596264105232,"position":0.19657126643346592,"holonomicRotation":169.96249504695902,"angularVelocity":-0.005987515991422874,"angularAcceleration":-0.04889065289676828,"curveRadius":-220.98103530194328},{"acceleration":5.107970452332121,"curvature":-0.004730614121742395,"pose":{"rotation":{"radians":3.1396954683090836},"translation":{"x":4.16027098649394,"y":4.110321291886017}},"time":0.28964064902248216,"velocity":1.4251209989529394,"position":0.2097292639154118,"holonomicRotation":169.2455304074561,"angularVelocity":-0.006477009349854849,"angularAcceleration":-0.053016218076235876,"curveRadius":-211.3890446916598},{"acceleration":5.1017787607537946,"curvature":-0.004942681396622698,"pose":{"rotation":{"radians":3.1396334906027596},"translation":{"x":4.147226193029273,"y":4.110346848795245}},"time":0.2985123665211619,"velocity":1.4703825388591116,"position":0.22277408241516136,"holonomicRotation":168.52856576795318,"angularVelocity":-0.0069859873618849195,"angularAcceleration":-0.05737085430254218,"curveRadius":-202.3193323128805},{"acceleration":5.09637793642263,"curvature":-0.0051616637206409145,"pose":{"rotation":{"radians":3.1395692918342175},"translation":{"x":4.1342937308465855,"y":4.11037301588034}},"time":0.3070547645424821,"velocity":1.513917827659108,"position":0.23570657107059786,"holonomicRotation":167.81160112845026,"angularVelocity":-0.007515309914371399,"angularAcceleration":-0.061964164063228265,"curveRadius":-193.7359840008779},{"acceleration":5.091625741271735,"curvature":-0.005387757726486164,"pose":{"rotation":{"radians":3.1395028263800007},"translation":{"x":4.121472750890436,"y":4.110399809552114}},"time":0.31529514999367164,"velocity":1.555874786340386,"position":0.24852757902382983,"holonomicRotation":167.09463648894732,"angularVelocity":-0.008065818596780771,"angularAcceleration":-0.066806181054298,"curveRadius":-185.60597019498667},{"acceleration":5.087412088406337,"curvature":-0.005621157345388674,"pose":{"rotation":{"radians":3.1394340479186935},"translation":{"x":4.108762404105387,"y":4.110427246221381}},"time":0.3232571455800259,"velocity":1.5963807389342424,"position":0.2612379554213652,"holonomicRotation":166.3776718494444,"angularVelocity":-0.008638344565905998,"angularAcceleration":-0.0719073457044434,"curveRadius":-177.89930766132204},{"acceleration":5.083650437548958,"curvature":-0.0058620663580636724,"pose":{"rotation":{"radians":3.1393629094312008},"translation":{"x":4.096161841435998,"y":4.11045534229895}},"time":0.33096135690699585,"velocity":1.6355462562175629,"position":0.27383854941429986,"holonomicRotation":165.66070720994148,"angularVelocity":-0.009233714454808114,"angularAcceleration":-0.07727849920444375,"curveRadius":-170.58831117195248},{"acceleration":5.080271814534036,"curvature":-0.006110686162059447,"pose":{"rotation":{"radians":3.1392893632017502},"translation":{"x":4.083670213826831,"y":4.110484114195633}},"time":0.33842589153816116,"velocity":1.6734681211128852,"position":0.28633021015849813,"holonomicRotation":164.94374257043856,"angularVelocity":-0.009852754804497177,"angularAcceleration":-0.08293086980995405,"curveRadius":-163.64774322872051},{"acceleration":5.077220566110419,"curvature":-0.006367225582509879,"pose":{"rotation":{"radians":3.1392133608195993},"translation":{"x":4.0712866722224454,"y":4.110513578322241}},"time":0.3456667683274118,"velocity":1.71023164966394,"position":0.29871378681479155,"holonomicRotation":164.2267779309356,"angularVelocity":-0.010496295457438892,"angularAcceleration":-0.08887606731509053,"curveRadius":-157.05427537339},{"acceleration":5.074451289424068,"curvature":-0.00663189949612861,"pose":{"rotation":{"radians":3.139134853181911},"translation":{"x":4.059010367567403,"y":4.110543751089585}},"time":0.352698244140326,"velocity":1.7459125311693369,"position":0.31099012854917263,"holonomicRotation":163.5098132914327,"angularVelocity":-0.01116517211705972,"angularAcceleration":-0.0951260698916645,"curveRadius":-150.78636227580844},{"acceleration":5.071926573697014,"curvature":-0.006904919672572635,"pose":{"rotation":{"radians":3.1390537904970754},"translation":{"x":4.046840450806264,"y":4.110574648908479}},"time":0.3595330774952417,"velocity":1.7805783040889245,"position":0.3231600845329988,"holonomicRotation":162.79284865192977,"angularVelocity":-0.011860228424949534,"angularAcceleration":-0.10169323402595049,"curveRadius":-144.82427709798685},{"acceleration":5.069615313799966,"curvature":-0.00718650865831388,"pose":{"rotation":{"radians":3.138970122289744},"translation":{"x":4.03477607288359,"y":4.110606288189731}},"time":0.36618274341820056,"velocity":1.8142895522836104,"position":0.3352245039431994,"holonomicRotation":162.07588401242685,"angularVelocity":-0.012582317412732642,"angularAcceleration":-0.10859026545829929,"curveRadius":-139.1496271062203},{"acceleration":5.06749143372506,"curvature":-0.0074768883399370335,"pose":{"rotation":{"radians":3.138883797405306},"translation":{"x":4.0228163847439395,"y":4.110638685344155}},"time":0.372657610126235,"velocity":1.8471008838610865,"position":0.34718423596249254,"holonomicRotation":161.3589193729239,"angularVelocity":-0.013332302938519464,"angularAcceleration":-0.11583026486957508,"curveRadius":-133.74547733428122},{"acceleration":5.0655329080888,"curvature":-0.00777628460525616,"pose":{"rotation":{"radians":3.1387947640171285},"translation":{"x":4.010960537331877,"y":4.110671856782562}},"time":0.37896708552569386,"velocity":1.879061739129822,"position":0.35904012977959654,"holonomicRotation":160.641954733421,"angularVelocity":-0.014111060356174428,"angularAcceleration":-0.12342665092596364,"curveRadius":-128.59611636694447},{"acceleration":5.063721003566362,"curvature":-0.008084931633320967,"pose":{"rotation":{"radians":3.1387029696337136},"translation":{"x":3.9992076815919604,"y":4.110705818915763}},"time":0.38511973960806656,"velocity":1.910217062834411,"position":0.37079303458946267,"holonomicRotation":159.92499009391807,"angularVelocity":-0.014919477380969529,"angularAcceleration":-0.13139321892176717,"curveRadius":-123.68688386660358},{"acceleration":5.06203968465941,"curvature":-0.008403056817336264,"pose":{"rotation":{"radians":3.1386083611074915},"translation":{"x":3.98755696846875,"y":4.110740588154568}},"time":0.39112340742711893,"velocity":1.9406078675879668,"position":0.3824437995935004,"holonomicRotation":159.20802545441515,"angularVelocity":-0.01575845451040471,"angularAcceleration":-0.1397440955631696,"curveRadius":-119.00431256598311},{"acceleration":5.060475143695697,"curvature":-0.008730899184571036,"pose":{"rotation":{"radians":3.1385108846442784},"translation":{"x":3.9760075489068094,"y":4.110776180909792}},"time":0.3969852763011788,"velocity":1.9702717093207502,"position":0.39399327399980844,"holonomicRotation":158.4910608149122,"angularVelocity":-0.0166289054408016,"angularAcceleration":-0.14849375670084275,"curveRadius":-114.53574011794431},{"acceleration":5.059015425729979,"curvature":-0.009068698595297265,"pose":{"rotation":{"radians":3.1384104858151294},"translation":{"x":3.9645585738506974,"y":4.110812613592243}},"time":0.40271196010221655,"velocity":1.9992430910084782,"position":0.4054423070234233,"holonomicRotation":157.77409617540928,"angularVelocity":-0.017531757058218446,"angularAcceleration":-0.15765697020904812,"curveRadius":-110.26940519542327},{"acceleration":5.057650126817142,"curvature":-0.00941669692676812,"pose":{"rotation":{"radians":3.138307109567889},"translation":{"x":3.9532091942449754,"y":4.110849902612735}},"time":0.408309562898818,"velocity":2.0275538075025814,"position":0.41679174788655965,"holonomicRotation":157.05713153590636,"angularVelocity":-0.018467949762884437,"angularAcceleration":-0.16724886325167587,"curveRadius":-106.19434901397081},{"acceleration":5.05637014929776,"curvature":-0.009775137142039064,"pose":{"rotation":{"radians":3.138200700241741},"translation":{"x":3.941958561034203,"y":4.110888064382077}},"time":0.41378373376384164,"velocity":2.0552332416566426,"position":0.4280424458188646,"holonomicRotation":156.34016689640345,"angularVelocity":-0.01943843712079474,"angularAcceleration":-0.17728481295881313,"curveRadius":-102.30035502002205},{"acceleration":5.055167502063784,"curvature":-0.010144269399217375,"pose":{"rotation":{"radians":3.1380912015815503},"translation":{"x":3.930805825162943,"y":4.110927115311081}},"time":0.4191397142040688,"velocity":2.0823086199197682,"position":0.4391952500576713,"holonomicRotation":155.6232022569005,"angularVelocity":-0.02044418597353312,"angularAcceleration":-0.18778053130748906,"curveRadius":-98.57782366043526},{"acceleration":5.054035136310057,"curvature":-0.010524339951173509,"pose":{"rotation":{"radians":3.137978556755206},"translation":{"x":3.9197501375757544,"y":4.110967071810561}},"time":0.42438237939305057,"velocity":2.1088052339927916,"position":0.4502510098482678,"holonomicRotation":154.90623761739758,"angularVelocity":-0.02148617588267364,"angularAcceleration":-0.19875194611519684,"curveRadius":-95.01783528842545},{"acceleration":5.052966809715414,"curvature":-0.01091560225236001,"pose":{"rotation":{"radians":3.137862708372148},"translation":{"x":3.9087906492171993,"y":4.1110079502913255}},"time":0.4295162741709134,"velocity":2.134746633909904,"position":0.4612105744441582,"holonomicRotation":154.18927297789466,"angularVelocity":-0.02256539879960222,"angularAcceleration":-0.21021523884403467,"curveRadius":-91.61198593360204},{"acceleration":5.051956973428783,"curvature":-0.011318307994753817,"pose":{"rotation":{"radians":3.137743598502336},"translation":{"x":3.8979265110318377,"y":4.111049767164188}},"time":0.43454564460242506,"velocity":2.1601547969333357,"position":0.47207479310734274,"holonomicRotation":153.4723083383917,"angularVelocity":-0.02368285880591171,"angularAcceleration":-0.22218685649162304,"curveRadius":-88.3524286901817},{"acceleration":5.051000677541281,"curvature":-0.011732713052556777,"pose":{"rotation":{"radians":3.1376211686988467},"translation":{"x":3.887156873964229,"y":4.111092538839958}},"time":0.43947446574680316,"velocity":2.185050275873069,"position":0.4828445151085951,"holonomicRotation":152.7553436988888,"angularVelocity":-0.024839571147568802,"angularAcceleration":-0.23468336703117343,"curveRadius":-85.23177849151278},{"acceleration":5.050093491570782,"curvature":-0.012159069758516255,"pose":{"rotation":{"radians":3.137495360020646},"translation":{"x":3.8764808889589375,"y":4.111136281729447}},"time":0.4443064661819551,"velocity":2.209452329821897,"position":0.49352058972774193,"holonomicRotation":152.03837905938587,"angularVelocity":-0.02603656185237924,"angularAcceleration":-0.24772156395155714,"curveRadius":-82.24313371502754},{"acceleration":5.049231437308729,"curvature":-0.012597635600531606,"pose":{"rotation":{"radians":3.1373661130580306},"translation":{"x":3.8658977069605207,"y":4.111181012243469}},"time":0.4490451497361773,"velocity":2.233379039795334,"position":0.5041038662539647,"holonomicRotation":151.32141441988296,"angularVelocity":-0.02727486677188086,"angularAcceleration":-0.2613183398579696,"curveRadius":-79.37997507705343},{"acceleration":5.0484109317859405,"curvature":-0.013048668354561529,"pose":{"rotation":{"radians":3.137233367960331},"translation":{"x":3.855406478913541,"y":4.111226746792833}},"time":0.4536938148073364,"velocity":2.256847411358785,"position":0.5145951939860841,"holonomicRotation":150.60444978038,"angularVelocity":-0.028555530602398158,"angularAcceleration":-0.27549066472065376,"curveRadius":-76.63617258311434},{"acceleration":5.047628738655617,"curvature":-0.013512424235279482,"pose":{"rotation":{"radians":3.137097064464381},"translation":{"x":3.8450063557625582,"y":4.111273501788352}},"time":0.458255571589858,"velocity":2.2798734659929982,"position":0.5249954222328688,"holonomicRotation":149.8874851408771,"angularVelocity":-0.02987960613592241,"angularAcceleration":-0.2902556178789375,"curveRadius":-74.00596536845757},{"acceleration":5.046881926555696,"curvature":-0.013989156116868448,"pose":{"rotation":{"radians":3.1369571419262274},"translation":{"x":3.8346964884521344,"y":4.111321293640836}},"time":0.4627333574806708,"velocity":2.3024723226763273,"position":0.5353054003133357,"holonomicRotation":149.17052050137417,"angularVelocity":-0.031248152896466607,"angularAcceleration":-0.30563023644165177,"curveRadius":-71.48394024956065},{"acceleration":5.0461678333625235,"curvature":-0.014479121817948542,"pose":{"rotation":{"radians":3.136813539354502},"translation":{"x":3.8244760279268286,"y":4.111370138761098}},"time":0.4671299508946385,"velocity":2.3246582709382646,"position":0.5455259775570684,"holonomicRotation":148.45355586187125,"angularVelocity":-0.032662236009632695,"angularAcceleration":-0.32163154060906235,"curveRadius":-69.06496212777108},{"acceleration":5.045484035304249,"curvature":-0.014982573006286028,"pose":{"rotation":{"radians":3.1366661954461073},"translation":{"x":3.8143441251312034,"y":4.111420053559947}},"time":0.47144798368622853,"velocity":2.3464448364521524,"position":0.555658003304526,"holonomicRotation":147.7365912223683,"angularVelocity":-0.03412292483784343,"angularAcceleration":-0.33827645567111675,"curveRadius":-66.74421006194623},{"acceleration":5.0448283202378015,"curvature":-0.015499763408035674,"pose":{"rotation":{"radians":3.136515048624224},"translation":{"x":3.804299931009819,"y":4.111471054448197}},"time":0.47568995234600886,"velocity":2.3678448400805734,"position":0.5657023269073703,"holonomicRotation":147.01962658286538,"angularVelocity":-0.03563129150774002,"angularAcceleration":-0.3555817571680736,"curveRadius":-64.51711382133495},{"acceleration":5.044198664463387,"curvature":-0.016030940611129647,"pose":{"rotation":{"radians":3.1363600370785205},"translation":{"x":3.7943425965072346,"y":4.111523157836659}},"time":0.4798582281169267,"velocity":2.388870451157352,"position":0.5756597977287911,"holonomicRotation":146.30266194336247,"angularVelocity":-0.03718840936219462,"angularAcceleration":-0.3735640202403723,"curveRadius":-62.379371507729225},{"acceleration":5.043593212446817,"curvature":-0.016576351436787803,"pose":{"rotation":{"radians":3.136201098808814},"translation":{"x":3.784471272568014,"y":4.111576380136143}},"time":0.48395506615545664,"velocity":2.4095332356809758,"position":0.585531265143831,"holonomicRotation":145.58569730385955,"angularVelocity":-0.03879535100287487,"angularAcceleration":-0.39223948458964825,"curveRadius":-60.326906304647096},{"acceleration":5.043010259218351,"curvature":-0.017136236533110655,"pose":{"rotation":{"radians":3.1360381716690524},"translation":{"x":3.7746851101367147,"y":4.111630737757461}},"time":0.4879826138459159,"velocity":2.429844200003453,"position":0.5953175785397308,"holonomicRotation":144.8687326643566,"angularVelocity":-0.04045318697215111,"angularAcceleration":-0.4116241685240465,"curveRadius":-58.35587050095853},{"acceleration":5.042448234799844,"curvature":-0.017710835597440532,"pose":{"rotation":{"radians":3.1358711934164876},"translation":{"x":3.7649832601579,"y":4.111686247111425}},"time":0.4919429183619813,"velocity":2.4498138305197568,"position":0.6050195873162576,"holonomicRotation":144.15176802485368,"angularVelocity":-0.042162983146239834,"angularAcceleration":-0.4317335111865156,"curveRadius":-56.46260982426567},{"acceleration":5.041905690621902,"curvature":-0.018300381120953876,"pose":{"rotation":{"radians":3.135700101762137},"translation":{"x":3.7553648735761285,"y":4.111742924608847}},"time":0.49583793355735006,"velocity":2.4694521297983454,"position":0.614638140886058,"holonomicRotation":143.43480338535076,"angularVelocity":-0.043925798942742754,"angularAcceleration":-0.452582521012737,"curveRadius":-54.64367071869358},{"acceleration":5.041381287480023,"curvature":-0.01890510007013995,"pose":{"rotation":{"radians":3.13552483442408},"translation":{"x":3.7458291013359633,"y":4.111800786660537}},"time":0.49966952625710315,"velocity":2.4887686495361256,"position":0.6241740886749949,"holonomicRotation":142.7178387458478,"angularVelocity":-0.04574268503757091,"angularAcceleration":-0.4741856030118337,"curveRadius":-52.895779249509005},{"acceleration":5.0408737849745595,"curvature":-0.0195252129036404,"pose":{"rotation":{"radians":3.1353453291838864},"translation":{"x":3.7363750943819634,"y":4.111859849677308}},"time":0.5034394820124889,"velocity":2.5077725206739636,"position":0.6336282801225079,"holonomicRotation":142.0008741063449,"angularVelocity":-0.04761468087177121,"angularAcceleration":-0.49655644672380406,"curveRadius":-51.2158307791642},{"acceleration":5.040382032061031,"curvature":-0.020160933432992818,"pose":{"rotation":{"radians":3.135161523945937},"translation":{"x":3.7270020036586904,"y":4.1119201300699695}},"time":0.5071495103741929,"velocity":2.526472480966733,"position":0.6430015646819591,"holonomicRotation":141.28390946684198,"angularVelocity":-0.0495428120838017,"angularAcceleration":-0.5197079439966653,"curveRadius":-49.60087802103087},{"acceleration":5.0399049586620235,"curvature":-0.02081246528076511,"pose":{"rotation":{"radians":3.134973356799173},"translation":{"x":3.717708980110705,"y":4.111981644249335}},"time":0.5108012497326109,"velocity":2.5448769002669653,"position":0.6522947918209928,"holonomicRotation":140.56694482733906,"angularVelocity":-0.05152808793165879,"angularAcceleration":-0.5436521210859766,"curveRadius":-48.04812820152548},{"acceleration":5.039441568461447,"curvature":-0.021480006788322365,"pose":{"rotation":{"radians":3.134780766083395},"translation":{"x":3.708495174682567,"y":4.112044408626214}},"time":0.5143962717679414,"velocity":2.562993803751345,"position":0.6615088110218946,"holonomicRotation":139.84998018783614,"angularVelocity":-0.053571498000598204,"angularAcceleration":-0.5683998731739383,"curveRadius":-46.554920110344256},{"acceleration":5.0389909319632835,"curvature":-0.022163742398154922,"pose":{"rotation":{"radians":3.1345836904561932},"translation":{"x":3.6993597383188392,"y":4.112108439611419}},"time":0.5179360855479944,"velocity":2.5808308932898707,"position":0.6706444717819485,"holonomicRotation":139.1330155483332,"angularVelocity":-0.0556740098341806,"angularAcceleration":-0.5939611415239299,"curveRadius":-45.11873410346294},{"acceleration":5.03855218074178,"curvature":-0.02286384752046633,"pose":{"rotation":{"radians":3.134382068965913},"translation":{"x":3.69030182196408,"y":4.112173753615762}},"time":0.521422141307331,"velocity":2.5983955671382635,"position":0.6797026236138055,"holonomicRotation":138.41605090883027,"angularVelocity":-0.0578365649316567,"angularAcceleration":-0.6203443796572112,"curveRadius":-43.7371706185873},{"acceleration":5.0381245023421,"curvature":-0.02358048578356664,"pose":{"rotation":{"radians":3.134175841125425},"translation":{"x":3.681320576562852,"y":4.1122403670500525}},"time":0.5248558339376027,"velocity":2.615694938112347,"position":0.6886841160458409,"holonomicRotation":137.69908626932735,"angularVelocity":-0.060060076044681755,"angularAcceleration":-0.6475568294676112,"curveRadius":-42.4079473670939},{"acceleration":5.037707135038101,"curvature":-0.024313805508431947,"pose":{"rotation":{"radians":3.133964946990018},"translation":{"x":3.6724151530597147,"y":4.1123082963251045}},"time":0.5282385062157148,"velocity":2.6327358503832876,"position":0.6975897986225242,"holonomicRotation":136.9821216298244,"angularVelocity":-0.062345423401273595,"angularAcceleration":-0.6756041285404498,"curveRadius":-41.12889689987868},{"acceleration":5.037299364110932,"curvature":-0.025063944384762005,"pose":{"rotation":{"radians":3.1337493272399914},"translation":{"x":3.66358470239923,"y":4.112377557851728}},"time":0.5315714517935589,"velocity":2.6495248950231782,"position":0.7064205209047797,"holonomicRotation":136.2651569903215,"angularVelocity":-0.06469345058018554,"angularAcceleration":-0.7044901046451311,"curveRadius":-39.89795000534572},{"acceleration":5.036900517634651,"curvature":-0.02583102099118723,"pose":{"rotation":{"radians":3.1335289232636176},"translation":{"x":3.654828375525958,"y":4.112448168040735}},"time":0.5348559179705711,"velocity":2.6660684244103243,"position":0.7151771324703555,"holonomicRotation":135.54819235081857,"angularVelocity":-0.06710496150527986,"angularAcceleration":-0.7342170067003225,"curveRadius":-38.71314263347043},{"acceleration":5.036509963182724,"curvature":-0.026615141835904466,"pose":{"rotation":{"radians":3.133303677246558},"translation":{"x":3.64614532338446,"y":4.112520143302935}},"time":0.5380931082681453,"velocity":2.682372565596775,"position":0.7238604829141846,"holonomicRotation":134.83122771131565,"angularVelocity":-0.06958071548290579,"angularAcceleration":-0.764784813386209,"curveRadius":-37.57259706393809},{"acceleration":5.036127104714375,"curvature":-0.027416392090227407,"pose":{"rotation":{"radians":3.133073532261965},"translation":{"x":3.637534696919296,"y":4.112593500049141}},"time":0.5412841848229999,"velocity":2.698443232727897,"position":0.7324714218487487,"holonomicRotation":134.11426307181273,"angularVelocity":-0.07212142380063812,"angularAcceleration":-0.7961915905361532,"curveRadius":-36.47452942418528},{"acceleration":5.035751379614808,"curvature":-0.02823484011221357,"pose":{"rotation":{"radians":3.132838432366527},"translation":{"x":3.6289956470750266,"y":4.112668254690166}},"time":0.5444302706148659,"velocity":2.714286138594673,"position":0.7410107989044403,"holonomicRotation":133.39729843230978,"angularVelocity":-0.07472774456626757,"angularAcceleration":-0.8284328330676485,"curveRadius":-35.4172361531252},{"acceleration":5.035382256404291,"curvature":-0.029070532245812443,"pose":{"rotation":{"radians":3.132598322698309},"translation":{"x":3.6205273247962135,"y":4.11274442363682}},"time":0.547532451542342,"velocity":2.7299068053930418,"position":0.7494794637299177,"holonomicRotation":132.68033379280686,"angularVelocity":-0.0774002786527389,"angularAcceleration":-0.8615016818653796,"curveRadius":-34.39909498540565},{"acceleration":5.035019232143005,"curvature":-0.02992349483375486,"pose":{"rotation":{"radians":3.1323531495782158},"translation":{"x":3.612128881027417,"y":4.112822023299913}},"time":0.5505917783594171,"velocity":2.7453105747544257,"position":0.7578782659924638,"holonomicRotation":131.96336915330394,"angularVelocity":-0.08013956492815062,"angularAcceleration":-0.8953885737616774,"curveRadius":-33.41855640711998},{"acceleration":5.034661830525836,"curvature":-0.030793732180261765,"pose":{"rotation":{"radians":3.132102860614401},"translation":{"x":3.603799466713198,"y":4.112901070090259}},"time":0.55360926848395,"velocity":2.7605026171084,"position":0.7662080553783356,"holonomicRotation":131.246404513801,"angularVelocity":-0.0829460755414085,"angularAcceleration":-0.9300811261784389,"curveRadius":-32.4741409760322},{"acceleration":5.034309599987436,"curvature":-0.03168122136623354,"pose":{"rotation":{"radians":3.1318474048129405},"translation":{"x":3.595538232798117,"y":4.1129815804186665}},"time":0.5565859076883318,"velocity":2.7754879404307187,"position":0.7744696815931107,"holonomicRotation":130.52943987429808,"angularVelocity":-0.08582020994825168,"angularAcceleration":-0.9655635800980622,"curveRadius":-31.56443965464726},{"acceleration":5.0339621117789966,"curvature":-0.03258591731478453,"pose":{"rotation":{"radians":3.131586732686538},"translation":{"x":3.5873443302267356,"y":4.1130635706959495}},"time":0.5595226516816023,"velocity":2.790271398424837,"position":0.7826639943620293,"holonomicRotation":129.81247523479516,"angularVelocity":-0.08876229150371587,"angularAcceleration":-1.001817510210605,"curveRadius":-30.688103401842575},{"acceleration":5.033618958691175,"curvature":-0.033507746762689423,"pose":{"rotation":{"radians":3.1313207963723877},"translation":{"x":3.5792169099436126,"y":4.1131470573329185}},"time":0.5624204275914343,"velocity":2.8048576981826057,"position":0.7907918434303296,"holonomicRotation":129.09551059529224,"angularVelocity":-0.09177256020663595,"angularAcceleration":-1.0388203907370543,"curveRadius":-29.84384497955831},{"acceleration":5.033279753391412,"curvature":-0.03444660697984107,"pose":{"rotation":{"radians":3.1310495497486643},"translation":{"x":3.5711551228933116,"y":4.113232056740386}},"time":0.5652801353536389,"velocity":2.819251407362726,"position":0.7988540785635709,"holonomicRotation":128.37854595578932,"angularVelocity":-0.09485116881812,"angularAcceleration":-1.0765465800990575,"curveRadius":-29.030435438393763},{"acceleration":5.03294412720363,"curvature":-0.03540236601395278,"pose":{"rotation":{"radians":3.130772948557117},"translation":{"x":3.5631581200203915,"y":4.113318585329162}},"time":0.5681026490161655,"velocity":2.8334569609244915,"position":0.8068515495479615,"holonomicRotation":127.66158131628637,"angularVelocity":-0.09799817631336132,"angularAcceleration":-1.11496625756781,"curveRadius":-28.246699658601347},{"acceleration":5.032611729061207,"curvature":-0.03637485901534823,"pose":{"rotation":{"radians":3.1304909505268514},"translation":{"x":3.555225052269413,"y":4.113406659510058}},"time":0.5708888179639405,"velocity":2.8474786674502104,"position":0.8147851061906631,"holonomicRotation":126.94461667678345,"angularVelocity":-0.10121354287970731,"angularAcceleration":-1.1540457978737002,"curveRadius":-27.491515488157738},{"acceleration":5.032282224211887,"curvature":-0.03736389229188107,"pose":{"rotation":{"radians":3.1302035155022048},"translation":{"x":3.5473550705849375,"y":4.113496295693886}},"time":0.5736394680703529,"velocity":2.861320715085736,"position":0.8226555983200937,"holonomicRotation":126.22765203728054,"angularVelocity":-0.10449712378051966,"angularAcceleration":-1.1937472138523053,"curveRadius":-26.76380694463391},{"acceleration":5.031955293271172,"curvature":-0.03836923379483828,"pose":{"rotation":{"radians":3.1299106055734893},"translation":{"x":3.5395473259115255,"y":4.113587510291457}},"time":0.5763554027806868,"velocity":2.8749871771275792,"position":0.8304638757862192,"holonomicRotation":125.5106873977776,"angularVelocity":-0.10784866351939786,"angularAcceleration":-1.2340280957881526,"curveRadius":-26.06254806512523},{"acceleration":5.0316306315837185,"curvature":-0.03939061752449049,"pose":{"rotation":{"radians":3.1296121852093117},"translation":{"x":3.5318009691937378,"y":4.113680319713583}},"time":0.5790374041323515,"velocity":2.8884820172825645,"position":0.8382107884608303,"holonomicRotation":124.79372275827467,"angularVelocity":-0.11126779037317272,"angularAcceleration":-1.274841584868174,"curveRadius":-25.38675610704163},{"acceleration":5.0313079481066305,"curvature":-0.04042774017326493,"pose":{"rotation":{"radians":3.129308221393051},"translation":{"x":3.5241151513761353,"y":4.113774740371076}},"time":0.5816862337163597,"velocity":2.901809094621765,"position":0.8458971862378086,"holonomicRotation":124.07675811877175,"angularVelocity":-0.11475400988265207,"angularAcceleration":-1.3161358248664472,"curveRadius":-24.735490920694726},{"acceleration":5.030986964812296,"curvature":-0.04148025892823211,"pose":{"rotation":{"radians":3.128998683760604},"translation":{"x":3.516489023403279,"y":4.113870788674745}},"time":0.5843026335841311,"velocity":2.9149721682512597,"position":0.8535239190333785,"holonomicRotation":123.35979347926882,"angularVelocity":-0.11830669931610231,"angularAcceleration":-1.3578541557091413,"curveRadius":-24.107853370206048},{"acceleration":5.030667415954325,"curvature":-0.042547791172250764,"pose":{"rotation":{"radians":3.1286835447403107},"translation":{"x":3.5089217362197287,"y":4.113968481035404}},"time":0.5868873271033698,"velocity":2.9279749017187218,"position":0.8610918367863443,"holonomicRotation":122.64282883976588,"angularVelocity":-0.12192510173738172,"angularAcceleration":-1.3999348063306494,"curveRadius":-23.50298270365184},{"acceleration":5.0303490476964265,"curvature":-0.0436299137764739,"pose":{"rotation":{"radians":3.1283627796958133},"translation":{"x":3.5014124407700464,"y":4.1140678338638645}},"time":0.5894410197664592,"velocity":2.9408208671746032,"position":0.8686017894583085,"holonomicRotation":121.92586420026296,"angularVelocity":-0.12560831972213268,"angularAcceleration":-1.4423105951579116,"curveRadius":-22.92005446362398},{"acceleration":5.0300316170588815,"curvature":-0.04472615934185759,"pose":{"rotation":{"radians":3.128036367070352},"translation":{"x":3.493960287998792,"y":4.114168863570935}},"time":0.5919643999545507,"velocity":2.9535135493025635,"position":0.8760546270338784,"holonomicRotation":121.20889956076005,"angularVelocity":-0.12935530959686847,"angularAcceleration":-1.4849089694921198,"curveRadius":-22.35828013661205},{"acceleration":5.029714891949708,"curvature":-0.04583601624399679,"pose":{"rotation":{"radians":3.127704288530537},"translation":{"x":3.486564428850526,"y":4.114271586567431}},"time":0.5944581396602616,"velocity":2.9660563490370238,"position":0.8834511995208478,"holonomicRotation":120.49193492125711,"angularVelocity":-0.13316487645235356,"angularAcceleration":-1.527652163038852,"curveRadius":-21.81690473877017},{"acceleration":5.02939865045786,"curvature":-0.04695892865458197,"pose":{"rotation":{"radians":3.1273665291161303},"translation":{"x":3.479224014269811,"y":4.11437601926416}},"time":0.5969228951716838,"velocity":2.9784525870798793,"position":0.8907923569503627,"holonomicRotation":119.77497028175418,"angularVelocity":-0.13703566655648003,"angularAcceleration":-1.5704560092018747,"curveRadius":-21.295204738501333},{"acceleration":5.029082680324364,"curvature":-0.04809429315278903,"pose":{"rotation":{"radians":3.1270230773847114},"translation":{"x":3.4719381952012056,"y":4.1144821780719365}},"time":0.5993593077201915,"velocity":2.990705507229704,"position":0.8980789493770682,"holonomicRotation":119.05800564225126,"angularVelocity":-0.14096616421930938,"angularAcceleration":-1.6132315790430507,"curveRadius":-20.792487724544284},{"acceleration":5.028766778843427,"curvature":-0.04924145874597623,"pose":{"rotation":{"radians":3.1266739255624603},"translation":{"x":3.4647061225892717,"y":4.11459007940157}},"time":0.601768004094344,"velocity":3.0028182795363625,"position":0.9053118268792261,"holonomicRotation":118.34104100274834,"angularVelocity":-0.14495468420091298,"angularAcceleration":-1.655883250543396,"curveRadius":-20.308090488519802},{"acceleration":5.028450752326548,"curvature":-0.05039972650520232,"pose":{"rotation":{"radians":3.1263190696914336},"translation":{"x":3.45752694737857,"y":4.114699739663873}},"time":0.604149597222018,"velocity":3.014794003290951,"position":0.9124918395588167,"holonomicRotation":117.62407636324541,"angularVelocity":-0.14899936807142497,"angularAcceleration":-1.6983101872074045,"curveRadius":-19.841377510189044},{"acceleration":5.028134415831017,"curvature":-0.05156834582127421,"pose":{"rotation":{"radians":3.12595850977869},"translation":{"x":3.4503998205136606,"y":4.114811175269657}},"time":0.6065046867227368,"velocity":3.0266357098618775,"position":0.9196198375416131,"holonomicRotation":116.90711172374247,"angularVelocity":-0.15309817849103696,"angularAcceleration":-1.7404053724331636,"curveRadius":-19.391740884336375},{"acceleration":5.027817593087781,"curvature":-0.052746518192626234,"pose":{"rotation":{"radians":3.125592249944893},"translation":{"x":3.443323892939105,"y":4.1149244026297325}},"time":0.6088338594320217,"velocity":3.03834636538696,"position":0.9266966709772274,"holonomicRotation":116.19014708423956,"angularVelocity":-0.15724889456981583,"angularAcceleration":-1.7820559472608715,"curveRadius":-18.958597349460618},{"acceleration":5.027500115794261,"curvature":-0.053933392374919446,"pose":{"rotation":{"radians":3.1252202985708353},"translation":{"x":3.4362983155994637,"y":4.115039438154912}},"time":0.6111376898994638,"velocity":3.0499288733287955,"position":0.9337231900391336,"holonomicRotation":115.47318244473662,"angularVelocity":-0.16144910804596974,"angularAcceleration":-1.8231434714974215,"curveRadius":-18.54138884957343},{"acceleration":5.02718182392649,"curvature":-0.05512806481573978,"pose":{"rotation":{"radians":3.1248426684445865},"translation":{"x":3.4293222394392977,"y":4.1151562982560055}},"time":0.6134167408620865,"velocity":3.0613860769038945,"position":0.9407002449246612,"holonomicRotation":114.7562178052337,"angularVelocity":-0.1656962184883457,"angularAcceleration":-1.863543427518811,"curveRadius":-18.1395810526345},{"acceleration":5.026862565353233,"curvature":-0.0563295808514952,"pose":{"rotation":{"radians":3.1244593769048015},"translation":{"x":3.4223948154031674,"y":4.115274999343827}},"time":0.615671563694461,"velocity":3.0727207613914613,"position":0.9476286858549576,"holonomicRotation":114.03925316573077,"angularVelocity":-0.16998743062282098,"angularAcceleration":-1.9031260784052058,"curveRadius":-17.752661832090595},{"acceleration":5.026542195278092,"curvature":-0.05753693255687519,"pose":{"rotation":{"radians":3.1240704459845454},"translation":{"x":3.415515194435634,"y":4.115395557829185}},"time":0.6179026988369349,"velocity":3.0839356563284746,"position":0.9545093630749206,"holonomicRotation":113.32228852622785,"angularVelocity":-0.1743197500016899,"angularAcceleration":-1.9417556993275897,"curveRadius":-17.380140990510768},{"acceleration":5.026220576985529,"curvature":-0.058749059248583244,"pose":{"rotation":{"radians":3.123675902549166},"translation":{"x":3.4086825274812576,"y":4.115517990122893}},"time":0.6201106762032403,"velocity":3.095033437600517,"position":0.961343126853101,"holonomicRotation":112.60532388672492,"angularVelocity":-0.17868998179069026,"angularAcceleration":-1.9792919328303868,"curveRadius":-17.02154915823806},{"acceleration":5.025897580507528,"curvature":-0.05996484914278793,"pose":{"rotation":{"radians":3.1232757784340834},"translation":{"x":3.4018959654845995,"y":4.115642312635762}},"time":0.6222960155686574,"velocity":3.1060167294297547,"position":0.9681308274815679,"holonomicRotation":111.888359247222,"angularVelocity":-0.18309472726047019,"angularAcceleration":-2.015588763688076,"curveRadius":-16.67643651731377},{"acceleration":5.025573083761846,"curvature":-0.06118313544562299,"pose":{"rotation":{"radians":3.1228701105778063},"translation":{"x":3.3951546593902204,"y":4.115768541778602}},"time":0.6244592269398357,"velocity":3.1168881062712357,"position":0.9748733152757441,"holonomicRotation":111.17139460771907,"angularVelocity":-0.1875303826903427,"angularAcceleration":-2.0504956145161657,"curveRadius":-16.34437321194103},{"acceleration":5.025246971457878,"curvature":-0.06240270108760551,"pose":{"rotation":{"radians":3.122458941148628},"translation":{"x":3.388457760142681,"y":4.115896693962227}},"time":0.626600810907296,"velocity":3.1276500946178385,"position":0.9815714405742034,"holonomicRotation":110.45442996821615,"angularVelocity":-0.19199313938925403,"angularAcceleration":-2.083857913917626,"curveRadius":-16.024947359187646},{"acceleration":5.024919135561793,"curvature":-0.06362227715318831,"pose":{"rotation":{"radians":3.1220423176718524},"translation":{"x":3.3818044186865417,"y":4.1160267855974455}},"time":0.6287212589815718,"velocity":3.138305174722232,"position":0.988226053738433,"holonomicRotation":109.73746532871321,"angularVelocity":-0.1964789809426491,"angularAcceleration":-2.115515870355428,"curveRadius":-15.71776498335987},{"acceleration":5.024589474926997,"curvature":-0.0648405436099186,"pose":{"rotation":{"radians":3.1216202931449852},"translation":{"x":3.3751937859663643,"y":4.116158833095072}},"time":0.6308210539138825,"velocity":3.1488557822386256,"position":0.9948380051525549,"holonomicRotation":109.0205006892103,"angularVelocity":-0.20098368672730815,"angularAcceleration":-2.1453074847179767,"curveRadius":-15.422449355391137},{"acceleration":5.024257895647132,"curvature":-0.06605613122017974,"pose":{"rotation":{"radians":3.121192926153157},"translation":{"x":3.368625012926709,"y":4.116292852865915}},"time":0.6329006700021782,"velocity":3.15930430979016,"position":1.0014081452230164,"holonomicRotation":108.30353604970736,"angularVelocity":-0.20550283017788296,"angularAcceleration":-2.1730662096764495,"curveRadius":-15.138640146314023},{"acceleration":5.023924310373312,"curvature":-0.06726762314782304,"pose":{"rotation":{"radians":3.120760280973665},"translation":{"x":3.362097250512136,"y":4.116428861320789}},"time":0.6349605733833342,"velocity":3.16965310846377,"position":1.0079373243782326,"holonomicRotation":107.58657141020444,"angularVelocity":-0.21003178277674342,"angularAcceleration":-2.198623799684624,"curveRadius":-14.865992779356327},{"acceleration":5.023588638920944,"curvature":-0.06847355401995721,"pose":{"rotation":{"radians":3.120322427676575},"translation":{"x":3.3556096496672065,"y":4.116566874870502}},"time":0.6370012223122314,"velocity":3.179904489239004,"position":1.0144263930681936,"holonomicRotation":106.86960677070151,"angularVelocity":-0.21456571529270257,"angularAcceleration":-2.2218091763629975,"curveRadius":-14.604178420599306},{"acceleration":5.023250807588927,"curvature":-0.06967241430186391,"pose":{"rotation":{"radians":3.1198794422145513},"translation":{"x":3.3491613613364812,"y":4.116706909925869}},"time":0.6390230674284081,"velocity":3.190060724351658,"position":1.020876201764031,"holonomicRotation":106.15264213119859,"angularVelocity":-0.2190996028722953,"angularAcceleration":-2.2424504940152903,"curveRadius":-14.352882844957586},{"acceleration":5.0229107498394985,"curvature":-0.07086265214213974,"pose":{"rotation":{"radians":3.119431406508523},"translation":{"x":3.3427515364645215,"y":4.116848982897699}},"time":0.641026552010925,"velocity":3.20012404859832,"position":1.0272876009575391,"holonomicRotation":105.43567749169566,"angularVelocity":-0.22362822750825337,"angularAcceleration":-2.260374087964785,"curveRadius":-14.11180600458125},{"acceleration":5.022568405743009,"curvature":-0.07204267305718862,"pose":{"rotation":{"radians":3.1189784085204346},"translation":{"x":3.3363793259958876,"y":4.1169931101968045}},"time":0.6430121122220508,"velocity":3.210096660582421,"position":1.0336614411606595,"holonomicRotation":104.71871285219274,"angularVelocity":-0.22814618541909296,"angularAcceleration":-2.2754071548794035,"curveRadius":-13.880662079351},{"acceleration":5.022223722039872,"curvature":-0.07321084570500891,"pose":{"rotation":{"radians":3.118520542318575},"translation":{"x":3.33004388087514,"y":4.117139308233996}},"time":0.6449801773403323,"velocity":3.2199807239059735,"position":1.0399985729049177,"holonomicRotation":104.0017482126898,"angularVelocity":-0.2326478923925569,"angularAcceleration":-2.2873770444113997,"curveRadius":-13.659178368589485},{"acceleration":5.021876652273996,"curvature":-0.07436550289048309,"pose":{"rotation":{"radians":3.1180579081334616},"translation":{"x":3.32374435204684,"y":4.117287593420086}},"time":0.646931169983582,"velocity":3.2297783683098675,"position":1.0462998467408173,"holonomicRotation":103.28478357318689,"angularVelocity":-0.2371275907749709,"angularAcceleration":-2.29611239074294,"curveRadius":-13.447095240822675},{"acceleration":5.02152715658121,"curvature":-0.07550494417029917,"pose":{"rotation":{"radians":3.117590612401052},"translation":{"x":3.3174798904555485,"y":4.117437982165885}},"time":0.6488655063222868,"velocity":3.2394916907646354,"position":1.0525661132371955,"holonomicRotation":102.56781893368395,"angularVelocity":-0.24157935880094597,"angularAcceleration":-2.3014446541163487,"curveRadius":-13.244165809122771},{"acceleration":5.021175202171069,"curvature":-0.07662744007132796,"pose":{"rotation":{"radians":3.117118767797546},"translation":{"x":3.3112496470458255,"y":4.117590490882206}},"time":0.6507835962839037,"velocity":3.2491227565154395,"position":1.0587982229805288,"holonomicRotation":101.85085429418102,"angularVelocity":-0.24599711846057315,"angularAcceleration":-2.30320774730665,"curveRadius":-13.0501553891029},{"acceleration":5.020820762517052,"curvature":-0.07773123605223194,"pose":{"rotation":{"radians":3.1166424932595564},"translation":{"x":3.305052772762232,"y":4.117745135979859}},"time":0.6526858437484904,"velocity":3.2586736000810816,"position":1.0649970265741986,"holonomicRotation":101.1338896546781,"angularVelocity":-0.250374647282331,"angularAcceleration":-2.3012404554362322,"curveRadius":-12.86484109590184},{"acceleration":5.020463817700217,"curvature":-0.07881455469502512,"pose":{"rotation":{"radians":3.1161619139941266},"translation":{"x":3.2988884185493292,"y":4.117901933869655}},"time":0.654572646736085,"velocity":3.268146226211429,"position":1.0711633746377103,"holonomicRotation":100.41692501517517,"angularVelocity":-0.25470558854825354,"angularAcceleration":-2.295386054822767,"curveRadius":-12.68801180022554},{"acceleration":5.020104355034864,"curvature":-0.0798756014122208,"pose":{"rotation":{"radians":3.1156771614751726},"translation":{"x":3.2927557353516774,"y":4.118060900962407}},"time":0.6564443975862306,"velocity":3.2775426108057855,"position":1.0772981178058747,"holonomicRotation":99.69996037567225,"angularVelocity":-0.25898346402045924,"angularAcceleration":-2.28549407196623,"curveRadius":-12.519467551038709},{"acceleration":5.019742367844054,"curvature":-0.08091256801616163,"pose":{"rotation":{"radians":3.1151883734266566},"translation":{"x":3.286653874113838,"y":4.118222053668926}},"time":0.6583014831300127,"velocity":3.286864701790619,"position":1.0834021067279376,"holonomicRotation":98.98299573616931,"angularVelocity":-0.26320168726347354,"angularAcceleration":-2.271421075425344,"curveRadius":-12.359019426997524},{"acceleration":5.01937785632122,"curvature":-0.08192363564465735,"pose":{"rotation":{"radians":3.1146956937928643},"translation":{"x":3.2805819857803713,"y":4.118385408400022}},"time":0.660144284854962,"velocity":3.29611441996242,"position":1.0894761920666747,"holonomicRotation":98.2660310966664,"angularVelocity":-0.2673535775021264,"angularAcceleration":-2.2530314479529983,"curveRadius":-12.206489520771347},{"acceleration":5.019010827274567,"curvature":-0.08290698351535081,"pose":{"rotation":{"radians":3.1141992726929533},"translation":{"x":3.274539221295838,"y":4.118550981566509}},"time":0.6619731790631515,"velocity":3.3052936597952627,"position":1.0955212244974395,"holonomicRotation":97.54906645716346,"angularVelocity":-0.2714323757427385,"angularAcceleration":-2.230199112856287,"curveRadius":-12.061710094841926},{"acceleration":5.0186412939158105,"curvature":-0.08386079021403273,"pose":{"rotation":{"radians":3.1136992663632554},"translation":{"x":3.268524731604799,"y":4.118718789579196}},"time":0.6637885370227989,"velocity":3.3144042902147883,"position":1.1015380547071707,"holonomicRotation":96.83210181766054,"angularVelocity":-0.27543125973618676,"angularAcceleration":-2.2028074254979377,"curveRadius":-11.924523933625734},{"acceleration":5.018269276246538,"curvature":-0.08478323966188624,"pose":{"rotation":{"radians":3.1131958370826016},"translation":{"x":3.2625376676518156,"y":4.118888848848895}},"time":0.665590725113672,"velocity":3.323448155341234,"position":1.1075275333933607,"holonomicRotation":96.11513717815761,"angularVelocity":-0.2793433622180619,"angularAcceleration":-2.170751489085641,"curveRadius":-11.794784016133127},{"acceleration":5.017894800173631,"curvature":-0.08567252683780395,"pose":{"rotation":{"radians":3.1126891530838807},"translation":{"x":3.2565771803814476,"y":4.1190611757864195}},"time":0.6673801049665722,"velocity":3.3324270752006373,"position":1.1134905112629838,"holonomicRotation":95.39817253865469,"angularVelocity":-0.28316178809081416,"angularAcceleration":-2.1339381163610844,"curveRadius":-11.672353284188869},{"acceleration":5.017517898723486,"curvature":-0.08652686402004256,"pose":{"rotation":{"radians":3.1121793884509},"translation":{"x":3.250642420738256,"y":4.119235786802579}},"time":0.6691570335971618,"velocity":3.341342846409375,"position":1.1194278390313845,"holonomicRotation":94.68120789915176,"angularVelocity":-0.2868796327579137,"angularAcceleration":-2.092286996279562,"curveRadius":-11.557104389780797},{"acceleration":5.017138610771363,"curvature":-0.08734448562074189,"pose":{"rotation":{"radians":3.1116667229978416},"translation":{"x":3.2447325396668023,"y":4.119412698308184}},"time":0.6709218635343844,"velocity":3.35019724282886,"position":1.1253403674211295,"holonomicRotation":93.96424325964884,"angularVelocity":-0.2904900026034858,"angularAcceleration":-2.045732435417474,"curveRadius":-11.44891967584646},{"acceleration":5.016756981778764,"curvature":-0.08812365196759568,"pose":{"rotation":{"radians":3.111151342133404},"translation":{"x":3.2388466881116464,"y":4.119591926714049}},"time":0.6726749429437155,"velocity":3.3589920161952342,"position":1.131228947160829,"holonomicRotation":93.2472786201459,"angularVelocity":-0.2939860349135306,"angularAcceleration":-1.994223588182301,"curveRadius":-11.347691314106163},{"acceleration":5.016373063252309,"curvature":-0.08886265900568248,"pose":{"rotation":{"radians":3.110633436712974},"translation":{"x":3.2329840170173494,"y":4.119773488430983}},"time":0.6744166157454646,"velocity":3.3677288967229275,"position":1.1370944289839158,"holonomicRotation":92.53031398064299,"angularVelocity":-0.2973609164186934,"angularAcceleration":-1.937724182047027,"curveRadius":-11.253320699485858},{"acceleration":5.015986912907008,"curvature":-0.08955984077198909,"pose":{"rotation":{"radians":3.1101132028685874},"translation":{"x":3.227143677328472,"y":4.119957399869798}},"time":0.6761472217283445,"velocity":3.3764095936844516,"position":1.1429376636273991,"holonomicRotation":91.81334934114005,"angularVelocity":-0.30060790817393523,"angularAcceleration":-1.8762166474419315,"curveRadius":-11.16571882419829},{"acceleration":5.015598594652535,"curvature":-0.09021357739981987,"pose":{"rotation":{"radians":3.1095908418290734},"translation":{"x":3.2213248199895754,"y":4.120143677441306}},"time":0.6778670966585069,"velocity":3.385035795967152,"position":1.1487595018305852,"holonomicRotation":91.09638470163713,"angularVelocity":-0.3037203638200986,"angularAcceleration":-1.8096988284314146,"curveRadius":-11.084805955184265},{"acceleration":5.015208177898027,"curvature":-0.09082229973339752,"pose":{"rotation":{"radians":3.1090665597222107},"translation":{"x":3.21552659594522,"y":4.120332337556318}},"time":0.6795765723842373,"velocity":3.3936091726067534,"position":1.1545607943337726,"holonomicRotation":90.37942006213422,"angularVelocity":-0.3066917528990996,"angularAcceleration":-1.7381873484815844,"curveRadius":-11.010511767874517},{"acceleration":5.014815738745933,"curvature":-0.09138449519868269,"pose":{"rotation":{"radians":3.108540567361215},"translation":{"x":3.2097481561399666,"y":4.120523396625645}},"time":0.6812759769364884,"velocity":3.402131373301879,"position":1.1603423918769182,"holonomicRotation":89.66245542263128,"angularVelocity":-0.30951568318382017,"angularAcceleration":-1.6617175003914053,"curveRadius":-10.942775334326244},{"acceleration":5.0144213578154515,"curvature":-0.09189871495505275,"pose":{"rotation":{"radians":3.1080130800167076},"translation":{"x":3.2039886515183755,"y":4.1207168710600985}},"time":0.6829656346254277,"velocity":3.410604028904693,"position":1.1661051451982842,"holonomicRotation":88.94549078312836,"angularVelocity":-0.3121859226045433,"angularAcceleration":-1.5803434258920757,"curveRadius":-10.881544975782257},{"acceleration":5.014025122718454,"curvature":-0.09236357718387542,"pose":{"rotation":{"radians":3.1074843171751683},"translation":{"x":3.198247233025008,"y":4.120912777270492}},"time":0.684645866133159,"velocity":3.419028751896441,"position":1.17184990503306,"holonomicRotation":88.22852614362543,"angularVelocity":-0.3146964207648358,"angularAcceleration":-1.4941382474622054,"curveRadius":-10.826778590539229},{"acceleration":5.013627125352221,"curvature":-0.09277777638875637,"pose":{"rotation":{"radians":3.1069545022819107},"translation":{"x":3.1925230516044256,"y":4.121111131667634}},"time":0.6863169886027789,"velocity":3.427407136839913,"position":1.1775775221119686,"holonomicRotation":87.51156150412251,"angularVelocity":-0.3170413317331903,"angularAcceleration":-1.403195164318472,"curveRadius":-10.778443275141791},{"acceleration":5.013227463477944,"curvature":-0.09314008402549147,"pose":{"rotation":{"radians":3.1064238624685347},"translation":{"x":3.1868152582011873,"y":4.121311950662338}},"time":0.6879793157239132,"velocity":3.4357407608168677,"position":1.1832888471598613,"holonomicRotation":86.79459686461958,"angularVelocity":-0.31921503693802306,"angularAcceleration":-1.3076278292021324,"curveRadius":-10.736515974435996},{"acceleration":5.012826239852436,"curvature":-0.09344935712848952,"pose":{"rotation":{"radians":3.1058926282713624},"translation":{"x":3.1811230037598555,"y":4.121515250665414}},"time":0.6896331578148739,"velocity":3.4440311838470077,"position":1.1889847308942885,"holonomicRotation":86.07763222511666,"angularVelocity":-0.3212121641334031,"angularAcceleration":-1.2075682474739708,"curveRadius":-10.700983192693727},{"acceleration":5.012423562558424,"curvature":-0.09370454302273193,"pose":{"rotation":{"radians":3.105361033333645},"translation":{"x":3.17544543922499,"y":4.121721048087674}},"time":0.6912788219015752,"velocity":3.4522799492912455,"position":1.194666024024076,"holonomicRotation":85.36066758561373,"angularVelocity":-0.323027610563552,"angularAcceleration":-1.103169501491605,"curveRadius":-10.67184116950881},{"acceleration":5.012019543708169,"curvature":-0.09390468325012072,"pose":{"rotation":{"radians":3.104829314096575},"translation":{"x":3.1697817155411516,"y":4.12192935933993}},"time":0.6929166117933331,"velocity":3.4604885842372237,"position":1.2003335772478834,"holonomicRotation":84.6437029461108,"angularVelocity":-0.3246565629363179,"angularAcceleration":-0.9946039971082529,"curveRadius":-10.649096140779692},{"acceleration":5.011614301063897,"curvature":-0.09404891708679854,"pose":{"rotation":{"radians":3.1042977094802553},"translation":{"x":3.164130983652902,"y":4.122140200832994}},"time":0.6945468281556719,"velocity":3.4686585998725494,"position":1.205988241252763,"holonomicRotation":83.92673830660787,"angularVelocity":-0.32609451640949816,"angularAcceleration":-0.8820629619477365,"curveRadius":-10.632764639672477},{"acceleration":5.0112079556572615,"curvature":-0.09413648874656731,"pose":{"rotation":{"radians":3.1037664605536217},"translation":{"x":3.158492394504801,"y":4.122353588977675}},"time":0.6961697685802565,"velocity":3.4767914918397853,"position":1.2116308667127214,"holonomicRotation":83.20977366710495,"angularVelocity":-0.32733729383170623,"angularAcceleration":-0.7657566497095586,"curveRadius":-10.622873375829679},{"acceleration":5.010800633663063,"curvature":-0.09416674806225969,"pose":{"rotation":{"radians":3.1032358101930595},"translation":{"x":3.1528650990414095,"y":4.122569540184787}},"time":0.6977857276520577,"velocity":3.4848887405807405,"position":1.2172623042872808,"holonomicRotation":82.49280902760202,"angularVelocity":-0.3283810647324887,"angularAcceleration":-0.6459141936181632,"curveRadius":-10.619459847321432},{"acceleration":5.010392464661209,"curvature":-0.09413915521540075,"pose":{"rotation":{"radians":3.102706002736357},"translation":{"x":3.1472482482072888,"y":4.122788070865139}},"time":0.6993949970138605,"velocity":3.4929518116647276,"position":1.2228834046200465,"holonomicRotation":81.7758443880991,"angularVelocity":-0.329222359710546,"angularAcceleration":-0.5227807090758301,"curveRadius":-10.622572485507119},{"acceleration":5.009983582319117,"curvature":-0.09405328422919368,"pose":{"rotation":{"radians":3.102177283624176},"translation":{"x":3.141640992946999,"y":4.123009197429545}},"time":0.7009978654282155,"velocity":3.500982156105264,"position":1.228495018337288,"holonomicRotation":81.05887974859617,"angularVelocity":-0.3298580890645128,"angularAcceleration":-0.39661980251988405,"curveRadius":-10.63227093232758},{"acceleration":5.009574123280023,"curvature":-0.09390882560005082,"pose":{"rotation":{"radians":3.101649899039912},"translation":{"x":3.136042484205101,"y":4.123232936288814}},"time":0.7025946188369301,"velocity":3.5089812106628195,"position":1.2340979960465293,"holonomicRotation":80.34191510909324,"angularVelocity":-0.3302855540408673,"angularAcceleration":-0.2677088234297913,"curveRadius":-10.64862640556181},{"acceleration":5.0091642283599445,"curvature":-0.0937055859175873,"pose":{"rotation":{"radians":3.1011240955387014},"translation":{"x":3.130451872926156,"y":4.123459303853761}},"time":0.7041855404181929,"velocity":3.516950398137807,"position":1.2396931883351576,"holonomicRotation":79.62495046959032,"angularVelocity":-0.33050246310267106,"angularAcceleration":-0.13634176841802223,"curveRadius":-10.67172239741914},{"acceleration":5.0087540404594035,"curvature":-0.09344349414753732,"pose":{"rotation":{"radians":3.1006001196788127},"translation":{"x":3.1248683100547248,"y":4.123688316535193}},"time":0.7057709106414208,"velocity":3.524891127649024,"position":1.2452814457690526,"holonomicRotation":78.90798583008738,"angularVelocity":-0.33050693914376583,"angularAcceleration":-0.002823341216574788,"curveRadius":-10.701654610872177},{"acceleration":5.0083437057951015,"curvature":-0.09312259943583007,"pose":{"rotation":{"radians":3.1000782176407276},"translation":{"x":3.1192909465353678,"y":4.123919990743924}},"time":0.7073510073199122,"velocity":3.532804794903294,"position":1.2508636188912376,"holonomicRotation":78.19102119058446,"angularVelocity":-0.3302975350745074,"angularAcceleration":0.13252611192018454,"curveRadius":-10.738531850038088},{"acceleration":5.00793337301459,"curvature":-0.09274307387741212,"pose":{"rotation":{"radians":3.099558634853655},"translation":{"x":3.113718933312646,"y":4.124154342890765}},"time":0.7089261056613887,"velocity":3.540692782453354,"position":1.2564405582205578,"holonomicRotation":77.47405655108153,"angularVelocity":-0.3298732360961509,"angularAcceleration":0.26937935694780496,"curveRadius":-10.782476342349844},{"acceleration":5.007523192571937,"curvature":-0.09230520874717214,"pose":{"rotation":{"radians":3.0990416156144835},"translation":{"x":3.1081514213311197,"y":4.1243913893865285}},"time":0.7104964783165039,"velocity":3.548556459944824,"position":1.2620131142503874,"holonomicRotation":76.75709191157861,"angularVelocity":-0.3292334704679061,"angularAcceleration":0.4073973309207193,"curveRadius":-10.833624814597865},{"acceleration":5.007113317481237,"curvature":-0.09180942183950887,"pose":{"rotation":{"radians":3.0985274027099043},"translation":{"x":3.10258756153535,"y":4.124631146642024}},"time":0.7120623954253923,"velocity":3.556397184354811,"position":1.2675821374473712,"holonomicRotation":76.04012727207568,"angularVelocity":-0.3283781125197743,"angularAcceleration":0.5462344994359097,"curveRadius":-10.892128280124561},{"acceleration":5.006703902007008,"curvature":-0.09125624957532444,"pose":{"rotation":{"radians":3.098016237038632},"translation":{"x":3.0970265048698975,"y":4.1248736310680645}},"time":0.713624124662332,"velocity":3.5642163002192757,"position":1.273148478250201,"holonomicRotation":75.32316263257276,"angularVelocity":-0.32730748658699954,"angularAcceleration":0.6855387652680774,"curveRadius":-10.958153602122156},{"acceleration":5.006295102068121,"curvature":-0.09064634844544658,"pose":{"rotation":{"radians":3.097508357238926},"translation":{"x":3.0914674022793234,"y":4.12511885907546}},"time":0.715181931278588,"velocity":3.572015139852207,"position":1.278712987068429,"holonomicRotation":74.60619799306983,"angularVelocity":-0.3260223665803173,"angularAcceleration":0.8249547750483479,"curveRadius":-11.031883988154547},{"acceleration":5.005887074575939,"curvature":-0.08998049553751326,"pose":{"rotation":{"radians":3.0970039993161045},"translation":{"x":3.085909404708188,"y":4.125366847075023}},"time":0.7167360781435038,"velocity":3.579795023555282,"position":1.2842765142813288,"holonomicRotation":73.88923335356691,"angularVelocity":-0.32452397788593373,"angularAcceleration":0.9641229720363067,"curveRadius":-11.113519591399623},{"acceleration":5.005479976880897,"curvature":-0.0892595827030764,"pose":{"rotation":{"radians":3.0965033962791826},"translation":{"x":3.080351663101052,"y":4.125617611477565}},"time":0.7182868257839039,"velocity":3.5875572598185,"position":1.2898399102367926,"holonomicRotation":73.17226871406397,"angularVelocity":-0.32281399234806846,"angularAcceleration":1.1026845976203514,"curveRadius":-11.203278905375548},{"acceleration":5.00507396767728,"curvature":-0.08848461540240975,"pose":{"rotation":{"radians":3.0960067777813536},"translation":{"x":3.0747933284024773,"y":4.125871168693896}},"time":0.7198344324218674,"velocity":3.5953031455143756,"position":1.2954040252502816,"holonomicRotation":72.45530407456106,"angularVelocity":-0.32089452555108444,"angularAcceleration":1.2402807986852873,"curveRadius":-11.301399632605133},{"acceleration":5.004669205323286,"curvature":-0.08765671008243889,"pose":{"rotation":{"radians":3.0955143697687633},"translation":{"x":3.0692335515570233,"y":4.12612753513483}},"time":0.7213791540109331,"velocity":3.603033966081971,"position":1.3009697096038255,"holonomicRotation":71.73833943505812,"angularVelocity":-0.3187681301768681,"angularAcceleration":1.3765557426451376,"curveRadius":-11.40813976545008},{"acceleration":5.004265848234559,"curvature":-0.08677709002246381,"pose":{"rotation":{"radians":3.0950263941386873},"translation":{"x":3.063671483509251,"y":4.126386727211176}},"time":0.7229212442707897,"velocity":3.6107509957042665,"position":1.3065378135450687,"holonomicRotation":71.0213747955552,"angularVelocity":-0.3164377875788751,"angularAcceleration":1.5111583664432722,"curveRadius":-11.523778911474585},{"acceleration":5.003864054667639,"curvature":-0.0858470823744975,"pose":{"rotation":{"radians":3.094543068404797},"translation":{"x":3.058106275203722,"y":4.1266487613337475}},"time":0.7244609547205078,"velocity":3.6184554974782066,"position":1.3121091872863755,"holonomicRotation":70.30441015605227,"angularVelocity":-0.31390689981912645,"angularAcceleration":1.6437426661695707,"curveRadius":-11.648619526026769},{"acceleration":5.003463982139995,"curvature":-0.08486811083782153,"pose":{"rotation":{"radians":3.094064605378105},"translation":{"x":3.0525370775849963,"y":4.126913653913354}},"time":0.7259985347103637,"velocity":3.62614872357711,"position":1.3176846810039893,"holonomicRotation":69.58744551654935,"angularVelocity":-0.3111792751264479,"angularAcceleration":1.773972548208136,"curveRadius":-11.782988806136466},{"acceleration":5.0030657875040845,"curvature":-0.08384169464192212,"pose":{"rotation":{"radians":3.0935912128529797},"translation":{"x":3.0469630415976345,"y":4.127181421360809}},"time":0.727534231452307,"velocity":3.633831915406708,"position":1.323265144837249,"holonomicRotation":68.87048087704642,"angularVelocity":-0.308259119262175,"angularAcceleration":1.9015185645166248,"curveRadius":-11.927239833007679},{"acceleration":5.002669626000826,"curvature":-0.08276944274812278,"pose":{"rotation":{"radians":3.093123093313394},"translation":{"x":3.0413833181861984,"y":4.127452080086921}},"time":0.729068290049118,"velocity":3.64150630375348,"position":1.3288514288878635,"holonomicRotation":68.1535162375435,"angularVelocity":-0.30515101610760165,"angularAcceleration":2.0260654717065316,"curveRadius":-12.081753444240508},{"acceleration":5.0022756523654435,"curvature":-0.08165304345781152,"pose":{"rotation":{"radians":3.092660443645313},"translation":{"x":3.0357970582952474,"y":4.127725646502504}},"time":0.7306009535223039,"velocity":3.6491731089286676,"position":1.3344443832192507,"holonomicRotation":67.43655159804057,"angularVelocity":-0.3018599165279194,"angularAcceleration":2.14730737520684,"curveRadius":-12.246940930213825},{"acceleration":5.001884018385853,"curvature":-0.08049426625602099,"pose":{"rotation":{"radians":3.0922034548699284},"translation":{"x":3.0302034128693434,"y":4.128002137018369}},"time":0.7321324628387761,"velocity":3.656833540902739,"position":1.3400448578559312,"holonomicRotation":66.71958695853763,"angularVelocity":-0.29839111683443365,"angularAcceleration":2.2649550062653985,"curveRadius":-12.42324511437111},{"acceleration":5.001494875189775,"curvature":-0.0792949510526245,"pose":{"rotation":{"radians":3.0917523118879227},"translation":{"x":3.024601532853047,"y":4.128281568045327}},"time":0.733663056936354,"velocity":3.6644887994377706,"position":1.3456537027829911,"holonomicRotation":66.00262231903471,"angularVelocity":-0.29475024287606505,"angularAcceleration":2.378732522312757,"curveRadius":-12.61114341739545},{"acceleration":5.001108371155198,"curvature":-0.07805700192545657,"pose":{"rotation":{"radians":3.091307193241215},"translation":{"x":3.0189905691909185,"y":4.128563955994189}},"time":0.7351929727481363,"velocity":3.672140074211238,"position":1.3512717679456063,"holonomicRotation":65.28565767953178,"angularVelocity":-0.2909432292153711,"angularAcceleration":2.488381145795811,"curveRadius":-12.81115050966199},{"acceleration":5.000724652023743,"curvature":-0.0767823836859579,"pose":{"rotation":{"radians":3.0908682708910327},"translation":{"x":3.013369672827519,"y":4.128849317275767}},"time":0.7367224452257783,"velocity":3.679788544934774,"position":1.3568999032486264,"holonomicRotation":64.56869304002886,"angularVelocity":-0.28697629842877437,"angularAcceleration":2.5936594770979644,"curveRadius":-13.02382072546781},{"acceleration":5.000343861401252,"curvature":-0.07547311128090034,"pose":{"rotation":{"radians":3.0904357100121},"translation":{"x":3.0077379947074085,"y":4.129137668300873}},"time":0.7382517073617177,"velocity":3.687435381468692,"position":1.3625389585562298,"holonomicRotation":63.85172840052593,"angularVelocity":-0.2828559399771604,"angularAcceleration":2.694344125039679,"curveRadius":-13.249751905392374},{"acceleration":4.999966139808897,"curvature":-0.07413124801968704,"pose":{"rotation":{"radians":3.0900096688065166},"translation":{"x":3.0020946857751487,"y":4.129429025480318}},"time":0.7397809902103823,"velocity":3.6950817439302055,"position":1.368189783691636,"holonomicRotation":63.13476376102301,"angularVelocity":-0.2785888862583229,"angularAcceleration":2.7902318544692863,"curveRadius":-13.489588084830704},{"acceleration":4.999591624706285,"curvature":-0.0727588924292364,"pose":{"rotation":{"radians":3.0895902983324137},"translation":{"x":2.9964388969753006,"y":4.129723405224913}},"time":0.7413105229084195,"velocity":3.7027287827970263,"position":1.3738532284368872,"holonomicRotation":62.417799121520076,"angularVelocity":-0.27418209145909883,"angularAcceleration":2.881138013511821,"curveRadius":-13.744024498071857},{"acceleration":4.999220450148743,"curvature":-0.07135817979977022,"pose":{"rotation":{"radians":3.089177742353017},"translation":{"x":2.990769779252424,"y":4.13002082394547}},"time":0.7428405326939808,"velocity":3.710377639005932,"position":1.379530142532694,"holonomicRotation":61.70083448201716,"angularVelocity":-0.26964270639959015,"angularAcceleration":2.9668993638778702,"curveRadius":-14.013810369126318},{"acceleration":4.998852747219622,"curvature":-0.06993126644991501,"pose":{"rotation":{"radians":3.088772137202909},"translation":{"x":2.9850864835510804,"y":4.130321298052801}},"time":0.7443712449250945,"velocity":3.718029444047638,"position":1.385221375678339,"holonomicRotation":60.983869842514224,"angularVelocity":-0.2649780552239295,"angularAcceleration":3.0473730338370366,"curveRadius":-14.299755327843275},{"acceleration":4.998488642952098,"curvature":-0.06848033048950734,"pose":{"rotation":{"radians":3.088373611673743},"translation":{"x":2.97938816081583,"y":4.130624843957715}},"time":0.7459028830971624,"velocity":3.7256853200558306,"position":1.390927777531649,"holonomicRotation":60.266905203011305,"angularVelocity":-0.26019561044763506,"angularAcceleration":3.1224377033107094,"curveRadius":-14.602733264454987},{"acceleration":4.99812826018471,"curvature":-0.06700755921193151,"pose":{"rotation":{"radians":3.0879822869166853},"translation":{"x":2.9736739619912345,"y":4.130931478071027}},"time":0.7474356688596083,"velocity":3.7333463798919206,"position":1.3966501977090267,"holonomicRotation":59.54994056350837,"angularVelocity":-0.2553029696943789,"angularAcceleration":3.19199256225387,"curveRadius":-14.923689383121687},{"acceleration":4.997771719130201,"curvature":-0.06551514808490388,"pose":{"rotation":{"radians":3.0875982763657097},"translation":{"x":2.9679430380218537,"y":4.131241216803545}},"time":0.7489698220317136,"velocity":3.741013727228282,"position":1.4023894857855432,"holonomicRotation":58.83297592400545,"angularVelocity":-0.25030782972512866,"angularAcceleration":3.255959092008777,"curveRadius":-15.263645572533196},{"acceleration":4.997419134534754,"curvature":-0.06400528813255606,"pose":{"rotation":{"radians":3.087221685676885},"translation":{"x":2.9621945398522485,"y":4.131554076566082}},"time":0.7505055606176653,"velocity":3.7486884566233605,"position":1.4081464912950914,"holonomicRotation":58.11601128450252,"angularVelocity":-0.24521796370135726,"angularAcceleration":3.3142789211207133,"curveRadius":-15.623709058679383},{"acceleration":4.997070617773726,"curvature":-0.06248016579651094,"pose":{"rotation":{"radians":3.086852612687305},"translation":{"x":2.95642761842698,"y":4.13187007376945}},"time":0.752043100820849,"velocity":3.756371653596336,"position":1.4139220637305956,"holonomicRotation":57.3990466449996,"angularVelocity":-0.24004119620156264,"angularAcceleration":3.3669152124121373,"curveRadius":-16.005079167953213},{"acceleration":4.996726275032141,"curvature":-0.06094195208729797,"pose":{"rotation":{"radians":3.086491147392717},"translation":{"x":2.950641424690609,"y":4.13218922482446}},"time":0.7535826570574138,"velocity":3.7640643946954686,"position":1.4197170525442804,"holonomicRotation":56.68208200549667,"angularVelocity":-0.23478537906128638,"angularAcceleration":3.413852001927284,"curveRadius":-16.409057566248002},{"acceleration":4.996386209368226,"curvature":-0.059392800583313116,"pose":{"rotation":{"radians":3.086137371939706},"translation":{"x":2.9448351095876957,"y":4.132511546141923}},"time":0.7551244419691348,"velocity":3.7717677475662033,"position":1.4255323071479937,"holonomicRotation":55.96511736599375,"angularVelocity":-0.22945837017943727,"angularAcceleration":3.455092108731961,"curveRadius":-16.837057525133073},{"acceleration":4.996050518030389,"curvature":-0.05783483600888036,"pose":{"rotation":{"radians":3.0857913606388174},"translation":{"x":2.9390078240628013,"y":4.132837054132651}},"time":0.756668666435602,"velocity":3.7794827710118524,"position":1.4313686769135818,"holonomicRotation":55.248152726490815,"angularVelocity":-0.22406800850668657,"angularAcceleration":3.4906594150021326,"curveRadius":-17.290617022696374},{"acceleration":4.995719293989686,"curvature":-0.05627015611235345,"pose":{"rotation":{"radians":3.0854531799920797},"translation":{"x":2.933158719060487,"y":4.133165765207455}},"time":0.758215539585761,"velocity":3.7872105150534563,"position":1.4372270111733179,"holonomicRotation":54.531188086987896,"angularVelocity":-0.21862209367521773,"angularAcceleration":3.52059561633031,"curveRadius":-17.771409732777723},{"acceleration":4.9953926259396555,"curvature":-0.05470082230919805,"pose":{"rotation":{"radians":3.0851228887377524},"translation":{"x":2.9272869455253128,"y":4.133497695777146}},"time":0.7597652688088287,"velocity":3.7949520209865715,"position":1.4431081592203803,"holonomicRotation":53.81422344748496,"angularVelocity":-0.21312836423995882,"angularAcceleration":3.544960857345339,"curveRadius":-18.28126082543092},{"acceleration":4.995070597352058,"curvature":-0.053128852890814274,"pose":{"rotation":{"radians":3.0848005379105268},"translation":{"x":2.92139165440184,"y":4.133832862252538}},"time":0.7613180597646096,"velocity":3.8027083214336272,"position":1.4490129703093755,"holonomicRotation":53.097258807982044,"angularVelocity":-0.20759447756025914,"angularAcceleration":3.5638323749228626,"curveRadius":-18.822164334229306},{"acceleration":4.994753287294406,"curvature":-0.05155622356353343,"pose":{"rotation":{"radians":3.0844861709178772},"translation":{"x":2.9154719966346287,"y":4.134171281044439}},"time":0.7628741163932379,"velocity":3.8104804403946844,"position":1.4549422936569099,"holonomicRotation":52.38029416847911,"angularVelocity":-0.20202798976966785,"angularAcceleration":3.577304121314996,"curveRadius":-19.396300405278645},{"acceleration":4.994440769501625,"curvature":-0.0499848598849621,"pose":{"rotation":{"radians":3.084179823628471},"translation":{"x":2.9095271231682407,"y":4.134512968563662}},"time":0.7644336409243638,"velocity":3.8182693932939777,"position":1.4608969784421992,"holonomicRotation":51.66332952897619,"angularVelocity":-0.19643633895587573,"angularAcceleration":3.5854843589764025,"curveRadius":-20.006057880355268},{"acceleration":4.994133113515475,"curvature":-0.048416634507320776,"pose":{"rotation":{"radians":3.0838815244783326},"translation":{"x":2.9035561849472358,"y":4.134857941221019}},"time":0.7659968338858131,"velocity":3.8260761870255657,"position":1.4668778738077262,"holonomicRotation":50.946364889473244,"angularVelocity":-0.19082682528316486,"angularAcceleration":3.588497268763454,"curveRadius":-20.654058469280766},{"acceleration":4.993830383011102,"curvature":-0.046853361693219533,"pose":{"rotation":{"radians":3.083591294586132},"translation":{"x":2.897558332916175,"y":4.135206215427321}},"time":0.7675638941117349,"velocity":3.833901819993782,"position":1.4728858288599276,"holonomicRotation":50.229400249970325,"angularVelocity":-0.18520659729576713,"angularAcceleration":3.5864786141781777,"curveRadius":-21.3431857152038},{"acceleration":4.993532638266166,"curvature":-0.045296798382409666,"pose":{"rotation":{"radians":3.083309147884172},"translation":{"x":2.8915327180196195,"y":4.135557807593378}},"time":0.7691350187502641,"velocity":3.8417472821550622,"position":1.4789216926699242,"holonomicRotation":49.512435610467406,"angularVelocity":-0.17958263465613358,"angularAcceleration":3.5795776488478745,"curveRadius":-22.076615471974176},{"acceleration":4.993239933031203,"curvature":-0.04374863718026871,"pose":{"rotation":{"radians":3.0830350912585884},"translation":{"x":2.88547849120213,"y":4.135912734130003}},"time":0.7707104032707169,"velocity":3.8496135550524664,"position":1.4849863142742792,"holonomicRotation":48.79547097096449,"angularVelocity":-0.17396173570670237,"angularAcceleration":3.567953649700472,"curveRadius":-22.857854883100565},{"acceleration":4.992952317622475,"curvature":-0.042210503752759754,"pose":{"rotation":{"radians":3.0827691247018443},"translation":{"x":2.8793948034082666,"y":4.136271011448009}},"time":0.77229024147034,"velocity":3.8575016118527428,"position":1.4910805426757916,"holonomicRotation":48.07850633146154,"angularVelocity":-0.1683505037462814,"angularAcceleration":3.55177635390753,"curveRadius":-23.690785730900433},{"acceleration":4.992669836621762,"curvature":-0.04068395777491968,"pose":{"rotation":{"radians":3.082511241475821},"translation":{"x":2.8732808055825907,"y":4.136632655958205}},"time":0.7738747254806324,"velocity":3.8654124173775393,"position":1.4972052268443121,"holonomicRotation":47.36154169195862,"angularVelocity":-0.16275533507957984,"angularAcceleration":3.531224443009007,"curveRadius":-24.579712857151453},{"acceleration":4.9923925303570185,"curvature":-0.03917049042727251,"pose":{"rotation":{"radians":3.082261428282414},"translation":{"x":2.867135648669663,"y":4.136997684071401}},"time":0.7754640457732618,"velocity":3.873346928134807,"position":1.5033612157175904,"holonomicRotation":46.6445770524557,"angularVelocity":-0.15718240971661507,"angularAcceleration":3.5064834878216598,"curveRadius":-25.529422508934136},{"acceleration":4.992120434324121,"curvature":-0.037671518624464745,"pose":{"rotation":{"radians":3.082019665442858},"translation":{"x":2.860958483614044,"y":4.137366112198413}},"time":0.7770583911655911,"velocity":3.8813060923472245,"position":1.5095493582021438,"holonomicRotation":45.92761241295278,"angularVelocity":-0.1516376819722214,"angularAcceleration":3.477745644745787,"curveRadius":-26.54525319164004},{"acceleration":4.99185357918273,"curvature":-0.03618839038687671,"pose":{"rotation":{"radians":3.081785927088336},"translation":{"x":2.854748461360295,"y":4.137737956750049}},"time":0.778657948825835,"velocity":3.889290849978622,"position":1.5157705031741435,"holonomicRotation":45.210647773449836,"angularVelocity":-0.146126870153889,"angularAcceleration":3.4452098572627623,"curveRadius":-27.633171558872043},{"acceleration":4.991591991307602,"curvature":-0.03472237815664827,"pose":{"rotation":{"radians":3.081560181351205},"translation":{"x":2.848504732852976,"y":4.138113234137122}},"time":0.7802629042778656,"velocity":3.8973021327593838,"position":1.5220254994803264,"holonomicRotation":44.49368313394692,"angularVelocity":-0.14065545361116114,"angularAcceleration":3.4090768910783247,"curveRadius":-28.799870662330502},{"acceleration":4.9913356920935446,"curvature":-0.03327468111993242,"pose":{"rotation":{"radians":3.0813423905679147},"translation":{"x":2.8422264490366485,"y":4.138491960770442}},"time":0.7818734414056816,"velocity":3.9053408642088936,"position":1.5283151959389119,"holonomicRotation":43.776718494444,"angularVelocity":-0.1352286634865934,"angularAcceleration":3.3695529465544363,"curveRadius":-30.052880037999024},{"acceleration":4.991084699150836,"curvature":-0.03184642451833314,"pose":{"rotation":{"radians":3.0811325114841135},"translation":{"x":2.835912760855873,"y":4.138874153060822}},"time":0.7834897424575623,"velocity":3.913407959658157,"position":1.5346404413405457,"holonomicRotation":43.05975385494108,"angularVelocity":-0.12985148005503017,"angularAcceleration":3.3268452218764635,"curveRadius":-31.4006992974777},{"acceleration":4.990839025117773,"curvature":-0.03043865884673662,"pose":{"rotation":{"radians":3.0809304954659162},"translation":{"x":2.8295628192552096,"y":4.139259827419072}},"time":0.7851119880499192,"velocity":3.921504326268817,"position":1.5410020844492438,"holonomicRotation":42.34278921543813,"angularVelocity":-0.12452862818615895,"angularAcceleration":3.281162786910591,"curveRadius":-32.852958635107925},{"acceleration":4.990598678618001,"curvature":-0.02905236248934525,"pose":{"rotation":{"radians":3.080736288712518},"translation":{"x":2.8231757751792204,"y":4.139649000256005}},"time":0.7867403571708639,"velocity":3.9296308630521057,"position":1.547400974003349,"holonomicRotation":41.62582457593521,"angularVelocity":-0.11926457637919628,"angularAcceleration":3.232714093662528,"curveRadius":-34.42060866364114},{"acceleration":4.990363664072099,"curvature":-0.027688437316055296,"pose":{"rotation":{"radians":3.080549832476184},"translation":{"x":2.8167507795724647,"y":4.140041687982431}},"time":0.7883750271835087,"velocity":3.937788460885957,"position":1.553837958716498,"holonomicRotation":40.90885993643229,"angularVelocity":-0.11406353263443289,"angularAcceleration":3.1817086656825007,"curveRadius":-36.11615883501466},{"acceleration":4.990133982066069,"curvature":-0.026347715826942782,"pose":{"rotation":{"radians":3.080371063278555},"translation":{"x":2.8102869833795046,"y":4.140437907009163}},"time":0.7900161738290131,"velocity":3.945978002531242,"position":1.5603138872785864,"holonomicRotation":40.191895296929374,"angularVelocity":-0.10892944766323014,"angularAcceleration":3.1283523536830447,"curveRadius":-37.95395420871417},{"acceleration":4.989909628960044,"curvature":-0.02503095466924219,"pose":{"rotation":{"radians":3.080199913135389},"translation":{"x":2.8037835375449,"y":4.14083767374701}},"time":0.7916639712293947,"velocity":3.9542003626459814,"position":1.5668296083567423,"holonomicRotation":39.47493065742643,"angularVelocity":-0.10386601115294236,"angularAcceleration":3.072851376701574,"curveRadius":-39.950533777634575},{"acceleration":4.989690597195425,"curvature":-0.023738843070897075,"pose":{"rotation":{"radians":3.080036309774506},"translation":{"x":2.797239593013212,"y":4.141241004606787}},"time":0.7933185918901168,"velocity":3.9624564077987117,"position":1.5733859705962967,"holonomicRotation":38.75796601792351,"angularVelocity":-0.09887665781459033,"angularAcceleration":3.0154061633526643,"curveRadius":-42.12505205133447},{"acceleration":4.989476875871124,"curvature":-0.022471999028640183,"pose":{"rotation":{"radians":3.079880176863468},"translation":{"x":2.7906543007290017,"y":4.141647915999302}},"time":0.7949802067024693,"velocity":3.9707469964815494,"position":1.5799838226217546,"holonomicRotation":38.04100137842059,"angularVelocity":-0.09396456379485746,"angularAcceleration":2.956217038519525,"curveRadius":-44.49982392423197},{"acceleration":4.989268449795273,"curvature":-0.021230973220367478,"pose":{"rotation":{"radians":3.0797314342265043},"translation":{"x":2.7840268116368287,"y":4.142058424335367}},"time":0.7966489849457565,"velocity":3.9790729791204873,"position":1.5866240130377631,"holonomicRotation":37.32403673891764,"angularVelocity":-0.08913265591882161,"angularAcceleration":2.8954763135679817,"curveRadius":-47.10099671929648},{"acceleration":4.989065301290755,"curvature":-0.02001625124409465,"pose":{"rotation":{"radians":3.0795899980686103},"translation":{"x":2.777356276681255,"y":4.142472546025797}},"time":0.7983250942893049,"velocity":3.9874351980875535,"position":1.5933073904300712,"holonomicRotation":36.60707209941472,"angularVelocity":-0.08438361043590922,"angularAcceleration":2.833374505781714,"curveRadius":-49.959404875826976},{"acceleration":4.988867408420143,"curvature":-0.018828252486689345,"pose":{"rotation":{"radians":3.0794557811958954},"translation":{"x":2.770641846806841,"y":4.142890297481399}},"time":0.8000087007943067,"velocity":3.9958344877089615,"position":1.6000348033664888,"holonomicRotation":35.8901074599118,"angularVelocity":-0.07971985871771532,"angularAcceleration":2.7700960434271424,"curveRadius":-53.11167357177471},{"acceleration":4.9886747463930545,"curvature":-0.017667330813692855,"pose":{"rotation":{"radians":3.079328693231146},"translation":{"x":2.7638826729581476,"y":4.143311695112986}},"time":0.8016999689155119,"velocity":4.004271674274597,"position":1.6068071003978341,"holonomicRotation":35.173142820408884,"angularVelocity":-0.07514359382514302,"angularAcceleration":2.7058186902449592,"curveRadius":-56.60164574633775},{"acceleration":4.988487287033454,"curvature":-0.016533786808209515,"pose":{"rotation":{"radians":3.0792086408305965},"translation":{"x":2.757077906079735,"y":4.1437367553313695}},"time":0.8033990615027802,"velocity":4.012747576045678,"position":1.6136251300588722,"holonomicRotation":34.45617818090594,"angularVelocity":-0.07065677376804287,"angularAcceleration":2.6407154564271167,"curveRadius":-60.482212066716045},{"acceleration":4.988304999754842,"curvature":-0.01542785840887949,"pose":{"rotation":{"radians":3.0790955278968304},"translation":{"x":2.7502266971161644,"y":4.144165494547362}},"time":0.8051061398025081,"velocity":4.021263003263184,"position":1.6204897408692416,"holonomicRotation":33.73921354140302,"angularVelocity":-0.06626112802451618,"angularAcceleration":2.5749526218142633,"curveRadius":-64.81781032061137},{"acceleration":4.988127850459496,"curvature":-0.014349724042812763,"pose":{"rotation":{"radians":3.078989255787636},"translation":{"x":2.7433281970119965,"y":4.1445979291717725}},"time":0.806821363458943,"velocity":4.029818758153613,"position":1.6274017813343715,"holonomicRotation":33.0222489019001,"angularVelocity":-0.06195816434536617,"angularAcceleration":2.508689559525955,"curveRadius":-69.68775127775801},{"acceleration":4.987955802584965,"curvature":-0.013299516939237461,"pose":{"rotation":{"radians":3.0788897235200077},"translation":{"x":2.736381556711792,"y":4.145034075615416}},"time":0.8085448905153955,"velocity":4.038415634935758,"position":1.6343620999463842,"holonomicRotation":32.30528426239718,"angularVelocity":-0.0577491761766309,"angularAcceleration":2.442078383961385,"curveRadius":-75.19070087799263},{"acceleration":4.987788817096265,"curvature":-0.012277306653399633,"pose":{"rotation":{"radians":3.0787968279752493},"translation":{"x":2.729385927160112,"y":4.145473950289101}},"time":0.8102768774153633,"velocity":4.047054419826774,"position":1.6413715451849809,"holonomicRotation":31.588319622894232,"angularVelocity":-0.05363524675623072,"angularAcceleration":2.3752658986489408,"curveRadius":-81.45108925198151},{"acceleration":4.9876268523520455,"curvature":-0.011283122938504787,"pose":{"rotation":{"radians":3.0787104640920613},"translation":{"x":2.7223404593015164,"y":4.14591756960364}},"time":0.8120174790035781,"velocity":4.0557358910474015,"position":1.648430965518318,"holonomicRotation":30.871354983391313,"angularVelocity":-0.04961726093599024,"angularAcceleration":2.308389149731414,"curveRadius":-88.62794506894893},{"acceleration":4.987469864019926,"curvature":-0.010316944423146351,"pose":{"rotation":{"radians":3.078630525062073},"translation":{"x":2.715244304080567,"y":4.146364949969843}},"time":0.8137668485269861,"velocity":4.064460818826434,"position":1.6555412094038588,"holonomicRotation":30.154390343888394,"angularVelocity":-0.04569590867951275,"angularAcceleration":2.241580297362342,"curveRadius":-96.92792351933895},{"acceleration":4.987317806184727,"curvature":-0.0093787093057386,"pose":{"rotation":{"radians":3.0785569025157673},"translation":{"x":2.7080966124418238,"y":4.146816107798524}},"time":0.8155251376356746,"velocity":4.073229965406616,"position":1.6627031252892168,"holonomicRotation":29.437425704385475,"angularVelocity":-0.04187169558282893,"angularAcceleration":2.174962625763147,"curveRadius":-106.62447970192709},{"acceleration":4.987170630509862,"curvature":-0.008468304603316873,"pose":{"rotation":{"radians":3.0784894867058963},"translation":{"x":2.7008965353298486,"y":4.147271059500493}},"time":0.8172924963837536,"velocity":4.082044085048611,"position":1.6699175616129716,"holonomicRotation":28.720461064882528,"angularVelocity":-0.038144949317333414,"angularAcceleration":2.108652965645075,"curveRadius":-118.08739137800015},{"acceleration":4.987028286438062,"curvature":-0.007585586298003647,"pose":{"rotation":{"radians":3.078428166684511},"translation":{"x":2.693643223689201,"y":4.1477298214865606}},"time":0.819069073230207,"velocity":4.0909039240349045,"position":1.6771853668054773,"holonomicRotation":28.00349642537961,"angularVelocity":-0.034515828295238,"angularAcceleration":2.0427605084127416,"curveRadius":-131.82896624130123},{"acceleration":4.986890722059134,"curvature":-0.006730371735334813,"pose":{"rotation":{"radians":3.0783728304733486},"translation":{"x":2.6863358284644425,"y":4.148192410167542}},"time":0.8208550150397179,"velocity":4.099810220674892,"position":1.684507389289641,"holonomicRotation":27.28653178587669,"angularVelocity":-0.030984330434210776,"angularAcceleration":1.9773868567387545,"curveRadius":-148.5802031929301},{"acceleration":4.986757883198392,"curvature":-0.005902434478225458,"pose":{"rotation":{"radians":3.0783233652332527},"translation":{"x":2.6789735006001334,"y":4.1486588419542425}},"time":0.8226504670834838,"velocity":4.108763705308046,"position":1.6918844774816872,"holonomicRotation":26.56956714637377,"angularVelocity":-0.027550298693703335,"angularAcceleration":1.9126279381457392,"curveRadius":-169.4216180948858},{"acceleration":4.986629714436672,"curvature":-0.00510152986456313,"pose":{"rotation":{"radians":3.0782796574196207},"translation":{"x":2.671555391040835,"y":4.149129133257479}},"time":0.8244555730400274,"velocity":4.117765100308653,"position":1.6993174797919017,"holonomicRotation":25.852602506870824,"angularVelocity":-0.024213433828358173,"angularAcceleration":1.8485700815782402,"curveRadius":-196.01963068888847},{"acceleration":4.986506158989752,"curvature":-0.004327370638100084,"pose":{"rotation":{"radians":3.078241592941875},"translation":{"x":2.6640806507311074,"y":4.14960330048806}},"time":0.8262704749960154,"velocity":4.12681512009015,"position":1.7068072446253542,"holonomicRotation":25.135637867367905,"angularVelocity":-0.02097329699833304,"angularAcceleration":1.7852957948140384,"curveRadius":-231.08720829123303},{"acceleration":4.986387157916302,"curvature":-0.003579641617435361,"pose":{"rotation":{"radians":3.0782090573081966},"translation":{"x":2.6565484306155116,"y":4.150081360056799}},"time":0.8280953134470928,"velocity":4.135914471107874,"position":1.7143546203825992,"holonomicRotation":24.418673227864986,"angularVelocity":-0.017829322732170097,"angularAcceleration":1.7228781343941577,"curveRadius":-279.3575745486084},{"acceleration":4.986272651680994,"curvature":-0.002858015407389563,"pose":{"rotation":{"radians":3.0781819357706954},"translation":{"x":2.648957881638609,"y":4.150563328374505}},"time":0.8299302272987419,"velocity":4.145063851864543,"position":1.7219604554603556,"holonomicRotation":23.701708588362038,"angularVelocity":-0.014780823348626404,"angularAcceleration":1.6613855635804624,"curveRadius":-349.89314522743393},{"acceleration":4.986162579662306,"curvature":-0.002162115664997583,"pose":{"rotation":{"radians":3.07816011346059},"translation":{"x":2.6413081547449595,"y":4.151049221851992}},"time":0.8317753538671765,"velocity":4.154263952914812,"position":1.7296255982521689,"holonomicRotation":22.98474394885912,"angularVelocity":-0.011826999014016923,"angularAcceleration":1.6008789777036734,"curveRadius":-462.50994624800416},{"acceleration":4.986056879492287,"curvature":-0.0014915655536315152,"pose":{"rotation":{"radians":3.0781434755200525},"translation":{"x":2.6335984008791242,"y":4.151539056900069}},"time":0.8336308288802768,"velocity":4.163515456868607,"position":1.7373508971490457,"holonomicRotation":22.2677793093562,"angularVelocity":-0.008966944000771027,"angularAcceleration":1.5414139199142187,"curveRadius":-670.4365071754974},{"acceleration":4.98595548842236,"curvature":-0.0008459635822892891,"pose":{"rotation":{"radians":3.078131907225631},"translation":{"x":2.625827770985664,"y":4.152032849929549}},"time":0.8354967864785764,"velocity":4.172819038397012,"position":1.7451372005400716,"holonomicRotation":21.55081466985328,"angularVelocity":-0.006199655572048763,"angularAcceleration":1.4830392883761656,"curveRadius":-1182.0839820242238},{"acceleration":4.985858342801436,"curvature":-0.00022483755193088384,"pose":{"rotation":{"radians":3.0781252941086934},"translation":{"x":2.617995416009139,"y":4.152530617351243}},"time":0.8373733592163064,"velocity":4.182175364237297,"position":1.7529853568130054,"holonomicRotation":20.833850030350334,"angularVelocity":-0.0035240397585730907,"angularAcceleration":1.4257991495241602,"curveRadius":-4447.655613629012},{"acceleration":4.985765377594775,"curvature":0.0003720617552200264,"pose":{"rotation":{"radians":3.078123522067021},"translation":{"x":2.610100486894112,"y":4.153032375575962}},"time":0.8392606780625074,"velocity":4.191585093197168,"position":1.7608962143548514,"holonomicRotation":20.116885390847415,"angularVelocity":-0.0009389201385217757,"angularAcceleration":1.369731259376213,"curveRadius":2687.725857253534},{"acceleration":4.9856765278127515,"curvature":0.0009454296465370401,"pose":{"rotation":{"radians":3.078126477472804},"translation":{"x":2.602142134585141,"y":4.153538141014519}},"time":0.8411588724022143,"velocity":4.201048876161872,"position":1.7688706215524141,"holonomicRotation":19.399920751344496,"angularVelocity":0.0015569563776424418,"angularAcceleration":1.3148688013417746,"curveRadius":1057.7201631690339},{"acceleration":4.985591727588008,"curvature":0.0014956269857845585,"pose":{"rotation":{"radians":3.078134047274115},"translation":{"x":2.5941195100267884,"y":4.154047930077724}},"time":0.8430680700377217,"velocity":4.210567356099788,"position":1.7769094267928243,"holonomicRotation":18.682956111841577,"angularVelocity":0.003964912364403831,"angularAcceleration":1.2612397700364366,"curveRadius":668.6159112563964},{"acceleration":4.985510910654245,"curvature":0.002023105413946939,"pose":{"rotation":{"radians":3.07814611908986},"translation":{"x":2.5860317641636144,"y":4.154561759176389}},"time":0.8449883971899376,"velocity":4.220141168069186,"position":1.7850134784640517,"holonomicRotation":17.96599147233863,"angularVelocity":0.006286332894307879,"angularAcceleration":1.2088672116234527,"curveRadius":494.28961689597236},{"acceleration":4.985434009921596,"curvature":0.0025283705263388153,"pose":{"rotation":{"radians":3.07816258130053},"translation":{"x":2.5778780479401804,"y":4.155079644721325}},"time":0.8469199784998317,"velocity":4.229770939224461,"position":1.793183624955391,"holonomicRotation":17.24902683283571,"angularVelocity":0.008522659950101041,"angularAcceleration":1.1577700841989096,"curveRadius":395.5116505206384},{"acceleration":4.985360958481587,"curvature":0.0030119335580024347,"pose":{"rotation":{"radians":3.0781833231335733},"translation":{"x":2.5696575123010468,"y":4.155601603123344}},"time":0.8488629370299846,"velocity":4.239457288824634,"position":1.8014207146579317,"holonomicRotation":16.53206219333279,"angularVelocity":0.010675386386910084,"angularAcceleration":1.107963141467367,"curveRadius":332.0126359836493},{"acceleration":4.9852916887157575,"curvature":0.0034742580187149858,"pose":{"rotation":{"radians":3.0782082347419557},"translation":{"x":2.5613693081907742,"y":4.156127650793256}},"time":0.8508173942662436,"velocity":4.2492008282405065,"position":1.809725595965004,"holonomicRotation":15.815097553829872,"angularVelocity":0.012746049348229331,"angularAcceleration":1.0594567754691318,"curveRadius":287.83124184019795},{"acceleration":4.985226133369124,"curvature":0.003915874010842029,"pose":{"rotation":{"radians":3.078237207278571},"translation":{"x":2.5530125865539235,"y":4.156657804141874}},"time":0.8527834701194913,"velocity":4.259002160964303,"position":1.8180991172726058,"holonomicRotation":15.098132914326925,"angularVelocity":0.014736225241410836,"angularAcceleration":1.0122579400453895,"curveRadius":255.3708309387028},{"acceleration":4.985164224461634,"curvature":0.004337279680844386,"pose":{"rotation":{"radians":3.0782701329657716},"translation":{"x":2.5445864983350552,"y":4.15719207958001}},"time":0.8547612829275335,"velocity":4.268861882617637,"position":1.82654212697981,"holonomicRotation":14.381168274824006,"angularVelocity":0.01664752451132852,"angularAcceleration":0.9663701550247484,"curveRadius":230.5592614690042},{"acceleration":1.381018701073878,"curvature":0.004738979968846007,"pose":{"rotation":{"radians":3.078306905160164},"translation":{"x":2.5360901944787306,"y":4.157730493518474}},"time":0.8567542874436025,"velocity":4.271614259125653,"position":1.8350554734891522,"holonomicRotation":13.664203635321087,"angularVelocity":0.01845063274874336,"angularAcceleration":0.904718590889749,"curveRadius":211.01587400115363},{"acceleration":-3.5889591973779607,"curvature":0.005121494262890359,"pose":{"rotation":{"radians":3.0783474184104382},"translation":{"x":2.5275228259295104,"y":4.158273062368078}},"time":0.858767361503086,"velocity":4.264389418464867,"position":1.8436400052069997,"holonomicRotation":12.947238995818168,"angularVelocity":0.02012506697567504,"angularAcceleration":0.8317797445372248,"curveRadius":195.2555150253437},{"acceleration":-4.973313530244613,"curvature":0.005485332658649037,"pose":{"rotation":{"radians":3.0783915685141072},"translation":{"x":2.5188835436319548,"y":4.158819802539633}},"time":0.860802156157011,"velocity":4.254269746681232,"position":1.8522965705439014,"holonomicRotation":12.23027435631522,"angularVelocity":0.02169757207874535,"angularAcceleration":0.7728077622167208,"curveRadius":182.3043491123994},{"acceleration":-4.973166604097148,"curvature":0.005831008372141636,"pose":{"rotation":{"radians":3.0784392525665125},"translation":{"x":2.5101714985306254,"y":4.159370730443952}},"time":0.8628590279529615,"velocity":4.244040580556701,"position":1.8610260179149183,"holonomicRotation":11.513309716812302,"angularVelocity":0.02318280239885202,"angularAcceleration":0.7220821069308603,"curveRadius":171.49692406164667},{"acceleration":-4.973021263348572,"curvature":0.006159024740059898,"pose":{"rotation":{"radians":3.0784903690078234},"translation":{"x":2.501385841570082,"y":4.159925862491844}},"time":0.8649383386188922,"velocity":4.233700124401921,"position":1.8698291957399393,"holonomicRotation":10.796345077309383,"angularVelocity":0.024583359354798086,"angularAcceleration":0.6735679179133995,"curveRadius":162.36336793644293},{"acceleration":-4.972877411997456,"curvature":0.0064698888188374605,"pose":{"rotation":{"radians":3.078544817663931},"translation":{"x":2.492525723694886,"y":4.1604852150941225}},"time":0.8670404552218027,"velocity":4.223246556229922,"position":1.8787069524439748,"holonomicRotation":10.079380437806464,"angularVelocity":0.025901824871385606,"angularAcceleration":0.6272085548261398,"curveRadius":154.56216142206978},{"acceleration":-4.972734953910177,"curvature":0.006764110929482284,"pose":{"rotation":{"radians":3.078602499785715},"translation":{"x":2.483590295849598,"y":4.161048804661596}},"time":0.8691657503324649,"velocity":4.212678026945758,"position":1.8876601364574366,"holonomicRotation":9.362415798303516,"angularVelocity":0.027140758709009474,"angularAcceleration":0.5829467312131799,"curveRadius":147.83908933861005},{"acceleration":-4.972593790934604,"curvature":0.007042183076450442,"pose":{"rotation":{"radians":3.078663318080503},"translation":{"x":2.4745787089787794,"y":4.161616647605081}},"time":0.8713146021964804,"velocity":4.201992659509116,"position":1.896689596216402,"holonomicRotation":8.645451158800597,"angularVelocity":0.028302693082914512,"angularAcceleration":0.5407233478317934,"curveRadius":142.00142046066236},{"acceleration":-4.972453824776027,"curvature":0.007304602286722257,"pose":{"rotation":{"radians":3.0787271767458786},"translation":{"x":2.46549011402699,"y":4.162188760335385}},"time":0.873487394911967,"velocity":4.191188548060549,"position":1.9057961801628591,"holonomicRotation":7.928486519297678,"angularVelocity":0.029390132303215594,"angularAcceleration":0.5004799641265016,"curveRadius":136.89999273714366},{"acceleration":-4.972314955825648,"curvature":0.0075518578484721445,"pose":{"rotation":{"radians":3.078793981493087},"translation":{"x":2.456323661938791,"y":4.162765159263319}},"time":0.8756845186141883,"velocity":4.180263757016196,"position":1.9149807367449359,"holonomicRotation":7.211521879794731,"angularVelocity":0.030405546642998913,"angularAcceleration":0.462156199378649,"curveRadius":132.41774674060042},{"acceleration":-4.972177082926556,"curvature":0.0077844314591994515,"pose":{"rotation":{"radians":3.078863639571344},"translation":{"x":2.4470785036587426,"y":4.163345860799699}},"time":0.8779063696674577,"velocity":4.169216320127453,"position":1.9242441144171192,"holonomicRotation":6.494557240291812,"angularVelocity":0.03135137171080572,"angularAcceleration":0.4256923822211364,"curveRadius":128.46153315644193},{"acceleration":-4.972040104316757,"curvature":0.008002803588965976,"pose":{"rotation":{"radians":3.0789360597897253},"translation":{"x":2.437753790131407,"y":4.16393088135533}},"time":0.8801533508646687,"velocity":4.158044239501274,"position":1.93358716164045,"holonomicRotation":5.777592600788893,"angularVelocity":0.03223000640644624,"angularAcceleration":0.3910289488541772,"curveRadius":124.95620926880797},{"acceleration":-4.971903916873492,"curvature":0.008207437969626745,"pose":{"rotation":{"radians":3.0790111525303154},"translation":{"x":2.4283486723013437,"y":4.164520237341029}},"time":0.882425871634825,"velocity":4.146745484582958,"position":1.9430107268827166,"holonomicRotation":5.060627961285974,"angularVelocity":0.03304380825746194,"angularAcceleration":0.3581053523043208,"curveRadius":121.840701532037},{"acceleration":-4.971768416513927,"curvature":0.008398802761043909,"pose":{"rotation":{"radians":3.079088829766494},"translation":{"x":2.418862301113114,"y":4.165113945167604}},"time":0.8847243482589608,"velocity":4.135317991096984,"position":1.9525156586186214,"holonomicRotation":4.343663321783026,"angularVelocity":0.033795095135047096,"angularAcceleration":0.3268629620575817,"curveRadius":119.06458913861997},{"acceleration":-4.971633497250062,"curvature":0.008577351488428551,"pose":{"rotation":{"radians":3.0791690050699585},"translation":{"x":2.409293827511278,"y":4.165712021245869}},"time":0.887049204094872,"velocity":4.123759659946891,"position":1.9621028053299439,"holonomicRotation":3.6266986822801073,"angularVelocity":0.03448613983984603,"angularAcceleration":0.2972419597484888,"curveRadius":116.58610485405316},{"acceleration":-4.971499052571742,"curvature":0.008743528016852848,"pose":{"rotation":{"radians":3.0792515936229585},"translation":{"x":2.3996424024403975,"y":4.166314481986634}},"time":0.889400869811098,"velocity":4.1120683560667075,"position":1.9717730155056838,"holonomicRotation":2.9097340427771883,"angularVelocity":0.03511917209584024,"angularAcceleration":0.2691846258702561,"curveRadius":114.37030888132738},{"acceleration":-4.971364974380392,"curvature":0.00894576692617091,"pose":{"rotation":{"radians":3.079336512221193},"translation":{"x":2.3899071768450324,"y":4.166921343800709}},"time":0.8917797836306268,"velocity":4.1002419072272325,"position":1.981527137642198,"holonomicRotation":2.1927694032742693,"angularVelocity":0.0356963743442299,"angularAcceleration":0.24263268540933505,"curveRadius":111.78471429593054},{"acceleration":-3.7284315688076237,"curvature":-0.05850656047721708,"pose":{"rotation":{"radians":3.0794685405423894},"translation":{"x":2.3701819278590945,"y":4.168148336292042}},"time":0.8966211477732225,"velocity":4.082191212321885,"position":2.0012905118007525,"holonomicRotation":0.7588401242685351,"angularVelocity":0.027270892522765336,"angularAcceleration":-1.7403115265250813,"curveRadius":-17.092100301972255},{"acceleration":-8.851196237227965,"curvature":-0.23220336431768876,"pose":{"rotation":{"radians":3.0786637646269432},"translation":{"x":2.362450016543886,"y":4.1686355401669495}},"time":0.8985268376471127,"velocity":4.065323577280785,"position":2.0090377577760634,"holonomicRotation":0.755804763771461,"angularVelocity":-0.42230161710589237,"angularAcceleration":-235.9106357168835,"curveRadius":-4.306569816240264},{"acceleration":-5.0047091679622,"curvature":-0.23410185649509602,"pose":{"rotation":{"radians":3.076868621183555},"translation":{"x":2.354751596762278,"y":4.1691345098944295}},"time":0.9004289445845702,"velocity":4.055804085252447,"position":2.0167523308635906,"holonomicRotation":0.7527694032743868,"angularVelocity":-0.9437657831098497,"angularAcceleration":-274.1508144126648,"curveRadius":-4.27164489411449},{"acceleration":-5.00465211039255,"curvature":-0.23599150745589778,"pose":{"rotation":{"radians":3.075066413837035},"translation":{"x":2.347086385766985,"y":4.169645201176951}},"time":0.902327518571744,"velocity":4.046302382940802,"position":2.024434535312081,"holonomicRotation":0.7497340427773127,"angularVelocity":-0.9492426203536243,"angularAcceleration":-2.884710988760303,"curveRadius":-4.237440621404058},{"acceleration":-5.0045940424615125,"curvature":-0.2378715054828685,"pose":{"rotation":{"radians":3.0732572620468566},"translation":{"x":2.339454100810722,"y":4.1701675697169875}},"time":0.9042226101064802,"velocity":4.0368182191361415,"position":2.032084675346435,"holonomicRotation":0.7466986822802385,"angularVelocity":-0.9546514018016542,"angularAcceleration":-2.854100368710047,"curveRadius":-4.203950355340144},{"acceleration":-5.004534958778758,"curvature":-0.2397410246430762,"pose":{"rotation":{"radians":3.0714412888959086},"translation":{"x":2.331854459146203,"y":4.170701571217012}},"time":0.9061142702010166,"velocity":4.027351340062907,"position":2.03970305516311,"holonomicRotation":0.7436633217831644,"angularVelocity":-0.9599891419144985,"angularAcceleration":-2.821722638364518,"curveRadius":-4.1711676234336155},{"acceleration":-5.004474853579516,"curvature":-0.24159922487753202,"pose":{"rotation":{"radians":3.0696186211135608},"translation":{"x":2.3242871780261427,"y":4.171247161379497}},"time":0.9080025503846918,"velocity":4.017901489367192,"position":2.047289978925441,"holonomicRotation":0.7406279612860902,"angularVelocity":-0.9652528253515872,"angularAcceleration":-2.7875542425298536,"curveRadius":-4.139086127063965},{"acceleration":-5.004413721170654,"curvature":-0.2434452519667097,"pose":{"rotation":{"radians":3.067789389099617},"translation":{"x":2.3167519747032554,"y":4.171804295906915}},"time":0.9098875027066705,"velocity":4.0084684081033295,"position":2.0548457507588735,"holonomicRotation":0.7375926007890161,"angularVelocity":-0.9704394072013932,"angularAcceleration":-2.7515719041431486,"curveRadius":-4.107699747361458},{"acceleration":-5.004351557211614,"curvature":-0.24527823823609385,"pose":{"rotation":{"radians":3.065953726945227},"translation":{"x":2.309248566430256,"y":4.172372930501739}},"time":0.9117691797386891,"velocity":3.999051834717978,"position":2.062370674746114,"holonomicRotation":0.7345572402919419,"angularVelocity":-0.9755458153307939,"angularAcceleration":-2.713753764599408,"curveRadius":-4.077002538796144},{"acceleration":-5.004288355420215,"curvature":-0.24709730275101224,"pose":{"rotation":{"radians":3.0641117724526756},"translation":{"x":2.3017766704598586,"y":4.172953020866441}},"time":0.9136476345778184,"velocity":3.9896515050403405,"position":2.0698650549221966,"holonomicRotation":0.7315218797948678,"angularVelocity":-0.9805689517695346,"angularAcceleration":-2.674078894049474,"curveRadius":-4.046988732239019},{"acceleration":-5.004224112002407,"curvature":-0.24890155145564602,"pose":{"rotation":{"radians":3.062263667152692},"translation":{"x":2.2943360040447773,"y":4.1735445227034935}},"time":0.91552292084925,"velocity":3.9802671522639352,"position":2.0773291952694675,"holonomicRotation":0.7284865192977936,"angularVelocity":-0.9855056948573578,"angularAcceleration":-2.63252771751718,"curveRadius":-4.017652739212431},{"acceleration":-5.0041588216329975,"curvature":-0.2506900778639253,"pose":{"rotation":{"radians":3.060409556321083},"translation":{"x":2.286926284437727,"y":4.174147391715369}},"time":0.9173950927091031,"velocity":3.9708985069358382,"position":2.0847633997124855,"holonomicRotation":0.7254511588007195,"angularVelocity":-0.99035290048345,"angularAcceleration":-2.58908155284019,"curveRadius":-3.988989147559325},{"acceleration":-5.004092480134253,"curvature":-0.2524619632993656,"pose":{"rotation":{"radians":3.058549588991842},"translation":{"x":2.2795472288914223,"y":4.17476158360454}},"time":0.9192642048472575,"velocity":3.9615452969407725,"position":2.0921679721128457,"holonomicRotation":0.7224157983036454,"angularVelocity":-0.9951074048865822,"angularAcceleration":-2.543723464247077,"curveRadius":-3.9609927251267356},{"acceleration":-5.0040250830931505,"curvature":-0.2542162771474284,"pose":{"rotation":{"radians":3.0566839179693672},"translation":{"x":2.2721985546585777,"y":4.17538705407348}},"time":0.9211303124902118,"velocity":3.952207247487677,"position":2.099543216263922,"holonomicRotation":0.7193804378065712,"angularVelocity":-0.9997660261019311,"angularAcceleration":-2.496437562397793,"curveRadius":-3.933658423532287},{"acceleration":-5.003956625787779,"curvature":-0.25595207787694163,"pose":{"rotation":{"radians":3.054812699838713},"translation":{"x":2.2648799789919076,"y":4.176023758824659}},"time":0.9229934714039705,"velocity":3.942884081096279,"position":2.1068894358855337,"holonomicRotation":0.7163450773094971,"angularVelocity":-1.0043255660245696,"angularAcceleration":-2.447209354482946,"curveRadius":-3.9069813704766516},{"acceleration":-5.003887105459624,"curvature":-0.25766841271444596,"pose":{"rotation":{"radians":3.052936094971789},"translation":{"x":2.257591219144126,"y":4.176671653560553}},"time":0.9248537378969605,"velocity":3.9335755175792877,"position":2.114206934618532,"holonomicRotation":0.713309716812423,"angularVelocity":-1.0087828136428068,"angularAcceleration":-2.396026394623228,"curveRadius":-3.8809568835595805},{"acceleration":-5.00381651745627,"curvature":-0.25936431877207633,"pose":{"rotation":{"radians":3.0510542675349193},"translation":{"x":2.2503319923679483,"y":4.177330693983633}},"time":0.9267111688229791,"velocity":3.9242812740316415,"position":2.1214960160193144,"holonomicRotation":0.7102743563153489,"angularVelocity":-1.0131345454139493,"angularAcceleration":-2.342876771450334,"curveRadius":-3.8555804620094176},{"acceleration":-5.003744858342127,"curvature":-0.2610388233060775,"pose":{"rotation":{"radians":3.0491673854901022},"translation":{"x":2.243102015916089,"y":4.17800083579637}},"time":0.9285658215841776,"velocity":3.9150010648137847,"position":2.128756983554266,"holonomicRotation":0.7072389958182747,"angularVelocity":-1.0173775297957888,"angularAcceleration":-2.287751362739028,"curveRadius":-3.8308477924276554},{"acceleration":-5.0036721253474425,"curvature":-0.2626909441977588,"pose":{"rotation":{"radians":3.0472756205961367},"translation":{"x":2.2359010070412615,"y":4.1786820347012394}},"time":0.9304177541340799,"velocity":3.9057346015358148,"position":2.13599014059413,"holonomicRotation":0.7042036353212006,"angularVelocity":-1.0215085285181364,"angularAcceleration":-2.2306421054943435,"curveRadius":-3.8067547514968036},{"acceleration":-5.003598314538145,"curvature":-0.26431969115824594,"pose":{"rotation":{"radians":3.0453791484087422},"translation":{"x":2.2287286829961803,"y":4.179374246400711}},"time":0.9322670249806401,"velocity":3.8964815930448418,"position":2.1431957904083063,"holonomicRotation":0.7011682748241264,"angularVelocity":-1.0255242983590238,"angularAcceleration":-2.1715422856295494,"curveRadius":-3.7832973987598546},{"acceleration":-5.003523423902806,"curvature":-0.2659240653422759,"pose":{"rotation":{"radians":3.0434781482734397},"translation":{"x":2.221584761033561,"y":4.180077426597259}},"time":0.9341136931893402,"velocity":3.887241745406434,"position":2.1503742361590805,"holonomicRotation":0.6981329143270523,"angularVelocity":-1.0294215963357423,"angularAcceleration":-2.1104484055972823,"curveRadius":-3.7604719930589243},{"acceleration":-5.003447449775616,"curvature":-0.2675030605211856,"pose":{"rotation":{"radians":3.0415728033220013},"translation":{"x":2.2144689584061177,"y":4.180791530993356}},"time":0.9359578183863332,"velocity":3.8780147618924725,"position":2.157525780895797,"holonomicRotation":0.6950975538299781,"angularVelocity":-1.0331971790989147,"angularAcceleration":-2.0473570717047687,"curveRadius":-3.7382749866549747},{"acceleration":-5.003370390640368,"curvature":-0.26905566400844216,"pose":{"rotation":{"radians":3.0396633004620317},"translation":{"x":2.2073809923665646,"y":4.181516515291473}},"time":0.9377994607616297,"velocity":3.8688003429617654,"position":2.164650727548957,"holonomicRotation":0.692062193332904,"angularVelocity":-1.0368478080127717,"angularAcceleration":-1.9822680900623801,"curveRadius":-3.716703023834588},{"acceleration":-5.003292243842429,"curvature":-0.27058085675140314,"pose":{"rotation":{"radians":3.0377498303641466},"translation":{"x":2.200320580167616,"y":4.182252335194084}},"time":0.9396386810723352,"velocity":3.859598186246495,"position":2.1717493789242637,"holonomicRotation":0.6890268328358298,"angularVelocity":-1.040370251865664,"angularAcceleration":-1.915183206921577,"curveRadius":-3.6957529516537546},{"acceleration":-5.003213006902823,"curvature":-0.27207761458646346,"pose":{"rotation":{"radians":3.035832587449873},"translation":{"x":2.1932874390619865,"y":4.182998946403662}},"time":0.9414755406459366,"velocity":3.8504079865359984,"position":2.178822037696604,"holonomicRotation":0.6859914723387557,"angularVelocity":-1.0437612879217981,"angularAcceleration":-1.8461052248460852,"curveRadius":-3.6754218149108713},{"acceleration":-5.003132678926024,"curvature":-0.27354490851542956,"pose":{"rotation":{"radians":3.033911769872593},"translation":{"x":2.186281286302391,"y":4.183756304622679}},"time":0.9433101013836458,"velocity":3.841229435757691,"position":2.1858690064039776,"holonomicRotation":0.6829561118416816,"angularVelocity":-1.047017707180604,"angularAcceleration":-1.7750403090344993,"curveRadius":-3.655706865198677},{"acceleration":-5.003051257776481,"curvature":-0.2749817059433129,"pose":{"rotation":{"radians":3.03198757949893},"translation":{"x":2.179301839141544,"y":4.184524365553607}},"time":0.9451424257637973,"velocity":3.8320622229629198,"position":2.19289058744137,"holonomicRotation":0.6799207513446074,"angularVelocity":-1.0501363156581558,"angularAcceleration":-1.7019958427306776,"curveRadius":-3.6366055573389624},{"acceleration":-5.002968742142798,"curvature":-0.27638697099855675,"pose":{"rotation":{"radians":3.030060221884995},"translation":{"x":2.172348814832159,"y":4.185303084898917}},"time":0.9469725768453093,"velocity":3.822906034308716,"position":2.199887083054579,"holonomicRotation":0.6768853908475332,"angularVelocity":-1.0531139387370982,"angularAcceleration":-1.6269821158602527,"curveRadius":-3.61811555872951},{"acceleration":-5.00288513104237,"curvature":-0.27775966538113417,"pose":{"rotation":{"radians":3.0281299062506672},"translation":{"x":2.1654219306269518,"y":4.186092418361085}},"time":0.948800618271206,"velocity":3.813760553040168,"position":2.206858795333987,"holonomicRotation":0.6738500303504591,"angularVelocity":-1.0559474238287316,"angularAcceleration":-1.5500114228776674,"curveRadius":-3.600234751967416},{"acceleration":-5.002800423563763,"curvature":-0.27909874983325617,"pose":{"rotation":{"radians":3.026196845453285},"translation":{"x":2.158520903778636,"y":4.186892321642581}},"time":0.9506266142722076,"velocity":3.8046254594729314,"position":2.2138060262082937,"holonomicRotation":0.670814669853385,"angularVelocity":-1.0586336423092138,"angularAcceleration":-1.4710976798462905,"curveRadius":-3.5829612300214055},{"acceleration":-5.002714619100733,"curvature":-0.28040318430850936,"pose":{"rotation":{"radians":3.024261255953225},"translation":{"x":2.151645451539926,"y":4.1877027504458795}},"time":0.9524506296703917,"velocity":3.795500430974971,"position":2.2207290774382065,"holonomicRotation":0.6677793093563108,"angularVelocity":-1.0611694956012245,"angularAcceleration":-1.390258708635541,"curveRadius":-3.5662933089225017},{"acceleration":-5.002627717255299,"curvature":-0.2816719290475553,"pose":{"rotation":{"radians":3.022323357781795},"translation":{"x":2.144795291163537,"y":4.18852366047345}},"time":0.9542727298829264,"velocity":3.786385141948128,"position":2.2276282506100884,"holonomicRotation":0.6647439488592367,"angularVelocity":-1.0635519155854685,"angularAcceleration":-1.3075131476603983,"curveRadius":-3.5502295290176673},{"acceleration":-5.002539717682422,"curvature":-0.2829039454594012,"pose":{"rotation":{"radians":3.020383374501991},"translation":{"x":2.1379701399021833,"y":4.189355007427769}},"time":0.9560929809258835,"velocity":3.7772792638095827,"position":2.2345038471295777,"holonomicRotation":0.6617085883621625,"angularVelocity":-1.0657778702065226,"angularAcceleration":-1.222883310336158,"curveRadius":-3.534768659292196},{"acceleration":-5.002450620807852,"curvature":-0.28409819718119594,"pose":{"rotation":{"radians":3.0184415331702006},"translation":{"x":2.1311697150085784,"y":4.190196747011306}},"time":0.9579114494181316,"velocity":3.7681824649716167,"position":2.2413561682151704,"holonomicRotation":0.6586732278650884,"angularVelocity":-1.0678443646773415,"angularAcceleration":-1.1363927830633684,"curveRadius":-3.519909699962674},{"acceleration":-5.002360426789003,"curvature":-0.28525365116926593,"pose":{"rotation":{"radians":3.016498064291127},"translation":{"x":2.124393733735438,"y":4.1910488349265345}},"time":0.9597282025853147,"velocity":3.7590944108228563,"position":2.248185514891773,"holonomicRotation":0.6556378673680142,"angularVelocity":-1.0697484469433811,"angularAcceleration":-1.0480687747978243,"curveRadius":-3.5056518852640823},{"acceleration":-5.00226913587134,"curvature":-0.28636927805045975,"pose":{"rotation":{"radians":3.014553201770944},"translation":{"x":2.1176419133354765,"y":4.191911226875928}},"time":0.9615433082639216,"velocity":3.750014763708416,"position":2.2549921879842403,"holonomicRotation":0.6526025068709401,"angularVelocity":-1.0714872104170665,"angularAcceleration":-0.9579406280188733,"curveRadius":-3.4919946958269557},{"acceleration":-5.002176749225815,"curvature":-0.2874440536437201,"pose":{"rotation":{"radians":3.0126071828695853},"translation":{"x":2.1109139710614073,"y":4.192783878561958}},"time":0.9633568349054481,"velocity":3.7409431829080706,"position":2.261776488110881,"holonomicRotation":0.6495671463738659,"angularVelocity":-1.0730577962289838,"angularAcceleration":-0.8660395584788875,"curveRadius":-3.478937857032435},{"acceleration":-5.002083267733302,"curvature":-0.2884769598249094,"pose":{"rotation":{"radians":3.010660248145752},"translation":{"x":2.104209624165946,"y":4.193666745687096}},"time":0.9651688515806568,"velocity":3.7318793246161555,"position":2.268538715676952,"holonomicRotation":0.6465317858767918,"angularVelocity":-1.0744573990242081,"angularAcceleration":-0.7724006154982735,"curveRadius":-3.466481346056019},{"acceleration":-5.001988692527501,"curvature":-0.28946698557143685,"pose":{"rotation":{"radians":3.008712641402219},"translation":{"x":2.097528589901807,"y":4.1945597839538165}},"time":0.9669794279839413,"velocity":3.722822841919969,"position":2.275279170868141,"holonomicRotation":0.6434964253797176,"angularVelocity":-1.075683268598887,"angularAcceleration":-0.6770603949411579,"curveRadius":-3.454625397179232},{"acceleration":-5.001893025287108,"curvature":-0.29041312779813444,"pose":{"rotation":{"radians":3.0067646096263285},"translation":{"x":2.090870585521704,"y":4.195462949064591}},"time":0.9687886344377971,"velocity":3.7137733847771237,"position":2.2819981536440372,"holonomicRotation":0.6404610648826435,"angularVelocity":-1.0767327143559677,"angularAcceleration":-0.580058596874947,"curveRadius":-3.4433705100793444},{"acceleration":-5.001796267618395,"curvature":-0.29131439253148067,"pose":{"rotation":{"radians":3.0048164029282485},"translation":{"x":2.0842353282783517,"y":4.196376196721893}},"time":0.9705965418974034,"velocity":3.704730599993465,"position":2.2886959637315973,"holonomicRotation":0.6374257043855693,"angularVelocity":-1.077603108349497,"angularAcceleration":-0.48143724885055855,"curveRadius":-3.432717454534745},{"acceleration":-5.001698421452452,"curvature":-0.2921697962764925,"pose":{"rotation":{"radians":3.0028682744749267},"translation":{"x":2.077622535424465,"y":4.1972994826281935}},"time":0.9724032219553247,"velocity":3.6956941311996907,"position":2.2953729006186125,"holonomicRotation":0.6343903438884952,"angularVelocity":-1.0782918894689526,"angularAcceleration":-0.3812413362485864,"curveRadius":-3.422667273429106},{"acceleration":-5.001599489004111,"curvature":-0.29297836621302287,"pose":{"rotation":{"radians":3.00092048042191},"translation":{"x":2.0710319242127584,"y":4.198232762485967}},"time":0.9742087468463327,"velocity":3.6866636188274406,"position":2.3020292635471793,"holonomicRotation":0.6313549833914212,"angularVelocity":-1.0787965664262402,"angularAcceleration":-0.27951813890854316,"curveRadius":-3.4132213000085674},{"acceleration":-5.001499472715685,"curvature":-0.29373914233396553,"pose":{"rotation":{"radians":2.9989732798421236},"translation":{"x":2.0644632118959456,"y":4.199175991997684}},"time":0.9760131894523572,"velocity":3.677638700084864,"position":2.3086653515071767,"holonomicRotation":0.628319622894347,"angularVelocity":-1.079114721236045,"angularAcceleration":-0.1763175003419804,"curveRadius":-3.404381152795272},{"acceleration":-5.001398375109138,"curvature":-0.2944511778539873,"pose":{"rotation":{"radians":2.9970269346504015},"translation":{"x":2.057916115726742,"y":4.200129126865818}},"time":0.9778166233075685,"velocity":3.668619008931793,"position":2.315281463229756,"holonomicRotation":0.6252842623972727,"angularVelocity":-1.0792440133569756,"angularAcceleration":-0.07169218907418845,"curveRadius":-3.396148751342},{"acceleration":-5.001296199074959,"curvature":-0.29511354035892745,"pose":{"rotation":{"radians":2.995081709525568},"translation":{"x":2.0513903529578617,"y":4.201092122792842}},"time":0.9796191226036014,"velocity":3.6596041760537084,"position":2.321877897180852,"holonomicRotation":0.6222489019001987,"angularVelocity":-1.0791821828251,"angularAcceleration":0.034302666309864886,"curveRadius":-3.3885263237456504},{"acceleration":-5.001192947762024,"curvature":-0.2957253129839647,"pose":{"rotation":{"radians":2.9931378718305583},"translation":{"x":2.0448856408420197,"y":4.202064935481228}},"time":0.981420762194921,"velocity":3.650593828835192,"position":2.3284549515547086,"holonomicRotation":0.6192135414031246,"angularVelocity":-1.0789270530993544,"angularAcceleration":0.14160974646362176,"curveRadius":-3.3815164143700596},{"acceleration":-5.001088624243837,"curvature":-0.2962855957048456,"pose":{"rotation":{"radians":2.991195691527201},"translation":{"x":2.0384016966319294,"y":4.203047520633448}},"time":0.9832216176043416,"velocity":3.6415875913332307,"position":2.33501292426744,"holonomicRotation":0.6161781809060504,"angularVelocity":-1.0784765357603998,"angularAcceleration":0.25016852357935143,"curveRadius":-3.375121890826519},{"acceleration":-5.000983231955446,"curvature":-0.29679350615909555,"pose":{"rotation":{"radians":2.9892554410897723},"translation":{"x":2.031938237580306,"y":4.204039833951975}},"time":0.9850217650286999,"velocity":3.632585084248967,"position":2.341552112950613,"holonomicRotation":0.6131428204089763,"angularVelocity":-1.0778286329079352,"angularAcceleration":0.3599165511100241,"curveRadius":-3.3693459568618462},{"acceleration":-5.000876774920945,"curvature":-0.2972481806502877,"pose":{"rotation":{"radians":2.987317395414313},"translation":{"x":2.0254949809398632,"y":4.205041831139282}},"time":0.9868212813446945,"velocity":3.6235859248982183,"position":2.3480728149448757,"holonomicRotation":0.6101074599119021,"angularVelocity":-1.0769814411981158,"angularAcceleration":0.4707885681776322,"curveRadius":-3.364192163640185},{"acceleration":-5.000769257007594,"curvature":-0.2976487758544412,"pose":{"rotation":{"radians":2.985381831726925},"translation":{"x":2.019071643963317,"y":4.206053467897841}},"time":0.9886202441148924,"velocity":3.6145897271825116,"position":2.3545753272936167,"holonomicRotation":0.607072099414828,"angularVelocity":-1.0759331540668895,"angularAcceleration":0.5827175240046737,"curveRadius":-3.3596644136343725},{"acceleration":-5.000660681776177,"curvature":-0.2979944690334853,"pose":{"rotation":{"radians":2.983449029486119},"translation":{"x":2.0126679439033808,"y":4.207074699930125}},"time":0.9904187315939146,"velocity":3.6055961015594984,"position":2.361059946736683,"holonomicRotation":0.6040367389177538,"angularVelocity":-1.0746820666533787,"angularAcceleration":0.6956330962008905,"curveRadius":-3.355766981996002},{"acceleration":-5.000551053990442,"curvature":-0.2982844596168819,"pose":{"rotation":{"radians":2.9815192702851183},"translation":{"x":2.0062835980127693,"y":4.208105482938607}},"time":0.992216822734803,"velocity":3.5966046550097577,"position":2.367526969704134,"holonomicRotation":0.6010013784206797,"angularVelocity":-1.0732265774065677,"angularAcceleration":0.8094635548295203,"curveRadius":-3.35250452297919},{"acceleration":-5.0004403779603726,"curvature":-0.2985179705668134,"pose":{"rotation":{"radians":2.9795928377504257},"translation":{"x":1.9999183235441966,"y":4.209145772625758}},"time":0.9940145971955802,"velocity":3.587614991005622,"position":2.373976692310065,"holonomicRotation":0.5979660179236055,"angularVelocity":-1.0715651916981146,"angularAcceleration":0.924134670227172,"curveRadius":-3.3498820794649045},{"acceleration":-5.000328658387886,"curvature":-0.29869424872745914,"pose":{"rotation":{"radians":2.977670017436169},"translation":{"x":1.9935718377503777,"y":4.2101955246940514}},"time":0.9958121353460052,"velocity":3.578626709477506,"position":2.380409410346481,"holonomicRotation":0.5949306574265314,"angularVelocity":-1.0696965256630733,"angularAcceleration":1.0395696105807013,"curveRadius":-3.347905104501831},{"acceleration":-5.0002158997329085,"curvature":-0.2988125662236413,"pose":{"rotation":{"radians":2.9757510967177834},"translation":{"x":1.987243857884027,"y":4.211254694845961}},"time":0.9976095182745376,"velocity":3.56963940678035,"position":2.3868254192772445,"holonomicRotation":0.5918952969294573,"angularVelocity":-1.0676193080083969,"angularAcceleration":1.1556900990333245,"curveRadius":-3.346579471666418},{"acceleration":-5.000102107606884,"curvature":-0.2988722218070553,"pose":{"rotation":{"radians":2.9738363646831525},"translation":{"x":1.9809341011978587,"y":4.212323238783956}},"time":0.9994068277955132,"velocity":3.560652675656498,"position":2.393225014232089,"holonomicRotation":0.5888599364323831,"angularVelocity":-1.0653323828116052,"angularAcceleration":1.2724158916992268,"curveRadius":-3.345911486700748},{"acceleration":-4.99998728648991,"curvature":-0.2988725416094405,"pose":{"rotation":{"radians":2.9719261120179548},"translation":{"x":1.9746422849445877,"y":4.213401112210511}},"time":1.0012041464565422,"velocity":3.5516661052015817,"position":2.399608490000712,"holonomicRotation":0.5858245759353089,"angularVelocity":-1.0628347140756964,"angularAcceleration":1.3896638309418092,"curveRadius":-3.3459079064773243},{"acceleration":-4.9998714421717665,"curvature":-0.2988128796322559,"pose":{"rotation":{"radians":2.9700206308932215},"translation":{"x":1.9683681263769282,"y":4.2144882708281}},"time":1.0030015575461382,"velocity":3.542679280824868,"position":2.4059761410269487,"holonomicRotation":0.5827892154382348,"angularVelocity":-1.0601253857633284,"angularAcceleration":1.507350393046172,"curveRadius":-3.3465759616208097},{"acceleration":-4.999754579558915,"curvature":-0.2986926197773691,"pose":{"rotation":{"radians":2.9681202148468007},"translation":{"x":1.962111342747595,"y":4.215584670339194}},"time":1.0047991451015839,"velocity":3.5336917842123703,"position":2.4123282614030295,"holonomicRotation":0.5797538549411607,"angularVelocity":-1.0572036063910721,"angularAcceleration":1.625389185302764,"curveRadius":-3.34792336263732},{"acceleration":-4.9996367047169405,"curvature":-0.298511175927172,"pose":{"rotation":{"radians":2.9662251586644177},"translation":{"x":1.9558716513093017,"y":4.216690266446264}},"time":1.0065969939170463,"velocity":3.5247031932850525,"position":2.4186651448639336,"holonomicRotation":0.5767184944440865,"angularVelocity":-1.054068710385715,"angularAcceleration":1.743692783506332,"curveRadius":-3.3499583286756764},{"acceleration":-4.999517822943039,"curvature":-0.2982679936628672,"pose":{"rotation":{"radians":2.964335758256646},"translation":{"x":1.9496487693147635,"y":4.217805014851785}},"time":1.008395189551947,"velocity":3.515713082159228,"position":2.4249870847818356,"holonomicRotation":0.5736831339470123,"angularVelocity":-1.0507201614222483,"angularAcceleration":1.8621716672399349,"curveRadius":-3.352689598771706},{"acceleration":-4.999397940470577,"curvature":-0.29796255007943645,"pose":{"rotation":{"radians":2.962452310536674},"translation":{"x":1.943442414016695,"y":4.218928871258229}},"time":1.0101938183395989,"velocity":3.50672102110257,"position":2.4312943741606547,"holonomicRotation":0.5706477734499382,"angularVelocity":-1.0471575529661583,"angularAcceleration":1.9807358141648355,"curveRadius":-3.3561264653339866},{"acceleration":-4.999277062491904,"curvature":-0.2975943560030783,"pose":{"rotation":{"radians":2.960575113293301},"translation":{"x":1.9372523026678103,"y":4.220061791368068}},"time":1.0119929673961185,"velocity":3.4977265764923073,"position":2.4375873056307147,"holonomicRotation":0.5676124129528641,"angularVelocity":-1.0433806118345732,"angularAcceleration":2.0992930618496537,"curveRadius":-3.360278781596436},{"acceleration":-4.999155195835733,"curvature":-0.29716295573122853,"pose":{"rotation":{"radians":2.9587044650625836},"translation":{"x":1.9310781525208243,"y":4.221203730883776}},"time":1.0137927246296232,"velocity":3.4887293107671895,"position":2.4438661714435077,"holonomicRotation":0.56457705245579,"angularVelocity":-1.0393891997725966,"angularAcceleration":2.217750254129624,"curveRadius":-3.365156997914835},{"acceleration":-4.999032345960137,"curvature":-0.29666792873348335,"pose":{"rotation":{"radians":2.9568406649993206},"translation":{"x":1.924919680828451,"y":4.222354645507822}},"time":1.015593178749724,"velocity":3.479728782383388,"position":2.4501312634665835,"holonomicRotation":0.5615416919587158,"angularVelocity":-1.0351833142843383,"angularAcceleration":2.336013698601011,"curveRadius":-3.370772177057153},{"acceleration":-4.998908519740269,"curvature":-0.2961088897713531,"pose":{"rotation":{"radians":2.954984012743002},"translation":{"x":1.9187766048434052,"y":4.223514490942682}},"time":1.0173944192773257,"velocity":3.470724545763859,"position":2.456382873178555,"holonomicRotation":0.5585063314616416,"angularVelocity":-1.0307630923622633,"angularAcceleration":2.453987601511933,"curveRadius":-3.377136028479833},{"acceleration":-4.998783722434712,"curvature":-0.29548548996390805,"pose":{"rotation":{"radians":2.9531348082879525},"translation":{"x":1.912648641818401,"y":4.224683222890827}},"time":1.0191965365547406,"velocity":3.461716151251599,"position":2.462621291664232,"holonomicRotation":0.5554709709645675,"angularVelocity":-1.026128808720982,"angularAcceleration":2.5715771661258113,"curveRadius":-3.3842609331583238},{"acceleration":-4.9986579615019915,"curvature":-0.294797417779414,"pose":{"rotation":{"radians":2.951293351845433},"translation":{"x":1.906535509006153,"y":4.2258607970547315}},"time":1.020999621756135,"velocity":3.4527031450543824,"position":2.4688468096098872,"holonomicRotation":0.5524356104674935,"angularVelocity":-1.0212808807345783,"angularAcceleration":2.6886849177480405,"curveRadius":-3.3921599705064684},{"acceleration":-4.998531242409257,"curvature":-0.29404439915952363,"pose":{"rotation":{"radians":2.9494599437097073},"translation":{"x":1.9004369236593763,"y":4.227047169136864}},"time":1.0228037668983103,"velocity":3.443685069195378,"position":2.4750597172986577,"holonomicRotation":0.5494002499704193,"angularVelocity":-1.016219866609537,"angularAcceleration":2.8052145067104415,"curveRadius":-3.40084695664441},{"acceleration":-4.998403571876967,"curvature":-0.29322619831689367,"pose":{"rotation":{"radians":2.9476348841182016},"translation":{"x":1.8943526030307847,"y":4.228242294839701}},"time":1.0246090648518393,"velocity":3.4346614614561566,"position":2.4812603046060895,"holonomicRotation":0.546364889473345,"angularVelocity":-1.0109464689405139,"angularAcceleration":2.9210677709541684,"curveRadius":-3.410336476549363},{"acceleration":-4.998274956494341,"curvature":-0.2923426188461167,"pose":{"rotation":{"radians":2.94581847311541},"translation":{"x":1.8882822643730932,"y":4.229446129865714}},"time":1.0264156093525634,"velocity":3.425631855320395,"position":2.4874488609958236,"holonomicRotation":0.543329528976271,"angularVelocity":-1.005461532812297,"angularAcceleration":3.0361478092670717,"curveRadius":-3.4206439141409626},{"acceleration":-4.9981454023706595,"curvature":-0.2913935041551383,"pose":{"rotation":{"radians":2.9440110104120825},"translation":{"x":1.8822256249390152,"y":4.230658629917373}},"time":1.0282234950134665,"velocity":3.41659577991634,"position":2.4936256755154367,"holonomicRotation":0.5402941684791969,"angularVelocity":-0.9997660484925698,"angularAcceleration":3.150356487081161,"curveRadius":-3.431785491922286},{"acceleration":-4.998014916292491,"curvature":-0.2903787368686407,"pose":{"rotation":{"radians":2.9422127952429564},"translation":{"x":1.8761824019812667,"y":4.231879750697155}},"time":1.0300328173369384,"velocity":3.4075527599552466,"position":2.499791036792432,"holonomicRotation":0.5372588079821227,"angularVelocity":-0.993861152210563,"angularAcceleration":3.2635955492308244,"curveRadius":-3.443778324762024},{"acceleration":-4.997883504122974,"curvature":-0.2892982415748908,"pose":{"rotation":{"radians":2.9404241262291726},"translation":{"x":1.8701523127525612,"y":4.233109447907529}},"time":1.0318436727274394,"velocity":3.3985023156707097,"position":2.505945233030394,"holonomicRotation":0.5342234474850486,"angularVelocity":-0.9877481234373997,"angularAcceleration":3.375768603738253,"curveRadius":-3.4566404363751704},{"acceleration":-4.9977511731328725,"curvature":-0.2881519824903365,"pose":{"rotation":{"radians":2.938645301231706},"translation":{"x":1.864135074505613,"y":4.234347677250969}},"time":1.0336561585045823,"velocity":3.3894439627517072,"position":2.5120885520053045,"holonomicRotation":0.5311880869879744,"angularVelocity":-0.9814283896178649,"angularAcceleration":3.4867770546022747,"curveRadius":-3.4703908380485844},{"acceleration":-4.997617929379435,"curvature":-0.28693996632641433,"pose":{"rotation":{"radians":2.9368766172125573},"translation":{"x":1.8581304044931375,"y":4.235594394429947}},"time":1.0354703729166426,"velocity":3.380377212278256,"position":2.51822128106202,"holonomicRotation":0.5281527264909003,"angularVelocity":-0.9749035215413392,"angularAcceleration":3.5965253242122506,"curveRadius":-3.4850495481777184},{"acceleration":-4.997483778375876,"curvature":-0.2856622410483333,"pose":{"rotation":{"radians":2.9351183700897043},"translation":{"x":1.8521380199678485,"y":4.236849555146936}},"time":1.0372864151545147,"velocity":3.3713015706536447,"position":2.5243437071109316,"holonomicRotation":0.5251173659938261,"angularVelocity":-0.9681752363387476,"angularAcceleration":3.704916693168545,"curveRadius":-3.500637663312326},{"acceleration":-4.997348727591519,"curvature":-0.28431889710835545,"pose":{"rotation":{"radians":2.9333708545940733},"translation":{"x":1.8461576381824605,"y":4.238113115104408}},"time":1.0391043853661284,"velocity":3.362216539529838,"position":2.5304561166247916,"holonomicRotation":0.522082005496752,"angularVelocity":-0.9612453958087012,"angularAcceleration":3.8118559290888085,"curveRadius":-3.5171774024534663},{"acceleration":-4.9972127823212,"curvature":-0.2829100668872942,"pose":{"rotation":{"radians":2.931634364126918},"translation":{"x":1.8401889763896881,"y":4.239385030004836}},"time":1.0409243846713387,"velocity":3.353121615738025,"position":2.5365587956357207,"holonomicRotation":0.5190466449996778,"angularVelocity":-0.95411600553045,"angularAcceleration":3.91724890105226,"curveRadius":-3.5346921762186017},{"acceleration":-4.997075949364756,"curvature":-0.281435925609068,"pose":{"rotation":{"radians":2.929909190616149},"translation":{"x":1.8342317518422457,"y":4.2406652555506925}},"time":1.0427465151773097,"velocity":3.3440162912100337,"position":2.5426520297323982,"holonomicRotation":0.5160112845026037,"angularVelocity":-0.9467892146669231,"angularAcceleration":4.0210022495742175,"curveRadius":-3.553206641390418},{"acceleration":-4.996938234328201,"curvature":-0.2798966909638051,"pose":{"rotation":{"radians":2.928195624372668},"translation":{"x":1.8282856817928483,"y":4.24195374744445}},"time":1.044570879994404,"velocity":3.3349000529021318,"position":2.548736104057439,"holonomicRotation":0.5129759240055296,"angularVelocity":-0.9392673150813342,"angularAcceleration":4.123023813608143,"curveRadius":-3.5727467750925115},{"acceleration":-4.996799642804853,"curvature":-0.2782926233560647,"pose":{"rotation":{"radians":2.926493953948514},"translation":{"x":1.8223504834942097,"y":4.243250461388581}},"time":1.0463975832525994,"velocity":3.325772382714071,"position":2.554811303304959,"holonomicRotation":0.5099405635084554,"angularVelocity":-0.9315527393512384,"angularAcceleration":4.223223282427002,"curveRadius":-3.593339945344288},{"acceleration":-4.996660181261626,"curvature":-0.2766240263738438,"pose":{"rotation":{"radians":2.9248044659940313},"translation":{"x":1.8164258741990447,"y":4.244555353085557}},"time":1.0482267301184467,"velocity":3.316632757403812,"position":2.5608779117183307,"holonomicRotation":0.5069052030113812,"angularVelocity":-0.9236480602120625,"angularAcceleration":4.321511458028342,"curveRadius":-3.6150149830027742},{"acceleration":-4.996519854537818,"curvature":-0.27489124601773746,"pose":{"rotation":{"radians":2.923127445115074},"translation":{"x":1.8105115711600674,"y":4.245868378237853}},"time":1.05005842681259,"velocity":3.307480648504033,"position":2.566936213088139,"holonomicRotation":0.5038698425143071,"angularVelocity":-0.9155559893290197,"angularAcceleration":4.417800670228884,"curveRadius":-3.6378022744873975},{"acceleration":-4.996378668883084,"curvature":-0.27309467101476864,"pose":{"rotation":{"radians":2.9214631737342596},"translation":{"x":1.804607291629993,"y":4.24718949254794}},"time":1.0518927806278664,"velocity":3.2983155222302023,"position":2.572986490750327,"holonomicRotation":0.500834482017233,"angularVelocity":-0.9072793737798693,"angularAcceleration":4.51200607005236,"curveRadius":-3.661733845937701},{"acceleration":-4.996236628668183,"curvature":-0.27123473290516076,"pose":{"rotation":{"radians":2.9198119319482805},"translation":{"x":1.7987127528615354,"y":4.248518651718291}},"time":1.053729899948005,"velocity":3.289136839391692,"position":2.5790290275845527,"holonomicRotation":0.4977991215201588,"angularVelocity":-0.8988211967933449,"angularAcceleration":4.604043348630522,"curveRadius":-3.6868434558108656},{"acceleration":-4.996093739497075,"curvature":-0.26931190541759586,"pose":{"rotation":{"radians":2.918173997390521},"translation":{"x":1.7928276721074095,"y":4.249855811451377}},"time":1.0555698942669465,"velocity":3.279944055294118,"position":2.58506410601274,"holonomicRotation":0.49476376102308467,"angularVelocity":-0.8901845733423271,"angularAcceleration":4.693831585298573,"curveRadius":-3.7131667033041},{"acceleration":-4.995950006202325,"curvature":-0.2673267047422146,"pose":{"rotation":{"radians":2.9165496450920267},"translation":{"x":1.7869517666203294,"y":4.251200927449672}},"time":1.057412874208804,"velocity":3.270736619642164,"position":2.5910920079978395,"holonomicRotation":0.4917284005260105,"angularVelocity":-0.8813727494273461,"angularAcceleration":4.781291274445181,"curveRadius":-3.740741131583949},{"acceleration":-4.9958054332299735,"curvature":-0.2652796887327644,"pose":{"rotation":{"radians":2.914939147344608},"translation":{"x":1.7810847536530094,"y":4.252553955415648}},"time":1.0592589515484852,"velocity":3.2615139764384224,"position":2.5971130150427957,"holonomicRotation":0.4886930400289364,"angularVelocity":-0.8723890992004244,"angularAcceleration":4.866345539170912,"curveRadius":-3.7696063531172674},{"acceleration":-4.995660025326037,"curvature":-0.26317145689779975,"pose":{"rotation":{"radians":2.913342773566612},"translation":{"x":1.7752263504581645,"y":4.253914851051778}},"time":1.061108239233,"velocity":3.252275563877564,"position":2.603127408189723,"holonomicRotation":0.48565767953186223,"angularVelocity":-0.8632371217107867,"angularAcceleration":4.948920368784365,"curveRadius":-3.7998041724879794},{"acceleration":-4.995513785824016,"curvature":-0.2610026503865336,"pose":{"rotation":{"radians":2.911760790168494},"translation":{"x":1.7693762742885089,"y":4.255283570060534}},"time":1.0629608514034767,"velocity":3.243020814240162,"position":2.6091354680192937,"holonomicRotation":0.48262231903478814,"angularVelocity":-0.853920439112329,"angularAcceleration":5.0289438593401625,"curveRadius":-3.831378717875253},{"acceleration":-4.995366719222774,"curvature":-0.25877395010875437,"pose":{"rotation":{"radians":2.910193460419652},"translation":{"x":1.763534242396757,"y":4.256660068144391}},"time":1.064816903417911,"velocity":3.233749153778111,"position":2.6151374746503384,"holonomicRotation":0.479586958537714,"angularVelocity":-0.8444427939803563,"angularAcceleration":5.1063467285759225,"curveRadius":-3.864376609700212},{"acceleration":-4.995218829053884,"curvature":-0.25648607811483815,"pose":{"rotation":{"radians":2.908641044320893},"translation":{"x":1.7576999720356237,"y":4.258044301005817}},"time":1.0666765118746708,"velocity":3.224460002600236,"position":2.621133707739658,"holonomicRotation":0.47655159804063985,"angularVelocity":-0.8348080441966093,"angularAcceleration":5.181063652793916,"curveRadius":-3.898847092793331},{"acceleration":-4.995070118447892,"curvature":-0.2541397958977663,"pose":{"rotation":{"radians":2.907103798472221},"translation":{"x":1.7518731804578234,"y":4.259436224347288}},"time":1.0685397946367878,"velocity":3.2151527745529664,"position":2.627124446482055,"holonomicRotation":0.4735162375435657,"angularVelocity":-0.8250201632979296,"angularAcceleration":5.253030349273977,"curveRadius":-3.9348422251911837},{"acceleration":-4.994920590066397,"curvature":-0.25173590450768296,"pose":{"rotation":{"radians":2.9055819759509145},"translation":{"x":1.74605358491607,"y":4.2608357938712755}},"time":1.070406870857055,"velocity":3.20582687709713,"position":2.633109969610577,"holonomicRotation":0.47048087704649155,"angularVelocity":-0.8150832326966572,"angularAcceleration":5.322187971442301,"curveRadius":-3.97241705332296},{"acceleration":-4.99477024683263,"curvature":-0.24927524246734545,"pose":{"rotation":{"radians":2.90407582618377},"translation":{"x":1.7402409026630785,"y":4.262242965280251}},"time":1.0722778610039667,"velocity":3.196481711179219,"position":2.6390905553969763,"holonomicRotation":0.4674455165494174,"angularVelocity":-0.8050014424878875,"angularAcceleration":5.388478515192272,"curveRadius":-4.011629835766775},{"acceleration":-4.994619091002733,"curvature":-0.24675868697161005,"pose":{"rotation":{"radians":2.9025855948268613},"translation":{"x":1.7344348509515632,"y":4.26365769427669}},"time":1.0741528868885233,"velocity":3.1871166711000884,"position":2.6450664816523908,"holonomicRotation":0.46441015605234326,"angularVelocity":-0.7947790850157584,"angularAcceleration":5.451848721835961,"curveRadius":-4.052542231735297},{"acceleration":-4.994467123486319,"curvature":-0.24418715238521504,"pose":{"rotation":{"radians":2.9011115236474905},"translation":{"x":1.7286351470342387,"y":4.265079936563062}},"time":1.0760320716919345,"velocity":3.177731144380496,"position":2.651038025728237,"holonomicRotation":0.4613747955552691,"angularVelocity":-0.7844205512384935,"angularAcceleration":5.512248586973199,"curveRadius":-4.095219548743743},{"acceleration":-4.994314347074531,"curvature":-0.24156158877585876,"pose":{"rotation":{"radians":2.8996538504046305},"translation":{"x":1.7228415081638195,"y":4.266509647841841}},"time":1.0779155399942528,"velocity":3.1683245116159675,"position":2.657005464517324,"holonomicRotation":0.45833943505819497,"angularVelocity":-0.7739303289923787,"angularAcceleration":5.569630363942185,"curveRadius":-4.139731010495566},{"acceleration":-4.9941607615927825,"curvature":-0.2388829822697412,"pose":{"rotation":{"radians":2.8982128087371426},"translation":{"x":1.71705365159302,"y":4.267946783815498}},"time":1.0798034178039668,"velocity":3.158896146336012,"position":2.662969074455183,"holonomicRotation":0.4553040745611208,"angularVelocity":-0.7633129962506616,"angularAcceleration":5.623951236190177,"curveRadius":-4.186150015788161},{"acceleration":-4.994006368190596,"curvature":-0.23615235295627707,"pose":{"rotation":{"radians":2.8967886280507584},"translation":{"x":1.7112712945745543,"y":4.269391300186508}},"time":1.0816958325885915,"velocity":3.1494454148503386,"position":2.668929131521614,"holonomicRotation":0.4522687140640467,"angularVelocity":-0.7525732191247099,"angularAcceleration":5.6751707993456195,"curveRadius":-4.2345544623269},{"acceleration":-4.99385116710245,"curvature":-0.23337075546292707,"pose":{"rotation":{"radians":2.8953815334113244},"translation":{"x":1.7054941543611373,"y":4.270843152657342}},"time":1.083592913306289,"velocity":3.1399716760941776,"position":2.6748859112424483,"holonomicRotation":0.4492333535669725,"angularVelocity":-0.7417157458338616,"angularAcceleration":5.723253201385315,"curveRadius":-4.285027050695984},{"acceleration":-4.993695156936029,"curvature":-0.23053927646459038,"pose":{"rotation":{"radians":2.8939917454372313},"translation":{"x":1.6997219482054835,"y":4.272302296930473}},"time":1.085494790438557,"velocity":3.130474281469683,"position":2.680839688691529,"holonomicRotation":0.4461979930698984,"angularVelocity":-0.730745404376244,"angularAcceleration":5.768165183486317,"curveRadius":-4.337655671239147},{"acceleration":-4.993538338211332,"curvature":-0.22765903505374768,"pose":{"rotation":{"radians":2.8926194801984955},"translation":{"x":1.6939543933603076,"y":4.2737686887083735}},"time":1.087401596024025,"velocity":3.1209525746751328,"position":2.6867907384929004,"holonomicRotation":0.44316263257282423,"angularVelocity":-0.7196670962126088,"angularAcceleration":5.8098781795396,"curveRadius":-4.392533772111928},{"acceleration":-4.993380708414245,"curvature":-0.22473118053316973,"pose":{"rotation":{"radians":2.8912649491168607},"translation":{"x":1.6881912070783234,"y":4.275242283693515}},"time":1.0893134636933952,"velocity":3.111405891537859,"position":2.6927393348232194,"holonomicRotation":0.4401272720757501,"angularVelocity":-0.708485792890155,"angularAcceleration":5.848366757589216,"curveRadius":-4.449760810349157},{"acceleration":-4.993222265723294,"curvature":-0.22175689213811448,"pose":{"rotation":{"radians":2.8899283588691},"translation":{"x":1.682432106612246,"y":4.276723037588372}},"time":1.0912305287055708,"velocity":3.101833559834225,"position":2.6986857514143696,"holonomicRotation":0.43709191157867594,"angularVelocity":-0.6972065314800339,"angularAcceleration":5.883609235203154,"curveRadius":-4.509442707093769},{"acceleration":-4.993063008111526,"curvature":-0.21873737756438147,"pose":{"rotation":{"radians":2.8886099112954464},"translation":{"x":1.6766768092147895,"y":4.278210906095415}},"time":1.0931529279850185,"velocity":3.0922348991051942,"position":2.7046302615562925,"holonomicRotation":0.43405655108160185,"angularVelocity":-0.6858344089852172,"angularAcceleration":5.9155882008465035,"curveRadius":-4.571692369794768},{"acceleration":-4.992902932043817,"curvature":-0.21567387232666788,"pose":{"rotation":{"radians":2.8873098033087623},"translation":{"x":1.6709250321386686,"y":4.279705844917118}},"time":1.095080800160405,"velocity":3.082609220468101,"position":2.710573138100023,"holonomicRotation":0.4310211905845277,"angularVelocity":-0.6743745790217709,"angularAcceleration":5.944289310129334,"curveRadius":-4.636630247382779},{"acceleration":-4.992742034040301,"curvature":-0.21256763801379394,"pose":{"rotation":{"radians":2.8860282268099557},"translation":{"x":1.6651764926365975,"y":4.281207809755953}},"time":1.0970142856045604,"velocity":3.0729558264188617,"position":2.716514653460936,"holonomicRotation":0.42798583008745356,"angularVelocity":-0.6628322456114819,"angularAcceleration":5.969702769255503,"curveRadius":-4.70438496350563},{"acceleration":-4.992580309015227,"curvature":-0.209419961220628,"pose":{"rotation":{"radians":2.8847653686041945},"translation":{"x":1.6594309079612912,"y":4.282716756314393}},"time":1.0989535264758117,"velocity":3.063274010630615,"position":2.722455079622193,"holonomicRotation":0.4249504695903794,"angularVelocity":-0.6512126598004071,"angularAcceleration":5.991821842934461,"curveRadius":-4.775093998544296},{"acceleration":-4.992417752853095,"curvature":-0.20623215275124432,"pose":{"rotation":{"radians":2.883521410323412},"translation":{"x":1.6536879953654637,"y":4.28423264029491}},"time":1.1008986667607463,"velocity":3.0535630577403174,"position":2.728394688138392,"holonomicRotation":0.42191510909330526,"angularVelocity":-0.6395211134214845,"angularAcceleration":6.01064430646728,"curveRadius":-4.848904434441862},{"acceleration":-4.992254359604431,"curvature":-0.20300554631008483,"pose":{"rotation":{"radians":2.8822965283497872},"translation":{"x":1.6479474721018297,"y":4.285755417399977}},"time":1.1028498523184525,"velocity":3.043822243133462,"position":2.7343337501394185,"holonomicRotation":0.4188797485962311,"angularVelocity":-0.6277629356097343,"angularAcceleration":6.02617099399482,"curveRadius":-4.925973788285224},{"acceleration":-4.992090122168185,"curvature":-0.19974149645857,"pose":{"rotation":{"radians":2.8810908937455366},"translation":{"x":1.6422090554231032,"y":4.287285043332066}},"time":1.1048072309262955,"velocity":3.034050832719905,"position":2.740272536334493,"holonomicRotation":0.41584438809915697,"angularVelocity":-0.6159434865690885,"angularAcceleration":6.038407180545549,"curveRadius":-5.006470952356253},{"acceleration":-4.991925034364357,"curvature":-0.19644137861946326,"pose":{"rotation":{"radians":2.8799046721840535},"translation":{"x":1.6364724625819997,"y":4.288821473793649}},"time":1.1067709523272915,"velocity":3.0242480826977562,"position":2.7462113170164075,"holonomicRotation":0.4128090276020828,"angularVelocity":-0.6040681539048385,"angularAcceleration":6.047361228648272,"curveRadius":-5.090577184031841},{"acceleration":-4.99175908765369,"curvature":-0.19310658657240126,"pose":{"rotation":{"radians":2.878738023886736},"translation":{"x":1.6307374108312327,"y":4.2903646644872}},"time":1.1087411682791373,"velocity":3.01441323931549,"position":2.752150362065962,"holonomicRotation":0.4097736671050087,"angularVelocity":-0.5921423467435897,"angularAcceleration":6.0530456826706205,"curveRadius":-5.1784872683515175},{"acceleration":-4.991592273341983,"curvature":-0.1897385320232895,"pose":{"rotation":{"radians":2.877591103562318},"translation":{"x":1.6250036174235172,"y":4.291914571115191}},"time":1.110718032604962,"velocity":3.004545538621258,"position":2.758089940956578,"holonomicRotation":0.40673830660793453,"angularVelocity":-0.5801714915055834,"angularAcceleration":6.055476383293261,"curveRadius":-5.270410755983159},{"acceleration":-4.9914245820082845,"curvature":-0.1863386429536352,"pose":{"rotation":{"radians":2.876464060351747},"translation":{"x":1.6192707996115674,"y":4.2934711493800926}},"time":1.1127017012458702,"velocity":2.9946442062044696,"position":2.7640303227591034,"holonomicRotation":0.4037029461108604,"angularVelocity":-0.5681610261555371,"angularAcceleration":6.054673196097461,"curveRadius":-5.366573374953794},{"acceleration":-4.99125600337064,"curvature":-0.18290836168230654,"pose":{"rotation":{"radians":2.875357037773208},"translation":{"x":1.6135386746480982,"y":4.295034354984382}},"time":1.1146923323153468,"velocity":2.9847084569284483,"position":2.769971776146795,"holonomicRotation":0.40066758561378624,"angularVelocity":-0.5561163972138214,"angularAcceleration":6.050658570742843,"curveRadius":-5.467218615936758},{"acceleration":-4.991086525872191,"curvature":-0.17944914536528506,"pose":{"rotation":{"radians":2.8742701736781573},"translation":{"x":1.6078069597858236,"y":4.2966041436305265}},"time":1.1166900861555964,"velocity":2.974737494654369,"position":2.775914569400475,"holonomicRotation":0.3976322251167121,"angularVelocity":-0.5440430513274647,"angularAcceleration":6.043460231741281,"curveRadius":-5.572609431849949},{"acceleration":-4.990916137893469,"curvature":-0.17596246231382046,"pose":{"rotation":{"radians":2.8732036002014927},"translation":{"x":1.6020753722774583,"y":4.298180471021002}},"time":1.1186951253959003,"velocity":2.9647305119528267,"position":2.7818589704138668,"holonomicRotation":0.39459686461963794,"angularVelocity":-0.5319464353739718,"angularAcceleration":6.033106839175493,"curveRadius":-5.68303027163003},{"acceleration":-4.990744825805205,"curvature":-0.17244979236653823,"pose":{"rotation":{"radians":2.8721574437254924},"translation":{"x":1.5963436293757165,"y":4.29976329285828}},"time":1.1207076150130684,"velocity":2.9546866898089585,"position":2.787805246699092,"holonomicRotation":0.3915615041225638,"angularVelocity":-0.5198319867470423,"angularAcceleration":6.019632858517194,"curveRadius":-5.79878923759167},{"acceleration":-4.990572575432876,"curvature":-0.168912624657258,"pose":{"rotation":{"radians":2.8711318248406035},"translation":{"x":1.5906114483333134,"y":4.301352564844834}},"time":1.1227277223940748,"velocity":2.9446051973138783,"position":2.7937536653923356,"holonomicRotation":0.38852614362548965,"angularVelocity":-0.5077051321786519,"angularAcceleration":6.003074233780939,"curveRadius":-5.920220599431855},{"acceleration":-4.990399372479648,"curvature":-0.16535245679054655,"pose":{"rotation":{"radians":2.870126858314057},"translation":{"x":1.5848785464029627,"y":4.302948242683134}},"time":1.1247556174009705,"velocity":2.9344851913440113,"position":2.7997044932596715,"holonomicRotation":0.38549078312841556,"angularVelocity":-0.4955712811210853,"angularAcceleration":5.983471045742665,"curveRadius":-6.047687584507492},{"acceleration":-4.9902252000473935,"curvature":-0.16177079278451018,"pose":{"rotation":{"radians":2.8691426530600994},"translation":{"x":1.5791446408373793,"y":4.304550282075655}},"time":1.1267914724381625,"velocity":2.9243258162337726,"position":2.8056579967030415,"holonomicRotation":0.3824554226313414,"angularVelocity":-0.48343582228488,"angularAcceleration":5.960865884117018,"curveRadius":-6.181585580359174},{"acceleration":-4.990050041332717,"curvature":-0.15816914270990498,"pose":{"rotation":{"radians":2.868179312117058},"translation":{"x":1.5734094488892776,"y":4.3061586387248685}},"time":1.128835462522165,"velocity":2.914126203430612,"position":2.8116144417663858,"holonomicRotation":0.37942006213426727,"angularVelocity":-0.47130411765744495,"angularAcceleration":5.935305030285933,"curveRadius":-6.322345704522664},{"acceleration":-4.989873877613869,"curvature":-0.15454902025606393,"pose":{"rotation":{"radians":2.867236932624493},"translation":{"x":1.5676726878113718,"y":4.307773268333247}},"time":1.1308877653539269,"velocity":2.9038854711414506,"position":2.8175740941419214,"holonomicRotation":0.3763847016371932,"angularVelocity":-0.4591814999135132,"angularAcceleration":5.906836728147423,"curveRadius":-6.470438947740685},{"acceleration":-4.989696690154808,"curvature":-0.15091194245102987,"pose":{"rotation":{"radians":2.8663156058079253},"translation":{"x":1.5619340748563768,"y":4.309394126603264}},"time":1.132948561393845,"velocity":2.893602723961987,"position":2.8235372191765586,"holonomicRotation":0.37334934114011903,"angularVelocity":-0.447073266214218,"angularAcceleration":5.875512891501907,"curveRadius":-6.626380813595946},{"acceleration":-4.989518457392002,"curvature":-0.1472594276680173,"pose":{"rotation":{"radians":2.865415416965438},"translation":{"x":1.556193327277007,"y":4.3110211692373905}},"time":1.1350180339395821,"velocity":2.8832770524979656,"position":2.829504081878457,"holonomicRotation":0.3703139806430449,"angularVelocity":-0.43498467488339077,"angularAcceleration":5.8413876307412655,"curveRadius":-6.790736700772783},{"acceleration":-4.989339158171172,"curvature":-0.14359299458626948,"pose":{"rotation":{"radians":2.8645364454581737},"translation":{"x":1.5504501623259763,"y":4.3126543519381}},"time":1.1370963692068128,"velocity":2.8729075329653635,"position":2.8354749469237115,"holonomicRotation":0.36727862014597074,"angularVelocity":-0.42292094116043843,"angularAcceleration":5.804517641192204,"curveRadius":-6.964128040377404},{"acceleration":-4.989158768547768,"curvature":-0.1399141601749037,"pose":{"rotation":{"radians":2.8636787647059414},"translation":{"x":1.5447042972560003,"y":4.314293630407866}},"time":1.1391837564130243,"velocity":2.862493226782139,"position":2.8414500786631636,"holonomicRotation":0.3642432596488966,"angularVelocity":-0.4108872324598076,"angularAcceleration":5.764962372492181,"curveRadius":-7.147239412722209},{"acceleration":-4.988977264930707,"curvature":-0.13622443962371447,"pose":{"rotation":{"radians":2.862842442185709},"translation":{"x":1.5389554493197926,"y":4.3159389603491585}},"time":1.1412803878645152,"velocity":2.852033180137712,"position":2.847429741129336,"holonomicRotation":0.36120789915182244,"angularVelocity":-0.3988886647854234,"angularAcceleration":5.72278340375545,"curveRadius":-7.340826673702948},{"acceleration":-4.988794620533434,"curvature":-0.13252534441671032,"pose":{"rotation":{"radians":2.8620275394333197},"translation":{"x":1.5332033357700678,"y":4.317590297464452}},"time":1.1433864590467295,"velocity":2.8415264235534208,"position":2.8534141980434824,"holonomicRotation":0.3581725386547483,"angularVelocity":-0.38693029906643744,"angularAcceleration":5.678044417479345,"curveRadius":-7.54572647519872},{"acceleration":-4.988610808305413,"curvature":-0.128818380962931,"pose":{"rotation":{"radians":2.8612341120508},"translation":{"x":1.5274476738595406,"y":4.3192475974562194}},"time":1.1455021687180829,"velocity":2.8309719714196713,"position":2.859403712822745,"holonomicRotation":0.35513717815767415,"angularVelocity":-0.3750171364544273,"angularAcceleration":5.6308116247300655,"curveRadius":-7.762867321611205},{"acceleration":-4.9884257996447845,"curvature":-0.12510504885840906,"pose":{"rotation":{"radians":2.8604622097158883},"translation":{"x":1.5216881808409255,"y":4.320910816026931}},"time":1.1476277190074418,"velocity":2.820368821517791,"position":2.865398548587421,"holonomicRotation":0.3521018176606,"angularVelocity":-0.36315411532528424,"angularAcceleration":5.581152884753023,"curveRadius":-7.993282518372031},{"acceleration":-4.988239563726739,"curvature":-0.12138684161187537,"pose":{"rotation":{"radians":2.8597118761945453},"translation":{"x":1.5159245739669367,"y":4.322579908879062}},"time":1.1497633155154248,"velocity":2.8097159545245134,"position":2.871398968168328,"holonomicRotation":0.34906645716352586,"angularVelocity":-0.35134610800224575,"angularAcceleration":5.529137774340495,"curveRadius":-8.238125209628729},{"acceleration":-4.9880520689322845,"curvature":-0.11766524352975154,"pose":{"rotation":{"radians":2.8589831493606495},"translation":{"x":1.5101565704902888,"y":4.324254831715082}},"time":1.1519091674197046,"velocity":2.799012333493748,"position":2.877405234114258,"holonomicRotation":0.3460310966664517,"angularVelocity":-0.3395979156074893,"angularAcceleration":5.474838394637093,"curveRadius":-8.498686358025095},{"acceleration":-4.987863281303143,"curvature":-0.1139417286828496,"pose":{"rotation":{"radians":2.8582760612136973},"translation":{"x":1.5043838876636964,"y":4.325935540237467}},"time":1.1540654875845047,"velocity":2.7882569033210083,"position":2.8834176086995322,"holonomicRotation":0.34299573616937756,"angularVelocity":-0.3279142673220611,"angularAcceleration":5.418327239225912,"curveRadius":-8.776415906269456},{"acceleration":-4.98767316555792,"curvature":-0.11021776066288139,"pose":{"rotation":{"radians":2.857590637905719},"translation":{"x":1.4986062427398739,"y":4.327621990148686}},"time":1.1562324926744865,"velocity":2.7774485901840786,"position":2.889436353931624,"holonomicRotation":0.3399603756723034,"angularVelocity":-0.3162998144983726,"angularAcceleration":5.359679530695543,"curveRadius":-9.0729478986482},{"acceleration":-4.987481684445575,"curvature":-0.10649479151576771,"pose":{"rotation":{"radians":2.8569268997671737},"translation":{"x":1.4928233529715358,"y":4.329314137151215}},"time":1.158410403273245,"velocity":2.7665863009624108,"position":2.89546173155887,"holonomicRotation":0.33692501517522927,"angularVelocity":-0.30475912965555907,"angularAcceleration":5.298970880343859,"curveRadius":-9.390130594808847},{"acceleration":-4.987288799136702,"curvature":-0.10277425966220824,"pose":{"rotation":{"radians":2.8562848613394314},"translation":{"x":1.4870349356113963,"y":4.331011936947523}},"time":1.1605994440066352,"velocity":2.7556689226319198,"position":2.901494003078249,"holonomicRotation":0.3338896546781551,"angularVelocity":-0.29329670204355435,"angularAcceleration":5.236278812524709,"curveRadius":-9.730062792830958},{"acceleration":-4.987094468308846,"curvature":-0.09905758910166837,"pose":{"rotation":{"radians":2.8556645314074025},"translation":{"x":1.4812407079121708,"y":4.332715345240086}},"time":1.162799843671169,"velocity":2.744695321636854,"position":2.9075334297432263,"holonomicRotation":0.330854294181081,"angularVelocity":-0.2819169362854258,"angularAcceleration":5.171681282063415,"curveRadius":-10.095137677676002},{"acceleration":-4.986898648753763,"curvature":-0.09534618922336006,"pose":{"rotation":{"radians":2.8550659130393634},"translation":{"x":1.4754403871265724,"y":4.334424317731374}},"time":1.1650118353677368,"velocity":2.733664343234186,"position":2.9135802725716635,"holonomicRotation":0.3278189336840069,"angularVelocity":-0.270624147897098,"angularAcceleration":5.105258037745125,"curveRadius":-10.488096148839029},{"acceleration":-4.986701295622703,"curvature":-0.0916414533320017,"pose":{"rotation":{"radians":2.8544890036260147},"translation":{"x":1.4696336905073166,"y":4.33613881012386}},"time":1.1672356566409194,"velocity":2.7225748108099728,"position":2.919634792353774,"holonomicRotation":0.32478357318693274,"angularVelocity":-0.2594225625529273,"angularAcceleration":5.037088852081793,"curveRadius":-10.912092329845171},{"acceleration":-4.986502361499456,"curvature":-0.08794475625149205,"pose":{"rotation":{"radians":2.8539337949245724},"translation":{"x":1.4638203353071177,"y":4.337858778120018}},"time":1.169471549624182,"velocity":2.7114255251688735,"position":2.9256972496601383,"holonomicRotation":0.3217482126898586,"angularVelocity":-0.24831631281030314,"angularAcceleration":4.967254616282083,"curveRadius":-11.370774593317885},{"acceleration":-4.986301796510541,"curvature":-0.08425745662319059,"pose":{"rotation":{"radians":2.853400273107507},"translation":{"x":1.4580000387786898,"y":4.339584177422319}},"time":1.1717197611912438,"velocity":2.700215263793098,"position":2.9317679048497545,"holonomicRotation":0.31871285219278445,"angularVelocity":-0.23730943514481792,"angularAcceleration":4.895837129719415,"curveRadius":-11.868385779458302},{"acceleration":-4.986099548694562,"curvature":-0.08058089224020057,"pose":{"rotation":{"radians":2.852888418809549},"translation":{"x":1.4521725181747478,"y":4.341314963733236}},"time":1.1739805431139523,"velocity":2.6889427800685843,"position":2.937847018078131,"holonomicRotation":0.3156774916957103,"angularVelocity":-0.22640586994116543,"angularAcceleration":4.822917723346605,"curveRadius":-12.409889890758933},{"acceleration":-4.985895563299854,"curvature":-0.0769163830751107,"pose":{"rotation":{"radians":2.8523982071825476},"translation":{"x":1.4463374907480062,"y":4.343051092755243}},"time":1.176254152227003,"velocity":2.677606802479147,"position":2.943934849305414,"holonomicRotation":0.31264213119863615,"angularVelocity":-0.21560945731063344,"angularAcceleration":4.748579062495846,"curveRadius":-13.001131358757158},{"acceleration":-4.98568978313861,"curvature":-0.07326522607085173,"pose":{"rotation":{"radians":2.851929607950889},"translation":{"x":1.440494673751179,"y":4.344792520190809}},"time":1.1785408505998636,"velocity":2.666206033764456,"position":2.9500316583045345,"holonomicRotation":0.309606770701562,"angularVelocity":-0.2049239362830492,"angularAcceleration":4.672903586412511,"curveRadius":-13.64903998293736},{"acceleration":-4.98548214835849,"curvature":-0.06962869818089311,"pose":{"rotation":{"radians":2.851482585467705},"translation":{"x":1.434643784436981,"y":4.346539201742409}},"time":1.1808409057162976,"velocity":2.6547391500412334,"position":2.9561377046693846,"holonomicRotation":0.30657141020448786,"angularVelocity":-0.19435294397515132,"angularAcceleration":4.595973475751693,"curveRadius":-14.361894249437672},{"acceleration":-4.985272596023949,"curvature":-0.06600805447321606,"pose":{"rotation":{"radians":2.851057098778758},"translation":{"x":1.4287845400581267,"y":4.348291093112516}},"time":1.1831545906618923,"velocity":2.643204799886127,"position":2.962253247823005,"holonomicRotation":0.3035360497074137,"angularVelocity":-0.18390001186503563,"angularAcceleration":4.517871860651681,"curveRadius":-15.149666324520558},{"acceleration":-4.9850610603161885,"curvature":-0.062404524791361174,"pose":{"rotation":{"radians":2.850653101682927},"translation":{"x":1.4229166578673305,"y":4.350048150003602}},"time":1.1854821843200358,"velocity":2.631601603376677,"position":2.9683785470257846,"holonomicRotation":0.30050068921033957,"angularVelocity":-0.17356856701242068,"angularAcceleration":4.438680616124102,"curveRadius":-16.0244790476865},{"acceleration":-4.98484747211047,"curvature":-0.05881931706078077,"pose":{"rotation":{"radians":2.8502705428005277},"translation":{"x":1.4170398551173067,"y":4.3518103281181375}},"time":1.1878239715768089,"velocity":2.6199281510895314,"position":2.974513861383667,"holonomicRotation":0.2974653287132654,"angularVelocity":-0.16336192849827652,"angularAcceleration":4.358482387596919,"curveRadius":-17.001217456616384},{"acceleration":-4.984631759475088,"curvature":-0.055253615404343585,"pose":{"rotation":{"radians":2.849909365638667},"translation":{"x":1.4111538490607702,"y":4.353577583158598}},"time":1.1901802435352937,"velocity":2.608183003051307,"position":2.9806594498563537,"holonomicRotation":0.2944299682161913,"angularVelocity":-0.15328330864354692,"angularAcceleration":4.277358485058052,"curveRadius":-18.098363205412767},{"acceleration":-4.984413846396504,"curvature":-0.05170857709126658,"pose":{"rotation":{"radians":2.8495695086646298},"translation":{"x":1.4052583569504355,"y":4.355349870827456}},"time":1.1925512977398314,"velocity":2.596364687643653,"position":2.9868155712655042,"holonomicRotation":0.2913946077191171,"angularVelocity":-0.14333580961032882,"angularAcceleration":4.195390815689024,"curveRadius":-19.339151379760107},{"acceleration":-4.984193653472561,"curvature":-0.048185334490827146,"pose":{"rotation":{"radians":2.849250905376479},"translation":{"x":1.3993530960390166,"y":4.357127146827182}},"time":1.1949374384107998,"velocity":2.5844717004551194,"position":2.992982484302927,"holonomicRotation":0.288359247222043,"angularVelocity":-0.1335224247367111,"angularAcceleration":4.1126598247180866,"curveRadius":-20.75320241245531},{"acceleration":-4.9839710980212075,"curvature":-0.04468499535680361,"pose":{"rotation":{"radians":2.8489534843780797},"translation":{"x":1.3934377835792282,"y":4.3589093668602485}},"time":1.1973389766905222,"velocity":2.572502503078191,"position":2.999160447538751,"holonomicRotation":0.28532388672496883,"angularVelocity":-0.12384603689675126,"angularAcceleration":4.0292457220703435,"curveRadius":-22.378876667998643},{"acceleration":-4.983746092321342,"curvature":-0.04120863840107315,"pose":{"rotation":{"radians":2.8486771694560202},"translation":{"x":1.3875121368237848,"y":4.36069648662913}},"time":1.1997562309009573,"velocity":2.5604555218527882,"position":3.0053497194295815,"holonomicRotation":0.2822885262278947,"angularVelocity":-0.11430941804410183,"angularAcceleration":3.9452279414721176,"curveRadius":-24.266756651051058},{"acceleration":-4.983518545322409,"curvature":-0.03775731670841565,"pose":{"rotation":{"radians":2.8484218796583485},"translation":{"x":1.381575873025401,"y":4.362488461836298}},"time":1.2021895268138707,"velocity":2.548329146544527,"position":3.0115505583266264,"holonomicRotation":0.2792531657308206,"angularVelocity":-0.104915228894661,"angularAcceleration":3.860685048450626,"curveRadius":-26.484932913071972},{"acceleration":-4.983288361366426,"curvature":-0.03433205560055355,"pose":{"rotation":{"radians":2.848187529374861},"translation":{"x":1.3756287094367912,"y":4.364285248184224}},"time":1.204639197934237,"velocity":2.53612172896123,"position":3.0177632224837962,"holonomicRotation":0.27621780523374645,"angularVelocity":-0.09566601881331345,"angularAcceleration":3.7756946246582093,"curveRadius":-29.127297579696236},{"acceleration":-4.983055439809178,"curvature":-0.03093385299401329,"pose":{"rotation":{"radians":2.847974028418153},"translation":{"x":1.3696703633106697,"y":4.366086801375382}},"time":1.207105585797672,"velocity":2.523831581501661,"position":3.023987970065766,"holonomicRotation":0.2731824447366723,"angularVelocity":-0.0865642261192391,"angularAcceleration":3.6903330692675564,"curveRadius":-32.327043132762434},{"acceleration":-4.982819675385366,"curvature":-0.027563677002225093,"pose":{"rotation":{"radians":2.8477812821088895},"translation":{"x":1.3637005518997514,"y":4.367893077112246}},"time":1.2095890402827596,"velocity":2.5114569756304426,"position":3.030225059156,"holonomicRotation":0.27014708423959816,"angularVelocity":-0.07761217707868422,"angularAcceleration":3.6046761051226572,"curveRadius":-36.27962988825019},{"acceleration":-4.9825809577656,"curvature":-0.024222466431023503,"pose":{"rotation":{"radians":2.8476091913609105},"translation":{"x":1.35771899245675,"y":4.369704031097284}},"time":1.2120899199391955,"velocity":2.498996140276622,"position":3.0364747477647294,"holonomicRotation":0.267111723742524,"angularVelocity":-0.06881208679358286,"angularAcceleration":3.518797980724446,"curveRadius":-41.283987443955176},{"acceleration":-4.982339170841508,"curvature":-0.02091113584669627,"pose":{"rotation":{"radians":2.847457652765477},"translation":{"x":1.351725402234381,"y":4.3715196190329735}},"time":1.2146085923327437,"velocity":2.4864472601517296,"position":3.042737293836887,"holonomicRotation":0.26407636324544986,"angularVelocity":-0.060166060429913654,"angularAcceleration":3.432771322628851,"curveRadius":-47.82140995741219},{"acceleration":-4.982094193058516,"curvature":-0.017630565519315276,"pose":{"rotation":{"radians":2.8473265586832834},"translation":{"x":1.3457194984853582,"y":4.373339796621783}},"time":1.2171454344080723,"velocity":2.473808473979528,"position":3.049012955259983,"holonomicRotation":0.2610410027483757,"angularVelocity":-0.051676091101063165,"angularAcceleration":3.3466684471285166,"curveRadius":-56.719678044612},{"acceleration":-4.9818458965983305,"curvature":-0.014381611187675931,"pose":{"rotation":{"radians":2.8472157973299326},"translation":{"x":1.339700998462396,"y":4.375164519566188}},"time":1.2197008328706214,"velocity":2.4610778726347045,"position":3.055301989871927,"holonomicRotation":0.2580056422513015,"angularVelocity":-0.04334406354787329,"angularAcceleration":3.2605590381699514,"curveRadius":-69.53323844945359},{"acceleration":-4.981594147124378,"curvature":-0.011165090634181871,"pose":{"rotation":{"radians":2.8471252528691},"translation":{"x":1.3336696194182094,"y":4.37699374356866}},"time":1.2222751845887396,"velocity":2.448253497183087,"position":3.0616046554687895,"holonomicRotation":0.2549702817542274,"angularVelocity":-0.03517175224943565,"angularAcceleration":3.1745123406879454,"curveRadius":-89.56487974566949},{"acceleration":-4.981338803810048,"curvature":-0.007981797428396184,"pose":{"rotation":{"radians":2.847054805502559},"translation":{"x":1.3276250786055126,"y":4.3788274243316705}},"time":1.2248688970174308,"velocity":2.435333336816123,"position":3.0679212098124955,"holonomicRotation":0.25193492125715333,"angularVelocity":-0.027160823907030954,"angularAcceleration":3.0885954255333514,"curveRadius":-125.28506379307277},{"acceleration":-4.981079718412226,"curvature":-0.004832505243742056,"pose":{"rotation":{"radians":2.8470043315632485},"translation":{"x":1.3215670932770198,"y":4.380665517557693}},"time":1.2274823886451487,"velocity":2.4223153266750574,"position":3.0742519106384534,"holonomicRotation":0.24889956076007913,"angularVelocity":-0.019312837575233378,"angularAcceleration":3.0028741047280874,"curveRadius":-206.93200515301436},{"acceleration":-4.980816734949517,"curvature":-0.0017179399288715304,"pose":{"rotation":{"radians":2.846973703608558},"translation":{"x":1.3154953806854461,"y":4.3825079789492}},"time":1.2301160894651988,"velocity":2.4091973455557016,"position":3.080597015663106,"holonomicRotation":0.24586420026300504,"angularVelocity":-0.011629245986293358,"angularAcceleration":2.9174124602329954,"curveRadius":-582.0925302416562},{"acceleration":-4.980549689608986,"curvature":0.0013612067326561395,"pose":{"rotation":{"radians":2.846962790514686},"translation":{"x":1.3094096580835055,"y":4.384354764208664}},"time":1.2327704414734357,"velocity":2.395977213484964,"position":3.0869567825914097,"holonomicRotation":0.24282883976593084,"angularVelocity":-0.00411139661876954,"angularAcceleration":2.8322729405122464,"curveRadius":734.642267048362},{"acceleration":-4.980278409688592,"curvature":0.004404234948259656,"pose":{"rotation":{"radians":2.84697145757143},"translation":{"x":1.3033096427239126,"y":4.386205829038558}},"time":1.2354458991940747,"velocity":2.3826526891628315,"position":3.0933314691242315,"holonomicRotation":0.23979347926885675,"angularVelocity":0.0032394669057897907,"angularAcceleration":2.7475162353916254,"curveRadius":227.05419028454702},{"acceleration":-4.9800027136186165,"curvature":0.0074105123748934324,"pose":{"rotation":{"radians":2.8469995665778933},"translation":{"x":1.297195051859382,"y":4.388061129141354}},"time":1.238142930235596,"velocity":2.3692214672573417,"position":3.099721332965663,"holonomicRotation":0.23675811877178254,"angularVelocity":0.010422203538107196,"angularAcceleration":2.6632013209109635,"curveRadius":134.94343567766873},{"acceleration":-4.979722409779344,"curvature":0.010379433144952028,"pose":{"rotation":{"radians":2.847046975938638},"translation":{"x":1.291065602742628,"y":4.389920620219525}},"time":1.2408620158788828,"velocity":2.355681175545357,"position":3.1061266318302496,"holonomicRotation":0.23372275827470845,"angularVelocity":0.017435773257754895,"angularAcceleration":2.5793853669021316,"curveRadius":96.34437507662388},{"acceleration":-4.979437296571129,"curvature":0.013310410409478272,"pose":{"rotation":{"radians":2.847113540760388},"translation":{"x":1.284921012626365,"y":4.391784257975542}},"time":1.2436036516999187,"velocity":2.3420293718844754,"position":3.1125476234501264,"holonomicRotation":0.23068739777763425,"angularVelocity":0.024279235498376118,"angularAcceleration":2.4961237331789103,"curveRadius":75.12916350707754},{"acceleration":-4.979147161014472,"curvature":0.016202886616761843,"pose":{"rotation":{"radians":2.8471991129484664},"translation":{"x":1.2787609987633077,"y":4.39365199811188}},"time":1.2463683482295709,"velocity":2.328263541007791,"position":3.1189845655820663,"holonomicRotation":0.22765203728056016,"angularVelocity":0.030951747202920866,"angularAcceleration":2.4134698448745238,"curveRadius":61.71739787190158},{"acceleration":-4.978851778656803,"curvature":0.019056340828949483,"pose":{"rotation":{"radians":2.847303541305536},"translation":{"x":1.2725852784061709,"y":4.395523796331009}},"time":1.249156631653208,"velocity":2.3143810911246168,"position":3.125437716014428,"holonomicRotation":0.22461667678348596,"angularVelocity":0.0374525617390363,"angularAcceleration":2.3314755168023122,"curveRadius":52.47597159266},{"acceleration":-4.978550912414035,"curvature":0.02187027596176406,"pose":{"rotation":{"radians":2.8474266716274217},"translation":{"x":1.2663935688076682,"y":4.397399608335403}},"time":1.2519690445531475,"velocity":2.3003793503155374,"position":3.13190733257401,"holonomicRotation":0.22158131628641187,"angularVelocity":0.0437810258544343,"angularAcceleration":2.250190260304201,"curveRadius":45.72416012254744},{"acceleration":-4.978244311502767,"curvature":0.024644228374367014,"pose":{"rotation":{"radians":2.8475683468022543},"translation":{"x":1.2601855872205148,"y":4.399279389827535}},"time":1.2548061466971934,"velocity":2.286255562705789,"position":3.1383936731327995,"holonomicRotation":0.21854595578933766,"angularVelocity":0.049936578818631956,"angularAcceleration":2.169662088873364,"curveRadius":40.57745224598394},{"acceleration":-4.977931711486476,"curvature":0.02737776019118898,"pose":{"rotation":{"radians":2.847728406907314},"translation":{"x":1.2539610508974248,"y":4.401163096509876}},"time":1.2576685158768313,"velocity":2.272006884396488,"position":3.144896995614621,"holonomicRotation":0.21551059529226357,"angularVelocity":0.05591874947451913,"angularAcceleration":2.0899367902794275,"curveRadius":36.52599748907989},{"acceleration":-4.977612831793197,"curvature":0.030070467556562137,"pose":{"rotation":{"radians":2.847906689307614},"translation":{"x":1.247719677091113,"y":4.4030506840849}},"time":1.2605567487989693,"velocity":2.257630379142046,"position":3.151417558001678,"holonomicRotation":0.21247523479518937,"angularVelocity":0.06172715466731501,"angularAcceleration":2.0110584393228885,"curveRadius":33.25521953122324},{"acceleration":-4.977287375958612,"curvature":0.032721970802277546,"pose":{"rotation":{"radians":2.8481030287532327},"translation":{"x":1.2414611830542936,"y":4.40494210825508}},"time":1.2634714620354903,"velocity":2.2431230137453704,"position":3.1579556183409867,"holonomicRotation":0.20943987429811528,"angularVelocity":0.06736149654740495,"angularAcceleration":1.9330690269945776,"curveRadius":30.56050645734324},{"acceleration":-4.976955029651743,"curvature":0.035331919010610724,"pose":{"rotation":{"radians":2.8483172574772775},"translation":{"x":1.2351852860396815,"y":4.406837324722885}},"time":1.26641329303528,"velocity":2.2284816531545815,"position":3.1645114347506995,"holonomicRotation":0.2064045138010412,"angularVelocity":0.07282156047035461,"angularAcceleration":1.8560086977599752,"curveRadius":28.303019705770424},{"acceleration":-4.97661545963501,"curvature":0.03789999241456692,"pose":{"rotation":{"radians":2.848549205292196},"translation":{"x":1.2288917032999906,"y":4.408736289190792}},"time":1.2693829012038538,"velocity":2.213703055233799,"position":3.1710852654263184,"holonomicRotation":0.203369153303967,"angularVelocity":0.07810721204670688,"angularAcceleration":1.7799154892852165,"curveRadius":26.385229555234645},{"acceleration":-4.976268312497752,"curvature":0.04042589532583422,"pose":{"rotation":{"radians":2.8487986996890693},"translation":{"x":1.2225801520879356,"y":4.410638957361272}},"time":1.272380969056206,"velocity":2.1987838651814204,"position":3.1776773686467896,"holonomicRotation":0.2003337928068929,"angularVelocity":0.08321839570029572,"angularAcceleration":1.7048258762985253,"curveRadius":24.736619731980277},{"acceleration":-4.975913212596697,"curvature":0.04290936345118566,"pose":{"rotation":{"radians":2.849065565932248},"translation":{"x":1.2162503496562311,"y":4.412545284936796}},"time":1.2754082034490732,"velocity":2.1837206095683253,"position":3.184288002780488,"holonomicRotation":0.1972984323098187,"angularVelocity":0.08815513057318358,"angularAcceleration":1.630773911831801,"curveRadius":23.30493672173942},{"acceleration":-4.9755497609078745,"curvature":0.04535015689600776,"pose":{"rotation":{"radians":2.849349627156988},"translation":{"x":1.2099020132575915,"y":4.414455227619837}},"time":1.2784653368994263,"velocity":2.1685096899603575,"position":3.1909174262910804,"holonomicRotation":0.1942630718127446,"angularVelocity":0.09291750895168359,"angularAcceleration":1.5577921133766617,"curveRadius":22.050640360365136},{"acceleration":-4.97517753302036,"curvature":0.047748061914850176,"pose":{"rotation":{"radians":2.8496507044650476},"translation":{"x":1.2035348601447313,"y":4.416368741112868}},"time":1.281553128996715,"velocity":2.153147376091289,"position":3.197565897743273,"holonomicRotation":0.1912277113156704,"angularVelocity":0.09750569292673703,"angularAcceleration":1.4859109131998138,"curveRadius":20.943258425510855},{"acceleration":-4.974796076915268,"curvature":0.05010289431682403,"pose":{"rotation":{"radians":2.8499686170199383},"translation":{"x":1.197148607570365,"y":4.418285781118364}},"time":1.2846723679171754,"velocity":2.137629798546821,"position":3.204233675808436,"holonomicRotation":0.1881923508185963,"angularVelocity":0.10191991155449577,"angularAcceleration":1.4151588705834717,"curveRadius":19.958926797253117},{"acceleration":-4.974404910804154,"curvature":0.05241449333314091,"pose":{"rotation":{"radians":2.8503031821430094},"translation":{"x":1.190742972787207,"y":4.420206303338793}},"time":1.2878238720493962,"velocity":2.1219529409150826,"position":3.210921019270108,"holonomicRotation":0.1851569903215221,"angularVelocity":0.10616045831909006,"angularAcceleration":1.3455628127658885,"curveRadius":19.07869248385379},{"acceleration":-4.974003520862067,"curvature":0.05468272518358657,"pose":{"rotation":{"radians":2.8506542154048407},"translation":{"x":1.184317673047972,"y":4.422130263476631}},"time":1.2910084917413434,"velocity":2.1061126313547307,"position":3.217628187029379,"holonomicRotation":0.18212162982444802,"angularVelocity":0.11022768675296606,"angularAcceleration":1.2771472977324898,"curveRadius":18.28731096781836},{"acceleration":-4.973591358442275,"curvature":0.05690747995648997,"pose":{"rotation":{"radians":2.851021530722415},"translation":{"x":1.177872425605374,"y":4.424057617234349}},"time":1.2942271111801589,"velocity":2.0901045335277235,"position":3.224355438110148,"holonomicRotation":0.17908626932737381,"angularVelocity":0.11412200931393024,"angularAcceleration":1.2099356991385508,"curveRadius":17.572382413780666},{"acceleration":-4.973167836757492,"curvature":0.05908867306042483,"pose":{"rotation":{"radians":2.851404940448917},"translation":{"x":1.171406947712128,"y":4.425988320314421}},"time":1.2974806504173255,"velocity":2.073924136837818,"position":3.2311030316642566,"holonomicRotation":0.17605090883029972,"angularVelocity":0.11784389200597231,"angularAcceleration":1.143948918619246,"curveRadius":16.923717325271245},{"acceleration":-4.9727323281980205,"curvature":0.0612262451220571,"pose":{"rotation":{"radians":2.851804255467171},"translation":{"x":1.1649209566209484,"y":4.427922328419317}},"time":1.3007700675532277,"velocity":2.0575667459051887,"position":3.2378712269764995,"holonomicRotation":0.17301554833322552,"angularVelocity":0.1213938523927738,"angularAcceleration":1.0792065098876216,"curveRadius":16.33286506475218},{"acceleration":-4.972284160167388,"curvature":0.06332015869079394,"pose":{"rotation":{"radians":2.8522192852805395},"translation":{"x":1.1584141695845493,"y":4.429859597251511}},"time":1.3040963610967664,"velocity":2.041027469206584,"position":3.2446602834695066,"holonomicRotation":0.16998018783615143,"angularVelocity":0.12477245556835503,"angularAcceleration":1.0157261021487711,"curveRadius":15.79275890452544},{"acceleration":-4.971822611262966,"curvature":0.06537040101395528,"pose":{"rotation":{"radians":2.8526498381025265},"translation":{"x":1.1518863038556455,"y":4.431800082513476}},"time":1.3074605725175426,"velocity":2.0243012067957,"position":3.2514704607084997,"holonomicRotation":0.16694482733907723,"angularVelocity":0.12798031043116667,"angularAcceleration":0.9535235636503392,"curveRadius":15.29744325396627},{"acceleration":-4.971346906634373,"curvature":0.06737698126777218,"pose":{"rotation":{"radians":2.8530957209475063},"translation":{"x":1.1453370766869515,"y":4.433743739907683}},"time":1.3108637890102344,"velocity":2.0073826370121495,"position":3.2583020184059226,"holonomicRotation":0.16390946684200314,"angularVelocity":0.1310180665665322,"angularAcceleration":0.892613250402643,"curveRadius":14.841864108244351},{"acceleration":-4.9708562133895065,"curvature":0.06933993204880766,"pose":{"rotation":{"radians":2.8535567397171677},"translation":{"x":1.1387662053311816,"y":4.435690525136607}},"time":1.3143071464932103,"velocity":1.990266202072977,"position":3.2651552164259448,"holonomicRotation":0.16087410634492905,"angularVelocity":0.13388640939568758,"angularAcceleration":0.8330075640814301,"curveRadius":14.421704354946733},{"acceleration":-4.9703496343830125,"curvature":0.07125930599677117,"pose":{"rotation":{"radians":2.854032699289761},"translation":{"x":1.1321734070410503,"y":4.4376403939027185}},"time":1.3177918328661722,"velocity":1.9729460924331867,"position":3.272030314788835,"holonomicRotation":0.15783874584785484,"angularVelocity":0.136586057295199,"angularAcceleration":0.77471761030156,"curveRadius":14.033254829135032},{"acceleration":-4.969826202594765,"curvature":0.07313517881119816,"pose":{"rotation":{"radians":2.854523403604409},"translation":{"x":1.1255583990692721,"y":4.439593301908491}},"time":1.3213190915548023,"velocity":1.9554162297791027,"position":3.2789275736752117,"holonomicRotation":0.15480338535078075,"angularVelocity":0.13911775629890402,"angularAcceleration":0.7177525742202543,"curveRadius":13.67331038571118},{"acceleration":-4.969284873629349,"curvature":0.0749676454720361,"pose":{"rotation":{"radians":2.8550286557483258},"translation":{"x":1.1189208986685615,"y":4.441549204856396}},"time":1.3248902253740227,"velocity":1.9376702485095447,"position":3.2858472534301613,"holonomicRotation":0.15176802485370655,"angularVelocity":0.14148227691650586,"angularAcceleration":0.662120418136012,"curveRadius":13.339087731827098},{"acceleration":-4.968724518490637,"curvature":0.07675682251499072,"pose":{"rotation":{"radians":2.855548258038345},"translation":{"x":1.1122606230916332,"y":4.4435080584489075}},"time":1.3285066007456918,"velocity":1.9197014755322666,"position":3.292789614567233,"holonomicRotation":0.14873266435663246,"angularVelocity":0.1436804083143411,"angularAcceleration":0.6078272225431834,"curveRadius":13.02815785273939},{"acceleration":-4.96814391413602,"curvature":0.07850284486366314,"pose":{"rotation":{"radians":2.856082012106542},"translation":{"x":1.1055772895912015,"y":4.445469818388497}},"time":1.3321696523114164,"velocity":1.9015029081888457,"position":3.299754917772304,"holonomicRotation":0.14569730385955826,"angularVelocity":0.1457129550648549,"angularAcceleration":0.5548780065048788,"curveRadius":12.738391860023828},{"acceleration":-4.9675417341699255,"curvature":0.08020586797907722,"pose":{"rotation":{"radians":2.85662971897934},"translation":{"x":1.0988706154199805,"y":4.447434440377638}},"time":1.3358808879868123,"velocity":1.8830671900859763,"position":3.3067434239073186,"holonomicRotation":0.14266194336248417,"angularVelocity":0.1475807307062824,"angularAcceleration":0.5032759449393478,"curveRadius":12.46791569241372},{"acceleration":-4.966916537087372,"curvature":0.08186606418052181,"pose":{"rotation":{"radians":2.85719117916013},"translation":{"x":1.0921403178306854,"y":4.449401880118801}},"time":1.3396418945101054,"velocity":1.8643865845893381,"position":3.3137553940138993,"holonomicRotation":0.13962658286540996,"angularVelocity":0.14928455383229672,"angularAcceleration":0.4530231775621759,"curveRadius":12.21507360846019},{"acceleration":-4.966266754168784,"curvature":0.08348362525214448,"pose":{"rotation":{"radians":2.857766192706212},"translation":{"x":1.0853861140760304,"y":4.45137209331446}},"time":1.3434543435456436,"velocity":1.8454529456921818,"position":3.3207910893168346,"holonomicRotation":0.13659122236833587,"angularVelocity":0.15082524139259654,"angularAcceleration":0.40412017208311557,"curveRadius":11.9783969249025},{"acceleration":-4.965590674446595,"curvature":0.08505875993538424,"pose":{"rotation":{"radians":2.858354559308637},"translation":{"x":1.0786077214087295,"y":4.4533450356670885}},"time":1.3473199984118565,"velocity":1.8262576859378863,"position":3.327850771227439,"holonomicRotation":0.13355586187126167,"angularVelocity":0.15220360399150612,"angularAcceleration":0.356566389554576,"curveRadius":11.75657863763427},{"acceleration":-4.964886428970463,"curvature":0.0865916942504869,"pose":{"rotation":{"radians":2.8589560783676857},"translation":{"x":1.0718048570814978,"y":4.455320662879158}},"time":1.3512407215137663,"velocity":1.8067917410174632,"position":3.334934701346786,"holonomicRotation":0.13052050137418758,"angularVelocity":0.15342043888682128,"angularAcceleration":0.3103598146786804,"curveRadius":11.548451715325768},{"acceleration":-4.9641519713882,"curvature":0.08808266996808088,"pose":{"rotation":{"radians":2.859570549068659},"translation":{"x":1.0649772383470495,"y":4.45729893065314}},"time":1.3552184825725944,"velocity":1.7870455306155706,"position":3.3420431414688214,"holonomicRotation":0.12748514087711338,"angularVelocity":0.15447652382480173,"angularAcceleration":0.26549732936738996,"curveRadius":11.352971025541992},{"acceleration":-4.963385057053959,"curvature":0.08953194518367731,"pose":{"rotation":{"radians":2.8601977704547368},"translation":{"x":1.0581245824580991,"y":4.459279794691509}},"time":1.359255367759745,"velocity":1.7670089150006247,"position":3.3491763535833505,"holonomicRotation":0.12444978038003929,"angularVelocity":0.1553726095738535,"angularAcceleration":0.22197454411237447,"curveRadius":11.169197742196618},{"acceleration":-4.962583218045978,"curvature":0.09093979351295882,"pose":{"rotation":{"radians":2.860837541500824},"translation":{"x":1.0512466066673614,"y":4.461263210696737}},"time":1.36335358985996,"velocity":1.7466711467822724,"position":3.3563345998789016,"holonomicRotation":0.12141441988296509,"angularVelocity":0.15610941292163352,"angularAcceleration":0.17978609498527992,"curveRadius":10.996286239175385},{"acceleration":-4.961743734852982,"curvature":0.0923065025540432,"pose":{"rotation":{"radians":2.8614896611845833},"translation":{"x":1.04434302822755,"y":4.463249134371295}},"time":1.3675154996093415,"velocity":1.7260208171582554,"position":3.363518142745468,"holonomicRotation":0.118379059385891,"angularVelocity":0.15668760810019036,"angularAcceleration":0.13892544850180133,"curveRadius":10.833472965943265},{"acceleration":-4.960863603287419,"curvature":0.0936323752854843,"pose":{"rotation":{"radians":2.8621539285541386},"translation":{"x":1.0374135643913807,"y":4.465237521417657}},"time":1.3717435983789836,"velocity":1.7050457958608334,"position":3.3707272447771306,"holonomicRotation":0.11534369888881679,"angularVelocity":0.15710781742490015,"angularAcceleration":0.09938493578411776,"curveRadius":10.68006655765176},{"acceleration":-4.95993949666873,"curvature":0.0949177268025948,"pose":{"rotation":{"radians":2.862830142799295},"translation":{"x":1.0304579324115668,"y":4.467228327538295}},"time":1.376040552405116,"velocity":1.6837331638712496,"position":3.37796216877456,"holonomicRotation":0.1123083383917427,"angularVelocity":0.1573706027673815,"angularAcceleration":0.06115619131207334,"curveRadius":10.535439834960972},{"acceleration":-4.958967720626286,"curvature":0.09616288690872325,"pose":{"rotation":{"radians":2.8635181033160473},"translation":{"x":1.0234758495408234,"y":4.469221508435683}},"time":1.3804092088031295,"velocity":1.6620691378109935,"position":3.3852231777473984,"holonomicRotation":0.10927297789466861,"angularVelocity":0.1574764536449468,"angularAcceleration":0.02422961842763614,"curveRadius":10.399022243884888},{"acceleration":-4.95794416180946,"curvature":0.09736819663027761,"pose":{"rotation":{"radians":2.86421760977405},"translation":{"x":1.0164670330318648,"y":4.471217019812291}},"time":1.3848526136472126,"velocity":1.6400389847057157,"position":3.392510534916525,"holonomicRotation":0.10623761739759441,"angularVelocity":0.1574257765267825,"angularAcceleration":-0.011405019335969975,"curveRadius":10.270293942047193},{"acceleration":-4.9568642258198,"curvature":0.09853400999705622,"pose":{"rotation":{"radians":2.864928462177917},"translation":{"x":1.0094312001374053,"y":4.473214817370593}},"time":1.3893740324515131,"velocity":1.6176269255847293,"position":3.3998245037162067,"holonomicRotation":0.10320225690052032,"angularVelocity":0.15721888076174811,"angularAcceleration":-0.04575903582247053,"curveRadius":10.148780101711843},{"acceleration":-4.9557227653635705,"curvature":0.09966069187312997,"pose":{"rotation":{"radians":2.865650460932627},"translation":{"x":1.0023680681101599,"y":4.475214856813061}},"time":1.3939769734553336,"velocity":1.594816026064471,"position":3.407165347796129,"holonomicRotation":0.10016689640344612,"angularVelocity":0.15685596537317406,"angularAcceleration":-0.07884424073061885,"curveRadius":10.034046334667432},{"acceleration":-4.954513994298721,"curvature":0.10074861860181207,"pose":{"rotation":{"radians":2.8663834069020924},"translation":{"x":0.9952773542028425,"y":4.477217093842169}},"time":1.398665214197209,"velocity":1.5715880717002082,"position":3.414533331023319,"holonomicRotation":0.09713153590637202,"angularVelocity":0.1563371016591552,"angularAcceleration":-0.11067343649492305,"curveRadius":9.925694405322734},{"acceleration":-4.953231385201262,"curvature":0.10179817685777319,"pose":{"rotation":{"radians":2.8671271014709943},"translation":{"x":0.9881587756681679,"y":4.479221484160388}},"time":1.403442831965089,"velocity":1.5479234254258498,"position":3.421928717483951,"holonomicRotation":0.09409617540929782,"angularVelocity":0.15566221599010252,"angularAcceleration":-0.14125987089003986,"curveRadius":9.823358638309848},{"acceleration":-4.951867546929785,"curvature":0.10280976310138717,"pose":{"rotation":{"radians":2.8678813466005506},"translation":{"x":0.9810120497588506,"y":4.481227983470191}},"time":1.4083142388380754,"velocity":1.5238008638236173,"position":3.4293517714850443,"holonomicRotation":0.09106081491222373,"angularVelocity":0.15483106815381897,"angularAcceleration":-0.17061761785748766,"curveRadius":9.726702696647955},{"acceleration":-4.9504140765576565,"curvature":0.10378378290744136,"pose":{"rotation":{"radians":2.868645944886895},"translation":{"x":0.9738368937276047,"y":4.48323654747405}},"time":1.4132842221967918,"velocity":1.49919738824437,"position":3.43680275755605,"holonomicRotation":0.08802545441514953,"angularVelocity":0.15384322867062794,"angularAcceleration":-0.19876112491574854,"curveRadius":9.635416748027398},{"acceleration":-4.948861380322936,"curvature":0.10472065207642517,"pose":{"rotation":{"radians":2.869420699614768},"translation":{"x":0.9666330248271452,"y":4.48524713187444}},"time":1.4183579917848077,"velocity":1.4740880058775814,"position":3.4442819404503306,"holonomicRotation":0.08499009391807544,"angularVelocity":0.152698051110424,"angularAcceleration":-0.22570547210279732,"curveRadius":9.549214793565262},{"acceleration":-4.9471984546657515,"curvature":0.10562079295362645,"pose":{"rotation":{"radians":2.8702054148131637},"translation":{"x":0.9594001603101863,"y":4.487259692373829}},"time":1.423541234666448,"velocity":1.4484454747033733,"position":3.451789585146531,"holonomicRotation":0.08195473342100124,"angularVelocity":0.15139464160073896,"angularAcceleration":-0.2514660299446688,"curveRadius":9.46783272531439},{"acceleration":-4.945412617229448,"curvature":0.10648463720298874,"pose":{"rotation":{"radians":2.8709998953046325},"translation":{"x":0.9521380174294426,"y":4.489274184674693}},"time":1.428840179765829,"velocity":1.4222400047508883,"position":3.4593259568498493,"holonomicRotation":0.07891937292392714,"angularVelocity":0.14993182163023425,"angularAcceleration":-0.27605871415342426,"curveRadius":9.391026032175208},{"acceleration":-4.943489174159716,"curvature":0.10731262378297804,"pose":{"rotation":{"radians":2.8718039467581624},"translation":{"x":0.9448463134376285,"y":4.491290564479506}},"time":1.4342616741143894,"velocity":1.3954389061310117,"position":3.4668913209932,"holonomicRotation":0.07588401242685294,"angularVelocity":0.14830808663360648,"angularAcceleration":-0.2994995276641612,"curveRadius":9.318568167919684},{"acceleration":-4.941411004271343,"curvature":0.10810519799799627,"pose":{"rotation":{"radians":2.872617375738411},"translation":{"x":0.9375247655874583,"y":4.493308787490736}},"time":1.4398132735164115,"velocity":1.3680061717545535,"position":3.474485943238275,"holonomicRotation":0.07284865192977885,"angularVelocity":0.14652155556330815,"angularAcceleration":-0.32180475227510275,"curveRadius":9.250249002999237},{"acceleration":-4.9391580363057255,"curvature":0.10886281191733056,"pose":{"rotation":{"radians":2.8734399897509255},"translation":{"x":0.9301730911316468,"y":4.495328809410857}},"time":1.4455033511163455,"velocity":1.3399019792496363,"position":3.4821100894765107,"holonomicRotation":0.06981329143270465,"angularVelocity":0.14456991105429376,"angularAcceleration":-0.3429908423458098,"curveRadius":9.185873324302802},{"acceleration":-4.936706584425937,"curvature":0.10958592430412276,"pose":{"rotation":{"radians":2.8742715972912114},"translation":{"x":0.9227910073229084,"y":4.497350585942344}},"time":1.451341228393297,"velocity":1.3110820920574398,"position":3.4897640258299507,"holonomicRotation":0.06677793093563056,"angularVelocity":0.14245032926080248,"angularAcceleration":-0.36307405807580634,"curveRadius":9.125259528995722},{"acceleration":-4.934028495846175,"curvature":0.11027499846124197,"pose":{"rotation":{"radians":2.8751120078884624},"translation":{"x":0.9153782314139575,"y":4.499374072787668}},"time":1.4573373345265075,"velocity":1.2814971335320609,"position":3.497448018652014,"holonomicRotation":0.06374257043855647,"angularVelocity":0.14015939320958126,"angularAcceleration":-0.3820706305601293,"curveRadius":9.068238621209023},{"acceleration":-4.931090044993099,"curvature":0.11093050366934527,"pose":{"rotation":{"radians":2.87596103214818},"translation":{"x":0.9079344806575085,"y":4.5013992256493}},"time":1.4635034020335187,"velocity":1.2510916994314825,"position":3.50516233452817,"holonomicRotation":0.060707209941482265,"angularVelocity":0.13769298807579572,"angularAcceleration":-0.399996453328006,"curveRadius":9.014653020784415},{"acceleration":-4.927850481931679,"curvature":0.11155291339437264,"pose":{"rotation":{"radians":2.876818481794728},"translation":{"x":0.900459472306276,"y":4.503426000229715}},"time":1.469852709324997,"velocity":1.2198032624352393,"position":3.512907240276519,"holonomicRotation":0.057671849444408174,"angularVelocity":0.1350461723122397,"angularAcceleration":-0.4168668552408034,"curveRadius":8.964355744477093},{"acceleration":-4.9242601018884296,"curvature":0.11214270575224855,"pose":{"rotation":{"radians":2.8776841697119653},"translation":{"x":0.8929529236129746,"y":4.505454352231384}},"time":1.4764003847234888,"velocity":1.1875608057103293,"position":3.5206830029482816,"holonomicRotation":0.05463648894733397,"angularVelocity":0.13221301676568464,"angularAcceleration":-0.4326963959159632,"curveRadius":8.917209490283314},{"acceleration":-4.920257640529206,"curvature":0.11270036236524639,"pose":{"rotation":{"radians":2.878557909981481},"translation":{"x":0.8854145518303186,"y":4.50748423735678}},"time":1.483163792148442,"velocity":1.1542830986516914,"position":3.5284898898282004,"holonomicRotation":0.05160112845025988,"angularVelocity":0.12918640185599323,"angularAcceleration":-0.4474985343223452,"curveRadius":8.87308593346965},{"acceleration":-4.915766703121865,"curvature":0.11322636895904487,"pose":{"rotation":{"radians":2.8794395179210213},"translation":{"x":0.8778440742110223,"y":4.509515611308376}},"time":1.4901630270251112,"velocity":1.1198764928976317,"position":3.5363281684348515,"holonomicRotation":0.04856576795318568,"angularVelocity":0.12595775896575057,"angularAcceleration":-0.46128511860700816,"curveRadius":8.831864955076941},{"acceleration":-4.910690781745909,"curvature":0.11372121352101514,"pose":{"rotation":{"radians":2.88032881011979},"translation":{"x":0.8702412080078007,"y":4.511548429788644}},"time":1.4974215635923638,"velocity":1.0842320642878587,"position":3.5441981065208727,"holonomicRotation":0.04553040745611159,"angularVelocity":0.12251673467910278,"angularAcceleration":-0.4740658471257424,"curveRadius":8.793434127531578},{"acceleration":-4.904906162196856,"curvature":0.11418538706918328,"pose":{"rotation":{"radians":2.8812256044741673},"translation":{"x":0.8626056704733679,"y":4.513582648500057}},"time":1.504967114310053,"velocity":1.0472218460754963,"position":3.5520999720731075,"holonomicRotation":0.042495046959037386,"angularVelocity":0.11885074899503717,"angularAcceleration":-0.4858473319212319,"curveRadius":8.757688051572785},{"acceleration":-4.89825159750758,"curvature":0.11461938312896308,"pose":{"rotation":{"radians":2.8821297202202607},"translation":{"x":0.8549371788604383,"y":4.515618223145086}},"time":1.5128327931294994,"velocity":1.0086937722326612,"position":3.5600340333126654,"holonomicRotation":0.039459686461963295,"angularVelocity":0.11494440172895602,"angularAcceleration":-0.4966319316806356,"curveRadius":8.72452784774507},{"acceleration":-4.890512884540111,"curvature":0.1150236968894336,"pose":{"rotation":{"radians":2.883040977966315},"translation":{"x":0.8472354504217267,"y":4.517655109426206}},"time":1.5210587253868668,"velocity":0.9684647445406516,"position":3.5680005586949055,"holonomicRotation":0.03642432596488909,"angularVelocity":0.11077865918941954,"angularAcceleration":-0.5064158577048201,"curveRadius":8.693860717772345},{"acceleration":-4.88139913977141,"curvature":0.11539882465835206,"pose":{"rotation":{"radians":2.8839591997238525},"translation":{"x":0.8395002024099474,"y":4.5196932630458875}},"time":1.5296943338827163,"velocity":0.9263108926576095,"position":3.5759998169093374,"holonomicRotation":0.033388965467815,"angularVelocity":0.10632971121594605,"angularAcceleration":-0.5151863908156334,"curveRadius":8.665599523743714},{"acceleration":-4.870505036876368,"curvature":0.11574526519458557,"pose":{"rotation":{"radians":2.8848842089357123},"translation":{"x":0.8317311520778148,"y":4.521732639706605}},"time":1.538801684807443,"velocity":0.8819534941061269,"position":3.584032076879451,"holonomicRotation":0.0303536049707408,"angularVelocity":0.10156731847768691,"angularAcceleration":-0.522917451805778,"curveRadius":8.639662264532777},{"acceleration":-4.85724822650697,"curvature":0.11606351705885408,"pose":{"rotation":{"radians":2.8858158305062256},"translation":{"x":0.8239280166780436,"y":4.523773195110828}},"time":1.5484605646215344,"velocity":0.8350379172590879,"position":3.5920976077624656,"holonomicRotation":0.02731824447366671,"angularVelocity":0.09645234110420937,"angularAcceleration":-0.5295621720041813,"curveRadius":8.615971886263923},{"acceleration":-4.840760497225719,"curvature":0.11635407975930628,"pose":{"rotation":{"radians":2.8867538908252217},"translation":{"x":0.816090513463348,"y":4.525814884961032}},"time":1.5587765279863512,"velocity":0.7851008093118547,"position":3.6001966789490147,"holonomicRotation":0.024282883976592506,"angularVelocity":0.0909328858413193,"angularAcceleration":-0.5350402156055013,"curveRadius":8.594455837462954},{"acceleration":-4.81968697751377,"curvature":0.1166174525884161,"pose":{"rotation":{"radians":2.8876982177961983},"translation":{"x":0.8082183596864427,"y":4.527857664959687}},"time":1.5698943678768469,"velocity":0.7315163011735497,"position":3.60832956006275,"holonomicRotation":0.021247523479518415,"angularVelocity":0.08493798977837894,"angularAcceleration":-0.5392141029180718,"curveRadius":8.57504582551079},{"acceleration":-4.791787228887135,"curvature":0.11685413528474495,"pose":{"rotation":{"radians":2.8886486408581096},"translation":{"x":0.8003112726000423,"y":4.52990149080927}},"time":1.582022282447579,"velocity":0.6734019150204817,"position":3.6164965209598856,"holonomicRotation":0.018212162982444213,"angularVelocity":0.0783665696495684,"angularAcceleration":-0.5418425476601862,"curveRadius":8.557677463131661},{"acceleration":-4.753062851350968,"curvature":0.11706462692106294,"pose":{"rotation":{"radians":2.889604991011169},"translation":{"x":0.7923689694568609,"y":4.531946318212248}},"time":1.5954794243149915,"velocity":0.6094392739251234,"position":3.624697831728669,"holonomicRotation":0.015176802485370122,"angularVelocity":0.07106636479587584,"angularAcceleration":-0.54247810758171,"curveRadius":8.542290069179508},{"acceleration":-4.695582219393605,"curvature":0.11724942614174404,"pose":{"rotation":{"radians":2.8905671008348186},"translation":{"x":0.7843911675096131,"y":4.533992102871096}},"time":1.6108024007771644,"velocity":0.5374889781011574,"position":3.6329337626887903,"holonomicRotation":0.012141441988296031,"angularVelocity":0.06278870335830303,"angularAcceleration":-0.5402123704886876,"curveRadius":8.528826390937638},{"acceleration":-4.600895991032509,"curvature":0.11740903012751237,"pose":{"rotation":{"radians":2.891534804511462},"translation":{"x":0.7763775840110135,"y":4.536038800488288}},"time":1.629036259720661,"velocity":0.4535968895869721,"position":3.641204584390728,"holonomicRotation":0.009106081491221829,"angularVelocity":0.053071797892156644,"angularAcceleration":-0.5329044990562533,"curveRadius":8.51723243871402},{"acceleration":-4.412153411495551,"curvature":0.11754393507203224,"pose":{"rotation":{"radians":2.8925079378445706},"translation":{"x":0.7683279362137767,"y":4.5380863667662945}},"time":1.6528756896977095,"velocity":0.3484136672856279,"position":3.6495105676150303,"holonomicRotation":0.006070720994147738,"angularVelocity":0.040820327249667936,"angularAcceleration":-0.5139162578251165,"curveRadius":8.507457227692681},{"acceleration":-3.5317773641803183,"curvature":0.11754393507203224,"pose":{"rotation":{"radians":2.8934863382766527},"translation":{"x":0.760241941370617,"y":4.540134757407588}},"time":1.7106387081663095,"velocity":0.14440754617149676,"position":3.6578519833715397,"holonomicRotation":0.003035360497073536,"angularVelocity":0.016938180483312897,"angularAcceleration":-0.41345046362730137,"curveRadius":8.507457227692681}] \ No newline at end of file diff --git a/src/main/deploy/pathplanner/generatedJSON/Blue1(1).wpilib.json b/src/main/deploy/pathplanner/generatedJSON/Blue1(1).wpilib.json new file mode 100644 index 0000000..c181baa --- /dev/null +++ b/src/main/deploy/pathplanner/generatedJSON/Blue1(1).wpilib.json @@ -0,0 +1 @@ +[{"acceleration":0.0,"curvature":0.002839585849452465,"pose":{"rotation":{"radians":2.3688620772000846},"translation":{"x":6.219218062337707,"y":5.134470725883456}},"time":0.0,"velocity":0,"position":0.0,"holonomicRotation":135.0,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":352.16403131210916},{"acceleration":2.4999999999999996,"curvature":0.002839585849452465,"pose":{"rotation":{"radians":2.3688620772000846},"translation":{"x":6.213682977366961,"y":5.139867325382476}},"time":0.055607511928353545,"velocity":0.13901877982088384,"position":0.007730488457154953,"holonomicRotation":135.0484,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":352.16403131210916},{"acceleration":8.574342094209518,"curvature":0.0032146919066287282,"pose":{"rotation":{"radians":2.3688839464898823},"translation":{"x":6.208189166762996,"y":5.145223448832123}},"time":0.07849374020868138,"velocity":0.33525313034258714,"position":0.015403168129869907,"holonomicRotation":135.0968,"angularVelocity":0.0009555654837432118,"angularAcceleration":0.041752859931253106,"curveRadius":311.0718006717812},{"acceleration":5.776640389057142,"curvature":0.0036026071524299565,"pose":{"rotation":{"radians":2.368908519772724},"translation":{"x":6.202736219349267,"y":5.150539471859252}},"time":0.0959553972437043,"velocity":0.4361228436309643,"position":0.023018595650492735,"holonomicRotation":135.1452,"angularVelocity":0.0014072709590276578,"angularAcceleration":0.025868419840021962,"curveRadius":277.57675419189144},{"acceleration":5.482218694000792,"curvature":0.004003605763415218,"pose":{"rotation":{"radians":2.3689358530620157},"translation":{"x":6.197323723949231,"y":5.155815770090722}},"time":0.11059353987066006,"velocity":0.516372342785911,"position":0.03057732765280819,"holonomicRotation":135.1936,"angularVelocity":0.0018672648564828423,"angularAcceleration":0.03142433498414736,"curveRadius":249.77484275249031},{"acceleration":5.353590253347074,"curvature":0.004417936448269042,"pose":{"rotation":{"radians":2.368966002844721},"translation":{"x":6.191951269386343,"y":5.161052719153389}},"time":0.12341786057489064,"velocity":0.5850285011138769,"position":0.03807992077220786,"holonomicRotation":135.242,"angularVelocity":0.002350984773420104,"angularAcceleration":0.03771895042968543,"curveRadius":226.35001922488098},{"acceleration":5.28077815469755,"curvature":0.004845880577030564,"pose":{"rotation":{"radians":2.368999026056138},"translation":{"x":6.186618444484056,"y":5.16625069467411}},"time":0.1349472958541544,"velocity":0.6459128910726123,"position":0.045526931645871696,"holonomicRotation":135.2904,"angularVelocity":0.002864252291419537,"angularAcceleration":0.044518010255243684,"curveRadius":206.36084280326514},{"acceleration":5.2337823641954735,"curvature":0.005287692779526828,"pose":{"rotation":{"radians":2.3690349800540655},"translation":{"x":6.181324838065827,"y":5.17141007227974}},"time":0.14549077896958598,"velocity":0.7010951870593508,"position":0.0529189169129423,"holonomicRotation":135.3388,"angularVelocity":0.0034100683364026657,"angularAcceleration":0.05176809589463521,"curveRadius":189.11840034879742},{"acceleration":5.200893225502387,"curvature":0.005743636853147396,"pose":{"rotation":{"radians":2.3690739225913386},"translation":{"x":6.176070038955114,"y":5.176531227597139}},"time":0.15525003473715768,"velocity":0.7518520342668595,"position":0.06025643321472166,"holonomicRotation":135.3872,"angularVelocity":0.00399031833989846,"angularAcceleration":0.059456378366869275,"curveRadius":174.10571482283396},{"acceleration":5.176567876607599,"curvature":0.006213968622436282,"pose":{"rotation":{"radians":2.369115911787839},"translation":{"x":6.170853635975369,"y":5.181614536253162}},"time":0.16436549174916198,"velocity":0.7990388162157985,"position":0.06754003719485958,"holonomicRotation":135.4356,"angularVelocity":0.004606373157695628,"angularAcceleration":0.06758353607349303,"curveRadius":160.92775177354125},{"acceleration":5.157836019346239,"curvature":0.006698943489830704,"pose":{"rotation":{"radians":2.369161006097118},"translation":{"x":6.16567521795005,"y":5.186660373874667}},"time":0.17293962588088937,"velocity":0.843262794075128,"position":0.07477028549955494,"holonomicRotation":135.484,"angularVelocity":0.005259342644554672,"angularAcceleration":0.07615573500801923,"curveRadius":149.27727059021242},{"acceleration":5.14296044851943,"curvature":0.007198813732042027,"pose":{"rotation":{"radians":2.3692092642764835},"translation":{"x":6.16053437370261,"y":5.19166911608851}},"time":0.18104997628031555,"velocity":0.8849740054030106,"position":0.08194773477775703,"holonomicRotation":135.5324,"angularVelocity":0.005950196599262163,"angularAcceleration":0.08518176412653766,"curveRadius":138.9117759151046},{"acceleration":5.130856539262057,"curvature":0.007713821430097895,"pose":{"rotation":{"radians":2.3692607453492713},"translation":{"x":6.155430692056507,"y":5.1966411385215485}},"time":0.1887569248333723,"velocity":0.9245172527842181,"position":0.08907294168137837,"holonomicRotation":135.5808,"angularVelocity":0.006679825670749103,"angularAcceleration":0.09467158973022496,"curveRadius":129.63743185682083},{"acceleration":5.120811796573003,"curvature":0.008244207577815677,"pose":{"rotation":{"radians":2.3693155085715234},"translation":{"x":6.150363761835197,"y":5.201576816800638}},"time":0.19610860548737363,"velocity":0.9621638258018657,"position":0.09614646286550585,"holonomicRotation":135.6292,"angularVelocity":0.007449075229112019,"angularAcceleration":0.10463587777636034,"curveRadius":121.29728546511834},{"acceleration":5.112338716327305,"curvature":0.008790207261690131,"pose":{"rotation":{"radians":2.3693736133913035},"translation":{"x":6.1453331718621325,"y":5.206476526552638}},"time":0.20314414093311395,"velocity":0.998131866051217,"position":0.10316885498863211,"holonomicRotation":135.6776,"angularVelocity":0.008258762993690856,"angularAcceleration":0.1150854502579566,"curveRadius":113.7629603295299},{"acceleration":5.105092398592753,"curvature":0.00935205032574558,"pose":{"rotation":{"radians":2.369435119409377},"translation":{"x":6.140338510960771,"y":5.211340643404403}},"time":0.20989585485460702,"velocity":1.032599989469304,"position":0.11014067471286561,"holonomicRotation":135.726,"angularVelocity":0.00910968959711317,"angularAcceleration":0.12603119938383597,"curveRadius":106.92842373260821},{"acceleration":5.098821917487819,"curvature":0.009929951129173907,"pose":{"rotation":{"radians":2.3695000863364775},"translation":{"x":6.135379367954569,"y":5.216169542982792}},"time":0.21639083040108345,"velocity":1.0657167131392256,"position":0.11706247870417612,"holonomicRotation":135.7744,"angularVelocity":0.01000264383380452,"angularAcceleration":0.1374838489077582,"curveRadius":100.70543016692491},{"acceleration":5.0933403331188245,"curvature":0.0105241250529304,"pose":{"rotation":{"radians":2.3695685739498304},"translation":{"x":6.13045533166698,"y":5.2209636009146605}},"time":0.2226520367143563,"velocity":1.0976071677885963,"position":0.1239348236326276,"holonomicRotation":135.8228,"angularVelocity":0.01093840546474275,"angularAcceleration":0.14945388861481068,"curveRadius":95.01977551298233},{"acceleration":5.088505504349559,"curvature":0.01113477567577317,"pose":{"rotation":{"radians":2.3696406420453253},"translation":{"x":6.1255659909214595,"y":5.225723192826865}},"time":0.22869916149615965,"velocity":1.1283779955262914,"position":0.13075826617261624,"holonomicRotation":135.8712,"angularVelocity":0.011917745721360574,"angularAcceleration":0.16195138879303367,"curveRadius":89.80872440706469},{"acceleration":5.084207418728069,"curvature":0.011762094007173008,"pose":{"rotation":{"radians":2.3697163503902288},"translation":{"x":6.1207109345414645,"y":5.230448694346263}},"time":0.23454923833014216,"velocity":1.1581209995657544,"position":0.13753336300312452,"holonomicRotation":135.9196,"angularVelocity":0.012941427446502018,"angularAcceleration":0.17498603081501088,"curveRadius":85.01887498859973},{"acceleration":5.08035959425425,"curvature":0.0124062633128878,"pose":{"rotation":{"radians":2.3697957586724008},"translation":{"x":6.1158897513504495,"y":5.235140481099712}},"time":0.2402171274559518,"velocity":1.1869159144652308,"position":0.14426067080797242,"holonomicRotation":135.968,"angularVelocity":0.014010203871210634,"angularAcceleration":0.18856692517885884,"curveRadius":80.60444751008839},{"acceleration":5.076893103273682,"curvature":0.013067457538522016,"pose":{"rotation":{"radians":2.3698789264475613},"translation":{"x":6.111102030171871,"y":5.239798928714068}},"time":0.24571588982080247,"velocity":1.214832543191882,"position":0.15094074627607176,"holonomicRotation":136.0164,"angularVelocity":0.015124817121051399,"angularAcceleration":0.20270256757513738,"curveRadius":76.52598044049999},{"acceleration":5.0737523303777285,"curvature":0.013745831173501795,"pose":{"rotation":{"radians":2.369965913084219},"translation":{"x":6.106347359829184,"y":5.244424412816188}},"time":0.25105708203649335,"velocity":1.241932429643239,"position":0.1575741461016963,"holonomicRotation":136.0648,"angularVelocity":0.016285996299140123,"angularAcceleration":0.2174007470986564,"curveRadius":72.74932940597486},{"acceleration":5.0708919042167775,"curvature":0.014441532804014735,"pose":{"rotation":{"radians":2.370056777707254},"translation":{"x":6.101625329145842,"y":5.249017309032931}},"time":0.25625099179105315,"velocity":1.2682701845688689,"position":0.1641614269847459,"holonomicRotation":136.1132,"angularVelocity":0.01749445549286269,"angularAcceleration":0.23266850038386708,"curveRadius":69.24472724404994},{"acceleration":5.068274440797262,"curvature":0.015154689885640145,"pose":{"rotation":{"radians":2.3701515791388825},"translation":{"x":6.0969355269453045,"y":5.2535779929911515}},"time":0.2613068277952298,"velocity":1.2938945489656999,"position":0.17070314563101457,"holonomicRotation":136.1616,"angularVelocity":0.018750891356071914,"angularAcceleration":0.24851198934682178,"curveRadius":65.98617375519851},{"acceleration":5.065868858393584,"curvature":0.015885423180822998,"pose":{"rotation":{"radians":2.370250375837056},"translation":{"x":6.092277542051025,"y":5.258106840317706}},"time":0.26623287456847006,"velocity":1.318849255909248,"position":0.17719985875247665,"holonomicRotation":136.21,"angularVelocity":0.020055980529920928,"angularAcceleration":0.2649364153297613,"curveRadius":62.95079385780591},{"acceleration":5.0636491019219125,"curvature":0.01663383220817456,"pose":{"rotation":{"radians":2.3703532258320563},"translation":{"x":6.087650963286459,"y":5.262604226639453}},"time":0.271036619715909,"velocity":1.3431737357109388,"position":0.18365212306756548,"holonomicRotation":136.2584,"angularVelocity":0.02141037707944248,"angularAcceleration":0.28194596256706916,"curveRadius":60.11843738020625},{"acceleration":5.061593165263359,"curvature":0.017399996515754853,"pose":{"rotation":{"radians":2.370460186661905},"translation":{"x":6.083055379475062,"y":5.267070527583248}},"time":0.27572485945337427,"velocity":1.3669036979232092,"position":0.19006049530145733,"holonomicRotation":136.3068,"angularVelocity":0.02281470996330984,"angularAcceleration":0.2995437440293133,"curveRadius":57.47127587609276},{"acceleration":5.059682333252767,"curvature":0.018183985618179525,"pose":{"rotation":{"radians":2.3705713153038017},"translation":{"x":6.0784903794402885,"y":5.2715061187759495}},"time":0.2803037867645507,"velocity":1.3900716155448172,"position":0.19642553218636663,"holonomicRotation":136.3552,"angularVelocity":0.024269579826134303,"angularAcceleration":0.3177315916925254,"curveRadius":54.993444286506985},{"acceleration":5.057900587964412,"curvature":0.018985844089324883,"pose":{"rotation":{"radians":2.3706866681048706},"translation":{"x":6.073955552005597,"y":5.275911375844413}},"time":0.2847790655661554,"velocity":1.4127071308267583,"position":0.20274779046183142,"holonomicRotation":136.4036,"angularVelocity":0.025775556380426824,"angularAcceleration":0.33651010832051925,"curveRadius":52.670821233714186},{"acceleration":5.056234139071775,"curvature":0.019805598548260115,"pose":{"rotation":{"radians":2.370806300710671},"translation":{"x":6.069450485994439,"y":5.280286674415497}},"time":0.28915589350730747,"velocity":1.4348373976836546,"position":0.20902782687502316,"holonomicRotation":136.452,"angularVelocity":0.027333175397546167,"angularAcceleration":0.3558785124894231,"curveRadius":50.49077398813822},{"acceleration":5.054671049098099,"curvature":0.020643253841898645,"pose":{"rotation":{"radians":2.370930267990678},"translation":{"x":6.064974770230274,"y":5.284632390116058}},"time":0.29343905546538107,"velocity":1.4564873724317275,"position":0.21526619818103732,"holonomicRotation":136.5004,"angularVelocity":0.028942935434277006,"angularAcceleration":0.3758345008870144,"curveRadius":48.44197565261475},{"acceleration":5.05320093192902,"curvature":0.021498792345560718,"pose":{"rotation":{"radians":2.371058623963882},"translation":{"x":6.060527993536554,"y":5.288948898572951}},"time":0.29763296937214706,"velocity":1.4776800620938275,"position":0.22146346114320345,"holonomicRotation":136.5488,"angularVelocity":0.03060529521048481,"angularAcceleration":0.3963743207808679,"curveRadius":46.51424061065876},{"acceleration":5.051814708384146,"curvature":0.02237217190464171,"pose":{"rotation":{"radians":2.3711914217186654},"translation":{"x":6.056109744736737,"y":5.293236575413035}},"time":0.30174172567504937,"velocity":1.4984367376179955,"position":0.22762017253339176,"holonomicRotation":136.5972,"angularVelocity":0.03232066956357579,"angularAcceleration":0.41749235696439135,"curveRadius":44.69838709725465},{"acceleration":5.0505044066260885,"curvature":0.023263330498688128,"pose":{"rotation":{"radians":2.371328713336438},"translation":{"x":6.051719612654278,"y":5.297495796263166}},"time":0.30576912148372504,"velocity":1.5187771178969394,"position":0.2337368891323224,"holonomicRotation":136.6456,"angularVelocity":0.034089427584172764,"angularAcceleration":0.43918157157207544,"curveRadius":42.98610639849665},{"acceleration":5.0492629981150765,"curvature":0.024172178659212628,"pose":{"rotation":{"radians":2.371470549807165},"translation":{"x":6.047357186112633,"y":5.301726936750201}},"time":0.30971869025286525,"velocity":1.53871952934147,"position":0.2398141677298756,"holonomicRotation":136.694,"angularVelocity":0.03591188785857029,"angularAcceleration":0.46143272365257704,"curveRadius":41.36987460246471},{"acceleration":5.048084261943264,"curvature":0.025098598979492195,"pose":{"rotation":{"radians":2.371616980948203},"translation":{"x":6.043022053935257,"y":5.305930372500998}},"time":0.3135937276958263,"velocity":1.5582810448717224,"position":0.24585256512540996,"holonomicRotation":136.7424,"angularVelocity":0.0377883164210329,"angularAcceleration":0.48423495000574185,"curveRadius":39.842861381110936},{"acceleration":5.046962671949891,"curvature":0.026042448072231772,"pose":{"rotation":{"radians":2.3717680553188583},"translation":{"x":6.038713804945605,"y":5.310106479142411}},"time":0.3173973144990825,"velocity":1.5774776054872777,"position":0.25185263812807357,"holonomicRotation":136.7908,"angularVelocity":0.03971892281408403,"angularAcceleration":0.5075752159509975,"curveRadius":38.39884780518265},{"acceleration":5.045893302303857,"curvature":0.02700355578755134,"pose":{"rotation":{"radians":2.3719238201329715},"translation":{"x":6.0344320279671315,"y":5.3142556323013}},"time":0.3211323363083361,"velocity":1.5963241270185493,"position":0.2578149435571256,"holonomicRotation":136.8392,"angularVelocity":0.041703856648806735,"angularAcceleration":0.5314383519274176,"curveRadius":37.03216005578794},{"acceleration":5.0448717481591245,"curvature":0.02798172082224877,"pose":{"rotation":{"radians":2.372084321172375},"translation":{"x":6.030176311823295,"y":5.318378207604521}},"time":0.324801501377223,"velocity":1.6148345942139093,"position":0.26374003824224546,"holonomicRotation":136.8876,"angularVelocity":0.04374320489542584,"angularAcceleration":0.5558071682061876,"curveRadius":35.73761622283366},{"acceleration":5.043894058522534,"curvature":0.028976711419574388,"pose":{"rotation":{"radians":2.3722496026974427},"translation":{"x":6.02594624533755,"y":5.32247458067893}},"time":0.32840735620497863,"velocity":1.6330221439555206,"position":0.2696284790238593,"holonomicRotation":136.936,"angularVelocity":0.0458369881658684,"angularAcceleration":0.5806621093910743,"curveRadius":34.510472410767726},{"acceleration":5.0429566793763305,"curvature":0.029988263593716685,"pose":{"rotation":{"radians":2.3724197073555935},"translation":{"x":6.02174141733335,"y":5.326545127151385}},"time":0.33195229943680343,"velocity":1.6508991391044614,"position":0.27548082275345304,"holonomicRotation":136.9844,"angularVelocity":0.047985157173660115,"angularAcceleration":0.6059812153002856,"curveRadius":33.34637888835704},{"acceleration":5.042056405133521,"curvature":0.03101608633050628,"pose":{"rotation":{"radians":2.3725946760897685},"translation":{"x":6.017561416634153,"y":5.330590222648742}},"time":0.33543859425766076,"velocity":1.668477234236149,"position":0.2812976262938889,"holonomicRotation":137.0328,"angularVelocity":0.050187589738027075,"angularAcceleration":0.6317401933968831,"curveRadius":32.24133404015054},{"acceleration":5.04119033709563,"curvature":0.0320598493050716,"pose":{"rotation":{"radians":2.3727745480469884},"translation":{"x":6.0134058320634125,"y":5.334610242797859}},"time":0.3388683794748186,"velocity":1.6857674343311986,"position":0.28707944651972417,"holonomicRotation":137.0812,"angularVelocity":0.052444087845525705,"angularAcceleration":0.6579123661185133,"curveRadius":31.1916625210652},{"acceleration":5.040355847725741,"curvature":0.033119193895084865,"pose":{"rotation":{"radians":2.372959360483079},"translation":{"x":6.009274252444586,"y":5.338605563225591}},"time":0.3422436794551633,"velocity":1.7027801473249575,"position":0.29282684031752143,"holonomicRotation":137.1296,"angularVelocity":0.05475437358665091,"angularAcceleration":0.68446827084367,"curveRadius":30.193971603530105},{"acceleration":5.03955054991882,"curvature":0.03419372452478213,"pose":{"rotation":{"radians":2.3731491486688845},"translation":{"x":6.005166266601129,"y":5.342576559558798}},"time":0.34556641305900404,"velocity":1.7195252312854268,"position":0.2985403645861655,"holonomicRotation":137.178,"angularVelocity":0.05711808662178317,"angularAcceleration":0.7113760285808239,"curveRadius":29.245132371445624},{"acceleration":5.038772270300912,"curvature":0.035283006103012916,"pose":{"rotation":{"radians":2.3733439457973406},"translation":{"x":6.001081463356495,"y":5.3465236074243325}},"time":0.34883840169176844,"velocity":1.7360120368769398,"position":0.304220576237169,"holonomicRotation":137.2264,"angularVelocity":0.05953478154096794,"angularAcceleration":0.7386012576525909,"curveRadius":28.34225624314384},{"acceleration":5.038019026100881,"curvature":0.0363865765668125,"pose":{"rotation":{"radians":2.373543782883858},"translation":{"x":5.997019431534142,"y":5.3504470824490555}},"time":0.3520613765779948,"velocity":1.7522494456743936,"position":0.30986803219498166,"holonomicRotation":137.2748,"angularVelocity":0.062003922950592504,"angularAcceleration":0.7661063138210097,"curveRadius":27.482662408864286},{"acceleration":5.03728900501368,"curvature":0.037503932041584934,"pose":{"rotation":{"radians":2.373748688676576},"translation":{"x":5.992979759957522,"y":5.354347360259823}},"time":0.3552369853476933,"velocity":1.768245904814221,"position":0.3154832893972932,"holonomicRotation":137.3232,"angularVelocity":0.0645248856450633,"angularAcceleration":0.7938517863175326,"curveRadius":26.663870841360975},{"acceleration":5.0365805474943794,"curvature":0.03863453081408878,"pose":{"rotation":{"radians":2.3739586895558036},"translation":{"x":5.9889620374500945,"y":5.3582248164834905}},"time":0.3583667980130559,"velocity":1.7840094584018875,"position":0.321066904795326,"holonomicRotation":137.3716,"angularVelocity":0.06709694850157266,"angularAcceleration":0.8217945070560381,"curveRadius":25.883580800089124},{"acceleration":5.035892131396777,"curvature":0.03977779594005106,"pose":{"rotation":{"radians":2.3741738094429268},"translation":{"x":5.9849658528353125,"y":5.362079826746916}},"time":0.3614523124032477,"velocity":1.799547776040766,"position":0.3266194353541375,"holonomicRotation":137.42,"angularVelocity":0.06971929471695626,"angularAcceleration":0.849889478305288,"curveRadius":25.13965332586792},{"acceleration":5.035222358385329,"curvature":0.04093311053305368,"pose":{"rotation":{"radians":2.3743940697025794},"translation":{"x":5.980990794936632,"y":5.365912766676956}},"time":0.3644949591162553,"velocity":1.8148681787987695,"position":0.33214143805290164,"holonomicRotation":137.4684,"angularVelocity":0.07239100705020175,"angularAcceleration":0.8780882518577299,"curveRadius":24.430100399833904},{"acceleration":5.034569941916143,"curvature":0.04209982240402563,"pose":{"rotation":{"radians":2.374619489050876},"translation":{"x":5.97703645257751,"y":5.369724011900467}},"time":0.3674961060393382,"velocity":1.8299776628889968,"position":0.3376334698851914,"holonomicRotation":137.5168,"angularVelocity":0.07511106722655615,"angularAcceleration":0.9063402246099452,"curveRadius":23.75306932184063},{"acceleration":5.033933696722898,"curvature":0.0432772394421339,"pose":{"rotation":{"radians":2.3748500834601147},"translation":{"x":5.9731024145814,"y":5.373513938044307}},"time":0.3704570624832291,"velocity":1.8448829213064282,"position":0.343096087859258,"holonomicRotation":137.5652,"angularVelocity":0.07787835235288822,"angularAcceleration":0.9345916357674028,"curveRadius":23.1068342826511},{"acceleration":5.033312529443079,"curvature":0.044464632172341645,"pose":{"rotation":{"radians":2.375085866068722},"translation":{"x":5.9691882697717595,"y":5.3772829207353325}},"time":0.37337908296973077,"velocity":1.8595903636324262,"position":0.348529848998293,"holonomicRotation":137.6136,"angularVelocity":0.08069163433194342,"angularAcceleration":0.9627865348827075,"curveRadius":22.489784602829356},{"acceleration":5.032705430252399,"curvature":0.045661229356574594,"pose":{"rotation":{"radians":2.375326847089056},"translation":{"x":5.965293606972042,"y":5.381031335600399}},"time":0.37626337070764154,"velocity":1.8741061341934202,"position":0.3539353103406904,"holonomicRotation":137.662,"angularVelocity":0.08354957696025526,"angularAcceleration":0.9908659911933727,"curveRadius":21.900417796263596},{"acceleration":5.032111465607936,"curvature":0.04686622635834266,"pose":{"rotation":{"radians":2.37557303371773},"translation":{"x":5.961418015005705,"y":5.384759558266366}},"time":0.3791110807878335,"velocity":1.8884361287386815,"position":0.35931302894029826,"holonomicRotation":137.7104,"angularVelocity":0.08645073471013001,"angularAcceleration":1.0187686485553953,"curveRadius":21.337327062646896},{"acceleration":5.03152977146136,"curvature":0.04807877685476044,"pose":{"rotation":{"radians":2.375824430050593},"translation":{"x":5.957561082696203,"y":5.388467964360089}},"time":0.38192332312476346,"velocity":1.9025860097815086,"position":0.36466356186665644,"holonomicRotation":137.7588,"angularVelocity":0.08939355245516183,"angularAcceleration":1.0464310654836422,"curveRadius":20.79919801247994},{"acceleration":5.03095954749574,"curvature":0.049297998240826486,"pose":{"rotation":{"radians":2.376081036994776},"translation":{"x":5.95372239886699,"y":5.392156929508425}},"time":0.38470116516861813,"velocity":1.9165612207334743,"position":0.3699874662052313,"holonomicRotation":137.8072,"angularVelocity":0.09237636270586644,"angularAcceleration":1.0737868473491443,"curveRadius":20.284799295802703},{"acceleration":5.030400051833257,"curvature":0.05052297115000814,"pose":{"rotation":{"radians":2.3763428521871246},"translation":{"x":5.949901552341525,"y":5.39582682933823}},"time":0.38744563440959306,"velocity":1.9303669989455294,"position":0.3752852990576304,"holonomicRotation":137.8556,"angularVelocity":0.09539738629236595,"angularAcceleration":1.100767879412027,"curveRadius":19.792976882355006},{"acceleration":5.029850596278637,"curvature":0.05175273811803925,"pose":{"rotation":{"radians":2.376609869914627},"translation":{"x":5.94609813194326,"y":5.399478039476361}},"time":0.39015772069347554,"velocity":1.9440083877576748,"position":0.3805576175418205,"holonomicRotation":137.904,"angularVelocity":0.09845473172791028,"angularAcceleration":1.1273038965292785,"curveRadius":19.322649126683288},{"acceleration":5.029310542019387,"curvature":0.05298630875170644,"pose":{"rotation":{"radians":2.376882081034795},"translation":{"x":5.942311726495653,"y":5.403110935549678}},"time":0.39283837836561447,"velocity":1.9574902476477083,"position":0.38580497879231446,"holonomicRotation":137.9524,"angularVelocity":0.10154639400511055,"angularAcceleration":1.153322301960845,"curveRadius":18.87279985261843},{"acceleration":5.028779295888006,"curvature":0.05422265380290382,"pose":{"rotation":{"radians":2.3771594729050602},"translation":{"x":5.938541924822158,"y":5.406725893185034}},"time":0.3954885282585877,"velocity":1.970817266560492,"position":0.39102793996035956,"holonomicRotation":138.0008,"angularVelocity":0.1046702569544091,"angularAcceleration":1.1787495332174742,"curveRadius":18.44247615830353},{"acceleration":5.028256306784514,"curvature":0.05546071126943101,"pose":{"rotation":{"radians":2.3774420293084493},"translation":{"x":5.934788315746232,"y":5.4103232880092875}},"time":0.39810905953726095,"velocity":1.9839939694896067,"position":0.39622705821410614,"holonomicRotation":138.0492,"angularVelocity":0.1078240911255565,"angularAcceleration":1.2035094550537808,"curveRadius":18.03078209981744},{"acceleration":5.027741062645303,"curvature":0.056699389559075455,"pose":{"rotation":{"radians":2.377729730388932},"translation":{"x":5.93105048809133,"y":5.413903495649295}},"time":0.40070083141354484,"velocity":1.9970247273770085,"position":0.4014028907387654,"holonomicRotation":138.0976,"angularVelocity":0.11100555689924878,"angularAcceleration":1.2275253863213762,"curveRadius":17.636874184652264},{"acceleration":5.027233087548275,"curvature":0.057937559985413944,"pose":{"rotation":{"radians":2.3780225525880807},"translation":{"x":5.927328030680907,"y":5.417466891731915}},"time":0.40326467474191174,"velocity":2.0099137653886645,"position":0.4065559947367499,"holonomicRotation":138.14600000000002,"angularVelocity":0.11421220474312034,"angularAcceleration":1.2507191092343826,"curveRadius":17.259960554979443},{"acceleration":5.02673193912806,"curvature":0.05917406718174179,"pose":{"rotation":{"radians":2.3783204685863812},"translation":{"x":5.923620532338418,"y":5.421013851884003}},"time":0.40580139350563915,"velocity":2.0226651706188785,"position":0.4116869274277967,"holonomicRotation":138.1944,"angularVelocity":0.11744147698217164,"angularAcceleration":1.2730115317577675,"curveRadius":16.899294701658615},{"acceleration":5.026237206348917,"curvature":0.06040772693729276,"pose":{"rotation":{"radians":2.37862344724871},"translation":{"x":5.919927581887321,"y":5.424544751732416}},"time":0.4083117662027775,"velocity":2.0352828992710377,"position":0.4167962460490793,"holonomicRotation":138.2428,"angularVelocity":0.12069070966010574,"angularAcceleration":1.2943228237137965,"curveRadius":16.554173624809067},{"acceleration":5.025748507204254,"curvature":0.061637325936966726,"pose":{"rotation":{"radians":2.3789314535766524},"translation":{"x":5.9162487681510685,"y":5.42805996690401}},"time":0.4107965471399681,"velocity":2.047770783356853,"position":0.4218845078553003,"holonomicRotation":138.2912,"angularVelocity":0.1239571357507224,"angularAcceleration":1.3145730642596556,"curveRadius":16.223935493610604},{"acceleration":5.025265486914145,"curvature":0.06286162841581681,"pose":{"rotation":{"radians":2.379244448662102},"translation":{"x":5.9125836799531175,"y":5.431559873025645}},"time":0.41325646764147145,"velocity":2.0601325369536103,"position":0.4269522701187666,"holonomicRotation":138.3396,"angularVelocity":0.1272378864513724,"angularAcceleration":1.3336815960698845,"curveRadius":15.907955698907521},{"acceleration":5.024787816034711,"curvature":0.06407937327743048,"pose":{"rotation":{"radians":2.379562389651271},"translation":{"x":5.908931906116924,"y":5.435044845724174}},"time":0.41569223718007753,"velocity":2.0723717620538666,"position":0.4320000901294448,"holonomicRotation":138.388,"angularVelocity":0.13052999642613985,"angularAcceleration":1.3515687435074117,"curveRadius":15.605645761710532},{"acceleration":5.024315188980028,"curvature":0.06528927983399117,"pose":{"rotation":{"radians":2.3798852297089623},"translation":{"x":5.9052930354659425,"y":5.438515260626457}},"time":0.4181045444359606,"velocity":2.084491954040087,"position":0.4370285251950056,"holonomicRotation":138.4364,"angularVelocity":0.1338304052702174,"angularAcceleration":1.3681544239559669,"curveRadius":15.316450151428626},{"acceleration":5.023847322372787,"curvature":0.066490046706823,"pose":{"rotation":{"radians":2.3802129179941005},"translation":{"x":5.90166665682363,"y":5.441971493359348}},"time":0.42049405828897823,"velocity":2.096496506812342,"position":0.44203813264083675,"holonomicRotation":138.4848,"angularVelocity":0.13713596375445178,"angularAcceleration":1.3833602513163696,"curveRadius":15.039845052438249},{"acceleration":5.023383953761776,"curvature":0.06768035832388108,"pose":{"rotation":{"radians":2.3805453996352175},"translation":{"x":5.898052359013439,"y":5.445413919549707}},"time":0.42286142874944493,"velocity":2.10838871759606,"position":0.4470294698100549,"holonomicRotation":138.5332,"angularVelocity":0.14044343573140786,"angularAcceleration":1.3971079018634234,"curveRadius":14.775335485290258},{"acceleration":5.022924840356172,"curvature":0.06885888383113357,"pose":{"rotation":{"radians":2.380882615718681},"translation":{"x":5.894449730858829,"y":5.448842914824389}},"time":0.42520728783193346,"velocity":2.120171791453467,"position":0.452003094063472,"holonomicRotation":138.5816,"angularVelocity":0.1437495056633473,"angularAcceleration":1.4093216240560833,"curveRadius":14.522454393137636},{"acceleration":5.022469757807395,"curvature":0.07002428023146193,"pose":{"rotation":{"radians":2.381224503278643},"translation":{"x":5.890858361183253,"y":5.4522588548102515}},"time":0.4275322503763058,"velocity":2.131848845520612,"position":0.4569595627795709,"holonomicRotation":138.63,"angularVelocity":0.1470507818672887,"angularAcceleration":1.419926618573808,"curveRadius":14.280760854585688},{"acceleration":5.022018499236972,"curvature":0.07117519549197542,"pose":{"rotation":{"radians":2.3815709952954514},"translation":{"x":5.887277838810167,"y":5.4556621151341504}},"time":0.42983691481976416,"velocity":2.1434229129901934,"position":0.4618994333544333,"holonomicRotation":138.6784,"angularVelocity":0.15034380288707125,"angularAcceleration":1.4288505335905197,"curveRadius":14.049838473752335},{"acceleration":5.0215708741145315,"curvature":0.07231027485554233,"pose":{"rotation":{"radians":2.3819220207009115},"translation":{"x":5.883707752563027,"y":5.459053071422944}},"time":0.4321218639234392,"velocity":2.154896946858042,"position":0.46682326320166867,"holonomicRotation":138.7268,"angularVelocity":0.153625043505604,"angularAcceleration":1.4360235040926237,"curveRadius":13.82929330579572},{"acceleration":5.021126707397046,"curvature":0.07342815657713007,"pose":{"rotation":{"radians":2.3822775043908915},"translation":{"x":5.880147691265288,"y":5.462432099303489}},"time":0.43438766545670077,"velocity":2.166273823450363,"position":0.4717316097523069,"holonomicRotation":138.7752,"angularVelocity":0.15689092127510526,"angularAcceleration":1.4413785680514255,"curveRadius":13.618753985054555},{"acceleration":5.020685838725166,"curvature":0.07452748147248599,"pose":{"rotation":{"radians":2.3826373672436887},"translation":{"x":5.876597243740405,"y":5.4657995744026415}},"time":0.43663487284213753,"velocity":2.177556345747104,"position":0.47662503045467447,"holonomicRotation":138.8236,"angularVelocity":0.1601378026475591,"angularAcceleration":1.4448516828022036,"curveRadius":13.417869224108687},{"acceleration":5.02024812149646,"curvature":0.07560689269699593,"pose":{"rotation":{"radians":2.3830015261473374},"translation":{"x":5.873055998811836,"y":5.469155872347259}},"time":0.4388640257639034,"velocity":2.188747246515127,"position":0.4815040827742506,"holonomicRotation":138.872,"angularVelocity":0.1633620107858025,"angularAcceleration":1.446382662562832,"curveRadius":13.226307342210518},{"acceleration":5.019813422160548,"curvature":0.07666503798913409,"pose":{"rotation":{"radians":2.3833698940335273},"translation":{"x":5.869523545303034,"y":5.472501368764199}},"time":0.4410756507419117,"velocity":2.199849191264519,"position":0.4863693241935026,"holonomicRotation":138.9204,"angularVelocity":0.16655983263564675,"angularAcceleration":1.4459150541535557,"curveRadius":13.043755357451623},{"acceleration":5.019381619668235,"curvature":0.07770057663134608,"pose":{"rotation":{"radians":2.383742379918488},"translation":{"x":5.865999472037455,"y":5.475836439280317}},"time":0.44327026167415795,"velocity":2.2108647810401587,"position":0.4912213122116916,"holonomicRotation":138.9688,"angularVelocity":0.169727526409201,"angularAcceleration":1.4433965159883695,"curveRadius":12.86991735910205},{"acceleration":5.018952604540557,"curvature":0.078712180802737,"pose":{"rotation":{"radians":2.384118888951799},"translation":{"x":5.862483367838554,"y":5.479161459522471}},"time":0.4454483603492843,"velocity":2.2217965550586305,"position":0.4960606043446651,"holonomicRotation":139.0172,"angularVelocity":0.17286132975078597,"angularAcceleration":1.4387793250015029,"curveRadius":12.704513962154481},{"acceleration":5.018526278400915,"curvature":0.07969853619287753,"pose":{"rotation":{"radians":2.384499322473461},"translation":{"x":5.858974821529789,"y":5.482476805117517}},"time":0.447610436931321,"velocity":2.232646993201497,"position":0.5008877581246207,"holonomicRotation":139.0656,"angularVelocity":0.17595746830763,"angularAcceleration":1.432020763079276,"curveRadius":12.547281892102902},{"acceleration":5.018102553543666,"curvature":0.08065834808001092,"pose":{"rotation":{"radians":2.3848835780771327},"translation":{"x":5.855473421934613,"y":5.485782851692313}},"time":0.4497569704184052,"velocity":2.243418518374301,"position":0.5057033310998559,"holonomicRotation":139.114,"angularVelocity":0.17901216355747288,"angularAcceleration":1.4230829699248493,"curveRadius":12.397972730708876},{"acceleration":5.01768135204393,"curvature":0.0815903465278173,"pose":{"rotation":{"radians":2.3852715496821553},"translation":{"x":5.851978757876483,"y":5.489079974873715}},"time":0.45188842907712745,"velocity":2.2541134987388243,"position":0.5105078808344855,"holonomicRotation":139.1624,"angularVelocity":0.18202164205011997,"angularAcceleration":1.4119337855002847,"curveRadius":12.256351916081902},{"acceleration":5.0172626055158345,"curvature":0.0824932846080554,"pose":{"rotation":{"radians":2.385663127612326},"translation":{"x":5.848490418178854,"y":5.49236855028858}},"time":0.45400527085404796,"velocity":2.2647342498279612,"position":0.5153019649081441,"holonomicRotation":139.2108,"angularVelocity":0.18498214389008896,"angularAcceleration":1.39854658588409,"curveRadius":12.1221988523215},{"acceleration":5.016846254455657,"curvature":0.08336594587974427,"pose":{"rotation":{"radians":2.3860581986814364},"translation":{"x":5.845007991665181,"y":5.495648953563765}},"time":0.45610794376580144,"velocity":2.275283036549637,"position":0.5200861409156692,"holonomicRotation":139.2592,"angularVelocity":0.18788993138302085,"angularAcceleration":1.3829005342095737,"curveRadius":11.995305630460958},{"acceleration":5.016432247911544,"curvature":0.08420714640596468,"pose":{"rotation":{"radians":2.386456646287785},"translation":{"x":5.841531067158921,"y":5.498921560326128}},"time":0.45819688626910327,"velocity":2.2857620750872334,"position":0.5248609664667543,"holonomicRotation":139.3076,"angularVelocity":0.19074129887192018,"angularAcceleration":1.3649813168109697,"curveRadius":11.875476639226983},{"acceleration":5.0160205429718205,"curvature":0.08501573676734678,"pose":{"rotation":{"radians":2.3868583505159253},"translation":{"x":5.838059233483528,"y":5.502186746202525}},"time":0.46027252761188764,"velocity":2.2961735347024814,"position":0.5296269991855901,"holonomicRotation":139.356,"angularVelocity":0.19353258188694378,"angularAcceleration":1.3447809876822103,"curveRadius":11.762528186241449},{"acceleration":5.015611104175818,"curvature":0.08579060632436987,"pose":{"rotation":{"radians":2.3872631882425375},"translation":{"x":5.834592079462457,"y":5.505444886819812}},"time":0.46233528816670677,"velocity":2.306519539446488,"position":0.5343847967104799,"holonomicRotation":139.4044,"angularVelocity":0.19626016488745965,"angularAcceleration":1.3222974397796898,"curveRadius":11.656287825021908},{"acceleration":5.01520390343199,"curvature":0.08653068816016746,"pose":{"rotation":{"radians":2.387671033252058},"translation":{"x":5.831129193919166,"y":5.508696357804847}},"time":0.4643855797474479,"velocity":2.3168021697853947,"position":0.5391349166934336,"holonomicRotation":139.4528,"angularVelocity":0.19892049177376203,"angularAcceleration":1.2975358779655988,"curveRadius":11.556593634723091},{"acceleration":5.014798919336775,"curvature":0.08723495572087112,"pose":{"rotation":{"radians":2.388081756359614},"translation":{"x":5.827670165677108,"y":5.511941534784486}},"time":0.46642380591035515,"velocity":2.327023464144506,"position":0.5438779167997521,"holonomicRotation":139.5012,"angularVelocity":0.2015100752951928,"angularAcceleration":1.2705084296126632,"curveRadius":11.463294636151781},{"acceleration":5.014396136990245,"curvature":0.08790243220645391,"pose":{"rotation":{"radians":2.3884952255366314},"translation":{"x":5.8242145835597405,"y":5.515180793385588}},"time":0.4684503622402599,"velocity":2.3371854203765734,"position":0.5486143547075772,"holonomicRotation":139.5496,"angularVelocity":0.2040255042092375,"angularAcceleration":1.2412331584007688,"curveRadius":11.3762494950234},{"acceleration":5.013995547418445,"curvature":0.08853219383625337,"pose":{"rotation":{"radians":2.388911306047802},"translation":{"x":5.820762036390518,"y":5.518414509235008}},"time":0.4704656366228822,"velocity":2.3472899971578682,"position":0.5533447881074351,"holonomicRotation":139.598,"angularVelocity":0.20646345468311617,"angularAcceleration":1.2097362497638264,"curveRadius":11.295326103062255},{"acceleration":5.013597147550916,"curvature":0.08912336566800455,"pose":{"rotation":{"radians":2.3893298605885533},"translation":{"x":5.817312112992897,"y":5.5216430579596025}},"time":0.472470009503993,"velocity":2.3573391153172336,"position":0.5580697747017587,"holonomicRotation":139.6464,"angularVelocity":0.20882069633640016,"angularAcceleration":1.1760494643978967,"curveRadius":11.220402107850397},{"acceleration":5.013200939465858,"curvature":0.08967512929341548,"pose":{"rotation":{"radians":2.389750749432834},"translation":{"x":5.813864402190332,"y":5.52486681518623}},"time":0.47446385413617764,"velocity":2.3673346591004507,"position":0.5627898722043908,"holonomicRotation":139.69480000000001,"angularVelocity":0.21109410306424833,"angularAcceleration":1.1402125778261865,"curveRadius":11.151363905236392},{"acceleration":5.012806930473599,"curvature":0.09018672597103845,"pose":{"rotation":{"radians":2.3901738305839917},"translation":{"x":5.810418492806279,"y":5.528086156541748}},"time":0.4764475368138965,"velocity":2.3772784773751803,"position":0.5675056383400738,"holonomicRotation":139.7432,"angularVelocity":0.21328066021344566,"angularAcceleration":1.102271635356394,"curveRadius":11.08810625103664},{"acceleration":5.0124151325621416,"curvature":0.09065745456807697,"pose":{"rotation":{"radians":2.3905989599311375},"translation":{"x":5.806973973664193,"y":5.53130145765301}},"time":0.47842141709748603,"velocity":2.3871723847785105,"position":0.5722176308439175,"holonomicRotation":139.7916,"angularVelocity":0.2153774728286348,"angularAcceleration":1.062279527599337,"curveRadius":11.030532511246218},{"acceleration":5.012025561938506,"curvature":0.09108667609717518,"pose":{"rotation":{"radians":2.391025991409264},"translation":{"x":5.80353043358753,"y":5.534513094146875}},"time":0.4803858480267146,"velocity":2.3970181628104665,"position":0.576926407460865,"holonomicRotation":139.84,"angularVelocity":0.2173817728955252,"angularAcceleration":1.0202955151380848,"curveRadius":10.978554085486191},{"acceleration":5.011638239373333,"curvature":0.09147381815375309,"pose":{"rotation":{"radians":2.39145477716533},"translation":{"x":5.8000874613997455,"y":5.537721441650202}},"time":0.4823411763244484,"velocity":2.406817560877918,"position":0.5816325259451323,"holonomicRotation":139.8884,"angularVelocity":0.2192909275454241,"angularAcceleration":0.976385731292055,"curveRadius":10.932089861157401},{"acceleration":5.011253188985213,"curvature":0.09181836836226387,"pose":{"rotation":{"radians":2.3918851677293644},"translation":{"x":5.796644645924294,"y":5.540926875789844}},"time":0.4842877425909668,"velocity":2.4165722972885795,"position":0.5863365440596371,"holonomicRotation":139.9368,"angularVelocity":0.22110244661970307,"angularAcceleration":0.9306228641879418,"curveRadius":10.891066981876218},{"acceleration":5.0108704387143055,"curvature":0.09211988673335003,"pose":{"rotation":{"radians":2.3923170121821045},"translation":{"x":5.793201575984633,"y":5.544129772192661}},"time":0.48622588148942586,"velocity":2.4262840602009903,"position":0.5910390195754238,"holonomicRotation":139.9852,"angularVelocity":0.22281398566602684,"angularAcceleration":0.883083791200176,"curveRadius":10.855419339524344},{"acceleration":5.010490019815686,"curvature":0.09237799828455273,"pose":{"rotation":{"radians":2.3927501583370985},"translation":{"x":5.789757840404217,"y":5.547330506485507}},"time":0.4881559219229311,"velocity":2.435954508530909,"position":0.5957405102710679,"holonomicRotation":140.0336,"angularVelocity":0.224423357912431,"angularAcceleration":0.8338541610142863,"curveRadius":10.825088425489493},{"acceleration":5.010111966394331,"curvature":0.09259239727119624,"pose":{"rotation":{"radians":2.3931844529143924},"translation":{"x":5.786313028006502,"y":5.550529454295242}},"time":0.49007818720366497,"velocity":2.445585272816498,"position":0.6004415739320771,"holonomicRotation":140.082,"angularVelocity":0.22592853423859213,"angularAcceleration":0.7830221672559653,"curveRadius":10.800022782335729},{"acceleration":5.009736315450571,"curvature":0.09276284843776193,"pose":{"rotation":{"radians":2.3936197417245895},"translation":{"x":5.782866727614942,"y":5.553726991248721}},"time":0.4919929952144755,"velocity":2.4551779560453713,"position":0.6051427683502781,"holonomicRotation":140.1304,"angularVelocity":0.22732765255812934,"angularAcceleration":0.7306833435196364,"curveRadius":10.7801778065379},{"acceleration":5.0093631064062745,"curvature":0.0928891867734586,"pose":{"rotation":{"radians":2.3940558698484478},"translation":{"x":5.779418528052995,"y":5.556923492972801}},"time":0.49390065856331866,"velocity":2.4647341344445097,"position":0.6098446513232006,"holonomicRotation":140.1788,"angularVelocity":0.22861901924297257,"angularAcceleration":0.676936360719159,"curveRadius":10.765515715395754},{"acceleration":5.0089923810004064,"curvature":0.09297131865926922,"pose":{"rotation":{"radians":2.394492681824146},"translation":{"x":5.7759680181441135,"y":5.56011933509434}},"time":0.4958014847309167,"velocity":2.4742553582356144,"position":0.6145477806534545,"holonomicRotation":140.2272,"angularVelocity":0.22980111655886773,"angularAcceleration":0.6218860704074409,"curveRadius":10.756005340366334},{"acceleration":5.008624182996924,"curvature":0.09300921937537887,"pose":{"rotation":{"radians":2.394930021829354},"translation":{"x":5.772514786711755,"y":5.563314893240194}},"time":0.4976957762119709,"velocity":2.4837431523572677,"position":0.6192527141480917,"holonomicRotation":140.2756,"angularVelocity":0.23087260307183075,"angularAcceleration":0.5656397252901614,"curveRadius":10.751622330729045},{"acceleration":5.008258557872124,"curvature":0.09300293773064691,"pose":{"rotation":{"radians":2.395367733867662},"translation":{"x":5.769058422579376,"y":5.566510543037219}},"time":0.49958383065026357,"velocity":2.4931990171555753,"position":0.6239600096179791,"holonomicRotation":140.324,"angularVelocity":0.23183231872484134,"angularAcceleration":0.5083093122454937,"curveRadius":10.752348521464755},{"acceleration":5.007895552900506,"curvature":0.09295259132137434,"pose":{"rotation":{"radians":2.3958056619534025},"translation":{"x":5.76559851457043,"y":5.569706660112274}},"time":0.5014659409679426,"velocity":2.5026244290455484,"position":0.6286702248771614,"holonomicRotation":140.3724,"angularVelocity":0.23267928645146632,"angularAcceleration":0.4500096081878132,"curveRadius":10.758172373512423},{"acceleration":5.007535216419589,"curvature":0.09285836819692005,"pose":{"rotation":{"radians":2.3962436502967916},"translation":{"x":5.762134651508373,"y":5.572903620092215}},"time":0.5033423954892773,"velocity":2.5120208411431415,"position":0.6333839177422114,"holonomicRotation":140.4208,"angularVelocity":0.2334127144619641,"angularAcceleration":0.39085839926251487,"curveRadius":10.769088660693999},{"acceleration":5.007177597982453,"curvature":0.0927205241905576,"pose":{"rotation":{"radians":2.3966815434870714},"translation":{"x":5.7586664222166615,"y":5.576101798603899}},"time":0.5052134780591655,"velocity":2.521389683871061,"position":0.6381016460315985,"holonomicRotation":140.4692,"angularVelocity":0.23403199694491297,"angularAcceleration":0.33097549670716664,"curveRadius":10.785098647035445},{"acceleration":5.006822748492447,"curvature":0.0925393866192785,"pose":{"rotation":{"radians":2.3971191866753117},"translation":{"x":5.755193415518749,"y":5.579301571274182}},"time":0.5070794681566357,"velocity":2.530732365539537,"position":0.6428239675650427,"holonomicRotation":140.51760000000002,"angularVelocity":0.23453671529852507,"angularAcceleration":0.2704828682083342,"curveRadius":10.806209512865655},{"acceleration":5.006470718865336,"curvature":0.09231534583946485,"pose":{"rotation":{"radians":2.3975564257535718},"translation":{"x":5.7517152202380935,"y":5.582503313729922}},"time":0.5089406410035948,"velocity":2.5400502729005847,"position":0.6475514401628762,"holonomicRotation":140.566,"angularVelocity":0.23492663724086227,"angularAcceleration":0.20950334783482288,"curveRadius":10.832435180809338},{"acceleration":5.006121561254551,"curvature":0.09204886170917273,"pose":{"rotation":{"radians":2.397993107535179},"translation":{"x":5.748231425198149,"y":5.5857074015979755}},"time":0.5107972676690442,"velocity":2.549344771681691,"position":0.6522846216454045,"holonomicRotation":140.6144,"angularVelocity":0.2352017181125511,"angularAcceleration":0.14816165080892055,"curveRadius":10.863795395531213},{"acceleration":5.005775327646432,"curvature":0.09174045579242175,"pose":{"rotation":{"radians":2.398429079928093},"translation":{"x":5.744741619222372,"y":5.5889142105052}},"time":0.5126496151689856,"velocity":2.558617207095125,"position":0.657024069832274,"holonomicRotation":140.6628,"angularVelocity":0.2353620975156973,"angularAcceleration":0.08658170410858536,"curveRadius":10.900316456489692},{"acceleration":5.005432070675019,"curvature":0.09139071064754795,"pose":{"rotation":{"radians":2.398864192108789},"translation":{"x":5.741245391134217,"y":5.592124116078451}},"time":0.5144979465622156,"velocity":2.567868904328034,"position":0.6617703425418427,"holonomicRotation":140.7112,"angularVelocity":0.23540809959161557,"angularAcceleration":0.024888435097058247,"curveRadius":10.94203112017086},{"acceleration":5.005091842707672,"curvature":0.09100027403491084,"pose":{"rotation":{"radians":2.3992982946887365},"translation":{"x":5.737742329757141,"y":5.595337493944586}},"time":0.5163425210422057,"velocity":2.577101169011099,"position":0.6665239975905533,"holonomicRotation":140.7596,"angularVelocity":0.23534022868504756,"angularAcceleration":-0.03679488538103236,"curveRadius":10.988977897103535},{"acceleration":5.004754695956406,"curvature":0.09056984680145758,"pose":{"rotation":{"radians":2.3997312398825894},"translation":{"x":5.734232023914597,"y":5.598554719730462}},"time":0.5181835940252526,"velocity":2.5863152876686017,"position":0.6712855927923211,"holonomicRotation":140.808,"angularVelocity":0.2351591695927449,"angularAcceleration":-0.09834433179449603,"curveRadius":11.041202291002513},{"acceleration":5.004420682626583,"curvature":0.09010018916580406,"pose":{"rotation":{"radians":2.4001628816646696},"translation":{"x":5.730714062430042,"y":5.601776169062937}},"time":0.5200214172350676,"velocity":2.595512528150811,"position":0.6760556859579222,"holonomicRotation":140.8564,"angularVelocity":0.2348657802203272,"angularAcceleration":-0.1596396056219426,"curveRadius":11.098755832352152},{"acceleration":5.004089854041364,"curvature":0.0895921128159022,"pose":{"rotation":{"radians":2.400593075928681},"translation":{"x":5.727188034126932,"y":5.605002217568868}},"time":0.5218562387839736,"velocity":2.604694140047668,"position":0.6808348348943909,"holonomicRotation":140.9048,"angularVelocity":0.23446109201614093,"angularAcceleration":-0.2205599800305125,"curveRadius":11.16169681202679},{"acceleration":5.003762261110144,"curvature":0.08904648360868787,"pose":{"rotation":{"radians":2.4010216806363607},"translation":{"x":5.723653527828723,"y":5.6082332408751085}},"time":0.5236883032508663,"velocity":2.613861355087027,"position":0.68562359740443,"holonomicRotation":140.9532,"angularVelocity":0.23394630234094763,"angularAcceleration":-0.2809888431854164,"curveRadius":11.23008971802267},{"acceleration":5.003437954361561,"curvature":0.08846421081398403,"pose":{"rotation":{"radians":2.4014485559628627},"translation":{"x":5.720110132358869,"y":5.611469614608519}},"time":0.5255178517560875,"velocity":2.6230153875173956,"position":0.6904225312858344,"holonomicRotation":141.0016,"angularVelocity":0.23332277077310795,"angularAcceleration":-0.34081171724076303,"curveRadius":11.304006341080978},{"acceleration":5.003116982696951,"curvature":0.08784625474020967,"pose":{"rotation":{"radians":2.4018735644391747},"translation":{"x":5.716557436540826,"y":5.614711714395955}},"time":0.5273451220333474,"velocity":2.632157434473532,"position":0.6952321943309167,"holonomicRotation":141.05,"angularVelocity":0.2325920153144027,"angularAcceleration":-0.39991645888370686,"curveRadius":11.383524578905835},{"acceleration":5.00279939482274,"curvature":0.087193613839158,"pose":{"rotation":{"radians":2.402296571083312},"translation":{"x":5.71299502919805,"y":5.617959915864273}},"time":0.5291703484988374,"velocity":2.6412886763305,"position":0.7000531443259541,"holonomicRotation":141.0984,"angularVelocity":0.23175570381823493,"angularAcceleration":-0.45819601675744215,"curveRadius":11.468729829740209},{"acceleration":5.002485237620269,"curvature":0.08650733090706414,"pose":{"rotation":{"radians":2.402717443531344},"translation":{"x":5.709422499153996,"y":5.621214594640332}},"time":0.5309937623176537,"velocity":2.6504102770412015,"position":0.7048859390506439,"holonomicRotation":141.1468,"angularVelocity":0.23081565121916994,"angularAcceleration":-0.5155453958746552,"curveRadius":11.559713951576104},{"acceleration":5.002174557433125,"curvature":0.08578848088929292,"pose":{"rotation":{"radians":2.403136052158281},"translation":{"x":5.70583943523212,"y":5.624476126350985}},"time":0.5328155914676568,"velocity":2.659523384463337,"position":0.709731136277574,"holonomicRotation":141.1952,"angularVelocity":0.2297738110823381,"angularAcceleration":-0.571864895690185,"curveRadius":11.656576613012481},{"acceleration":5.001867398623609,"curvature":0.08503817637862693,"pose":{"rotation":{"radians":2.403552270191619},"translation":{"x":5.702245426255877,"y":5.627744886623094}},"time":0.5346360608008809,"velocity":2.6686291306713845,"position":0.7145892937717098,"holonomicRotation":141.24360000000001,"angularVelocity":0.22863226847160784,"angularAcceleration":-0.6270595114659585,"curveRadius":11.75942432664084},{"acceleration":5.0015638046583994,"curvature":0.08425755967298458,"pose":{"rotation":{"radians":2.4039659738246493},"translation":{"x":5.698640061048724,"y":5.631021251083512}},"time":0.5364553921026012,"velocity":2.677728632258751,"position":0.7194609692898908,"holonomicRotation":141.292,"angularVelocity":0.22739323653634544,"angularAcceleration":-0.6810370019417642,"curveRadius":11.868371264028301},{"acceleration":5.001263817161769,"curvature":0.08344779908209439,"pose":{"rotation":{"radians":2.4043770423139277},"translation":{"x":5.695022928434114,"y":5.634305595359097}},"time":0.5382738041481675,"velocity":2.6868229906269328,"position":0.7243467205803513,"holonomicRotation":141.3404,"angularVelocity":0.22605904436273586,"angularAcceleration":-0.7337127890582504,"curveRadius":11.983539542082093},{"acceleration":5.00096747636165,"curvature":0.0826100895026915,"pose":{"rotation":{"radians":2.40478535807711},"translation":{"x":5.691393617235505,"y":5.637598295076706}},"time":0.5400915127576991,"velocity":2.6959132922647027,"position":0.7292471053822515,"holonomicRotation":141.3888,"angularVelocity":0.22463213357815343,"angularAcceleration":-0.7850052407190578,"curveRadius":12.105058910115565},{"acceleration":5.000674820579198,"curvature":0.08174564520435312,"pose":{"rotation":{"radians":2.405190806780867},"translation":{"x":5.687751716276351,"y":5.640899725863195}},"time":0.5419087308487379,"velocity":2.7050006090160617,"position":0.7341626814252266,"holonomicRotation":141.4372,"angularVelocity":0.22311504918226074,"angularAcceleration":-0.8348389240530877,"curveRadius":12.233067553630955},{"acceleration":5.000385886680861,"curvature":0.08085569901418087,"pose":{"rotation":{"radians":2.4055932774205964},"translation":{"x":5.684096814380108,"y":5.644210263345424}},"time":0.5437256684869507,"velocity":2.71408599833916,"position":0.7390940064289553,"holonomicRotation":141.4856,"angularVelocity":0.22151043121385844,"angularAcceleration":-0.8831442173109911,"curveRadius":12.367712012787312},{"acceleration":5.000100709530403,"curvature":0.07994150010794038,"pose":{"rotation":{"radians":2.4059926623967702},"translation":{"x":5.680428500370231,"y":5.647530283150247}},"time":0.5455425329349646,"velocity":2.723170503554795,"position":0.744041638102744,"holonomicRotation":141.534,"angularVelocity":0.2198210089973735,"angularAcceleration":-0.9298559495353355,"curveRadius":12.509147297082965},{"acceleration":4.999819322024519,"curvature":0.0790043082588532,"pose":{"rotation":{"radians":2.406388857579662},"translation":{"x":5.676746363070176,"y":5.650860160904521}},"time":0.5473595286994198,"velocity":2.732255154085955,"position":0.7490061341451293,"holonomicRotation":141.5824,"angularVelocity":0.21804959078189773,"angularAcceleration":-0.9749159850170834,"curveRadius":12.657537570274725},{"acceleration":4.999541755404641,"curvature":0.07804539452172303,"pose":{"rotation":{"radians":2.4067817623699566},"translation":{"x":5.673049991303399,"y":5.654200272235104}},"time":0.5491768575763195,"velocity":2.7413409656893175,"position":0.7539880522435045,"holonomicRotation":141.6308,"angularVelocity":0.2161990574676285,"angularAcceleration":-1.0182710118083922,"curveRadius":12.813055864835965},{"acceleration":4.999268038842436,"curvature":0.07706603194574356,"pose":{"rotation":{"radians":2.4071712797521747},"translation":{"x":5.669338973893356,"y":5.6575509927688525}},"time":0.5509947186947445,"velocity":2.750428940677714,"position":0.7589879500737533,"holonomicRotation":141.6792,"angularVelocity":0.21427235462059813,"angularAcceleration":-1.0598735115142897,"curveRadius":12.975885416080917},{"acceleration":4.998998199223123,"curvature":0.07606749844782519,"pose":{"rotation":{"radians":2.4075573163392354},"translation":{"x":5.6656128996635005,"y":5.6609126981326225}},"time":0.552813308559016,"velocity":2.7595200681343326,"position":0.7640063852999163,"holonomicRotation":141.7276,"angularVelocity":0.21227248355711423,"angularAcceleration":-1.0996822883344235,"curveRadius":13.146219087063859},{"acceleration":4.998732262067119,"curvature":0.0750510740189569,"pose":{"rotation":{"radians":2.407939782410685},"translation":{"x":5.661871357437289,"y":5.664285763953273}},"time":0.5546328210893633,"velocity":2.768615324121015,"position":0.769043915573866,"holonomicRotation":141.776,"angularVelocity":0.21020249383857645,"angularAcceleration":-1.1376617000503324,"curveRadius":13.324259686775612},{"acceleration":4.998470249857766,"curvature":0.07401803363782587,"pose":{"rotation":{"radians":2.4083185919462404},"translation":{"x":5.658113936038178,"y":5.667670565857659}},"time":0.556453447661169,"velocity":2.7777156718762863,"position":0.7741010985350051,"holonomicRotation":141.8244,"angularVelocity":0.2080654767000153,"angularAcceleration":-1.1737811430718876,"curveRadius":13.510221102239118},{"acceleration":3.9464403220642095,"curvature":0.07296964810159667,"pose":{"rotation":{"radians":2.4086936626487723},"translation":{"x":5.654340224289622,"y":5.671067479472638}},"time":0.5582766275561095,"velocity":2.7849107425280564,"position":0.7791784918099861,"holonomicRotation":141.8728,"angularVelocity":0.20572336475007041,"angularAcceleration":-1.2846301982840218,"curveRadius":13.704328114720875},{"acceleration":-1.0569689798231747,"curvature":0.07190718058611292,"pose":{"rotation":{"radians":2.4090649159639272},"translation":{"x":5.650549811015076,"y":5.674476880425067}},"time":0.5601085384335646,"velocity":2.7829744695567857,"position":0.7842766530124469,"holonomicRotation":141.9212,"angularVelocity":0.20265904838707635,"angularAcceleration":-1.672743145262131,"curveRadius":13.906816980571826},{"acceleration":-4.98136139605534,"curvature":0.07083188249834686,"pose":{"rotation":{"radians":2.4094322770902763},"translation":{"x":5.646742285037997,"y":5.677899144341803}},"time":0.5619542096046168,"velocity":2.7737805144354937,"position":0.789396139742767,"holonomicRotation":141.9696,"angularVelocity":0.19903931540503414,"angularAcceleration":-1.9612014527910113,"curveRadius":14.117936227705636},{"acceleration":-4.981045573510598,"curvature":0.06974499587788117,"pose":{"rotation":{"radians":2.4097956749863085},"translation":{"x":5.64291723518184,"y":5.681334646849703}},"time":0.5638139811367784,"velocity":2.7645169076774794,"position":0.7945375095878449,"holonomicRotation":142.018,"angularVelocity":0.19539921423029383,"angularAcceleration":-1.9572840597842416,"curveRadius":14.337946219839674},{"acceleration":-4.980730506831411,"curvature":0.06864774350383697,"pose":{"rotation":{"radians":2.410155042368009},"translation":{"x":5.63907425027006,"y":5.684783763575624}},"time":0.5656881987584305,"velocity":2.755181934792876,"position":0.7997013201208911,"holonomicRotation":142.0664,"angularVelocity":0.19174261171647816,"angularAcceleration":-1.9510020989944938,"curveRadius":14.567121203978196},{"acceleration":-4.98041616593203,"curvature":0.06754133718959143,"pose":{"rotation":{"radians":2.4105103157028545},"translation":{"x":5.635212919126113,"y":5.688246870146423}},"time":0.5675772140448075,"velocity":2.7457738525229107,"position":0.8048881289012414,"holonomicRotation":142.1148,"angularVelocity":0.18807329798091865,"angularAcceleration":-1.9424478785435546,"curveRadius":14.80574773331711},{"acceleration":-4.980102516274179,"curvature":0.06642696207889152,"pose":{"rotation":{"radians":2.410861435196643},"translation":{"x":5.631332830573454,"y":5.691724342188955}},"time":0.5694813846123502,"velocity":2.7362908878880763,"position":0.810098493474193,"holonomicRotation":142.1632,"angularVelocity":0.1843949800366522,"angularAcceleration":-1.9317166261073644,"curveRadius":15.054128153751137},{"acceleration":-4.979789517679167,"curvature":0.06530578868411975,"pose":{"rotation":{"radians":2.41120834477401},"translation":{"x":5.62743357343554,"y":5.69521655533008}},"time":0.5714010743218662,"velocity":2.726731237195432,"position":0.8153329713708528,"holonomicRotation":142.2116,"angularVelocity":0.1807112762273618,"angularAcceleration":-1.918905847663915,"curveRadius":15.312578259133215},{"acceleration":-4.979477125162371,"curvature":0.06417896232696534,"pose":{"rotation":{"radians":2.411550992056966},"translation":{"x":5.6235147365358245,"y":5.698723885196653}},"time":0.5733366534909801,"velocity":2.7170930649988887,"position":0.8205921201080085,"holonomicRotation":142.26,"angularVelocity":0.17702571324572913,"angularAcceleration":-1.9041137869446505,"curveRadius":15.581429860230717},{"acceleration":-4.979165288406445,"curvature":0.06304760502948925,"pose":{"rotation":{"radians":2.411889328332922},"translation":{"x":5.619575908697764,"y":5.702246707415531}},"time":0.5752884991163734,"velocity":2.7073745030126024,"position":0.825876497188015,"holonomicRotation":142.3084,"angularVelocity":0.17334171901426176,"angularAcceleration":-1.887441395743087,"curveRadius":15.861030716904633},{"acceleration":-4.978853951641728,"curvature":0.06191281304178335,"pose":{"rotation":{"radians":2.412223308522462},"translation":{"x":5.615616678744815,"y":5.705785397613571}},"time":0.5772569951063554,"velocity":2.6975736489740894,"position":0.8311866600987018,"holonomicRotation":142.3568,"angularVelocity":0.16966262122927553,"angularAcceleration":-1.8689892200490454,"curveRadius":16.151745509045533},{"acceleration":-4.978543053548987,"curvature":0.06077565363043514,"pose":{"rotation":{"radians":2.412552891139785},"translation":{"x":5.611636635500432,"y":5.70934033141763}},"time":0.5792425325243384,"velocity":2.6876885654542284,"position":0.8365231663132963,"holonomicRotation":142.4052,"angularVelocity":0.1659916425336766,"angularAcceleration":-1.8488589851547823,"curveRadius":16.453957140153594},{"acceleration":-4.978232527439856,"curvature":0.059637167837524735,"pose":{"rotation":{"radians":2.4128780382495143},"translation":{"x":5.6076353677880695,"y":5.712911884454566}},"time":0.5812455098438292,"velocity":2.6777172786106154,"position":0.8418865732903618,"holonomicRotation":142.4536,"angularVelocity":0.16233189790291228,"angularAcceleration":-1.8271523072936435,"curveRadius":16.7680665642003},{"acceleration":-4.977922300706727,"curvature":0.058498367342105825,"pose":{"rotation":{"radians":2.413198715419065},"translation":{"x":5.603612464431185,"y":5.716500432351233}},"time":0.5832663332155931,"velocity":2.6676577768825225,"position":0.8472774384737537,"holonomicRotation":142.502,"angularVelocity":0.15868639190896947,"angularAcceleration":-1.803970621519872,"curveRadius":17.094494178818255},{"acceleration":-4.977612294907105,"curvature":0.057360232054175765,"pose":{"rotation":{"radians":2.4135148916669835},"translation":{"x":5.599567514253232,"y":5.720106350734491}},"time":0.5853054167476924,"velocity":2.657508009622802,"position":0.8526963192925977,"holonomicRotation":142.5504,"angularVelocity":0.15505801647721812,"angularAcceleration":-1.779414807992545,"curveRadius":17.43368121411219},{"acceleration":-4.9773024254529945,"curvature":0.056223711482065654,"pose":{"rotation":{"radians":2.4138265394074896},"translation":{"x":5.595500106077669,"y":5.723730015231196}},"time":0.5873631827991395,"velocity":2.64726588566392,"position":0.8581437731612708,"holonomicRotation":142.5988,"angularVelocity":0.15144954903251484,"angularAcceleration":-1.7535848850095417,"curveRadius":17.786090132434282},{"acceleration":-4.976992601802138,"curvature":0.05508972161132598,"pose":{"rotation":{"radians":2.4141336343924995},"translation":{"x":5.591409828727948,"y":5.727371801468204}},"time":0.5894400622879755,"velocity":2.6369292718131483,"position":0.8636203574794109,"holonomicRotation":142.6472,"angularVelocity":0.14786365153137476,"angularAcceleration":-1.726579476765749,"curveRadius":18.15220645069313},{"acceleration":-4.976682726852807,"curvature":0.05395914861746201,"pose":{"rotation":{"radians":2.414436155647527},"translation":{"x":5.587296271027528,"y":5.731032085072372}},"time":0.591536495014625,"velocity":2.626495991274423,"position":0.8691266296319323,"holonomicRotation":142.6956,"angularVelocity":0.14430286800144404,"angularAcceleration":-1.69849644334714,"curveRadius":18.532538515190446},{"acceleration":-4.97637269710332,"curvature":0.05283284273578125,"pose":{"rotation":{"radians":2.4147340854090125},"translation":{"x":5.583159021799862,"y":5.734711241670558}},"time":0.59365293000145,"velocity":2.6159638219907926,"position":0.8746631469890621,"holonomicRotation":142.744,"angularVelocity":0.14076962597008064,"angularAcceleration":-1.669430931428623,"curveRadius":18.927620552258226},{"acceleration":-4.9760624023352635,"curvature":0.05171162201884368,"pose":{"rotation":{"radians":2.4150274090543338},"translation":{"x":5.578997669868406,"y":5.738409646889618}},"time":0.5957898258494859,"velocity":2.605330494903675,"position":0.8802304669063831,"holonomicRotation":142.79240000000001,"angularVelocity":0.13726623391164067,"angularAcceleration":-1.639477217226137,"curveRadius":19.338012635449736},{"acceleration":-4.9757517253165915,"curvature":0.050596269252295954,"pose":{"rotation":{"radians":2.4153161150328017},"translation":{"x":5.5748118040566155,"y":5.74212767635641}},"time":0.5979476511134226,"velocity":2.59459369212371,"position":0.8858291467248984,"holonomicRotation":142.8408,"angularVelocity":0.13379488288187993,"angularAcceleration":-1.6087266600204904,"curveRadius":19.76430307565853},{"acceleration":-4.97544054161336,"curvature":0.04948753503379026,"pose":{"rotation":{"radians":2.4156001947918577},"translation":{"x":5.5706010131879475,"y":5.74586570569779}},"time":0.6001268846959614,"velocity":2.583751045007501,"position":0.8914597437710985,"holonomicRotation":142.8892,"angularVelocity":0.13035764561090588,"angularAcceleration":-1.577268861179026,"curveRadius":20.207108705600238},{"acceleration":-4.975128719443454,"curvature":0.0483861339194282,"pose":{"rotation":{"radians":2.415879642704131},"translation":{"x":5.5663648860858554,"y":5.749624110540615}},"time":0.6023280162627797,"velocity":2.5728001321341503,"position":0.8971228153570531,"holonomicRotation":142.9376,"angularVelocity":0.1269564784250305,"angularAcceleration":-1.5451903180834514,"curveRadius":20.66707792081888},{"acceleration":-4.97481611940674,"curvature":0.047292747548314,"pose":{"rotation":{"radians":2.4161544559882646},"translation":{"x":5.562103011573797,"y":5.753403266511741}},"time":0.6045515466794091,"velocity":2.5617384771755107,"position":0.9028189187805029,"holonomicRotation":142.986,"angularVelocity":0.12359322007838891,"angularAcceleration":-1.5125758215350829,"curveRadius":21.14489116916723},{"acceleration":-4.974502593964244,"curvature":0.04620802313005017,"pose":{"rotation":{"radians":2.4164246346334255},"translation":{"x":5.557814978475227,"y":5.757203549238026}},"time":0.6067979884714535,"velocity":2.5505635466537964,"position":0.9085486113249709,"holonomicRotation":143.0344,"angularVelocity":0.12026959528517511,"angularAcceleration":-1.479506304140269,"curveRadius":21.641263405394987},{"acceleration":-4.974187987337835,"curvature":0.04513257268640936,"pose":{"rotation":{"radians":2.4166901813186383},"translation":{"x":5.5535003756135985,"y":5.761025334346328}},"time":0.6090678663096687,"velocity":2.539272747578222,"position":0.9143124502598825,"holonomicRotation":143.0828,"angularVelocity":0.11698721435230879,"angularAcceleration":-1.4460606106658425,"curveRadius":22.156946535005016},{"acceleration":-4.973872135304647,"curvature":0.044066975470248314,"pose":{"rotation":{"radians":2.416951101331758},"translation":{"x":5.54915879181237,"y":5.764868997463502}},"time":0.6113617175215529,"velocity":2.5278634249528964,"position":0.9201109928406884,"holonomicRotation":143.1312,"angularVelocity":0.11374757515572001,"angularAcceleration":-1.4123144429789352,"curveRadius":22.692730538658072},{"acceleration":-4.97355486426579,"curvature":0.043011778857574214,"pose":{"rotation":{"radians":2.4172074024892596},"translation":{"x":5.544789815894996,"y":5.768734914216405}},"time":0.6136800926312321,"velocity":2.5163328591489584,"position":0.9259447963090074,"holonomicRotation":143.1796,"angularVelocity":0.11055206572541006,"angularAcceleration":-1.378340121479331,"curveRadius":23.249445304536707},{"acceleration":-4.973235991473243,"curvature":0.041967492789098323,"pose":{"rotation":{"radians":2.4174590950527333},"translation":{"x":5.540393036684932,"y":5.772623460231895}},"time":0.6160235559295619,"velocity":2.504678263129008,"position":0.9318144178927746,"holonomicRotation":143.228,"angularVelocity":0.10740196513982764,"angularAcceleration":-1.3442073480849988,"curveRadius":23.82796620768741},{"acceleration":-4.9729153243510815,"curvature":0.04093459948386959,"pose":{"rotation":{"radians":2.417706191646867},"translation":{"x":5.535968043005634,"y":5.776535011136829}},"time":0.618392686076527,"velocity":2.4928967795157835,"position":0.9377204148063976,"holonomicRotation":143.2764,"angularVelocity":0.10429844660516084,"angularAcceleration":-1.3099822897625653,"curveRadius":24.42921178193164},{"acceleration":-4.972592659836482,"curvature":0.03991354628002494,"pose":{"rotation":{"radians":2.4179487071765746},"translation":{"x":5.531514423680557,"y":5.780469942558063}},"time":0.6207880767381926,"velocity":2.480985477494144,"position":0.943663344250915,"holonomicRotation":143.3248,"angularVelocity":0.10124257958775408,"angularAcceleration":-1.2757280331392362,"curveRadius":25.0541506130328},{"acceleration":-4.972267784012131,"curvature":0.038904749746020796,"pose":{"rotation":{"radians":2.418186658742197},"translation":{"x":5.527031767533157,"y":5.784428630122453}},"time":0.6232103372606584,"velocity":2.468941349533803,"position":0.9496437634141743,"holonomicRotation":143.3732,"angularVelocity":0.09823533159031485,"angularAcceleration":-1.2415047719053187,"curveRadius":25.703802402745968},{"acceleration":-4.971940471650076,"curvature":0.037908595777692844,"pose":{"rotation":{"radians":2.418420065557943},"translation":{"x":5.5225196633868885,"y":5.788411449456858}},"time":0.6256600933836621,"velocity":2.4567613079201682,"position":0.9556622294710103,"holonomicRotation":143.4216,"angularVelocity":0.09527757214440623,"angularAcceleration":-1.2073689369054665,"curveRadius":26.379241422296257},{"acceleration":-4.971610485447593,"curvature":0.0369254388404388,"pose":{"rotation":{"radians":2.418648948867751},"translation":{"x":5.517977700065209,"y":5.792418776188135}},"time":0.6281379879967132,"velocity":2.4444421810800896,"position":0.9617192995834234,"holonomicRotation":143.47,"angularVelocity":0.09237007441833003,"angularAcceleration":-1.1733742471380526,"curveRadius":27.081600961363595},{"acceleration":-4.971277575399809,"curvature":0.035955605370565205,"pose":{"rotation":{"radians":2.4188733318631357},"translation":{"x":5.513405466391571,"y":5.796450985943138}},"time":0.630644681940901,"velocity":2.4319807096869583,"position":0.9678155309007772,"holonomicRotation":143.5184,"angularVelocity":0.0895135187543703,"angularAcceleration":-1.139570975779935,"curveRadius":27.81207518810524},{"acceleration":-4.970941477946113,"curvature":0.034999392197728144,"pose":{"rotation":{"radians":2.419093239599137},"translation":{"x":5.508802551189434,"y":5.800508454348727}},"time":0.63318085485978,"velocity":2.4193735425292586,"position":0.9739514805599925,"holonomicRotation":143.5668,"angularVelocity":0.08670849466314715,"angularAcceleration":-1.1060066410861662,"curveRadius":28.5719247451649},{"acceleration":-4.970601915362799,"curvature":0.034057067435108675,"pose":{"rotation":{"radians":2.41930869891569},"translation":{"x":5.504168543282249,"y":5.804591557031757}},"time":0.635747206103058,"velocity":2.4066172321239274,"position":0.9801277056857479,"holonomicRotation":143.61520000000002,"angularVelocity":0.08395550574653307,"angularAcceleration":-1.0727249139512596,"curveRadius":29.362481132744925},{"acceleration":-4.970258594933293,"curvature":0.03312887396383559,"pose":{"rotation":{"radians":2.419519738352122},"translation":{"x":5.499503031493476,"y":5.808700669619087}},"time":0.6383444556871457,"velocity":2.3937082300554287,"position":0.9863447633906867,"holonomicRotation":143.6636,"angularVelocity":0.08125496976687775,"angularAcceleration":-1.0397676050081681,"curveRadius":30.185149096574428},{"acceleration":-4.969911207545169,"curvature":0.03221502695702234,"pose":{"rotation":{"radians":2.419726388072037},"translation":{"x":5.494805604646568,"y":5.812836167737571}},"time":0.6409733453170032,"velocity":2.3806428820206005,"position":0.9926032107756247,"holonomicRotation":143.712,"angularVelocity":0.07860722548718428,"angularAcceleration":-1.0071720963945412,"curveRadius":31.041414347847276},{"acceleration":-4.969559427338995,"curvature":0.031315714754310324,"pose":{"rotation":{"radians":2.419928679779084},"translation":{"x":5.49007585156498,"y":5.816998427014068}},"time":0.6436346394741399,"velocity":2.3674174225530797,"position":0.9989036049297688,"holonomicRotation":143.7604,"angularVelocity":0.07601253191224391,"angularAcceleration":-0.9749743627484,"curveRadius":31.932849300920367},{"acceleration":-4.9692029099150306,"curvature":0.030431103273967846,"pose":{"rotation":{"radians":2.4201266466422653},"translation":{"x":5.48531336107217,"y":5.821187823075435}},"time":0.6463291265760754,"velocity":2.354027969405413,"position":1.0052465029309272,"holonomicRotation":143.8088,"angularVelocity":0.07347107471357718,"angularAcceleration":-0.9432062958628084,"curveRadius":32.86111551714412},{"acceleration":-4.968841291560093,"curvature":0.029561331686113235,"pose":{"rotation":{"radians":2.4203203232173047},"translation":{"x":5.480517721991591,"y":5.825404731548527}},"time":0.6490576202131033,"velocity":2.34047051755799,"position":1.0116324618457355,"holonomicRotation":143.8572,"angularVelocity":0.07098296745540768,"angularAcceleration":-0.9118977682058217,"curveRadius":33.82797536383522},{"acceleration":-4.968474187558782,"curvature":0.02870652041573119,"pose":{"rotation":{"radians":2.4205097453708255},"translation":{"x":5.475688523146699,"y":5.829649528060203}},"time":0.651820960468749,"velocity":2.326740932826372,"position":1.0180620387298733,"holonomicRotation":143.9056,"angularVelocity":0.06854825537093989,"angularAcceleration":-0.8810757486319211,"curveRadius":34.83529126894806},{"acceleration":-4.968101190999234,"curvature":0.02786676317996456,"pose":{"rotation":{"radians":2.4206949502063306},"translation":{"x":5.470825353360952,"y":5.833922588237319}},"time":0.6546200153309749,"velocity":2.3128349450316756,"position":1.0245357906282901,"holonomicRotation":143.954,"angularVelocity":0.06616691869977318,"angularAcceleration":-0.8507645574595942,"curveRadius":35.88504318000494},{"acceleration":-4.9677218707697275,"curvature":0.02704213687531843,"pose":{"rotation":{"radians":2.420875975990624},"translation":{"x":5.465927801457801,"y":5.8382242877067325}},"time":0.6574556822018853,"velocity":2.298748140698837,"position":1.0310542745754367,"holonomicRotation":144.0024,"angularVelocity":0.06383887548653909,"angularAcceleration":-0.8209861451344064,"curveRadius":36.97932617568798},{"acceleration":-4.967335770099017,"curvature":0.02623269346072792,"pose":{"rotation":{"radians":2.4210528620824054},"translation":{"x":5.460995456260706,"y":5.842555002095299}},"time":0.6603288895144802,"velocity":2.284475955240074,"position":1.0376180475954797,"holonomicRotation":144.0508,"angularVelocity":0.061563984960663065,"angularAcceleration":-0.7917599666073174,"curveRadius":38.12037073116667},{"acceleration":-4.9669424043659784,"curvature":0.02543846814507094,"pose":{"rotation":{"radians":2.4212256488618333},"translation":{"x":5.45602790659312,"y":5.846915107029877}},"time":0.6632405984659269,"velocity":2.270013664579962,"position":1.0442276667025434,"holonomicRotation":144.0992,"angularVelocity":0.05934205042782311,"angularAcceleration":-0.7631032393316668,"curveRadius":39.31054316231553},{"acceleration":-4.966541258973852,"curvature":0.024659477621511584,"pose":{"rotation":{"radians":2.4213943776621427},"translation":{"x":5.451024741278499,"y":5.851304978137322}},"time":0.6661918048777864,"velocity":2.2553563761717133,"position":1.0508836889009296,"holonomicRotation":144.1476,"angularVelocity":0.05717282248755572,"angularAcceleration":-0.735030911951894,"curveRadius":40.55235943553218},{"acceleration":-4.966131786991758,"curvature":0.02389572005269521,"pose":{"rotation":{"radians":2.4215590907023654},"translation":{"x":5.445985549140301,"y":5.855724991044492}},"time":0.669183541194799,"velocity":2.2404990193494996,"position":1.0575866711853485,"holonomicRotation":144.196,"angularVelocity":0.05505600185619771,"angularAcceleration":-0.7075558829568913,"curveRadius":41.84849829989574},{"acceleration":-4.965713406370056,"curvature":0.023147177893459072,"pose":{"rotation":{"radians":2.421719831022987},"translation":{"x":5.440909919001976,"y":5.860175521378243}},"time":0.6722168786350884,"velocity":2.22543633495621,"position":1.0643371705411517,"holonomicRotation":144.2444,"angularVelocity":0.052991242743528406,"angularAcceleration":-0.6806888957505118,"curveRadius":43.2018108040108},{"acceleration":-4.965285497112944,"curvature":0.02241381499335583,"pose":{"rotation":{"radians":2.4218766424198632},"translation":{"x":5.435797439686985,"y":5.864656944765433}},"time":0.6752929295060872,"velocity":2.210162864178058,"position":1.071135743944556,"holonomicRotation":144.2928,"angularVelocity":0.05097815460557753,"angularAcceleration":-0.6544391566896309,"curveRadius":44.61534104285379},{"acceleration":-4.96484739811205,"curvature":0.02169558133690791,"pose":{"rotation":{"radians":2.422029569385755},"translation":{"x":5.43064770001878,"y":5.869169636832918}},"time":0.6784128497021252,"velocity":2.1946729365104414,"position":1.077982948362873,"holonomicRotation":144.34120000000001,"angularVelocity":0.0490163069190606,"angularAcceleration":-0.6288134193330577,"curveRadius":46.09233486169961},{"acceleration":-4.9643984032310335,"curvature":0.020992414061030175,"pose":{"rotation":{"radians":2.4221786570470525},"translation":{"x":5.425460288820819,"y":5.873713973207556}},"time":0.6815778414014626,"velocity":2.1789606567720115,"position":1.084879340754739,"holonomicRotation":144.3896,"angularVelocity":0.04710522979523143,"angularAcceleration":-0.6038174205099115,"curveRadius":47.63625551081219},{"acceleration":-4.963937757674139,"curvature":0.020304236474519614,"pose":{"rotation":{"radians":2.4223239511070225},"translation":{"x":5.420234794916556,"y":5.878290329516203}},"time":0.6847891559826531,"velocity":2.1630198910706704,"position":1.0918254780703394,"holonomicRotation":144.438,"angularVelocity":0.04524441822704511,"angularAcceleration":-0.5794547750275124,"curveRadius":49.25080542944471},{"acceleration":-4.963464653266672,"curvature":0.019630955933400897,"pose":{"rotation":{"radians":2.4224654977886293},"translation":{"x":5.414970807129447,"y":5.882899081385715}},"time":0.6880480971825201,"velocity":2.146844251618056,"position":1.0988219172516351,"holonomicRotation":144.4864,"angularVelocity":0.04343333399589854,"angularAcceleration":-0.5557278023980514,"curveRadius":50.93995439613615},{"acceleration":-4.962978223704575,"curvature":0.018972470804019165,"pose":{"rotation":{"radians":2.4226033437793832},"translation":{"x":5.409667914282948,"y":5.88754060444295}},"time":0.6913560245207548,"velocity":2.1304270802728,"position":1.105869215232585,"holonomicRotation":144.5348,"angularVelocity":0.04167140830472743,"angularAcceleration":-0.5326373620139347,"curveRadius":52.707947759137305},{"acceleration":-4.962477538830535,"curvature":0.018328668474177003,"pose":{"rotation":{"radians":2.422737536178695},"translation":{"x":5.404325705200513,"y":5.892215274314766}},"time":0.6947143570192804,"velocity":2.1137614306809422,"position":1.1129679289393708,"holonomicRotation":144.5832,"angularVelocity":0.03995804446718348,"angularAcceleration":-0.5101829072303533,"curveRadius":54.55933699760491},{"acceleration":-4.961961598666886,"curvature":0.01769942422116078,"pose":{"rotation":{"radians":2.4228681224462147},"translation":{"x":5.398943768705599,"y":5.896923466628018}},"time":0.6981245772481064,"velocity":2.0968400488625107,"position":1.1201186152906142,"holonomicRotation":144.6316,"angularVelocity":0.038292620053099656,"angularAcceleration":-0.48836271628626465,"curveRadius":56.49901304724008},{"acceleration":-4.96142932622865,"curvature":0.01708460530824396,"pose":{"rotation":{"radians":2.42299515035221},"translation":{"x":5.393521693621661,"y":5.901665557009564}},"time":0.7015882357335324,"velocity":2.0796553520768777,"position":1.1273218311975968,"holonomicRotation":144.68,"angularVelocity":0.03667448928056162,"angularAcceleration":-0.46717387968434176,"curveRadius":58.532227227834326},{"acceleration":-4.960879560045226,"curvature":0.01648406664522855,"pose":{"rotation":{"radians":2.423118667930159},"translation":{"x":5.388059068772154,"y":5.906441921086261}},"time":0.7051069557693178,"velocity":2.062199405773828,"position":1.134578133564478,"holonomicRotation":144.7284,"angularVelocity":0.03510298537327234,"angularAcceleration":-0.4466123736208197,"curveRadius":60.6646418946297},{"acceleration":-4.960311045183684,"curvature":0.01589765818669088,"pose":{"rotation":{"radians":2.423238723429785},"translation":{"x":5.3825554829805355,"y":5.911252934484964}},"time":0.708682438676936,"velocity":2.044463898415304,"position":1.1418880792885044,"holonomicRotation":144.7768,"angularVelocity":0.03357742233093208,"angularAcceleration":-0.4266732863104352,"curveRadius":62.90234626111001},{"acceleration":-4.959722423481845,"curvature":0.015325219461193714,"pose":{"rotation":{"radians":2.423355365273755},"translation":{"x":5.377010525070259,"y":5.9160989728325335}},"time":0.712316469567431,"velocity":2.0264401139200903,"position":1.1492522252602282,"holonomicRotation":144.8252,"angularVelocity":0.03209709754402032,"angularAcceleration":-0.4073506339155357,"curveRadius":65.25192037426835},{"acceleration":-4.959112222477655,"curvature":0.01476658722226072,"pose":{"rotation":{"radians":2.423468642014675},"translation":{"x":5.37142378386478,"y":5.9209804117558225}},"time":0.716010923664805,"velocity":2.00811890145042,"position":1.156671128363706,"holonomicRotation":144.8736,"angularVelocity":0.03066129336950801,"angularAcceleration":-0.38863770848658474,"curveRadius":67.72045462830395},{"acceleration":-4.95847884257658,"curvature":0.01422158641461879,"pose":{"rotation":{"radians":2.4235786022935164},"translation":{"x":5.365794848187556,"y":5.92589762688169}},"time":0.7197677732595675,"velocity":1.9894906422200478,"position":1.164145345476714,"holonomicRotation":144.922,"angularVelocity":0.02926927897107383,"angularAcceleration":-0.37052705021111443,"curveRadius":70.31564347645987},{"acceleration":-4.957820542868143,"curvature":0.013690039025652887,"pose":{"rotation":{"radians":2.423685294801426},"translation":{"x":5.36012330686204,"y":5.9308509938369935}},"time":0.7235890953712012,"velocity":1.9705452129540741,"position":1.1716754334709494,"holonomicRotation":144.9704,"angularVelocity":0.02792031260190944,"angularAcceleration":-0.3530103795902435,"curveRadius":73.04581076256716},{"acceleration":-4.957135424795328,"curvature":0.013171759421676373,"pose":{"rotation":{"radians":2.423788768241888},"translation":{"x":5.354408748711689,"y":5.935840888248589}},"time":0.7274770802102547,"velocity":1.9512719455773349,"position":1.1792619492122245,"holonomicRotation":145.0188,"angularVelocity":0.026613642991293533,"angularAcceleration":-0.33607888525974955,"curveRadius":75.9200018757046},{"acceleration":-4.956421413338656,"curvature":0.012666561305571927,"pose":{"rotation":{"radians":2.4238890712941306},"translation":{"x":5.348650762559959,"y":5.940867685743332}},"time":0.7314340405448418,"velocity":1.9316595826432554,"position":1.186905449560669,"holonomicRotation":145.0672,"angularVelocity":0.025348510917809892,"angularAcceleration":-0.31972321340331067,"curveRadius":78.9480251092384},{"acceleration":-4.9556762358076005,"curvature":0.012174248065797987,"pose":{"rotation":{"radians":2.4239862525791946},"translation":{"x":5.342848937230305,"y":5.945931761948082}},"time":0.7354624220929764,"velocity":1.9116962279363992,"position":1.1946064913709264,"holonomicRotation":145.1156,"angularVelocity":0.024124151077270044,"angularAcceleration":-0.3039334347827147,"curveRadius":82.14059665905557},{"acceleration":-4.954897397049325,"curvature":0.011694625924724623,"pose":{"rotation":{"radians":2.4240803606276495},"translation":{"x":5.337002861546182,"y":5.951033492489695}},"time":0.7395648150819601,"velocity":1.8913692915936102,"position":1.2023656314923392,"holonomicRotation":145.16400000000002,"angularVelocity":0.022939793605244348,"angularAcceleration":-0.2886991751414558,"curveRadius":85.50936185875028},{"acceleration":-4.954082151309961,"curvature":0.011227494168963115,"pose":{"rotation":{"radians":2.4241714438476074},"translation":{"x":5.331112124331046,"y":5.956173252995026}},"time":0.7437439671396723,"velocity":1.8706654289768883,"position":1.210183426769139,"holonomicRotation":145.2124,"angularVelocity":0.021794665209607225,"angularAcceleration":-0.27400974643263415,"curveRadius":89.06706919201653},{"acceleration":-4.953227469263,"curvature":0.010772647281375666,"pose":{"rotation":{"radians":2.4242595504950106},"translation":{"x":5.325176314408353,"y":5.961351419090935}},"time":0.7480027977108874,"velocity":1.8495704724046085,"position":1.2180604340406325,"holonomicRotation":145.26080000000002,"angularVelocity":0.02068799073593585,"angularAcceleration":-0.25985407382750625,"curveRadius":92.82769349822249},{"acceleration":-4.952330000008178,"curvature":0.010329879924628105,"pose":{"rotation":{"radians":2.4243447286461266},"translation":{"x":5.319195020601557,"y":5.966568366404277}},"time":0.752344414225813,"velocity":1.8280693546892115,"position":1.2259972101413805,"holonomicRotation":145.3092,"angularVelocity":0.019618994635557285,"angularAcceleration":-0.2462207559565831,"curveRadius":96.80654637774039},{"acceleration":-4.951386026525089,"curvature":0.009898985702120633,"pose":{"rotation":{"radians":2.424427026169914},"translation":{"x":5.313167831734114,"y":5.971824470561909}},"time":0.7567721302892313,"velocity":1.8061460232433815,"position":1.2339943119013743,"holonomicRotation":145.3576,"angularVelocity":0.01858690182670944,"angularAcceleration":-0.23309823711935262,"curveRadius":101.02045099284997},{"acceleration":-4.950391413890663,"curvature":0.009479751584689809,"pose":{"rotation":{"radians":2.424506490702719},"translation":{"x":5.307094336629482,"y":5.97712010719069}},"time":0.7612894862086979,"velocity":1.783783343286166,"position":1.242052296146214,"holonomicRotation":145.406,"angularVelocity":0.017590939085099833,"angularAcceleration":-0.22047471117290596,"curveRadius":105.4879962904346},{"acceleration":-4.949341547966157,"curvature":0.009071974190377714,"pose":{"rotation":{"radians":2.4245831696253344},"translation":{"x":5.3009741241111135,"y":5.982455651917474}},"time":0.7659002722414073,"velocity":1.760962988405695,"position":1.2501717196972733,"holonomicRotation":145.4544,"angularVelocity":0.01663033636162154,"angularAcceleration":-0.20833816981826078,"curveRadius":110.22959049648318},{"acceleration":-4.948231263332675,"curvature":0.008675431962124546,"pose":{"rotation":{"radians":2.4246571100380607},"translation":{"x":5.294806783002465,"y":5.987831480369119}},"time":0.7706085550145204,"velocity":1.7376653163911662,"position":1.2583531393718739,"holonomicRotation":145.5028,"angularVelocity":0.01570432709534538,"angularAcceleration":-0.19667664643342755,"curveRadius":115.26803557054326},{"acceleration":-4.947054757743496,"curvature":0.008289924427881092,"pose":{"rotation":{"radians":2.424728358741492},"translation":{"x":5.288591902126992,"y":5.993247968172482}},"time":0.7754187076666081,"velocity":1.713869227828183,"position":1.2665971119834432,"holonomicRotation":145.5512,"angularVelocity":0.014812150171661013,"angularAcceleration":-0.1854778815173653,"curveRadius":120.6283614162693},{"acceleration":-4.9458054899744885,"curvature":0.007915223196009985,"pose":{"rotation":{"radians":2.4247969622152796},"translation":{"x":5.28232907030815,"y":5.9987054909544195}},"time":0.7803354443734081,"velocity":1.689552004430933,"position":1.2749041943416761,"holonomicRotation":145.5996,"angularVelocity":0.013953050138455736,"angularAcceleration":-0.174729721039796,"curveRadius":126.3388252278336},{"acceleration":-4.9444760575186635,"curvature":0.007551127321591673,"pose":{"rotation":{"radians":2.424862966599116},"translation":{"x":5.276017876369395,"y":6.004204424341789}},"time":0.7853638600656748,"velocity":1.6646891234332688,"position":1.2832749432526938,"holonomicRotation":145.648,"angularVelocity":0.013126278310246552,"angularAcceleration":-0.16441994433369622,"curveRadius":132.4305573739437},{"acceleration":-4.943058049200852,"curvature":0.007197422140180354,"pose":{"rotation":{"radians":2.4249264176753},"translation":{"x":5.269657909134183,"y":6.009745143961449}},"time":0.7905094763291962,"velocity":1.6392540435437706,"position":1.2917099155191958,"holonomicRotation":145.6964,"angularVelocity":0.012331093679430747,"angularAcceleration":-0.15453632569787126,"curveRadius":138.93863393358527},{"acceleration":-4.941541866232434,"curvature":0.006853893623117274,"pose":{"rotation":{"radians":2.4249873608526618},"translation":{"x":5.263248757425967,"y":6.015328025440252}},"time":0.79577829470855,"velocity":1.613217956936619,"position":1.300209667940607,"holonomicRotation":145.7448,"angularVelocity":0.011566763736011171,"angularAcceleration":-0.14506667119418173,"curveRadius":145.90246872626278},{"acceleration":-4.939916504061861,"curvature":0.006520331601323291,"pose":{"rotation":{"radians":2.425045841149055},"translation":{"x":5.256790010068206,"y":6.020953444405059}},"time":0.8011768589325529,"velocity":1.5865495004282293,"position":1.3087747573132285,"holonomicRotation":145.7932,"angularVelocity":0.010832564727751985,"angularAcceleration":-0.1359989393096079,"curveRadius":153.36643305028406},{"acceleration":-4.938169283994323,"curvature":0.006196523179810055,"pose":{"rotation":{"radians":2.4251019031799714},"translation":{"x":5.250281255884354,"y":6.026621776482724}},"time":0.8067123279619656,"velocity":1.5592144172946816,"position":1.317405740430377,"holonomicRotation":145.8416,"angularVelocity":0.010127783322127151,"angularAcceleration":-0.12732099156909352,"curveRadius":161.38082130609467},{"acceleration":-4.93628552114476,"curvature":0.005882259155243296,"pose":{"rotation":{"radians":2.4251555911419764},"translation":{"x":5.2437220836978655,"y":6.032333397300107}},"time":0.8123925622585739,"velocity":1.5311751589796239,"position":1.3261031740825278,"holonomicRotation":145.89000000000001,"angularVelocity":0.009451716109150111,"angularAcceleration":-0.1190210082321281,"curveRadius":170.00271045668322},{"acceleration":-4.934248109939164,"curvature":0.005577337919179543,"pose":{"rotation":{"radians":2.425206948803048},"translation":{"x":5.237112082332197,"y":6.038088682484062}},"time":0.8182262263306695,"velocity":1.502390413057866,"position":1.3348676150574443,"holonomicRotation":145.9384,"angularVelocity":0.008803671318187555,"angularAcceleration":-0.11108709431219607,"curveRadius":179.2970077285734},{"acceleration":-4.9320370024199685,"curvature":0.0052815512465390875,"pose":{"rotation":{"radians":2.42525601948907},"translation":{"x":5.2304508406108035,"y":6.043888007661447}},"time":0.8242229114821338,"velocity":1.472814539998982,"position":1.3436996201403169,"holonomicRotation":145.98680000000002,"angularVelocity":0.008182968553906926,"angularAcceleration":-0.10350764607494357,"curveRadius":189.33831242388936},{"acceleration":-4.929628545545269,"curvature":0.00499469062550934,"pose":{"rotation":{"radians":2.425302846074418},"translation":{"x":5.223737947357141,"y":6.049731748459121}},"time":0.8303932838652491,"velocity":1.4423968961625324,"position":1.3525997461138894,"holonomicRotation":146.0352,"angularVelocity":0.007588939927851547,"angularAcceleration":-0.0962711144761511,"curveRadius":200.21260073501023},{"acceleration":-4.926994630827586,"curvature":0.004716558880690003,"pose":{"rotation":{"radians":2.4253474709723517},"translation":{"x":5.216972991394666,"y":6.0556202805039385}},"time":0.8367492645344569,"velocity":1.411081013531702,"position":1.361568549758583,"holonomicRotation":146.0836,"angularVelocity":0.007020930404959599,"angularAcceleration":-0.08936615015897308,"curveRadius":212.01897936524995},{"acceleration":-4.924101591290456,"curvature":0.004446946701364387,"pose":{"rotation":{"radians":2.4253899361260647},"translation":{"x":5.2101555615468325,"y":6.061553979422756}},"time":0.8433042504022514,"velocity":1.3788035971892083,"position":1.3706065878526226,"holonomicRotation":146.132,"angularVelocity":0.006478298286135855,"angularAcceleration":-0.08278158485280039,"curveRadius":224.8733945232997},{"acceleration":-4.92090875352478,"curvature":0.00418566455825344,"pose":{"rotation":{"radians":2.4254302830002645},"translation":{"x":5.203285246637097,"y":6.067533220842431}},"time":0.8500733880847938,"velocity":1.345493288313371,"position":1.3797144171721525,"holonomicRotation":146.1804,"angularVelocity":0.005960415652927648,"angularAcceleration":-0.07650644107059996,"curveRadius":238.91068815540055},{"acceleration":-4.917366511886418,"curvature":0.003932519034518671,"pose":{"rotation":{"radians":2.4254685525747535},"translation":{"x":5.196361635488913,"y":6.073558380389821}},"time":0.8570739170170669,"velocity":1.3110691217763193,"position":1.3888925944913575,"holonomicRotation":146.2288,"angularVelocity":0.005466668998753758,"angularAcceleration":-0.07052990694712676,"curveRadius":254.28993253999522},{"acceleration":-4.913413730233973,"curvature":0.0036873067678398173,"pose":{"rotation":{"radians":2.4255047853378913},"translation":{"x":5.1893843169257385,"y":6.079629833691783}},"time":0.8643256045795497,"velocity":1.2754385805394497,"position":1.398141676582566,"holonomicRotation":146.2772,"angularVelocity":0.004996459489685354,"angularAcceleration":-0.0648413910578657,"curveRadius":271.20065211873947},{"acceleration":-4.908974179953833,"curvature":0.0034498361938138274,"pose":{"rotation":{"radians":2.425539021280997},"translation":{"x":5.182352879771028,"y":6.085747956375172}},"time":0.8718513053766318,"velocity":1.2384951096405155,"position":1.40746222021637,"holonomicRotation":146.3256,"angularVelocity":0.004549203327228097,"angularAcceleration":-0.05943050016427259,"curveRadius":289.8688354517176},{"acceleration":-4.903951569305102,"curvature":0.003219934757636731,"pose":{"rotation":{"radians":2.4255712998927845},"translation":{"x":5.1752669128482385,"y":6.091913124066848}},"time":0.8796776909964238,"velocity":1.2001148935983497,"position":1.4168547821617263,"holonomicRotation":146.374,"angularVelocity":0.004124331889016816,"angularAcceleration":-0.05428705648451978,"curveRadius":310.5652987621244},{"acceleration":-4.898222467833417,"curvature":0.002997398958820563,"pose":{"rotation":{"radians":2.4256016601563792},"translation":{"x":5.168126004980822,"y":6.098125712393666}},"time":0.8878362185358499,"velocity":1.1601526107002949,"position":1.4263199191860618,"holonomicRotation":146.4224,"angularVelocity":0.0037212920405051628,"angularAcceleration":-0.04940105264877276,"curveRadius":333.6225886971973},{"acceleration":-4.891626005153176,"curvature":0.0027820536848971356,"pose":{"rotation":{"radians":2.4256301405438565},"translation":{"x":5.160929744992239,"y":6.104386096982483}},"time":0.8963644410943157,"velocity":1.1184357354555698,"position":1.4358581880553682,"holonomicRotation":146.4708,"angularVelocity":0.003339545524524115,"angularAcceleration":-0.04476272908732874,"curveRadius":359.4466941557148},{"acceleration":-4.883948485240711,"curvature":0.002573717284619598,"pose":{"rotation":{"radians":2.4256567790152737},"translation":{"x":5.15367772170594,"y":6.110694653460158}},"time":0.9053078207554786,"velocity":1.0747567299065008,"position":1.445470145534312,"holonomicRotation":146.5192,"angularVelocity":0.0029785687767265273,"angularAcceleration":-0.04036245373381041,"curveRadius":388.5430641414846},{"acceleration":-4.874899720064227,"curvature":0.0023722114952859194,"pose":{"rotation":{"radians":2.4256816130146244},"translation":{"x":5.146369523945384,"y":6.1170517574535435}},"time":0.9147223021182094,"velocity":1.0288620773467745,"position":1.4551563483863137,"holonomicRotation":146.5676,"angularVelocity":0.0026378510290567593,"angularAcceleration":-0.03619081439988506,"curveRadius":421.54757364054984},{"acceleration":-4.864075358975254,"curvature":0.0021773683647137855,"pose":{"rotation":{"radians":2.4257046794684043},"translation":{"x":5.139004740534024,"y":6.123457784589499}},"time":0.9246780775622906,"velocity":0.9804364353297281,"position":1.464917353373652,"holonomicRotation":146.616,"angularVelocity":0.0023168917287735473,"angularAcceleration":-0.03223850337785839,"curveRadius":459.2700143007036},{"acceleration":-4.850894460050388,"curvature":0.0019890038377956528,"pose":{"rotation":{"radians":2.425726014784447},"translation":{"x":5.131582960295319,"y":6.129913110494882}},"time":0.9352652983130066,"velocity":0.9290789448427491,"position":1.4747537172575444,"holonomicRotation":146.6644,"angularVelocity":0.0020151951626507596,"angularAcceleration":-0.028496295035917038,"curveRadius":502.7642385588692},{"acceleration":-4.834490913504388,"curvature":0.0018069651761656804,"pose":{"rotation":{"radians":2.4257456548511906},"translation":{"x":5.12410377205272,"y":6.136418110796549}},"time":0.9466031243562252,"velocity":0.8742663278579157,"position":1.484665996798241,"holonomicRotation":146.71280000000002,"angularVelocity":0.0017322603706153479,"angularAcceleration":-0.024954942063575125,"curveRadius":553.4140962926394},{"acceleration":-4.813513125406402,"curvature":0.0016310666546304382,"pose":{"rotation":{"radians":2.4257636350365495},"translation":{"x":5.116566764629686,"y":6.142973161121357}},"time":0.9588548660026311,"velocity":0.8152924086338523,"position":1.494654748755099,"holonomicRotation":146.7612,"angularVelocity":0.001467561582486264,"angularAcceleration":-0.021604992642554867,"curveRadius":613.0957292034008},{"acceleration":-4.7857260614592425,"curvature":0.0014611654470937621,"pose":{"rotation":{"radians":2.4257799901888295},"translation":{"x":5.108971526849673,"y":6.149578637096162}},"time":0.9722551393916774,"velocity":0.7511623710452149,"position":1.504720529886669,"holonomicRotation":146.8096,"angularVelocity":0.0012205088512160132,"angularAcceleration":-0.018436394847899017,"curveRadius":684.3851953856329},{"acceleration":-4.747140913529588,"curvature":0.0012970803017350306,"pose":{"rotation":{"radians":2.425794754636521},"translation":{"x":5.101317647536133,"y":6.156234914347822}},"time":0.9871632758912272,"velocity":0.6803913463237182,"position":1.5148638969507755,"holonomicRotation":146.858,"angularVelocity":0.00099036171905166,"angularAcceleration":-0.015437686136781963,"curveRadius":770.9622902008125},{"acceleration":-4.6898449151786785,"curvature":0.001138692466288043,"pose":{"rotation":{"radians":2.425807962189687},"translation":{"x":5.093604715512524,"y":6.162942368503192}},"time":1.0041829017973962,"velocity":0.6005719403094282,"position":1.525085406704584,"holonomicRotation":146.9064,"angularVelocity":0.0007760190052719519,"angularAcceleration":-0.012593855761660213,"curveRadius":878.2002424762161},{"acceleration":-4.595431967640678,"curvature":0.0009858183487382992,"pose":{"rotation":{"radians":2.425819646140417},"translation":{"x":5.085832319602301,"y":6.169701375189131}},"time":1.024488531100805,"velocity":0.5072588022854824,"position":1.5353856159046841,"holonomicRotation":146.9548,"angularVelocity":0.0005754045124852844,"angularAcceleration":-0.009879747620182846,"curveRadius":1014.3856637278574},{"acceleration":-4.407181227182845,"curvature":0.0008383058621769422,"pose":{"rotation":{"radians":2.4258298392658046},"translation":{"x":5.07800004862892,"y":6.1765123100324955}},"time":1.0511058617115465,"velocity":0.38995140250010285,"position":1.5457650813071517,"holonomicRotation":147.0032,"angularVelocity":0.0003829506999335961,"angularAcceleration":-0.007230394939529456,"curveRadius":1192.8820316288434},{"acceleration":-3.5287826970090874,"curvature":0.0008383058621769422,"pose":{"rotation":{"radians":2.4258385738285737},"translation":{"x":5.070107491415835,"y":6.183375548660142}},"time":1.115787476906196,"velocity":0.16170403798662386,"position":1.5562243596676235,"holonomicRotation":147.0516,"angularVelocity":0.00013503934221151533,"angularAcceleration":-0.003832794789926464,"curveRadius":1192.8820316288434}] \ No newline at end of file diff --git a/src/main/deploy/pathplanner/generatedJSON/Blue1(2).wpilib.json b/src/main/deploy/pathplanner/generatedJSON/Blue1(2).wpilib.json new file mode 100644 index 0000000..c54c2f0 --- /dev/null +++ b/src/main/deploy/pathplanner/generatedJSON/Blue1(2).wpilib.json @@ -0,0 +1 @@ +[{"acceleration":0.0,"curvature":0.34736921845213314,"pose":{"rotation":{"radians":2.0524528770930246},"translation":{"x":5.06,"y":6.19}},"time":0.0,"velocity":0,"position":0.0,"holonomicRotation":147.1,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":2.8787812704187496},{"acceleration":2.5000000000000004,"curvature":0.34736921845213314,"pose":{"rotation":{"radians":2.0524528770930246},"translation":{"x":5.054837457123343,"y":6.199876340437652}},"time":0.06676596111159534,"velocity":0.16691490277898838,"position":0.011144233907887656,"holonomicRotation":146.5116,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":2.8787812704187496},{"acceleration":8.55535052720389,"curvature":0.3479921420377856,"pose":{"rotation":{"radians":2.0563166257260925},"translation":{"x":5.049656723313958,"y":6.209694888763092}},"time":0.09433082329903059,"velocity":0.40274196102656507,"position":0.022245760560682337,"holonomicRotation":145.9232,"angularVelocity":0.14016934337618875,"angularAcceleration":5.085073250976798,"curveRadius":2.873628105922628},{"acceleration":5.767586945808878,"curvature":0.3486024220675352,"pose":{"rotation":{"radians":2.060172461240242},"translation":{"x":5.044458191050643,"y":6.219455794900254}},"time":0.11542043976875517,"velocity":0.5243781576694645,"position":0.03330469479103211,"holonomicRotation":145.3348,"angularVelocity":0.18283099266811562,"angularAcceleration":2.022874591065714,"curveRadius":2.868597395477271},{"acceleration":5.474084662374513,"curvature":0.3492000417640714,"pose":{"rotation":{"radians":2.064020230467272},"translation":{"x":5.0392422528122065,"y":6.229159208773062}},"time":0.1331482609842469,"velocity":0.6214217518825053,"position":0.04432114850782282,"holonomicRotation":144.7464,"angularVelocity":0.21704693319377427,"angularAcceleration":1.9300702612997098,"curveRadius":2.8636880882036837},{"acceleration":5.3458742056492605,"curvature":0.3497849858949489,"pose":{"rotation":{"radians":2.067859780853759},"translation":{"x":5.0340093010774485,"y":6.2388052803054475}},"time":0.14872152594119833,"velocity":0.7046744673136135,"position":0.05529523069569634,"holonomicRotation":144.158,"angularVelocity":0.24654755422836985,"angularAcceleration":1.8943118938862842,"curveRadius":2.858899153265345},{"acceleration":5.2733178543514505,"curvature":0.3503572409493468,"pose":{"rotation":{"radians":2.071690960466726},"translation":{"x":5.028759728325171,"y":6.2483941594213395}},"time":0.16276000419614903,"velocity":0.7787038253433696,"position":0.06622704741482616,"holonomicRotation":143.5696,"angularVelocity":0.2729056200671901,"angularAcceleration":1.8775586185436468,"curveRadius":2.854229578045387},{"acceleration":5.226505287240373,"curvature":0.3509167949246111,"pose":{"rotation":{"radians":2.0755136179989577},"translation":{"x":5.023493927034176,"y":6.2579259960446665}},"time":0.17563223143943418,"velocity":0.845980589088959,"position":0.07711670180098748,"holonomicRotation":142.9812,"angularVelocity":0.29696939464969974,"angularAcceleration":1.869433636285639,"curveRadius":2.849678369525842},{"acceleration":5.193761309164231,"curvature":0.35146363741148146,"pose":{"rotation":{"radians":2.079327602773388},"translation":{"x":5.018212289683268,"y":6.267400940099358}},"time":0.18757856387755117,"velocity":0.9080269882924646,"position":0.08796429406591143,"holonomicRotation":142.3928,"angularVelocity":0.3192598895256624,"angularAcceleration":1.8658860358548808,"curveRadius":2.8452445532202657},{"acceleration":5.16955921950467,"curvature":0.35199775915067616,"pose":{"rotation":{"radians":2.08313276474721},"translation":{"x":5.012915208751248,"y":6.276819141509342}},"time":0.19876611531940816,"velocity":0.9658616979923992,"position":0.09876992149792073,"holonomicRotation":141.8044,"angularVelocity":0.3401246460048084,"angularAcceleration":1.8649975901860714,"curveRadius":2.8409271763913133},{"acceleration":5.150937336259482,"curvature":0.3525191522612039,"pose":{"rotation":{"radians":2.0869289545135974},"translation":{"x":5.0076030767169195,"y":6.286180750198548}},"time":0.20931667727426284,"velocity":1.020206981484179,"position":0.10953367846284484,"holonomicRotation":141.21599999999998,"angularVelocity":0.35980924832545474,"angularAcceleration":1.865739702290338,"curveRadius":2.8367253058041975},{"acceleration":5.136163483944558,"curvature":0.3530278098742002,"pose":{"rotation":{"radians":2.0907160233041835},"translation":{"x":5.002276286059083,"y":6.295485916090905}},"time":0.21932228013151428,"velocity":1.0715973935144452,"position":0.12025565640521617,"holonomicRotation":140.6276,"angularVelocity":0.37849481381738725,"angularAcceleration":1.867510209881094,"curveRadius":2.8326380302909997},{"acceleration":5.124156181370395,"curvature":0.35352372636035023,"pose":{"rotation":{"radians":2.0944938229886354},"translation":{"x":4.996935229256546,"y":6.304734789110342}},"time":0.22885448988362705,"velocity":1.120441925037853,"position":0.130935943849738,"holonomicRotation":140.0392,"angularVelocity":0.39631940365292284,"angularAcceleration":1.8699326073458298,"curveRadius":2.828664458522623},{"acceleration":5.11420500704371,"curvature":0.35400689672128,"pose":{"rotation":{"radians":2.0982622060762752},"translation":{"x":4.991580298788106,"y":6.313927519180789}},"time":0.23797027243169597,"velocity":1.1670619057883087,"position":0.1415746264030391,"holonomicRotation":139.4508,"angularVelocity":0.41339106848683227,"angularAcceleration":1.8727591124391059,"curveRadius":2.8248037234916623},{"acceleration":5.105823885920438,"curvature":0.3544773169694589,"pose":{"rotation":{"radians":2.1020210257126006},"translation":{"x":4.986211887132567,"y":6.323064256226171}},"time":0.24671585823022388,"velocity":1.211715326654799,"position":0.15217178675568993,"holonomicRotation":138.86239999999998,"angularVelocity":0.42979621067328666,"angularAcceleration":1.8758197065788051,"curveRadius":2.8210549790585278},{"acceleration":5.098668940022714,"curvature":0.35493498369755744,"pose":{"rotation":{"radians":2.1057701356780334},"translation":{"x":4.980830386768734,"y":6.3321451501704225}},"time":0.255129382615569,"velocity":1.254613102114482,"position":0.16272750468450362,"holonomicRotation":138.274,"angularVelocity":0.445605170166625,"angularAcceleration":1.8789937212132823,"curveRadius":2.8174174029914925},{"acceleration":5.092489997889658,"curvature":0.35537989389219377,"pose":{"rotation":{"radians":2.1095093903853597},"translation":{"x":4.975436190175405,"y":6.341170350937469}},"time":0.2632427450510996,"velocity":1.2959303191666753,"position":0.17324185705509573,"holonomicRotation":137.6856,"angularVelocity":0.4608760839958367,"angularAcceleration":1.8821929810920568,"curveRadius":2.813890198029478},{"acceleration":5.087100692265149,"curvature":0.3558120451810469,"pose":{"rotation":{"radians":2.1132386448737583},"translation":{"x":4.970029689831387,"y":6.35014000845124}},"time":0.2710829524885095,"velocity":1.3358142438490255,"position":0.1837149178247189,"holonomicRotation":137.0972,"angularVelocity":0.47565763000151984,"angularAcceleration":1.885351391999196,"curveRadius":2.8104725895132994},{"acceleration":5.08235932761997,"curvature":0.35623143516601513,"pose":{"rotation":{"radians":2.1169577548046075},"translation":{"x":4.9646112782154805,"y":6.359054272635666}},"time":0.27867311176026016,"velocity":1.3743901606219286,"position":0.19414675804536632,"holonomicRotation":136.50879999999998,"angularVelocity":0.489991026234593,"angularAcceleration":1.8884183743574048,"curveRadius":2.8071638302609885},{"acceleration":5.078156246126512,"curvature":0.35663806186628055,"pose":{"rotation":{"radians":2.120666576454642},"translation":{"x":4.959181347806489,"y":6.367913293414674}},"time":0.2860331770037398,"velocity":1.4117657219100035,"position":0.2045374458671321,"holonomicRotation":135.9204,"angularVelocity":0.5039115180834028,"angularAcceleration":1.8913544090036598,"curveRadius":2.8039631966566274},{"acceleration":5.074405253815195,"curvature":0.3570319229227786,"pose":{"rotation":{"radians":2.124364966708362},"translation":{"x":4.953740291083212,"y":6.376717220712194}},"time":0.2931805222328665,"velocity":1.448034248091515,"position":0.21488704654184104,"holonomicRotation":135.332,"angularVelocity":0.5174495053979475,"angularAcceleration":1.8941280826026168,"curveRadius":2.800869994519474},{"acceleration":5.071037661400605,"curvature":0.35741301607168474,"pose":{"rotation":{"radians":2.128052783048764},"translation":{"x":4.948288500524456,"y":6.385466204452154}},"time":0.30013038661683633,"velocity":1.4832772721242526,"position":0.2251956224269293,"holonomicRotation":134.7436,"angularVelocity":0.5306314104355518,"angularAcceleration":1.8967139945937583,"curveRadius":2.7978835549722523},{"acceleration":5.06799805416196,"curvature":0.35778133842631604,"pose":{"rotation":{"radians":2.1317298835490983},"translation":{"x":4.942826368609023,"y":6.394160394558484}},"time":0.30689622545062156,"velocity":1.5175665301686496,"position":0.23546323298959707,"holonomicRotation":134.15519999999998,"angularVelocity":0.5434803563414516,"angularAcceleration":1.8990913353919339,"curveRadius":2.7950032396839135},{"acceleration":5.065241232386286,"curvature":0.3581368867709621,"pose":{"rotation":{"radians":2.1353961268601562},"translation":{"x":4.937354287815713,"y":6.402799940955113}},"time":0.31348999015037254,"velocity":1.5509655390024815,"position":0.24568993481120188,"holonomicRotation":133.5668,"angularVelocity":0.5560167033555767,"angularAcceleration":1.9012427020027782,"curveRadius":2.792228438171257},{"acceleration":5.062729961027937,"curvature":0.35847965713997687,"pose":{"rotation":{"radians":2.1390513721990496},"translation":{"x":4.93187265062333,"y":6.41138499356597}},"time":0.3199223540748046,"velocity":1.583530860562939,"position":0.2558757815919118,"holonomicRotation":132.9784,"angularVelocity":0.56825847881673,"angularAcceleration":1.9031534292789676,"curveRadius":2.789558570709987},{"acceleration":5.060433289304934,"curvature":0.35880964448328156,"pose":{"rotation":{"radians":2.1426954793359325},"translation":{"x":4.926381849510677,"y":6.419915702314983}},"time":0.3262028964651338,"velocity":1.6153131263498515,"position":0.2660208241556072,"holonomicRotation":132.39,"angularVelocity":0.580221724559034,"angularAcceleration":1.9048109221784941,"curveRadius":2.7869930905566673},{"acceleration":5.05832527866095,"curvature":0.35912684306651416,"pose":{"rotation":{"radians":2.1463283085791227},"translation":{"x":4.920882276956557,"y":6.428392217126082}},"time":0.3323402536287384,"velocity":1.6463578752346837,"position":0.2761251104550357,"holonomicRotation":131.80159999999998,"angularVelocity":0.5919207806143928,"angularAcceleration":1.906204208667503,"curveRadius":2.7845314804685577},{"acceleration":5.05638402777455,"curvature":0.35943124556790657,"pose":{"rotation":{"radians":2.14994972075989},"translation":{"x":4.915374325439772,"y":6.436814687923196}},"time":0.3383422442304253,"velocity":1.6767062446479062,"position":0.2861886855772021,"holonomicRotation":131.21319999999997,"angularVelocity":0.6033685190625523,"angularAcceleration":1.907323621090321,"curveRadius":2.7821732593669912},{"acceleration":5.054590916671239,"curvature":0.35972284327303355,"pose":{"rotation":{"radians":2.1535595772149745},"translation":{"x":4.909858387439123,"y":6.445183264630253}},"time":0.34421597391696485,"velocity":1.7063955453684712,"position":0.29621159174901174,"holonomicRotation":130.6248,"angularVelocity":0.6145765378609583,"angularAcceleration":1.9081604698443588,"curveRadius":2.7799179804686163},{"acceleration":5.052930014597589,"curvature":0.36000162593649854,"pose":{"rotation":{"radians":2.157157739768438},"translation":{"x":4.904334855433414,"y":6.453498097171183}},"time":0.3499679232976335,"velocity":1.7354597430364977,"position":0.3061938683431459,"holonomicRotation":130.0364,"angularVelocity":0.6255553231320464,"angularAcceleration":1.9087068651866068,"curveRadius":2.7777652320281248},{"acceleration":5.051387611674335,"curvature":0.3602675814011176,"pose":{"rotation":{"radians":2.160744070712398},"translation":{"x":4.898804121901449,"y":6.461759335469914}},"time":0.35560402240929595,"velocity":1.7639298642673182,"position":0.3161355518841778,"holonomicRotation":129.44799999999998,"angularVelocity":0.6363143856961476,"angularAcceleration":1.9089555295147442,"curveRadius":2.7757146399653765},{"acceleration":5.049951845177278,"curvature":0.3605206953148552,"pose":{"rotation":{"radians":2.164318432786227},"translation":{"x":4.893266579322029,"y":6.469967129450376}},"time":0.3611297141221848,"velocity":1.7918343413287021,"position":0.3260366760549275,"holonomicRotation":128.85959999999997,"angularVelocity":0.6468623766128301,"angularAcceleration":1.9088996391309567,"curveRadius":2.7737658697420002},{"acceleration":5.048612398811863,"curvature":0.36076095099379013,"pose":{"rotation":{"radians":2.167880689154323},"translation":{"x":4.887722620173956,"y":6.4781216290364965}},"time":0.36655000843161256,"velocity":1.8191993063844885,"position":0.33589727170303824,"holonomicRotation":128.2712,"angularVelocity":0.6572071855766509,"angularAcceleration":1.9085327056554224,"curveRadius":2.771918627127727},{"acceleration":5.0473602589508415,"curvature":0.36098832944403336,"pose":{"rotation":{"radians":2.171430703381813},"translation":{"x":4.8821726369360325,"y":6.486222984152207}},"time":0.3718695291888247,"velocity":1.8460488440511051,"position":0.3457173668477956,"holonomicRotation":127.68279999999999,"angularVelocity":0.6673560250097618,"angularAcceleration":1.907848450323492,"curveRadius":2.770172657770193},{"acceleration":5.046187515530748,"curvature":0.36120280856341386,"pose":{"rotation":{"radians":2.174968339411241},"translation":{"x":4.876617022087063,"y":6.494271344721434}},"time":0.3770925545205864,"velocity":1.8724052092735417,"position":0.3554969866871538,"holonomicRotation":127.09439999999998,"angularVelocity":0.6773155029356734,"angularAcceleration":1.9068408237170962,"curveRadius":2.768527753084835},{"acceleration":5.045087198449339,"curvature":0.36140436350436,"pose":{"rotation":{"radians":2.178493461534807},"translation":{"x":4.8710561681058495,"y":6.502266860668108}},"time":0.38222305195004214,"velocity":1.8982890161765662,"position":0.36523615360501177,"holonomicRotation":126.50599999999999,"angularVelocity":0.6870916849752028,"angularAcceleration":1.905503739930028,"curveRadius":2.7669837472450327},{"acceleration":5.044053142218438,"curvature":0.3615929657571626,"pose":{"rotation":{"radians":2.1820059343676306},"translation":{"x":4.865490467471193,"y":6.510209681916157}},"time":0.3872647090446966,"velocity":1.923719402486846,"position":0.37493488717868406,"holonomicRotation":125.91759999999998,"angularVelocity":0.6966901490678356,"angularAcceleration":1.9038312031989888,"curveRadius":2.765540524014443},{"acceleration":5.043079873323441,"curvature":0.36176858349978036,"pose":{"rotation":{"radians":2.1855056228175638},"translation":{"x":4.859920312661897,"y":6.518099958389509}},"time":0.39222096026938835,"velocity":1.9487141732852236,"position":0.3845932041866031,"holonomicRotation":125.32919999999999,"angularVelocity":0.706116032314499,"angularAcceleration":1.9018170829808492,"curveRadius":2.7641980138958284},{"acceleration":5.042162516058042,"curvature":0.36193118107022115,"pose":{"rotation":{"radians":2.188992392055297},"translation":{"x":4.854346096156764,"y":6.525937840012097}},"time":0.3970950106038798,"velocity":1.9732899271831765,"position":0.39421111861623886,"holonomicRotation":124.74079999999998,"angularVelocity":0.7153740725775596,"angularAcceleration":1.899455202082254,"curveRadius":2.7629561980347366},{"acceleration":5.041296713321846,"curvature":0.3620807184498217,"pose":{"rotation":{"radians":2.1924661074819713},"translation":{"x":4.8487682104345975,"y":6.533723476707846}},"time":0.40188985638964003,"velocity":1.9974621674838147,"position":0.4037886416722141,"holonomicRotation":124.15239999999997,"angularVelocity":0.7244686444328774,"angularAcceleration":1.896739178208181,"curveRadius":2.761815112059283},{"acceleration":5.0404785596365755,"curvature":0.3622171512487963,"pose":{"rotation":{"radians":2.1959266346951285},"translation":{"x":4.843187047974198,"y":6.541457018400686}},"time":0.4066083037935409,"velocity":2.02124540045795,"position":0.4133257817846515,"holonomicRotation":123.56399999999998,"angularVelocity":0.7334037908944869,"angularAcceleration":1.8936624056088025,"curveRadius":2.7607748461174593},{"acceleration":5.039704544395759,"curvature":0.3623404304287617,"pose":{"rotation":{"radians":2.199373839453143},"translation":{"x":4.8376030012543705,"y":6.549138615014546}},"time":0.4112529852135816,"velocity":2.0446532225177996,"position":0.4228225446177063,"holonomicRotation":122.97559999999999,"angularVelocity":0.7421832513938724,"angularAcceleration":1.8902180161386712,"curveRadius":2.7598355469652898},{"acceleration":5.038971503352946,"curvature":0.362450501692986,"pose":{"rotation":{"radians":2.2028075876388957},"translation":{"x":4.8320164627539155,"y":6.556768416473357}},"time":0.4158263739006053,"velocity":2.0676983977854686,"position":0.43227893307831533,"holonomicRotation":122.38719999999998,"angularVelocity":0.7508104866519368,"angularAcceleration":1.8863988714851516,"curveRadius":2.7589974226247613},{"acceleration":5.038276577180105,"curvature":0.36254730534612617,"pose":{"rotation":{"radians":2.206227745220608},"translation":{"x":4.826427824951637,"y":6.564346572701044}},"time":0.42033079702783327,"velocity":2.0903929273210897,"position":0.44169494732513426,"holonomicRotation":121.79879999999997,"angularVelocity":0.7592887002640633,"angularAcceleration":1.8821974252103388,"curveRadius":2.7582607435057165},{"acceleration":5.037617175830761,"curvature":0.3626307760589619,"pose":{"rotation":{"radians":2.2096341782109588},"translation":{"x":4.820837480326337,"y":6.57187323362154}},"time":0.42476844740526,"velocity":2.1127481110827464,"position":0.4510705847776882,"holonomicRotation":121.21039999999998,"angularVelocity":0.7676208580284802,"angularAcceleration":1.8776057273012556,"curveRadius":2.7576258443034223},{"acceleration":5.0369909477328685,"curvature":0.3627008421037585,"pose":{"rotation":{"radians":2.2130267526262597},"translation":{"x":4.815245821356818,"y":6.579348549158771}},"time":0.4291413940070098,"velocity":2.1347746035306794,"position":0.46040584012569946,"holonomicRotation":120.62199999999997,"angularVelocity":0.775809705506906,"angularAcceleration":1.8726154751464448,"curveRadius":2.7570931299738426},{"acceleration":5.0363957532349,"curvature":0.3627574253545672,"pose":{"rotation":{"radians":2.216405334441107},"translation":{"x":4.809653240521882,"y":6.586772669236667}},"time":0.43345159145566253,"velocity":2.156482463656678,"position":0.46970070533861685,"holonomicRotation":120.03359999999998,"angularVelocity":0.7838577826413899,"angularAcceleration":1.8672177389459481,"curveRadius":2.756663075945524},{"acceleration":5.035829641413222,"curvature":0.3628004409101585,"pose":{"rotation":{"radians":2.219769789542969},"translation":{"x":4.804060130300333,"y":6.594145743779158}},"time":0.4377008885873237,"velocity":2.1778812001074694,"position":0.4789551696753323,"holonomicRotation":119.44519999999997,"angularVelocity":0.7917674376766018,"angularAcceleration":1.8614031427168762,"curveRadius":2.7563362312661392},{"acceleration":5.035290829930902,"curvature":0.3628297962546063,"pose":{"rotation":{"radians":2.2231199836853173},"translation":{"x":4.798466883170973,"y":6.601467922710173}},"time":0.44189103620420905,"velocity":2.198979811978829,"position":0.4881692196940744,"holonomicRotation":118.85679999999998,"angularVelocity":0.7995408392887239,"angularAcceleration":1.8551617563059046,"curveRadius":2.756113225326941},{"acceleration":5.034777687435674,"curvature":0.3628453912601201,"pose":{"rotation":{"radians":2.2264557824370326},"translation":{"x":4.792873891612604,"y":6.608739355953638}},"time":0.44602369410716164,"velocity":2.2197868257784195,"position":0.4973428392624976,"holonomicRotation":118.26839999999997,"angularVelocity":0.8071799868389866,"angularAcceleration":1.84848292059329,"curveRadius":2.7559947682596038},{"acceleration":5.034288718086054,"curvature":0.3628471175461432,"pose":{"rotation":{"radians":2.229777051130787},"translation":{"x":4.787281548104029,"y":6.6159601934334855}},"time":0.4501004374883201,"velocity":2.2403103289887176,"position":0.5064760095679434,"holonomicRotation":117.67999999999998,"angularVelocity":0.8146867200678897,"angularAcceleration":1.8413553483883658,"curveRadius":2.7559816563041326},{"acceleration":5.033822547949797,"curvature":0.36283485810599386,"pose":{"rotation":{"radians":2.2330836548099895},"translation":{"x":4.781690245124051,"y":6.623130585073643}},"time":0.4541227627538054,"velocity":2.2605580006053057,"position":0.515568709127873,"holonomicRotation":117.09159999999997,"angularVelocity":0.8220627276405738,"angularAcceleration":1.8337670590630788,"curveRadius":2.756074775229763},{"acceleration":5.033377913102329,"curvature":0.3628084867092813,"pose":{"rotation":{"radians":2.23637545817276},"translation":{"x":4.776100375151471,"y":6.630250680798039}},"time":0.4580920928374501,"velocity":2.2805371389781355,"position":0.5246209138004879,"holonomicRotation":116.50319999999996,"angularVelocity":0.8293095543588256,"angularAcceleration":1.8257052362845299,"curveRadius":2.7562751055525907},{"acceleration":5.032953648931624,"curvature":0.3627678674801891,"pose":{"rotation":{"radians":2.2396523255134357},"translation":{"x":4.770512330665093,"y":6.637320630530603}},"time":0.4620097820589981,"velocity":2.3002546872411056,"position":0.5336325967955077,"holonomicRotation":115.91479999999997,"angularVelocity":0.8364286076221704,"angularAcceleration":1.8171562012088,"curveRadius":2.756583726519302},{"acceleration":5.032548680867031,"curvature":0.362712854348891,"pose":{"rotation":{"radians":2.242914120663076},"translation":{"x":4.764926504143719,"y":6.644340584195263}},"time":0.46587712057370767,"velocity":2.3197172565817734,"position":0.5426037286851227,"holonomicRotation":115.32639999999998,"angularVelocity":0.8434211634781241,"angularAcceleration":1.8081054527182685,"curveRadius":2.7570018211654195},{"acceleration":5.0321620159447304,"curvature":0.36264329047326904,"pose":{"rotation":{"radians":2.2461607069265312},"translation":{"x":4.759343288066153,"y":6.65131069171595}},"time":0.46969533845466777,"velocity":2.338931147570942,"position":0.5515342774151126,"holonomicRotation":114.73799999999997,"angularVelocity":0.8502883713485365,"angularAcceleration":1.798537455040577,"curveRadius":2.7575306817201723},{"acceleration":5.031792735507163,"curvature":0.36255900768391724,"pose":{"rotation":{"radians":2.2493919470179033},"translation":{"x":4.753763074911195,"y":6.658231103016592}},"time":0.4734656094442879,"velocity":2.3579023697474057,"position":0.5604242083161278,"holonomicRotation":114.14959999999996,"angularVelocity":0.8570312585668179,"angularAcceleration":1.788435695164925,"curveRadius":2.7581717149662173},{"acceleration":5.03143998848203,"curvature":0.36245982589942155,"pose":{"rotation":{"radians":2.2526077029926643},"translation":{"x":4.748186257157649,"y":6.665101968021118}},"time":0.47718905440721177,"velocity":2.376636659628773,"position":0.5692734841151228,"holonomicRotation":113.56119999999997,"angularVelocity":0.8636507338719401,"angularAcceleration":1.7777825027724279,"curveRadius":2.758926447968577},{"acceleration":5.031102985536488,"curvature":0.3623455524541318,"pose":{"rotation":{"radians":2.25580783617829},"translation":{"x":4.742613227284318,"y":6.671923436653457}},"time":0.4808667445132634,"velocity":2.3951394973012072,"position":0.5780820649469609,"holonomicRotation":112.97279999999998,"angularVelocity":0.8701475908369565,"angularAcceleration":1.7665591112002041,"curveRadius":2.759796534625844},{"acceleration":5.030780993755029,"curvature":0.3622159814450763,"pose":{"rotation":{"radians":2.258992207101237},"translation":{"x":4.737044377770005,"y":6.678695658837537}},"time":0.48449970417582733,"velocity":2.4134161217227126,"position":0.586849908366161,"holonomicRotation":112.38439999999997,"angularVelocity":0.8765225102168487,"angularAcceleration":1.7547454340280637,"curveRadius":2.760783762247201},{"acceleration":5.030473331918316,"curvature":0.3620708930432059,"pose":{"rotation":{"radians":2.2621606754122796},"translation":{"x":4.73148010109351,"y":6.685418784497289}},"time":0.4880889137683045,"velocity":2.4314715448603343,"position":0.595576969358809,"holonomicRotation":111.79599999999996,"angularVelocity":0.8827760623629871,"angularAcceleration":1.7423201362343466,"curveRadius":2.761890058587698},{"acceleration":5.030179366129024,"curvature":0.36191005282523303,"pose":{"rotation":{"radians":2.265313099808014},"translation":{"x":4.725920789733638,"y":6.69209296355664}},"time":0.49163531213882605,"velocity":2.4493105647678055,"position":0.6042632003546028,"holonomicRotation":111.20759999999997,"angularVelocity":0.8889087086037026,"angularAcceleration":1.7292603932179234,"curveRadius":2.7631174989297733},{"acceleration":5.029898506141586,"curvature":0.36173321095016586,"pose":{"rotation":{"radians":2.2684493379501722},"translation":{"x":4.720366836169191,"y":6.698718345939521}},"time":0.49513979894129345,"velocity":2.466937777700329,"position":0.6129085512390618,"holonomicRotation":110.61919999999998,"angularVelocity":0.8949208026550118,"angularAcceleration":1.7155419295847472,"curveRadius":2.7644683145716606},{"acceleration":5.02963020164026,"curvature":0.36154010128758746,"pose":{"rotation":{"radians":2.2715692463817696},"translation":{"x":4.714818632878971,"y":6.705295081569858}},"time":0.4986032367989081,"velocity":2.484357589350492,"position":0.6215129693658706,"holonomicRotation":110.03079999999997,"angularVelocity":0.900812591378821,"angularAcceleration":1.7011388585637648,"curveRadius":2.7659449019309448},{"acceleration":5.029373939416149,"curvature":0.3613304407399959,"pose":{"rotation":{"radians":2.2746726804392803},"translation":{"x":4.70927657234178,"y":6.711823320371582}},"time":0.5020264533147113,"velocity":2.5015742252840516,"position":0.6300763995693706,"holonomicRotation":109.44239999999996,"angularVelocity":0.9065842149287844,"angularAcceleration":1.6860235171567064,"curveRadius":2.7675498304322894},{"acceleration":5.029129240184487,"curvature":0.36110392846954914,"pose":{"rotation":{"radians":2.2777594941631727},"translation":{"x":4.703741047036423,"y":6.718303212268623}},"time":0.5054102429421823,"velocity":2.518591740642199,"position":0.6385987841771897,"holonomicRotation":108.85399999999997,"angularVelocity":0.9122357072178465,"angularAcceleration":1.6701665621234294,"curveRadius":2.769285851411963},{"acceleration":5.028895656321751,"curvature":0.3608602443846623,"pose":{"rotation":{"radians":2.280829540204652},"translation":{"x":4.6982124494417,"y":6.7247349071849065}},"time":0.508755368727646,"velocity":2.5354140291745675,"position":0.6470800630230081,"holonomicRotation":108.26559999999998,"angularVelocity":0.9177669954355943,"angularAcceleration":1.6535366896467536,"curveRadius":2.7711559130188936},{"acceleration":5.028672769243979,"curvature":0.3605990490657589,"pose":{"rotation":{"radians":2.2838826697263848},"translation":{"x":4.692691172036414,"y":6.7311185550443655}},"time":0.5120625639350999,"velocity":2.5520448316568647,"position":0.655520173459471,"holonomicRotation":107.67719999999997,"angularVelocity":0.9231778985563561,"angularAcceleration":1.6361003150242464,"curveRadius":2.7731631644365202},{"acceleration":5.028460187538437,"curvature":0.3603199817537461,"pose":{"rotation":{"radians":2.2869187323043523},"translation":{"x":4.68717760729937,"y":6.737454305770926}},"time":0.5153325335630261,"velocity":2.5684877437453517,"position":0.6639190503712191,"holonomicRotation":107.08879999999996,"angularVelocity":0.9284681276666548,"angularAcceleration":1.6178220938564487,"curveRadius":2.7753109753525442},{"acceleration":5.028257544814884,"curvature":0.36002266037863495,"pose":{"rotation":{"radians":2.2899375758214355},"translation":{"x":4.681672147709368,"y":6.743742309288519}},"time":0.5185659557618757,"velocity":2.584746223312289,"position":0.6722766261880697,"holonomicRotation":106.50039999999997,"angularVelocity":0.9336372831724,"angularAcceleration":1.598663950406594,"curveRadius":2.7776029401824385},{"acceleration":5.028064498122006,"curvature":0.3597066793326218,"pose":{"rotation":{"radians":2.2929390463596873},"translation":{"x":4.676175185745211,"y":6.749982715521073}},"time":0.5217634831600666,"velocity":2.600823597304905,"position":0.6805928308983136,"holonomicRotation":105.91199999999998,"angularVelocity":0.9386848537873044,"angularAcceleration":1.5785855713887444,"curveRadius":2.7800429001077767},{"acceleration":5.0278807261694505,"curvature":0.3593716091966896,"pose":{"rotation":{"radians":2.2959229880873613},"translation":{"x":4.670687113885702,"y":6.756175674392516}},"time":0.5249257441056395,"velocity":2.6167230681642697,"position":0.6888675920621492,"holonomicRotation":105.32359999999997,"angularVelocity":0.9436102140310257,"angularAcceleration":1.557543899284064,"curveRadius":2.7826349505886667},{"acceleration":1.9749036283587356,"curvature":0.35901699481021887,"pose":{"rotation":{"radians":2.2988892431424954},"translation":{"x":4.665208324609644,"y":6.762321335826777}},"time":0.5280647021496963,"velocity":2.622922207794743,"position":0.6971008348252415,"holonomicRotation":104.73519999999996,"angularVelocity":0.9449807909189568,"angularAcceleration":0.43663434448450533,"curveRadius":2.7853834622191442},{"acceleration":-3.044428394791427,"curvature":0.3586423545443229,"pose":{"rotation":{"radians":2.301837651511359},"translation":{"x":4.659739210395839,"y":6.7684198497477865}},"time":0.5311992056946863,"velocity":2.613379436198801,"position":0.7052924819324107,"holonomicRotation":104.14679999999996,"angularVelocity":0.940630095498253,"angularAcceleration":-1.3880014357162367,"curveRadius":2.7882930929074488},{"acceleration":-4.997707720032013,"curvature":0.3582471783991952,"pose":{"rotation":{"radians":2.3047680509026414},"translation":{"x":4.654280163723088,"y":6.774471366079473}},"time":0.5343365859412158,"velocity":2.5976997267200446,"position":0.7134424537414373,"holonomicRotation":103.55839999999996,"angularVelocity":0.9340274882280754,"angularAcceleration":-2.1044969851777657,"curveRadius":2.7913688098492124},{"acceleration":-4.997693331100764,"curvature":0.35783092676874406,"pose":{"rotation":{"radians":2.3076802766166686},"translation":{"x":4.6488315770701965,"y":6.780476034745762}},"time":0.537476863620078,"velocity":2.5820055819065906,"position":0.7215506682369961,"holonomicRotation":102.96999999999997,"angularVelocity":0.9273784078491054,"angularAcceleration":-2.1173542784850654,"curveRadius":2.794615907099253},{"acceleration":-4.997679273410633,"curvature":0.3573930292120417,"pose":{"rotation":{"radians":2.310574161408967},"translation":{"x":4.643393842915966,"y":6.786434005670588}},"time":0.5406200590978961,"velocity":2.5662968990148207,"position":0.7296170410447183,"holonomicRotation":102.38159999999996,"angularVelocity":0.9206824114888112,"angularAcceleration":-2.13031496372035,"curveRadius":2.7980400239051635},{"acceleration":-4.9976655495419875,"curvature":0.3569328819455178,"pose":{"rotation":{"radians":2.313449535351372},"translation":{"x":4.637967353739198,"y":6.792345428777877}},"time":0.5437661923726159,"velocity":2.550573577133486,"position":0.737641485445359,"holonomicRotation":101.79319999999996,"angularVelocity":0.9139390138077,"angularAcceleration":-2.1433922508294856,"curveRadius":2.8016471739710433},{"acceleration":-4.997652162323476,"curvature":0.3564498472216723,"pose":{"rotation":{"radians":2.3163062256823728},"translation":{"x":4.632552502018696,"y":6.798210453991558}},"time":0.5469152830688585,"velocity":2.5348355172060564,"position":0.7456239123890979,"holonomicRotation":101.20479999999996,"angularVelocity":0.9071476837454405,"angularAcceleration":-2.1566003387462795,"curveRadius":2.8054437610071714},{"acceleration":-4.997639114517182,"curvature":0.3559432508297731,"pose":{"rotation":{"radians":2.319144056657459},"translation":{"x":4.627149680233263,"y":6.804029231235561}},"time":0.5500673504331217,"velocity":2.5190826220548215,"position":0.7535642305099595,"holonomicRotation":100.61639999999997,"angularVelocity":0.9003078447054033,"angularAcceleration":-2.169953319394258,"curveRadius":2.809436610102327},{"acceleration":-4.997626409096481,"curvature":0.35541238028296485,"pose":{"rotation":{"radians":2.3219628493893376},"translation":{"x":4.621759280861701,"y":6.809801910433814}},"time":0.5532224133288166,"velocity":2.5033147964049363,"position":0.7614623461403407,"holonomicRotation":100.02799999999996,"angularVelocity":0.8934188715302815,"angularAcceleration":-2.18346619476961,"curveRadius":2.813632995012275},{"acceleration":-4.997614049063161,"curvature":0.3548564828096748,"pose":{"rotation":{"radians":2.3247624216839506},"translation":{"x":4.6163816963828115,"y":6.815528641510246}},"time":0.5563804902311421,"velocity":2.4875319469098525,"position":0.7693181633256735,"holonomicRotation":99.43959999999996,"angularVelocity":0.8864800893706919,"angularAcceleration":-2.197154272741163,"curveRadius":2.8180406683914074},{"acceleration":-4.997602037500323,"curvature":0.3542747635437459,"pose":{"rotation":{"radians":2.3275425878687015},"translation":{"x":4.611017319275399,"y":6.821209574388787}},"time":0.5595415992217752,"velocity":2.471733982177504,"position":0.777131583839188,"holonomicRotation":98.85119999999996,"angularVelocity":0.8794907714314836,"angularAcceleration":-2.2110335201725,"curveRadius":2.8226678919976753},{"acceleration":-4.997590377739308,"curvature":0.35366638255369287,"pose":{"rotation":{"radians":2.33030315861529},"translation":{"x":4.605666542018265,"y":6.826844858993365}},"time":0.5627057579833818,"velocity":2.455920812796859,"position":0.7849025071968114,"holonomicRotation":98.26279999999997,"angularVelocity":0.8724501374851273,"angularAcceleration":-2.225120316902539,"curveRadius":2.8275234778589176},{"acceleration":-4.997579073032847,"curvature":0.353030453185726,"pose":{"rotation":{"radians":2.3330439407531625},"translation":{"x":4.600329757090213,"y":6.8324346452479086}},"time":0.5658729837939255,"velocity":2.4400923513665167,"position":0.7926308306721696,"holonomicRotation":97.67439999999996,"angularVelocity":0.8653573511394189,"angularAcceleration":-2.2394318466642598,"curveRadius":2.8326168209457823},{"acceleration":-4.997568126949781,"curvature":0.35236603901484276,"pose":{"rotation":{"radians":2.335764737077484},"translation":{"x":4.5950073569700445,"y":6.837979083076348}},"time":0.5690432935207742,"velocity":2.4242485125230586,"position":0.80031644931172,"holonomicRotation":97.08599999999996,"angularVelocity":0.8582115183509551,"angularAcceleration":-2.253985699866218,"curveRadius":2.837957945084137},{"acceleration":-4.997557543100391,"curvature":0.3516721513202105,"pose":{"rotation":{"radians":2.3384653461478493},"translation":{"x":4.589699734136562,"y":6.843478322402612}},"time":0.5722167036145871,"velocity":2.408389212971373,"position":0.8079592559499934,"holonomicRotation":96.49759999999996,"angularVelocity":0.8510116847584502,"angularAcceleration":-2.268800243164974,"curveRadius":2.843557547124233},{"acceleration":-4.997547325221169,"curvature":0.3509477464375958,"pose":{"rotation":{"radians":2.3411455620787605},"translation":{"x":4.584407281068569,"y":6.848932513150629}},"time":0.5753932301029742,"velocity":2.39251437151584,"position":0.8155591412249602,"holonomicRotation":95.90919999999996,"angularVelocity":0.8437568333554465,"angularAcceleration":-2.283894508522584,"curveRadius":2.849427044768946},{"acceleration":-4.997537477240409,"curvature":0.3501917221946632,"pose":{"rotation":{"radians":2.343805174322206},"translation":{"x":4.579130390244867,"y":6.854341805244328}},"time":0.5785728885839184,"velocity":2.376623909092496,"position":0.8231159935935211,"holonomicRotation":95.32079999999996,"angularVelocity":0.8364458822810005,"angularAcceleration":-2.299288152567534,"curveRadius":2.8555786348488383},{"acceleration":-4.997528003241023,"curvature":0.3494029152948679,"pose":{"rotation":{"radians":2.3464439674392557},"translation":{"x":4.573869454144259,"y":6.859706348607639}},"time":0.581755694218942,"velocity":2.360717748802592,"position":0.8306296993471102,"holonomicRotation":94.73239999999996,"angularVelocity":0.8290776816567824,"angularAcceleration":-2.3150017528995055,"curveRadius":2.8620253473159507},{"acceleration":-4.9975189074856035,"curvature":0.3485800975306895,"pose":{"rotation":{"radians":2.3490617208646354},"translation":{"x":4.568624865245549,"y":6.8650262931644885}},"time":0.5849416617260098,"velocity":2.344795815947386,"position":0.838100142627427,"holonomicRotation":94.14399999999995,"angularVelocity":0.8216510116856108,"angularAcceleration":-2.331056407416639,"curveRadius":2.868781112530266},{"acceleration":-4.997510194404676,"curvature":0.3477219721949762,"pose":{"rotation":{"radians":2.3516582086578395},"translation":{"x":4.563397016027537,"y":6.870301788838807}},"time":0.5881308053721562,"velocity":2.3288580380643484,"position":0.845527205442297,"holonomicRotation":93.55559999999996,"angularVelocity":0.8141645787393562,"angularAcceleration":-2.347474362059796,"curveRadius":2.8758608312484655},{"acceleration":-4.997501868605297,"curvature":0.3468271704815326,"pose":{"rotation":{"radians":2.354233199245824},"translation":{"x":4.558186298969027,"y":6.875532985554526}},"time":0.5913231389658157,"velocity":2.312904344964824,"position":0.8529107676816491,"holonomicRotation":92.96719999999996,"angularVelocity":0.8066170130524588,"angularAcceleration":-2.3642785020613886,"curveRadius":2.8832804494861417},{"acceleration":-4.997493934900544,"curvature":0.3458942469142283,"pose":{"rotation":{"radians":2.3567864551549436},"translation":{"x":4.552993106548822,"y":6.88072003323557}},"time":0.5945186758488471,"velocity":2.2969346687731234,"position":0.8602507071336272,"holonomicRotation":92.37879999999996,"angularVelocity":0.7990068656936763,"angularAcceleration":-2.3814925745946014,"curveRadius":2.8910570468319206},{"acceleration":-4.997486398366737,"curvature":0.34492167550636615,"pose":{"rotation":{"radians":2.3593177327273214},"translation":{"x":4.547817831245723,"y":6.885863081805871}},"time":0.5977174288882382,"velocity":2.280948943967032,"position":0.8675468995008376,"holonomicRotation":91.79039999999995,"angularVelocity":0.791332604051125,"angularAcceleration":-2.399141649275959,"curveRadius":2.899208924843412},{"acceleration":-4.99747926420153,"curvature":0.3439078447483928,"pose":{"rotation":{"radians":2.361826781829352},"translation":{"x":4.542660865538534,"y":6.890962281189356}},"time":0.6009194104674644,"velocity":2.2649471074204937,"position":0.8747992184167198,"holonomicRotation":91.20199999999996,"angularVelocity":0.7835926097479513,"angularAcceleration":-2.4172513525340458,"curveRadius":2.907755712090872},{"acceleration":-4.997472537946694,"curvature":0.34285105284436695,"pose":{"rotation":{"radians":2.364313345543488},"translation":{"x":4.5375226019060575,"y":6.896017781309955}},"time":0.6041246324774963,"velocity":2.2489290984473373,"position":0.8820075354620642,"holonomicRotation":90.61359999999996,"angularVelocity":0.7757851738049629,"angularAcceleration":-2.435848723911291,"curveRadius":2.9167184749872646},{"acceleration":-4.997466225298032,"curvature":0.3417495025328719,"pose":{"rotation":{"radians":2.366777159848054},"translation":{"x":4.5324034328270955,"y":6.901029732091597}},"time":0.6073331063074292,"velocity":2.232894858847495,"position":0.8891717201816682,"holonomicRotation":90.02519999999996,"angularVelocity":0.7679084933091541,"angularAcceleration":-2.4549617398541863,"curveRadius":2.9261198409610354},{"acceleration":-4.997460332344864,"curvature":0.340601295219998,"pose":{"rotation":{"radians":2.3692179532813222},"translation":{"x":4.52730375078045,"y":6.905998283458213}},"time":0.6105448428347182,"velocity":2.216844332954425,"position":0.8962916401011316,"holonomicRotation":89.43679999999995,"angularVelocity":0.7599606669257715,"angularAcceleration":-2.474619669407103,"curveRadius":2.935984137564977},{"acceleration":-4.997454865305761,"curvature":0.33940442503783724,"pose":{"rotation":{"radians":2.3716354465905756},"translation":{"x":4.522223948244926,"y":6.910923585333728}},"time":0.6137598524149975,"velocity":2.2007774676854535,"position":0.9033671607438032,"holonomicRotation":88.84839999999996,"angularVelocity":0.7519396906566324,"angularAcceleration":-2.494852991524293,"curveRadius":2.94633754373862},{"acceleration":-4.997449830731194,"curvature":0.3381567727850926,"pose":{"rotation":{"radians":2.3740293523643947},"translation":{"x":4.517164417699322,"y":6.915805787642072}},"time":0.616978144871469,"velocity":2.184694212593617,"position":0.91039814564789,"holonomicRotation":88.25999999999996,"angularVelocity":0.743843453072582,"angularAcceleration":-2.515693552887086,"curveRadius":2.957208255105764},{"acceleration":-4.997445235585527,"curvature":0.3368560990263358,"pose":{"rotation":{"radians":2.3763993746473937},"translation":{"x":4.512125551622446,"y":6.9206450403071775}},"time":0.6201997294838253,"velocity":2.168594519921561,"position":0.9173844563837096,"holonomicRotation":87.67159999999996,"angularVelocity":0.7356697303273692,"angularAcceleration":-2.537174629485972,"curveRadius":2.968626671419771},{"acceleration":-4.997441087049233,"curvature":0.3355000361774013,"pose":{"rotation":{"radians":2.3787452085392826},"translation":{"x":4.507107742493095,"y":6.925441493252968}},"time":0.6234246149766957,"velocity":2.1524783446584617,"position":0.9243259525711163,"holonomicRotation":87.08319999999995,"angularVelocity":0.7274161817761053,"angularAcceleration":-2.559330732675905,"curveRadius":2.980625610040868},{"acceleration":-4.99743739264724,"curvature":0.3340860819357644,"pose":{"rotation":{"radians":2.3810665397681037},"translation":{"x":4.502111382790075,"y":6.930195296403378}},"time":0.6266528095075835,"velocity":2.1363456445990634,"position":0.931222491897097,"holonomicRotation":86.49479999999994,"angularVelocity":0.719080342467038,"angularAcceleration":-2.58219857239357,"curveRadius":2.99324052712939},{"acceleration":-4.997434160316324,"curvature":0.33261158987123407,"pose":{"rotation":{"radians":2.383363044252082},"translation":{"x":4.497136864992188,"y":6.934906599682332}},"time":0.6298843206542692,"velocity":2.120196380405173,"position":0.9380739301335391,"holonomicRotation":85.90639999999995,"angularVelocity":0.7106596201389423,"angularAcceleration":-2.6058156527580003,"curveRadius":3.0065097863460983},{"acceleration":-4.997431398391549,"curvature":0.33107376121745946,"pose":{"rotation":{"radians":2.385634387631071},"translation":{"x":4.492184581578236,"y":6.9395755530137615}},"time":0.6331191554016548,"velocity":2.104030515669981,"position":0.9448801211551878,"holonomicRotation":85.31799999999996,"angularVelocity":0.7021512863445283,"angularAcceleration":-2.6302220851593012,"curveRadius":3.0204749428728337},{"acceleration":-4.997429115532255,"curvature":0.32946963489208453,"pose":{"rotation":{"radians":2.3878802247809405},"translation":{"x":4.487254925027021,"y":6.9442023063215945}},"time":0.636357320128014,"velocity":2.0878480169855833,"position":0.9516409169577897,"holonomicRotation":84.72959999999995,"angularVelocity":0.6935524717405965,"angularAcceleration":-2.655459289620357,"curveRadius":3.035181073143639},{"acceleration":-4.997427320844266,"curvature":0.32779607794469023,"pose":{"rotation":{"radians":2.3901001993003965},"translation":{"x":4.482348287817348,"y":6.94878700952976}},"time":0.639598820590624,"velocity":2.071648854013207,"position":0.9583561676764389,"holonomicRotation":84.14119999999994,"angularVelocity":0.6848601581468031,"angularAcceleration":-2.6815709866641884,"curveRadius":3.0506771352179882},{"acceleration":-4.997426023982486,"curvature":0.32604977417788594,"pose":{"rotation":{"radians":2.392293942974187},"translation":{"x":4.477465062428017,"y":6.953329812562187}},"time":0.6428436619107423,"velocity":2.0554329995563543,"position":0.965025721604134,"holonomicRotation":83.55279999999995,"angularVelocity":0.6760711718595551,"angularAcceleration":-2.7086028006225193,"curveRadius":3.0670163858307746},{"acceleration":-4.997425234891399,"curvature":0.32422721229522383,"pose":{"rotation":{"radians":2.3944610752065314},"translation":{"x":4.4726056413378315,"y":6.957830865342806}},"time":0.6460918485578937,"velocity":2.0392004296382424,"position":0.9716494252105504,"holonomicRotation":82.96439999999996,"angularVelocity":0.6671821750898246,"angularAcceleration":-2.736602829620627,"curveRadius":3.0842568485258846},{"acceleration":-4.997424964226271,"curvature":0.3223246741673696,"pose":{"rotation":{"radians":2.3966012024279},"translation":{"x":4.467770417025593,"y":6.962290317795544}},"time":0.6493433843334321,"velocity":2.022951123581492,"position":0.9782271231610412,"holonomicRotation":82.37599999999995,"angularVelocity":0.6581896583974831,"angularAcceleration":-2.765621328848059,"curveRadius":3.102461834742264},{"acceleration":-4.997425222967943,"curvature":0.3203382206442847,"pose":{"rotation":{"radians":2.398713917469052},"translation":{"x":4.462959781970107,"y":6.966708319844329}},"time":0.652598272353337,"velocity":2.006685064092883,"position":0.9847586583358793,"holonomicRotation":81.78759999999994,"angularVelocity":0.6490899312762446,"angularAcceleration":-2.795711270430843,"curveRadius":3.1217005513383205},{"acceleration":-4.997426022798427,"curvature":0.3182636772544207,"pose":{"rotation":{"radians":2.400798798903173},"translation":{"x":4.458174128650174,"y":6.971085021413094}},"time":0.65585651503021,"velocity":1.9904022373508854,"position":0.9912438718497595,"holonomicRotation":81.19919999999995,"angularVelocity":0.639879113032079,"angularAcceleration":-2.826928242498291,"curveRadius":3.1420487836587077},{"acceleration":-4.997427375873718,"curvature":0.3160966191154683,"pose":{"rotation":{"radians":2.4028554103539137},"translation":{"x":4.453413849544596,"y":6.975420572425764}},"time":0.6591181140544138,"velocity":1.9741026330982065,"position":0.9976826030715507,"holonomicRotation":80.61079999999994,"angularVelocity":0.6305531230169654,"angularAcceleration":-2.859330636876896,"curveRadius":3.1635896733039894},{"acceleration":-4.997429295069093,"curvature":0.3138323536268021,"pose":{"rotation":{"radians":2.404883299763743},"translation":{"x":4.448679337132177,"y":6.979715122806271}},"time":0.6623830703743244,"velocity":1.9577862447379641,"position":1.004074689644342,"holonomicRotation":80.02239999999995,"angularVelocity":0.6211076691785098,"angularAcceleration":-2.892980154391208,"curveRadius":3.186414620556181},{"acceleration":-4.9974317938727735,"curvature":0.31146590341021374,"pose":{"rotation":{"radians":2.4068819986264165},"translation":{"x":4.4439709838917185,"y":6.983968822478541}},"time":0.6656513841756367,"velocity":1.9414530694349328,"position":1.0104199675057763,"holonomicRotation":79.43399999999994,"angularVelocity":0.6115382378126977,"angularAcceleration":-2.9279414240975674,"curveRadius":3.2106243060671646},{"acceleration":-4.9974348864682065,"curvature":0.3089919857750377,"pose":{"rotation":{"radians":2.4088510211745606},"translation":{"x":4.439289182302023,"y":6.9881818213665055}},"time":0.6689230548596767,"velocity":1.925103108221476,"position":1.0167182709086988,"holonomicRotation":78.84559999999995,"angularVelocity":0.6018400805892532,"angularAcceleration":-2.964282826738778,"curveRadius":3.236329892154718},{"acceleration":-4.997438587673859,"curvature":0.30640499323507153,"pose":{"rotation":{"radians":2.41078986352368},"translation":{"x":4.434634324841895,"y":6.992354269394092}},"time":0.6721980810206609,"velocity":1.9087363661089323,"position":1.0229694324421275,"holonomicRotation":78.25719999999994,"angularVelocity":0.5920082020159178,"angularAcceleration":-3.0020763468896545,"curveRadius":3.263654385791317},{"acceleration":-4.997442913250666,"curvature":0.3036989704498886,"pose":{"rotation":{"radians":2.4126980027692446},"translation":{"x":4.430006803990134,"y":6.996486316485231}},"time":0.6754764604218565,"velocity":1.8923528522034805,"position":1.029173283052585,"holonomicRotation":77.66879999999995,"angularVelocity":0.5820373459120644,"angularAcceleration":-3.041397862680927,"curveRadius":3.2927342444349956},{"acceleration":-4.9974478796563355,"curvature":0.3008675895325452,"pose":{"rotation":{"radians":2.4145748960314624},"translation":{"x":4.425407012225545,"y":7.000578112563849}},"time":0.67875818997056,"velocity":1.8759525798287064,"position":1.0353296520657755,"holonomicRotation":77.08039999999994,"angularVelocity":0.5719219802738508,"angularAcceleration":-3.0823276227042236,"curveRadius":3.323721247455365},{"acceleration":-4.9974535042035235,"curvature":0.2979041255059829,"pose":{"rotation":{"radians":2.4164199794463666},"translation":{"x":4.42083534202693,"y":7.004629807553877}},"time":0.6820432656918569,"velocity":1.8595355666537374,"position":1.0414383672086778,"holonomicRotation":76.49199999999995,"angularVelocity":0.5616562817540748,"angularAcceleration":-3.1249503483966263,"curveRadius":3.356784664534351},{"acceleration":-4.997459805188399,"curvature":0.2948014265036065,"pose":{"rotation":{"radians":2.4182326670997565},"translation":{"x":4.4162921858730915,"y":7.0086415513792435}},"time":0.6853316827010656,"velocity":1.8431018348275192,"position":1.0474992546320283,"holonomicRotation":75.90359999999994,"angularVelocity":0.551234119125949,"angularAcceleration":-3.1693555284929538,"curveRadius":3.3921138437495526},{"acceleration":-4.99746680184715,"curvature":0.2915518844020051,"pose":{"rotation":{"radians":2.4200123498988773},"translation":{"x":4.411777936242831,"y":7.012613493963877}},"time":0.6886234351748117,"velocity":1.8266514111200747,"position":1.0535121389332547,"holonomicRotation":75.31519999999995,"angularVelocity":0.5406490352220895,"angularAcceleration":-3.2156378671490056,"curveRadius":3.429921237007524},{"acceleration":-4.997474514328865,"curvature":0.2881474011260537,"pose":{"rotation":{"radians":2.421758394375936},"translation":{"x":4.407292985614952,"y":7.016545785231707}},"time":0.6919185163206437,"velocity":1.8101843270711337,"position":1.0594768431798673,"holonomicRotation":74.72679999999994,"angularVelocity":0.529894227117087,"angularAcceleration":-3.2638978006980093,"curveRadius":3.4704460151023104},{"acceleration":-4.997482964005254,"curvature":0.28457935420919406,"pose":{"rotation":{"radians":2.4234701414254656},"translation":{"x":4.402837726468258,"y":7.020438575106662}},"time":0.6952169183451142,"velocity":1.793700619145402,"position":1.0653931889333506,"holonomicRotation":74.13839999999995,"angularVelocity":0.5189625269540548,"angularAcceleration":-3.314241284698182,"curveRadius":3.513958357164943},{"acceleration":-4.997492173324367,"curvature":0.28083855707244243,"pose":{"rotation":{"radians":2.4251469049608607},"translation":{"x":4.39841255128155,"y":7.024292013512673}},"time":0.6985186324202329,"velocity":1.7772003288964413,"position":1.0712609962735735,"holonomicRotation":73.54999999999995,"angularVelocity":0.5078463783496641,"angularAcceleration":-3.3667811177717013,"curveRadius":3.560764627280326},{"acceleration":-4.997502165940716,"curvature":0.27691521758337445,"pose":{"rotation":{"radians":2.4267879704938102},"translation":{"x":4.394017852533631,"y":7.028106250373665}},"time":0.7018236486481984,"velocity":1.760683503138715,"position":1.077080083823758,"holonomicRotation":72.96159999999995,"angularVelocity":0.49653781396400637,"angularAcceleration":-3.4216365686710386,"curveRadius":3.611213600779874},{"acceleration":-4.997512966760837,"curvature":0.2727988928673511,"pose":{"rotation":{"radians":2.428392593623711},"translation":{"x":4.389654022703304,"y":7.03188143561357}},"time":0.7051319560243153,"velocity":1.7441501941285398,"position":1.0828502687760493,"holonomicRotation":72.37319999999994,"angularVelocity":0.4850284291855387,"angularAcceleration":-3.478934533579059,"curveRadius":3.665704026468508},{"acceleration":-4.997524602149302,"curvature":0.2684784403437793,"pose":{"rotation":{"radians":2.4299599984371816},"translation":{"x":4.385321454269372,"y":7.035617719156316}},"time":0.7084435423979808,"velocity":1.7276004597540042,"position":1.0885713669177088,"holonomicRotation":71.78479999999995,"angularVelocity":0.47330935588296247,"angularAcceleration":-3.538809494980748,"curveRadius":3.724693866366056},{"acceleration":-4.997537099708553,"curvature":0.26394196399382197,"pose":{"rotation":{"radians":2.431489375803834},"translation":{"x":4.3810205397106365,"y":7.039315250925833}},"time":0.7117583944316354,"velocity":1.7110343637357712,"position":1.0942431926579912,"holonomicRotation":71.19639999999994,"angularVelocity":0.4613712319961849,"angularAcceleration":-3.601404758213602,"curveRadius":3.788711673083583},{"acceleration":-4.997550488852783,"curvature":0.2591767557954063,"pose":{"rotation":{"radians":2.432979881568818},"translation":{"x":4.376751671505901,"y":7.042974180846049}},"time":0.7150764975575531,"velocity":1.694451975836777,"position":1.0998655590557327,"holonomicRotation":70.60799999999995,"angularVelocity":0.4492041713055122,"angularAcceleration":-3.6668723752543007,"curveRadius":3.858370697368395},{"acceleration":-4.997564800285368,"curvature":0.25416923344568554,"pose":{"rotation":{"radians":2.434430634626167},"translation":{"x":4.372515242133966,"y":7.046594658840893}},"time":0.7183978359323477,"velocity":1.6778533720850664,"position":1.1054382778477174,"holonomicRotation":70.01959999999994,"angularVelocity":0.43679772839730446,"angularAcceleration":-3.7353745713954303,"curveRadius":3.93438649691523},{"acceleration":-4.997580066745655,"curvature":0.24890487066306966,"pose":{"rotation":{"radians":2.435840714869185},"translation":{"x":4.3683116440736365,"y":7.050176834834295}},"time":0.7217223923890526,"velocity":1.6612386350062678,"position":1.110961159477855,"holonomicRotation":69.43119999999995,"angularVelocity":0.42414086251239064,"angularAcceleration":-3.8070840576005307,"curveRadius":4.017599162828963},{"acceleration":-4.997596322507428,"curvature":0.24336812339773745,"pose":{"rotation":{"radians":2.437209161010557},"translation":{"x":4.3641412698037145,"y":7.053720858750181}},"time":0.7250501483866336,"velocity":1.6446078538705546,"position":1.1164340131272417,"holonomicRotation":68.84279999999994,"angularVelocity":0.41122189919177504,"angularAcceleration":-3.882184670392409,"curveRadius":4.109001565359882},{"acceleration":-4.997613603958845,"curvature":0.2375423462729617,"pose":{"rotation":{"radians":2.4385349682526454},"translation":{"x":4.360004511803002,"y":7.057226880512484}},"time":0.728381083956783,"velocity":1.6279611249512655,"position":1.1218566467451623,"holonomicRotation":68.25439999999995,"angularVelocity":0.39802848604148705,"angularAcceleration":-3.9608731158063826,"curveRadius":4.209775712372953},{"acceleration":-4.997631949525072,"curvature":0.23140970449898948,"pose":{"rotation":{"radians":2.43981708580823},"translation":{"x":4.355901762550301,"y":7.060695050045131}},"time":0.7317151776478175,"velocity":1.6112985517982419,"position":1.1272288670810857,"holonomicRotation":67.66599999999994,"angularVelocity":0.3845475485683836,"angularAcceleration":-4.043358922202597,"curveRadius":4.321339946243986},{"acceleration":-4.997651399671395,"curvature":0.2249510754831173,"pose":{"rotation":{"radians":2.4410544142506247},"translation":{"x":4.351833414524416,"y":7.06412551727205}},"time":0.7350524064655204,"velocity":1.5946202455264251,"position":1.132550479717749,"holonomicRotation":67.07759999999995,"angularVelocity":0.37076523965966557,"angularAcceleration":-4.129866323701651,"curveRadius":4.445411064838632},{"acceleration":-4.99767199737108,"curvature":0.21814594357974745,"pose":{"rotation":{"radians":2.442245802685015},"translation":{"x":4.347799860204148,"y":7.067518432117171}},"time":0.7383927458107291,"velocity":1.5779263251191586,"position":1.1378212891053852,"holonomicRotation":66.48919999999994,"angularVelocity":0.3566668865842218,"angularAcceleration":-4.220634977001966,"curveRadius":4.584087073039846},{"acceleration":-4.997693787939675,"curvature":0.21097228059098982,"pose":{"rotation":{"radians":2.4433900457248026},"translation":{"x":4.3438014920683,"y":7.070873944504423}},"time":0.7417361694134741,"velocity":1.5612169177492692,"position":1.1430410985971928,"holonomicRotation":65.90079999999995,"angularVelocity":0.34223693307901754,"angularAcceleration":-4.315921408629513,"curveRadius":4.73995918894526},{"acceleration":-4.997716819327355,"curvature":0.20340642039354745,"pose":{"rotation":{"radians":2.4444858802553413},"translation":{"x":4.339838702595674,"y":7.074192204357736}},"time":0.745082649263453,"velocity":1.5444921591174894,"position":1.14820971048613,"holonomicRotation":65.31239999999994,"angularVelocity":0.32745887609203445,"angularAcceleration":-4.416000588521732,"curveRadius":4.916265661945263},{"acceleration":-4.997741142340608,"curvature":0.19542291583278212,"pose":{"rotation":{"radians":2.4455319819733328},"translation":{"x":4.335911884265074,"y":7.0774733616010375}},"time":0.7484321555366139,"velocity":1.5277521938095853,"position":1.1533269260431305,"holonomicRotation":64.72399999999995,"angularVelocity":0.3123151989216229,"angularAcceleration":-4.521166982655223,"curveRadius":5.117107150604957},{"acceleration":-4.997766810606661,"curvature":0.18699438651693204,"pose":{"rotation":{"radians":2.446526961674247},"translation":{"x":4.332021429555302,"y":7.080717566158256}},"time":0.751784656517609,"velocity":1.510997175674242,"position":1.158392545556859,"holonomicRotation":64.13559999999994,"angularVelocity":0.29678729597829834,"angularAcceleration":-4.631737031950334,"curveRadius":5.347754115118593},{"acceleration":-4.997793881112592,"curvature":0.17809134836608223,"pose":{"rotation":{"radians":2.447469361276395},"translation":{"x":4.32816773094516,"y":7.0839249679533225}},"time":0.7551401185178566,"velocity":1.4942272682210986,"position":1.1634063683751088,"holonomicRotation":63.54719999999993,"angularVelocity":0.28085539400490706,"angularAcceleration":-4.748050185701883,"curveRadius":5.615095899798643},{"acceleration":-4.997822413991229,"curvature":0.1686820264935057,"pose":{"rotation":{"radians":2.4483576495528423},"translation":{"x":4.32435118091345,"y":7.087095716910165}},"time":0.7584985057889367,"velocity":1.4774426450428313,"position":1.1683681929479717,"holonomicRotation":62.95879999999994,"angularVelocity":0.2644984645149857,"angularAcceleration":-4.870471500048407,"curveRadius":5.928313886118153},{"acceleration":-4.9978524731614185,"curvature":0.15873215134872481,"pose":{"rotation":{"radians":2.4491902175461715},"translation":{"x":4.320572171938976,"y":7.090229962952711}},"time":0.7618597804310255,"velocity":1.460643490259893,"position":1.1732778168729143,"holonomicRotation":62.37039999999993,"angularVelocity":0.24769412856184236,"angularAcceleration":-4.9993939033499,"curveRadius":6.299920913961919},{"acceleration":-4.99788412619139,"curvature":0.1482047294114927,"pose":{"rotation":{"radians":2.4499653736444316},"translation":{"x":4.3168310965005405,"y":7.093327856004892}},"time":0.7652239022960674,"velocity":1.443829998992027,"position":1.1781350369419268,"holonomicRotation":61.78199999999994,"angularVelocity":0.23041855478395948,"angularAcceleration":-5.135240181814245,"curveRadius":6.747423000405639},{"acceleration":-4.9979174447636705,"curvature":0.13705979496426066,"pose":{"rotation":{"radians":2.4506813382804515},"translation":{"x":4.313128347076945,"y":7.096389545990636}},"time":0.768590828885332,"velocity":1.4270023778563026,"position":1.182939649190875,"holonomicRotation":61.19359999999993,"angularVelocity":0.212646345870091,"angularAcceleration":-5.278466412227329,"curveRadius":7.29608562642865},{"acceleration":-4.9979525049681275,"curvature":0.12525413341249636,"pose":{"rotation":{"radians":2.451336238226733},"translation":{"x":4.309464316146992,"y":7.099415182833871}},"time":0.7719605152410187,"velocity":1.4101608454939414,"position":1.1876914489512596,"holonomicRotation":60.60519999999994,"angularVelocity":0.1943504163751677,"angularAcceleration":-5.429564524320517,"curveRadius":7.983768461410568},{"acceleration":-4.997989387419241,"curvature":0.11274097515918978,"pose":{"rotation":{"radians":2.45192810044768},"translation":{"x":4.305839396189486,"y":7.102404916458527}},"time":0.775332913831525,"velocity":1.3933056331284432,"position":1.1923902309045664,"holonomicRotation":60.01679999999993,"angularVelocity":0.1755018587106675,"angularAcceleration":-5.589065811366739,"curveRadius":8.869889572872722},{"acceleration":-4.998028177664027,"curvature":0.09946965765722414,"pose":{"rotation":{"radians":2.4524548454690573},"translation":{"x":4.302253979683228,"y":7.105358896788533}},"time":0.7787079744299777,"velocity":1.376436985156053,"position":1.1970357891394197,"holonomicRotation":59.42839999999994,"angularVelocity":0.15606979667824872,"angularAcceleration":-5.757544632332628,"curveRadius":10.053316996887979},{"acceleration":-4.998068966552547,"curvature":0.08538524534722837,"pose":{"rotation":{"radians":2.4529142802197663},"translation":{"x":4.29870845910702,"y":7.1082772737478175}},"time":0.7820856439855965,"velocity":1.3595551597708453,"position":1.201627917211762,"holonomicRotation":58.83999999999993,"angularVelocity":0.136021225032123,"angularAcceleration":-5.935622569346561,"curveRadius":11.711625304036914},{"acceleration":-4.998111850450811,"curvature":0.07042811773416531,"pose":{"rotation":{"radians":2.4533040902960375},"translation":{"x":4.295203226939666,"y":7.111160197260309}},"time":0.785465866487446,"velocity":1.3426604296271911,"position":1.2061664082083308,"holonomicRotation":58.25159999999994,"angularVelocity":0.1153208334829638,"angularAcceleration":-6.123973063262336,"curveRadius":14.198874429308951},{"acceleration":-4.998156931774634,"curvature":0.05453350329155176,"pose":{"rotation":{"radians":2.4536218315963754},"translation":{"x":4.291738675659969,"y":7.114007817249939}},"time":0.7888485828200882,"velocity":1.3257530825409682,"position":1.2106510548136928,"holonomicRotation":57.66319999999993,"angularVelocity":0.09393081449715288,"angularAcceleration":-6.323326250978734,"curveRadius":18.337351162893626},{"acceleration":-4.998204319257553,"curvature":0.037630962703190614,"pose":{"rotation":{"radians":2.453864921265583},"translation":{"x":4.28831519774673,"y":7.1168202836406325}},"time":0.7922337306106317,"velocity":1.3088334222329483,"position":1.2150816493811543,"holonomicRotation":57.07479999999994,"angularVelocity":0.07181065177919368,"angularAcceleration":-6.534474736893943,"curveRadius":26.573861739530066},{"acceleration":-4.998254128350117,"curvature":0.01964381326186848,"pose":{"rotation":{"radians":2.4540306278747837},"translation":{"x":4.284933185678751,"y":7.119597746356322}},"time":0.7956212440666349,"velocity":1.2919017691166388,"position":1.2194579840078712,"holonomicRotation":56.48639999999993,"angularVelocity":0.048916885896585376,"angularAcceleration":-6.758280426026671,"curveRadius":50.906613022082965},{"acceleration":-4.998306481899741,"curvature":0.0004885221270891651,"pose":{"rotation":{"radians":2.4541160607777144},"translation":{"x":4.281593031934837,"y":7.122340355320935}},"time":0.7990110538042953,"velocity":1.2749584611324842,"position":1.2237798506145305,"holonomicRotation":55.89799999999994,"angularVelocity":0.02520286079232654,"angularAcceleration":-6.995680271019083,"curveRadius":2046.9901864188844},{"acceleration":-4.99836151029261,"curvature":-0.019926219636289308,"pose":{"rotation":{"radians":2.4541181585435976},"translation":{"x":4.278295128993788,"y":7.125048260458399}},"time":0.8024030866663396,"velocity":1.258003854633194,"position":1.2280470410300248,"holonomicRotation":55.30959999999993,"angularVelocity":0.0006184391391656783,"angularAcceleration":-7.2476956011398705,"curveRadius":-50.18513387149544},{"acceleration":-4.998419352162828,"curvature":-0.04169986160356959,"pose":{"rotation":{"radians":2.4540336763852757},"translation":{"x":4.2750398693344085,"y":7.127721611692646}},"time":0.8057972655289658,"velocity":1.2410383253215413,"position":1.2322593470815402,"holonomicRotation":54.72119999999994,"angularVelocity":-0.024890308301708644,"angularAcceleration":-7.515439955670914,"curveRadius":-23.980894936936625},{"acceleration":-4.998480154938027,"curvature":-0.06494134951000995,"pose":{"rotation":{"radians":2.453859172478709},"translation":{"x":4.271827645435501,"y":7.130360558947604}},"time":0.8091935090971984,"velocity":1.2240622692443945,"position":1.2364165606905777,"holonomicRotation":54.13279999999993,"angularVelocity":-0.05138144631287477,"angularAcceleration":-7.800129018706305,"curveRadius":-15.39850969444147},{"acceleration":-4.998544075272079,"curvature":-0.0897699106130901,"pose":{"rotation":{"radians":2.453590993054213},"translation":{"x":4.268658849775867,"y":7.132965252147201}},"time":0.8125917316879623,"velocity":1.2070761038468762,"position":1.2405184739754413,"holonomicRotation":53.544399999999925,"angularVelocity":-0.07891755685021995,"angularAcceleration":-8.103092072952105,"curveRadius":-11.13959001596891},{"acceleration":-4.998611279707467,"curvature":-0.1163162335353054,"pose":{"rotation":{"radians":2.4532252561350996},"translation":{"x":4.265533874834309,"y":7.135535841215366}},"time":0.8159918430001714,"velocity":1.190080269089407,"position":1.244564879360809,"holonomicRotation":52.95599999999993,"angularVelocity":-0.10756616049596729,"angularAcceleration":-8.42578404503297,"curveRadius":-8.597252245934103},{"acceleration":-4.998681945270441,"curvature":-0.1447237583121148,"pose":{"rotation":{"radians":2.452757833778728},"translation":{"x":4.262453113089631,"y":7.138072476076029}},"time":0.8193937478710939,"velocity":1.173075228631599,"position":1.2485555696950494,"holonomicRotation":52.367599999999925,"angularVelocity":-0.13740018433992723,"angularAcceleration":-8.769799561111684,"curveRadius":-6.909715527449029},{"acceleration":-4.998756260165003,"curvature":-0.17515011768222874,"pose":{"rotation":{"radians":2.4521843326635033},"translation":{"x":4.259416957020633,"y":7.140575306653118}},"time":0.8227973460182543,"velocity":1.156061471086395,"position":1.2524903383760426,"holonomicRotation":51.77919999999993,"angularVelocity":-0.16849848026361505,"angularAcceleration":-9.136888251520793,"curveRadius":-5.709388113653908},{"acceleration":-4.998834424306417,"curvature":-0.2077687744770686,"pose":{"rotation":{"radians":2.4515000728289404},"translation":{"x":4.256425799106121,"y":7.143044482870562}},"time":0.8262025317660998,"velocity":1.1390395113489071,"position":1.2563689794863209,"holonomicRotation":51.190799999999925,"angularVelocity":-0.20094640505171107,"angularAcceleration":-9.528973510072339,"curveRadius":-4.813042780450966},{"acceleration":-4.998916650123531,"curvature":-0.24277087486957777,"pose":{"rotation":{"radians":2.450700064380375},"translation":{"x":4.253480031824895,"y":7.145480154652291}},"time":0.8296091937566967,"velocity":1.1220098920027692,"position":1.2601912879384805,"holonomicRotation":50.60239999999993,"angularVelocity":-0.2348364618425608,"angularAcceleration":-9.948171225790295,"curveRadius":-4.1191102538029885},{"acceleration":-4.999003163097305,"curvature":-0.28036734314202627,"pose":{"rotation":{"radians":2.4497789819198075},"translation":{"x":4.250580047655759,"y":7.147882471922234}},"time":0.8330172146436811,"velocity":1.1049731848088329,"position":1.2639570596318666,"holonomicRotation":50.013999999999925,"angularVelocity":-0.27026901862174296,"angularAcceleration":-10.396813269103967,"curveRadius":-3.5667492112069126},{"acceleration":-4.999094202626779,"curvature":-0.3207912688844471,"pose":{"rotation":{"radians":2.4487311364464515},"translation":{"x":4.247726239077514,"y":7.150251584604318}},"time":0.8364264707687683,"velocity":1.0879299922786394,"position":1.2676660916217086,"holonomicRotation":49.42559999999993,"angularVelocity":-0.30735311015366956,"angularAcceleration":-10.877473023819116,"curveRadius":-3.1172918249224923},{"acceleration":-4.999190022488638,"curvature":-0.3643006159363525,"pose":{"rotation":{"radians":2.447550444436692},"translation":{"x":4.2449189985689655,"y":7.152587642622474}},"time":0.8398368318201486,"velocity":1.0708809493374953,"position":1.2713181823019943,"holonomicRotation":48.837199999999925,"angularVelocity":-0.34620733464030073,"angularAcceleration":-11.392994437027674,"curveRadius":-2.744985751478146},{"acceleration":-4.999290891664178,"curvature":-0.41118131720733264,"pose":{"rotation":{"radians":2.4462303937763408},"translation":{"x":4.242158718608912,"y":7.154890795900631}},"time":0.8432481604721703,"velocity":1.05382672507897,"position":1.2749131316035225,"holonomicRotation":48.24879999999993,"angularVelocity":-0.3869608574855116,"angularAcceleration":-11.94652494741539,"curveRadius":-2.432017113014314},{"acceleration":-4.999397094737933,"curvature":-0.4617508036739008,"pose":{"rotation":{"radians":2.444764006161729},"translation":{"x":4.239445791676158,"y":7.1571611943627165}},"time":0.8466603120058332,"velocity":1.03676802461477,"position":1.2784507412087645,"holonomicRotation":47.660399999999925,"angularVelocity":-0.4297545405427968,"angularAcceleration":-12.541554100132966,"curveRadius":-2.165670296713167},{"acceleration":-4.999508932558376,"curvature":-0.5163620459686109,"pose":{"rotation":{"radians":2.443143795559845},"translation":{"x":4.236780610249508,"y":7.15939898793266}},"time":0.8500731339097803,"velocity":1.0197055910207555,"position":1.2819308147853774,"holonomicRotation":47.07199999999993,"angularVelocity":-0.4747422067380764,"angularAcceleration":-13.181955420307498,"curveRadius":-1.9366256830983062},{"acceleration":-4.999626722514368,"curvature":-0.5754081870091554,"pose":{"rotation":{"radians":2.4413617222336086},"translation":{"x":4.234163566807762,"y":7.16160432653439}},"time":0.8534864654616647,"velocity":1.002640207381153,"position":1.2853531582404194,"holonomicRotation":46.483599999999925,"angularVelocity":-0.5220920672803563,"angularAcceleration":-13.872036695685061,"curveRadius":-1.7378967184978353},{"acceleration":-4.999750798744856,"curvature":-0.6393278640431587,"pose":{"rotation":{"radians":2.439409141790244},"translation":{"x":4.2315950538297225,"y":7.163777360091838}},"time":0.8569001372900604,"velocity":0.9855726989304787,"position":1.2887175799975943,"holonomicRotation":45.89519999999993,"angularVelocity":-0.5719883285565576,"angularAcceleration":-14.616595790243492,"curveRadius":-1.564142682091037},{"acceleration":-4.999881512228886,"curvature":-0.7086113366932383,"pose":{"rotation":{"radians":2.4372767486266},"translation":{"x":4.229075463794194,"y":7.1659182385289295}},"time":0.8603139709174707,"velocity":0.9685039352909646,"position":1.2920238913001698,"holonomicRotation":45.306799999999924,"angularVelocity":-0.6246330068701924,"angularAcceleration":-15.420985337697962,"curveRadius":-1.4112108404397508},{"acceleration":-5.000019230299023,"curvature":-0.783807554946832,"pose":{"rotation":{"radians":2.434954513057409},"translation":{"x":4.226605189179978,"y":7.168027111769597}},"time":0.8637277782854753,"velocity":0.9514348328024053,"position":1.2952719065425669,"holonomicRotation":44.71839999999992,"angularVelocity":-0.6802479808778995,"angularAcceleration":-16.291186939529968,"curveRadius":-1.2758233748688899},{"acceleration":-5.000164336001283,"curvature":-0.8655323324161924,"pose":{"rotation":{"radians":2.432431611310555},"translation":{"x":4.224184622465877,"y":7.170104129737766}},"time":0.8671413612636448,"velocity":0.934366356936981,"position":1.2984614436339812,"holonomicRotation":44.129999999999924,"angularVelocity":-0.7390773164116429,"angularAcceleration":-17.233896439596656,"curveRadius":-1.1553583413902424},{"acceleration":-5.000317226816192,"curvature":-0.954477813424975,"pose":{"rotation":{"radians":2.4296963474536244},"translation":{"x":4.221814156130693,"y":7.172149442357368}},"time":0.8705545111447397,"velocity":0.9172995247888367,"position":1.3015923243979426,"holonomicRotation":43.54159999999992,"angularVelocity":-0.8013899044049723,"angularAcceleration":-18.256622229944618,"curveRadius":-1.047693289393157},{"acceleration":-5.000478312641647,"curvature":-1.051423469868031,"pose":{"rotation":{"radians":2.426736066182963},"translation":{"x":4.2194941826532295,"y":7.17416319955233}},"time":0.8739670081296563,"velocity":0.900235407623806,"position":1.304664375012174,"holonomicRotation":42.953199999999924,"angularVelocity":-0.8674824574925148,"angularAcceleration":-19.367798236796734,"curveRadius":-0.9510915712443767},{"acceleration":-5.00064801287895,"curvature":-1.1572488946298836,"pose":{"rotation":{"radians":2.4235370552385116},"translation":{"x":4.2172250945122896,"y":7.176145551246583}},"time":0.8773786208069921,"velocity":0.8831751334681741,"position":1.3076774264938218,"holonomicRotation":42.36479999999992,"angularVelocity":-0.9376829221275164,"angularAcceleration":-20.576915164303585,"curveRadius":-0.8641183453623643},{"acceleration":-5.000826752404539,"curvature":-1.2729487292180932,"pose":{"rotation":{"radians":2.42008443603406},"translation":{"x":4.215007284186674,"y":7.178096647364055}},"time":0.8807891056337293,"velocity":0.8661198897079574,"position":1.310631315235806,"holonomicRotation":41.776399999999924,"angularVelocity":-1.0123543659787215,"angularAcceleration":-21.89467118158827,"curveRadius":-0.7855775940121709},{"acceleration":-5.001014955893718,"curvature":-1.399650112564896,"pose":{"rotation":{"radians":2.41636204086322},"translation":{"x":4.2128411441551865,"y":7.1800166378286745}},"time":0.8841982064256881,"velocity":0.8490709256612219,"position":1.313525883600907,"holonomicRotation":41.18799999999992,"angularVelocity":-1.0918994180577952,"angularAcceleration":-23.333147634325805,"curveRadius":-0.7144642729085153},{"acceleration":-5.001213040349077,"curvature":-1.5386331288589172,"pose":{"rotation":{"radians":2.4123522748032613},"translation":{"x":4.21072706689663,"y":7.181905672564372}},"time":0.8876056538691529,"velocity":0.8320295550726617,"position":1.3163609805812264,"holonomicRotation":40.599599999999924,"angularVelocity":-1.1767653431159848,"angularAcceleration":-24.906011454690525,"curveRadius":-0.6499275111420623},{"acceleration":-5.001421404910135,"curvature":-1.6913548268216283,"pose":{"rotation":{"radians":2.4080359601438817},"translation":{"x":4.208665444889807,"y":7.183763901495074}},"time":0.891011165068469,"velocity":0.8149971584657411,"position":1.3191364625317923,"holonomicRotation":40.01119999999992,"angularVelocity":-1.267449850185919,"angularAcceleration":-26.628750211758483,"curveRadius":-0.5912419937803275},{"acceleration":-5.001640417645408,"curvature":-1.8594774932852534,"pose":{"rotation":{"radians":2.4033921608190076},"translation":{"x":4.206656670613519,"y":7.185591474544712}},"time":0.8944144431488259,"velocity":0.7979751852665413,"position":1.3218521939884786,"holonomicRotation":39.422799999999924,"angularVelocity":-1.3645077525921805,"angularAcceleration":-28.518945591446677,"curveRadius":-0.5377854820029246},{"acceleration":-5.001870397964162,"curvature":-2.0449020200306447,"pose":{"rotation":{"radians":2.398397983945279},"translation":{"x":4.204701136546569,"y":7.187388541637213}},"time":0.8978151769389507,"velocity":0.7809651555903594,"position":1.3245080485820049,"holonomicRotation":38.83439999999992,"angularVelocity":-1.4685586058605178,"angularAcceleration":-30.596588762838007,"curveRadius":-0.48902098496876345},{"acceleration":-5.002111594024953,"curvature":-2.2498073625227666,"pose":{"rotation":{"radians":2.3930283550884295},"translation":{"x":4.202799235167759,"y":7.189155252696508}},"time":0.9012130407654995,"velocity":0.763968661548662,"position":1.327103910061698,"holonomicRotation":38.245999999999924,"angularVelocity":-1.5802954829722253,"angularAcceleration":-32.884448234407614,"curveRadius":-0.4444824995499501},{"acceleration":-5.002364152983333,"curvature":-2.4766973112303217,"pose":{"rotation":{"radians":2.3872557633710354},"translation":{"x":4.200951358955894,"y":7.190891757646525}},"time":0.9046076943998528,"velocity":0.7469873678963784,"position":1.3296396734449434,"holonomicRotation":37.65759999999992,"angularVelocity":-1.7004950546283826,"angularAcceleration":-35.40849365006139,"curveRadius":-0.40376351016557654},{"acceleration":-5.002628082730957,"curvature":-2.7284560525683705,"pose":{"rotation":{"radians":2.3810499719014366},"translation":{"x":4.199157900389774,"y":7.192598206411191}},"time":0.9079987832094099,"velocity":0.7300230117866535,"position":1.3321152463109323,"holonomicRotation":37.069199999999924,"angularVelocity":-1.83002917886109,"angularAcceleration":-38.19838745232583,"curveRadius":-0.3665076441523302},{"acceleration":-5.002903202421486,"curvature":-3.0084142854039624,"pose":{"rotation":{"radians":2.3743776882939347},"translation":{"x":4.197419251948203,"y":7.194274748914438}},"time":0.9113859385799129,"velocity":0.7130774013364647,"position":1.3345305502604534,"holonomicRotation":36.48079999999992,"angularVelocity":-1.9698782245442128,"angularAcceleration":-41.28805159072253,"curveRadius":-0.33240102762832163},{"acceleration":-5.003189078123809,"curvature":-3.3204280791157097,"pose":{"rotation":{"radians":2.367202189275362},"translation":{"x":4.195735806109981,"y":7.195921535080194}},"time":0.9147687786938347,"velocity":0.6961524126254522,"position":1.3368855225672862,"holonomicRotation":35.89239999999991,"angularVelocity":-2.1211463672323,"angularAcceleration":-44.716314574122954,"curveRadius":-0.3011659870875198},{"acceleration":-5.0034849404999004,"curvature":-3.6689730414690285,"pose":{"rotation":{"radians":2.3594828923760165},"translation":{"x":4.194107955353915,"y":7.197538714832387}},"time":0.918146909773445,"velocity":0.679249984641587,"position":1.3391801180512288,"holonomicRotation":35.30399999999992,"angularVelocity":-2.2850791509948376,"angularAcceleration":-48.527656239273234,"curveRadius":-0.2725558320263939},{"acceleration":-5.003789577617417,"curvature":-4.059256956800572,"pose":{"rotation":{"radians":2.351174866752653},"translation":{"x":4.192536092158804,"y":7.199126438094948}},"time":0.9215199279274089,"velocity":0.6623721115576684,"position":1.3414143112081922,"holonomicRotation":34.71559999999991,"angularVelocity":-2.4630835780116174,"angularAcceleration":-52.773041499226885,"curveRadius":-0.2463505046963523},{"acceleration":-5.004101197415102,"curvature":-4.497354622626682,"pose":{"rotation":{"radians":2.34222827396478},"translation":{"x":4.191020609003453,"y":7.2006848547918025}},"time":0.9248874217785382,"velocity":0.6455208315449441,"position":1.3435880986391957,"holonomicRotation":34.12719999999992,"angularVelocity":-2.6567510390175033,"angularAcceleration":-57.510858094347235,"curveRadius":-0.22235293498290992},{"acceleration":-5.00441724924905,"curvature":-4.990369346494815,"pose":{"rotation":{"radians":2.3325877283338663},"translation":{"x":4.189561898366662,"y":7.202214114846885}},"time":0.9282489761003614,"velocity":0.6286982111125246,"position":1.3457015018278835,"holonomicRotation":33.53879999999991,"angularVelocity":-2.8678833384686295,"angularAcceleration":-62.80793919659665,"curveRadius":-0.20038596956804205},{"acceleration":-5.004734193520267,"curvature":-5.546626338756747,"pose":{"rotation":{"radians":2.3221915651942027},"translation":{"x":4.188160352727235,"y":7.2037143681841185}},"time":0.9316041767545101,"velocity":0.6119063236725848,"position":1.3477545703253475,"holonomicRotation":32.95039999999992,"angularVelocity":-3.098522029318477,"angularAcceleration":-68.74065506772612,"curveRadius":-0.18028977236352753},{"acceleration":-5.00504720329302,"curvature":-6.175904031714639,"pose":{"rotation":{"radians":2.3109710040670786},"translation":{"x":4.186816364563976,"y":7.205185764727435}},"time":0.9349526173045734,"velocity":0.5951472206620979,"position":1.34974738541227,"holonomicRotation":32.36199999999991,"angularVelocity":-3.350981138641461,"angularAcceleration":-75.39602556725012,"curveRadius":-0.16191961449931505},{"acceleration":-5.005349777538372,"curvature":-6.889710175972938,"pose":{"rotation":{"radians":2.2988491927008754},"translation":{"x":4.185530326355684,"y":7.2066284544007635}},"time":0.9382939077903311,"velocity":0.5784228930725195,"position":1.3516800643216376,"holonomicRotation":31.773599999999917,"angularVelocity":-3.627883124161916,"angularAcceleration":-82.87276628618588,"curveRadius":-0.1451439863881914},{"acceleration":-5.005633238999097,"curvature":-7.701610065917918,"pose":{"rotation":{"radians":2.285740117113378},"translation":{"x":4.184302630581164,"y":7.208042587128033}},"time":0.9416276862876574,"velocity":0.5617352206148425,"position":1.3535527651213142,"holonomicRotation":31.18519999999991,"angularVelocity":-3.9321975344224884,"angularAcceleration":-91.28213242260496,"curveRadius":-0.1298429797718946},{"acceleration":-5.005886082177535,"curvature":-8.627614433421416,"pose":{"rotation":{"radians":2.2715473628415563},"translation":{"x":4.183133669719219,"y":7.209428312833172}},"time":0.94495363406423,"velocity":0.5450859049300479,"position":1.3553656923748574,"holonomicRotation":30.596799999999917,"angularVelocity":-4.267281155703282,"angularAcceleration":-100.74831109527797,"curveRadius":-0.11590689497275486},{"acceleration":-5.00609312451906,"curvature":-9.686633641955666,"pose":{"rotation":{"radians":2.2561627138006752},"translation":{"x":4.18202383624865,"y":7.2107857814401095}},"time":0.9482714953839226,"velocity":0.5284763821894272,"position":1.3571191037216948,"holonomicRotation":30.00839999999991,"angularVelocity":-4.6369174472628565,"angularAcceleration":-111.40799929329874,"curveRadius":-0.10323503881355697},{"acceleration":-5.0062344020855205,"curvature":-10.901002296244702,"pose":{"rotation":{"radians":2.2394645786566403},"translation":{"x":4.180973522648261,"y":7.212115142872774}},"time":0.9515811033329495,"velocity":0.511907709017593,"position":1.3588133175446275,"holonomicRotation":29.419999999999916,"angularVelocity":-5.045351413584972,"angularAcceleration":-123.40856458306597,"curveRadius":-0.0917346839147526},{"acceleration":-5.006283729999945,"curvature":-12.297072840878995,"pose":{"rotation":{"radians":2.221316241532021},"translation":{"x":4.1799831213968535,"y":7.213416547055095}},"time":0.9548824134653563,"velocity":0.4953804138140411,"position":1.3604487219241477,"holonomicRotation":28.83159999999991,"angularVelocity":-5.497313610881115,"angularAcceleration":-136.90388941636604,"curveRadius":-0.08132016561500013},{"acceleration":-5.006206828037698,"curvature":-13.905866127155994,"pose":{"rotation":{"radians":2.201563946257791},"translation":{"x":4.17905302497323,"y":7.214690143911002}},"time":0.9581755476307814,"velocity":0.47889430306944575,"position":1.362025785115213,"holonomicRotation":28.243199999999916,"angularVelocity":-5.998023245336021,"angularAcceleration":-152.0465335764029,"curveRadius":-0.0719120974454914},{"acceleration":-5.005958879245756,"curvature":-15.763748289402102,"pose":{"rotation":{"radians":2.1800348442663453},"translation":{"x":4.178183625856195,"y":7.215936083364424}},"time":0.961460851105546,"velocity":0.4624482089689308,"position":1.3635450678230374,"holonomicRotation":27.65479999999991,"angularVelocity":-6.553154725831845,"angularAcceleration":-168.97418602572037,"curveRadius":-0.06343668914532818},{"acceleration":-5.005481356560474,"curvature":-17.91307172105087,"pose":{"rotation":{"radians":2.1565348696880506},"translation":{"x":4.1773753165245475,"y":7.217154515339288}},"time":0.9647389671711062,"velocity":0.446039660118128,"position":1.3650072375987476,"holonomicRotation":27.066399999999902,"angularVelocity":-7.168743909096148,"angularAcceleration":-187.78748859189955,"curveRadius":-0.05582515470112432},{"acceleration":-5.00469790765236,"curvature":-20.402666859864393,"pose":{"rotation":{"radians":2.130846657421775},"translation":{"x":4.1766284894570935,"y":7.218345589759525}},"time":0.9680109346761907,"velocity":0.429664451191525,"position":1.3664130857211363,"holonomicRotation":26.47799999999991,"angularVelocity":-7.850998589184425,"angularAcceleration":-208.5151148439216,"curveRadius":-0.049013200424655005},{"acceleration":-5.003509039766612,"curvature":-23.287991843199567,"pose":{"rotation":{"radians":2.102727698980011},"translation":{"x":4.1759435371326346,"y":7.219509456549064}},"time":0.971278316032828,"velocity":0.41331607903722545,"position":1.367763546972181,"holonomicRotation":25.889599999999902,"angularVelocity":-8.605961585917592,"angularAcceleration":-231.06056940661404,"curveRadius":-0.04294058529104194},{"acceleration":-5.001785293760358,"curvature":-26.630627756276336,"pose":{"rotation":{"radians":2.071909047137016},"translation":{"x":4.175320852029972,"y":7.220646265631832}},"time":0.974543365760289,"velocity":0.39698500132701475,"position":1.3690597227425698,"holonomicRotation":25.30119999999991,"angularVelocity":-9.438953282638256,"angularAcceleration":-255.12373968295495,"curveRadius":-0.03755074830199295},{"acceleration":-4.999358542717649,"curvature":-30.496638207366644,"pose":{"rotation":{"radians":2.0380950462566205},"translation":{"x":4.174760826627909,"y":7.221756166931761}},"time":0.9778092534587421,"velocity":0.3806576577621965,"position":1.3703029079043774,"holonomicRotation":24.712799999999902,"angularVelocity":-10.353693697554547,"angularAcceleration":-280.0893660089866,"curveRadius":-0.03279049950359591},{"acceleration":-4.9960110013013255,"curvature":-34.95309047503608,"pose":{"rotation":{"radians":2.0009647921422875},"translation":{"x":4.174263853405249,"y":7.222839310372778}},"time":0.9810803605339355,"velocity":0.36431517082809567,"position":1.3714946218372734,"holonomicRotation":24.12439999999991,"angularVelocity":-11.350974841487789,"angularAcceleration":-304.8757258654634,"curveRadius":-0.028609773453772625},{"acceleration":-4.9914614825532215,"curvature":-40.061781537987656,"pose":{"rotation":{"radians":1.9601763189298413},"translation":{"x":4.173830324840794,"y":7.223895845878811}},"time":0.9843626780593092,"velocity":0.3479316093266836,"position":1.3726366438561979,"holonomicRotation":23.535999999999902,"angularVelocity":-12.426729863011255,"angularAcceleration":-327.7425213153318,"curveRadius":-0.0249614460867591},{"acceleration":-4.985348352606691,"curvature":-45.86899695428581,"pose":{"rotation":{"radians":1.9153748585418948},"translation":{"x":4.173460633413347,"y":7.2249259233737915}},"time":0.9876643455317463,"velocity":0.3314716468321142,"position":1.3737310530105786,"holonomicRotation":22.94759999999991,"angularVelocity":-13.569343600455532,"angularAcceleration":-346.0717189065883,"curveRadius":-0.021801217955487995},{"acceleration":-4.977208391284145,"curvature":-52.390119123099176,"pose":{"rotation":{"radians":1.8662068690134228},"translation":{"x":4.17315517160171,"y":7.225929692781647}},"time":0.9909963900662729,"velocity":0.31488736681473584,"position":1.3747802717401651,"holonomicRotation":22.359199999999902,"angularVelocity":-14.756102152595389,"angularAcceleration":-356.16527325570604,"curveRadius":-0.0190875687388749},{"acceleration":-4.9664500121526,"curvature":-59.58840103486643,"pose":{"rotation":{"radians":1.8123417586199089},"translation":{"x":4.172914331884685,"y":7.226907304026307}},"time":0.9943737588737824,"velocity":0.2981138334596365,"position":1.3757871121023788,"holonomicRotation":21.77079999999991,"angularVelocity":-15.948838715436173,"angularAcceleration":-353.15555712741934,"curveRadius":-0.01678178945286481},{"acceleration":-4.9501518262123705,"curvature":-67.34868771951163,"pose":{"rotation":{"radians":1.7535031103180587},"translation":{"x":4.172738506741075,"y":7.227858907031699}},"time":0.9978167000319024,"velocity":0.28107075199822734,"position":1.3767548221627772,"holonomicRotation":21.1823999999999,"angularVelocity":-17.089646787335667,"angularAcceleration":-331.3469558458695,"curveRadius":-0.014848099255693283},{"acceleration":-4.5814172621401825,"curvature":-75.44976070531632,"pose":{"rotation":{"radians":1.689510369984808},"translation":{"x":4.1726280886496845,"y":7.228784651721755}},"time":1.0013355065436014,"velocity":0.26494963110339825,"position":1.3776871286499761,"holonomicRotation":20.59399999999991,"angularVelocity":-18.185921880186825,"angularAcceleration":-311.5474207537028,"curveRadius":-0.013253852505983339},{"acceleration":-3.87637790943412,"curvature":-83.5433221564263,"pose":{"rotation":{"radians":1.6203299541920635},"translation":{"x":4.172583470089314,"y":7.2296846880204}},"time":1.004925217888989,"velocity":0.25103455334289293,"position":1.3785882702341954,"holonomicRotation":20.0055999999999,"angularVelocity":-19.2718603632671,"angularAcceleration":-302.5141518622675,"curveRadius":-0.011969837614640252},{"acceleration":-3.177796497326494,"curvature":-91.15220843694422,"pose":{"rotation":{"radians":1.5461312367837194},"translation":{"x":4.172605043538765,"y":7.230559165851566}},"time":1.0085787467941834,"velocity":0.23942438198508495,"position":1.3794630141343862,"holonomicRotation":19.41719999999991,"angularVelocity":-20.308780725082368,"angularAcceleration":-283.81337296689213,"curveRadius":-0.010970661239565726},{"acceleration":-2.4837987781049495,"curvature":-97.70205772584109,"pose":{"rotation":{"radians":1.467338129731677},"translation":{"x":4.172693201476843,"y":7.231408235139182}},"time":1.0122867399482816,"velocity":0.23021447311971432,"position":1.3803166478246884,"holonomicRotation":18.828799999999916,"angularVelocity":-21.249528728217218,"angularAcceleration":-253.7081283699522,"curveRadius":-0.010235198963834222},{"acceleration":-1.7924932792534265,"curvature":-102.59484965897754,"pose":{"rotation":{"radians":1.3846623452288833},"translation":{"x":4.172848336382348,"y":7.232232045807176}},"time":1.0160376307522783,"velocity":0.22349102656233674,"position":1.381154938260997,"holonomicRotation":18.24039999999991,"angularVelocity":-22.041639925827656,"angularAcceleration":-211.17948748772304,"curveRadius":-0.009747077980268722},{"acceleration":-1.1020148942735437,"curvature":-105.3170155152234,"pose":{"rotation":{"radians":1.2991026012455034},"translation":{"x":4.173070840734084,"y":7.233030747779477}},"time":1.0198179363843771,"velocity":0.21932507345085764,"position":1.3819840540714237,"holonomicRotation":17.6519999999999,"angularVelocity":-22.6330229113979,"angularAcceleration":-156.4378764904002,"curveRadius":-0.009495141835418339},{"acceleration":-0.4105927579435364,"curvature":-105.55384376257612,"pose":{"rotation":{"radians":1.2118981044583914},"translation":{"x":4.173361107010853,"y":7.233804490980013}},"time":1.0236128084932643,"velocity":0.21776692644562665,"position":1.3828104517068303,"holonomicRotation":17.063599999999894,"angularVelocity":-22.979561441053153,"angularAcceleration":-91.31757796097949,"curveRadius":-0.009473837847623203},{"acceleration":0.28337296919742483,"curvature":-103.26876015083907,"pose":{"rotation":{"radians":1.124435782381438},"translation":{"x":4.173719527691459,"y":7.234553425332714}},"time":1.0274067866501027,"velocity":0.2188420373010001,"position":1.3836407336161483,"holonomicRotation":16.475199999999887,"angularVelocity":-23.052932426431983,"angularAcceleration":-19.338800157977794,"curveRadius":-0.009683470572701311},{"acceleration":0.9812494560367122,"curvature":-98.71393018015709,"pose":{"rotation":{"radians":1.0381258149716643},"translation":{"x":4.174146495254703,"y":7.235277700761509}},"time":1.0311846471123072,"velocity":0.2225490608245209,"position":1.384481492913938,"holonomicRotation":15.886799999999909,"angularVelocity":-22.846256041814893,"angularAcceleration":54.70725737087888,"curveRadius":-0.01013028250597416},{"acceleration":1.6841479602520704,"curvature":-92.36721018893563,"pose":{"rotation":{"radians":0.9542719584715642},"translation":{"x":4.174642402179387,"y":7.235977467190328}},"time":1.0349322108620633,"velocity":0.22886051266958732,"position":1.3853391622749691,"holonomicRotation":15.298399999999901,"angularVelocity":-22.375565060249155,"angularAcceleration":125.59919270122222,"curveRadius":-0.010826352749579816},{"acceleration":2.392949941332771,"curvature":-84.82241606048132,"pose":{"rotation":{"radians":0.8739652228000199},"translation":{"x":4.175207640944315,"y":7.236652874543099}},"time":1.038636987763855,"velocity":0.2377258583393808,"position":1.3862198835439035,"holonomicRotation":14.709999999999894,"angularVelocity":-21.67653756227699,"angularAcceleration":188.68275108120486,"curveRadius":-0.01178933643303635},{"acceleration":3.108375099983395,"curvature":-76.67481688273978,"pose":{"rotation":{"radians":0.7980204174349064},"translation":{"x":4.17584260402829,"y":7.2373040727437505}},"time":1.0422885817474021,"velocity":0.24907638215308775,"position":1.3871294093624174,"holonomicRotation":14.121599999999887,"angularVelocity":-20.79771346630992,"angularAcceleration":240.66862305250052,"curveRadius":-0.013042091793050103},{"acceleration":3.8310696883378257,"curvature":-68.43572176525393,"pose":{"rotation":{"radians":0.7269601925921108},"translation":{"x":4.176547683910113,"y":7.237931211716212}},"time":1.0458788433521278,"velocity":0.2628309245601553,"position":1.3880730411394002,"holonomicRotation":13.533199999999908,"angularVelocity":-19.792492209833227,"angularAcceleration":279.9855183682381,"curveRadius":-0.014612251821207772},{"acceleration":4.5616903548359415,"curvature":-60.48950473559918,"pose":{"rotation":{"radians":0.6610380723600429},"translation":{"x":4.177323273068587,"y":7.238534441384411}},"time":1.0494018071292792,"velocity":0.2789015944428234,"position":1.389055601354012,"holonomicRotation":12.944799999999901,"angularVelocity":-18.712119795160202,"angularAcceleration":306.66577433463704,"curveRadius":-0.016531793480059388},{"acceleration":4.983775704791471,"curvature":-53.088010751163864,"pose":{"rotation":{"radians":0.600285371116775},"translation":{"x":4.178169763982515,"y":7.23911391167228}},"time":1.0528655383411196,"velocity":0.29616405390432154,"position":1.3900814340313457,"holonomicRotation":12.356399999999894,"angularVelocity":-17.539669659005593,"angularAcceleration":338.49339467990774,"curveRadius":-0.01883664476876404},{"acceleration":5.029085435810858,"curvature":-46.368522695141934,"pose":{"rotation":{"radians":0.5445669516943998},"translation":{"x":4.179087549130699,"y":7.239669772503745}},"time":1.056289435338415,"velocity":0.3133831244271358,"position":1.3911544255700747,"holonomicRotation":11.767999999999887,"angularVelocity":-16.273392414079662,"angularAcceleration":369.83508730730796,"curveRadius":-0.02156635454130547},{"acceleration":5.017337491094505,"curvature":-40.38146540227392,"pose":{"rotation":{"radians":0.4936347891091133},"translation":{"x":4.180077020991942,"y":7.240202173802735}},"time":1.0596897511576346,"velocity":0.3304436564684687,"position":1.3922780383625253,"holonomicRotation":11.179599999999908,"angularVelocity":-14.978656481671715,"angularAcceleration":380.7693170998006,"curveRadius":-0.024763836330310318},{"acceleration":5.00852095761643,"curvature":-35.11829359417467,"pose":{"rotation":{"radians":0.4471732335970402},"translation":{"x":4.181138572045048,"y":7.2407112654931804}},"time":1.0630785167655925,"velocity":0.34741636003637544,"position":1.3934553509750585,"holonomicRotation":10.591199999999901,"angularVelocity":-13.710465959335469,"angularAcceleration":374.23376800040216,"curveRadius":-0.028475187648806414},{"acceleration":5.001944507557393,"curvature":-30.53474237529469,"pose":{"rotation":{"radians":0.40483387514172753},"translation":{"x":4.182272594768817,"y":7.24119719749901}},"time":1.0664646486299552,"velocity":0.3643536037171893,"position":1.3946891003225006,"holonomicRotation":10.002799999999894,"angularVelocity":-12.503753590022082,"angularAcceleration":356.3689831496027,"curveRadius":-0.03274958038647441},{"acceleration":4.997079232185751,"curvature":-26.56803536452875,"pose":{"rotation":{"radians":0.3662604231114881},"translation":{"x":4.183479481642053,"y":7.241660119744151}},"time":1.0698547411635693,"velocity":0.3812941647121003,"position":1.3959817228234017,"holonomicRotation":9.414399999999887,"angularVelocity":-11.378288836593217,"angularAcceleration":331.9864405674585,"curveRadius":-0.03763921518017512},{"acceleration":4.993519233782345,"curvature":-23.14850609425405,"pose":{"rotation":{"radians":0.3311052143349693},"translation":{"x":4.184759625143557,"y":7.242100182152535}},"time":1.0732536446968668,"velocity":0.3982666548793923,"position":1.3973353927638659,"holonomicRotation":8.82599999999988,"angularVelocity":-10.343102836582165,"angularAcceleration":304.5646897212002,"curveRadius":-0.04319933199698883},{"acceleration":4.990952929802148,"curvature":-20.2068086960801,"pose":{"rotation":{"radians":0.2990392897508607},"translation":{"x":4.186113417752133,"y":7.242517534648088}},"time":1.0766648929511367,"velocity":0.4152920343483229,"position":1.3987520569910488,"holonomicRotation":8.237599999999901,"angularVelocity":-9.400055989467107,"angularAcceleration":276.4521303703551,"curveRadius":-0.049488269772850826},{"acceleration":4.989141335869193,"curvature":-17.677973760058936,"pose":{"rotation":{"radians":0.26975783992898306},"translation":{"x":4.187541251946585,"y":7.242912327154743}},"time":1.0800910224813363,"velocity":0.43238547880948386,"position":1.4002334656484274,"holonomicRotation":7.649199999999894,"angularVelocity":-8.54650986303244,"angularAcceleration":249.12838785314088,"curveRadius":-0.05656756897441317},{"acceleration":4.98790135198043,"curvature":-15.503368216870259,"pose":{"rotation":{"radians":0.24298249226558521},"translation":{"x":4.189043520205712,"y":7.243284709596425}},"time":1.0835338132570502,"velocity":0.4495577795742533,"position":1.4017811990250961,"holonomicRotation":7.060799999999887,"angularVelocity":-7.777221855093755,"angularAcceleration":223.4489569814624,"curveRadius":-0.0645021124449481},{"acceleration":4.987092836831103,"curvature":-13.631350840202826,"pose":{"rotation":{"radians":0.21846155503721576},"translation":{"x":4.190620615008319,"y":7.243634831897065}},"time":1.0869944709421422,"velocity":0.46681640072629993,"position":1.4033966907897966,"holonomicRotation":6.47239999999988,"angularVelocity":-7.0856292241796375,"angularAcceleration":199.8442763909888,"curveRadius":-0.0733603009505638},{"acceleration":4.986608618223714,"curvature":-12.017170913301284,"pose":{"rotation":{"radians":0.1959690177817941},"translation":{"x":4.1922729288332095,"y":7.243962843980593}},"time":1.0904737656527348,"velocity":0.4841662817154812,"position":1.4050812479728165,"holonomicRotation":5.883999999999901,"angularVelocity":-6.464682967770399,"angularAcceleration":178.46900250179635,"curveRadius":-0.08321426126120446},{"acceleration":4.986366792925038,"curvature":-10.62246751241353,"pose":{"rotation":{"radians":0.17530285715677163},"translation":{"x":4.194000854159183,"y":7.244268895770934}},"time":1.0939721379770617,"velocity":0.501610449302793,"position":1.4068360680862506,"holonomicRotation":5.295599999999894,"angularVelocity":-5.907364542451484,"angularAcceleration":159.30792198515942,"curveRadius":-0.09414008551510175},{"acceleration":4.986304808004557,"curvature":-9.414591177817824,"pose":{"rotation":{"radians":0.1562830112942324},"translation":{"x":4.195804783465044,"y":7.244553137192022}},"time":1.097489780215731,"velocity":0.5191504857103099,"position":1.408662253763011,"holonomicRotation":4.707199999999887,"angularVelocity":-5.406987002104583,"angularAcceleration":142.2479906700754,"curveRadius":-0.10621810136123049},{"acceleration":4.98637492310889,"curvature":-8.365878430483251,"pose":{"rotation":{"radians":0.1387492533994057},"translation":{"x":4.197685109229596,"y":7.244815718167781}},"time":1.1010266987692976,"velocity":0.5367868876908926,"position":1.410560825265396,"holonomicRotation":4.1187999999998794,"angularVelocity":-4.957354157094221,"angularAcceleration":127.12558635453047,"curveRadius":-0.11953317374972128},{"acceleration":4.986540736941219,"curvature":-7.452951076603088,"pose":{"rotation":{"radians":0.1225591046322978},"translation":{"x":4.199642223931639,"y":7.245056788622145}},"time":1.1045827621196813,"velocity":0.5545193424507247,"position":1.412532731176164,"holonomicRotation":3.5303999999999007,"angularVelocity":-4.552829118007946,"angularAcceleration":113.75642085865104,"curveRadius":-0.13417503881640677},{"acceleration":4.986774531070953,"curvature":-6.656075847976563,"pose":{"rotation":{"radians":0.1075858656127977},"translation":{"x":4.201676520049977,"y":7.245276498479039}},"time":1.1081577377617926,"velocity":0.5723469399320043,"position":1.4145788575452578,"holonomicRotation":2.9419999999998936,"angularVelocity":-4.188347143718519,"angularAcceleration":101.95369445207544,"curveRadius":-0.15023867258123244},{"acceleration":4.9870552392195595,"curvature":-5.958598612991372,"pose":{"rotation":{"radians":0.0937168067631946},"translation":{"x":4.203788390063413,"y":7.245474997662393}},"time":1.1117513206321286,"velocity":0.5902683362130828,"position":1.4167000357271748,"holonomicRotation":2.3535999999998864,"angularVelocity":-3.8593958592379756,"angularAcceleration":91.5385275224753,"curveRadius":-0.16782469586384405},{"acceleration":4.987366894806196,"curvature":-5.3464551250489105,"pose":{"rotation":{"radians":0.08085153282438062},"translation":{"x":4.205978226450749,"y":7.2456524360961385}},"time":1.1153631549757768,"velocity":0.6082818792481179,"position":1.418897049109262,"holonomicRotation":1.7651999999998793,"angularVelocity":-3.5619778524557604,"angularAcceleration":82.34541744841003,"curveRadius":-0.18703981920934046},{"acceleration":4.987697442390773,"curvature":-4.644066420704674,"pose":{"rotation":{"radians":0.06890052201601549},"translation":{"x":4.208246421690787,"y":7.2458089637042}},"time":1.1189928511378584,"velocity":0.6263857055123881,"position":1.4211706389005432,"holonomicRotation":1.1767999999999006,"angularVelocity":-3.2925650728603126,"angularAcceleration":74.22460932403187,"curveRadius":-0.21532853094901763},{"acceleration":3.741137579744753,"curvature":-2.013459267737106,"pose":{"rotation":{"radians":0.05252246368256985},"translation":{"x":4.213019458644182,"y":7.246059886138997}},"time":1.1263040796054586,"velocity":0.653738017086627,"position":1.4259502669014195,"holonomicRotation":0.0,"angularVelocity":-2.240123996401578,"angularAcceleration":143.94859648041836,"curveRadius":-0.4966576756846359},{"acceleration":4.83719354197316,"curvature":-0.0923384428560879,"pose":{"rotation":{"radians":0.0422658110952554},"translation":{"x":4.2184230458683984,"y":7.246288409229852}},"time":1.1341246006024344,"velocity":0.6915673907480635,"position":1.4313586842015884,"holonomicRotation":0.0,"angularVelocity":-1.311505025212618,"angularAcceleration":118.74131807178411,"curveRadius":-10.829725616648405},{"acceleration":5.1355029631367906,"curvature":-0.09177090406508007,"pose":{"rotation":{"radians":0.04176619609446153},"translation":{"x":4.223831294669405,"y":7.246514422645496}},"time":1.141543033731102,"velocity":0.7296647760621688,"position":1.43677165354915,"holonomicRotation":0.0,"angularVelocity":-0.06734777979775336,"angularAcceleration":167.71159405709966,"curveRadius":-10.896699887481136},{"acceleration":5.121942070666339,"curvature":-0.09120778898513765,"pose":{"rotation":{"radians":0.041269235636969714},"translation":{"x":4.2292441703754715,"y":7.246737934794451}},"time":1.1486164481398933,"velocity":0.7658943949058138,"position":1.442189141997689,"holonomicRotation":0.0,"angularVelocity":-0.07025750631465441,"angularAcceleration":-0.4113609564971491,"curveRadius":-10.96397589643304},{"acceleration":5.110831380766273,"curvature":-0.09064905104257247,"pose":{"rotation":{"radians":0.040774913900453846},"translation":{"x":4.234661638314865,"y":7.246958954085237}},"time":1.1553895918029555,"velocity":0.8005107900854306,"position":1.4476111165827692,"holonomicRotation":0.0,"angularVelocity":-0.07298261503172912,"angularAcceleration":-0.4023403094099795,"curveRadius":-11.031555085230396},{"acceleration":5.101561712853608,"curvature":-0.09009464068496977,"pose":{"rotation":{"radians":0.04028321520947875},"translation":{"x":4.240083663815854,"y":7.2471774889263765}},"time":1.1618983204154754,"velocity":0.8337154707744165,"position":1.453037544322099,"holonomicRotation":0.0,"angularVelocity":-0.07554450649997771,"angularAcceleration":-0.39360858637133467,"curveRadius":-11.09943934952423},{"acceleration":5.093710554719565,"curvature":-0.08954451256516915,"pose":{"rotation":{"radians":0.039794124031170774},"translation":{"x":4.245510212206704,"y":7.247393547726389}},"time":1.168171889184231,"velocity":0.8656712142275861,"position":1.458468392215688,"holonomicRotation":0.0,"angularVelocity":-0.07796059887695932,"angularAcceleration":-0.3851224822806629,"curveRadius":-11.16763016909847},{"acceleration":5.0869755952649385,"curvature":-0.08899862027603624,"pose":{"rotation":{"radians":0.03930762497675966},"translation":{"x":4.250941248815688,"y":7.247607138893798}},"time":1.174234536992202,"velocity":0.8965117556694213,"position":1.4639036272460175,"holonomicRotation":0.0,"angularVelocity":-0.08024531027045247,"angularAcceleration":-0.3768504234221315,"curveRadius":-11.236129244458185},{"acceleration":5.081134788390929,"curvature":-0.08845691875610331,"pose":{"rotation":{"radians":0.03882370279759151},"translation":{"x":4.25637673897107,"y":7.247818270837122}},"time":1.1801066129442543,"velocity":0.926348565069468,"position":1.46934321637818,"holonomicRotation":0.0,"angularVelocity":-0.08241074930221542,"angularAcceleration":-0.36876890718794825,"curveRadius":-11.304938201128586},{"acceleration":5.076021356565797,"curvature":-0.08791936186325149,"pose":{"rotation":{"radians":0.038342342386241235},"translation":{"x":4.26181664800112,"y":7.248026951964885}},"time":1.1858053971731612,"velocity":0.9552757155218599,"position":1.4747871265600538,"holonomicRotation":0.0,"angularVelocity":-0.0844672112533385,"angularAcceleration":-0.3608597673678781,"curveRadius":-11.37405889678073},{"acceleration":5.0715075929767375,"curvature":-0.08738590676019022,"pose":{"rotation":{"radians":0.03786352877242605},"translation":{"x":4.267260941234103,"y":7.248233190685607}},"time":1.1913457115829573,"velocity":0.9833734621186191,"position":1.4802353247224407,"holonomicRotation":0.0,"angularVelocity":-0.08642354538012789,"angularAcceleration":-0.3531088638814987,"curveRadius":-11.443492859143312},{"acceleration":5.067494047633372,"curvature":-0.08685650756877765,"pose":{"rotation":{"radians":0.03738724712338026},"translation":{"x":4.272709583998292,"y":7.248436995407807}},"time":1.196740382716568,"velocity":1.0107109259771303,"position":1.4856877777792343,"holonomicRotation":0.0,"angularVelocity":-0.08828742980798075,"angularAcceleration":-0.3455047363759107,"curveRadius":-11.513242104607375},{"acceleration":5.06390211833749,"curvature":-0.08633112222257158,"pose":{"rotation":{"radians":0.03691348274303552},"translation":{"x":4.278162541621952,"y":7.248638374540008}},"time":1.2020005982831323,"velocity":1.0373481427275677,"position":1.4911444526275566,"holonomicRotation":0.0,"angularVelocity":-0.09006558274077937,"angularAcceleration":-0.33803803481004074,"curveRadius":-11.583308246843876},{"acceleration":5.0606688575732175,"curvature":-0.0858097070748994,"pose":{"rotation":{"radians":0.036442221069037384},"translation":{"x":4.2836197794333515,"y":7.248837336490732}},"time":1.2071361857596399,"velocity":1.0633376503352725,"position":1.4966053161479174,"holonomicRotation":0.0,"angularVelocity":-0.09176392694193117,"angularAcceleration":-0.33070105590076526,"curveRadius":-11.653693201949114},{"acceleration":5.057743258614767,"curvature":-0.08529222034627844,"pose":{"rotation":{"radians":0.035973447671555636},"translation":{"x":4.289081262760758,"y":7.2490338896685}},"time":1.2121558329224151,"velocity":1.0887257369334238,"position":1.5020703352043556,"holonomicRotation":0.0,"angularVelocity":-0.0933877187540355,"angularAcceleration":-0.3234872411244476,"curveRadius":-11.724398731092865},{"acceleration":5.055083551479784,"curvature":-0.08477861915359158,"pose":{"rotation":{"radians":0.03550714825369283},"translation":{"x":4.294546956932441,"y":7.249228042481832}},"time":1.2170672644486764,"velocity":1.1135534336560464,"position":1.5075394766445904,"holonomicRotation":0.0,"angularVelocity":-0.09494165099717142,"angularAcceleration":-0.3163909004588769,"curveRadius":-11.795426842094724},{"acceleration":5.052655201861216,"curvature":-0.08426886399643231,"pose":{"rotation":{"radians":0.035043308648461835},"translation":{"x":4.300016827276667,"y":7.24941980333925}},"time":1.221877384831067,"velocity":1.1378573134277103,"position":1.5130127073001611,"holonomicRotation":0.0,"angularVelocity":-0.09642993695731247,"angularAcceleration":-0.30940721683173833,"curveRadius":-11.866779170564552},{"acceleration":5.0504294090686,"curvature":-0.08376291126058584,"pose":{"rotation":{"radians":0.03458191481812056},"translation":{"x":4.305490839121704,"y":7.249609180649274}},"time":1.2265923951399984,"velocity":1.1616701401559997,"position":1.5184899939865746,"holonomicRotation":0.0,"angularVelocity":-0.0978563778465695,"angularAcceleration":-0.3025318707267646,"curveRadius":-11.93845802337274},{"acceleration":5.04838196321081,"curvature":-0.08326072223089803,"pose":{"rotation":{"radians":0.03412295285344635},"translation":{"x":4.310968957795821,"y":7.249796182820425}},"time":1.231217889254494,"velocity":1.1850214012145572,"position":1.523971303503444,"holonomicRotation":0.0,"angularVelocity":-0.0992244186920242,"angularAcceleration":-0.2957610174375635,"curveRadius":-12.010465117355183},{"acceleration":5.0464923652677465,"curvature":-0.08276225658140846,"pose":{"rotation":{"radians":0.033666408971650075},"translation":{"x":4.316451148627287,"y":7.249980818261227}},"time":1.2357589338081496,"velocity":1.2079377478849207,"position":1.5294566026346317,"holonomicRotation":0.0,"angularVelocity":-0.10053719500037912,"angularAcceleration":-0.2890912636605021,"curveRadius":-12.08280249120996},{"acceleration":5.044743142217605,"curvature":-0.08226747437464489,"pose":{"rotation":{"radians":0.03321226951536671},"translation":{"x":4.321937376944368,"y":7.2501630953801985}},"time":1.2402201350963136,"velocity":1.2304433624894382,"position":1.5349458581483824,"holonomicRotation":0.0,"angularVelocity":-0.10179757131520703,"angularAcceleration":-0.2825194904726264,"curveRadius":-12.155472227651167},{"acceleration":5.043119308441352,"curvature":-0.08177633657339285,"pose":{"rotation":{"radians":0.032760520951862215},"translation":{"x":4.327427608075333,"y":7.250343022585863}},"time":1.2446056954526168,"velocity":1.252560266600646,"position":1.5404390367974667,"holonomicRotation":0.0,"angularVelocity":-0.10300817382554357,"angularAcceleration":-0.27604283420625675,"curveRadius":-12.228476377179323},{"acceleration":5.041607938150265,"curvature":-0.08128880505125896,"pose":{"rotation":{"radians":0.032311149870765554},"translation":{"x":4.332921807348451,"y":7.250520608286738}},"time":1.2489194610520136,"velocity":1.2743085814898842,"position":1.545936105319314,"holonomicRotation":0.0,"angularVelocity":-0.10417141839127733,"angularAcceleration":-0.2696587329400612,"curveRadius":-12.301816952154994},{"acceleration":5.040197823303244,"curvature":-0.08080484208801557,"pose":{"rotation":{"radians":0.031864142985472466},"translation":{"x":4.338419940091987,"y":7.250695860891349}},"time":1.253164962681674,"velocity":1.2957067495625296,"position":1.5514370304361438,"holonomicRotation":0.0,"angularVelocity":-0.10528953331925377,"angularAcceleration":-0.2633646210767888,"curveRadius":-12.375495999494234},{"acceleration":5.038879197263129,"curvature":-0.08032440778407464,"pose":{"rotation":{"radians":0.03141948712788345},"translation":{"x":4.343921971634214,"y":7.250868788808213}},"time":1.2573454507039472,"velocity":1.3167717236923693,"position":1.5569417788551076,"holonomicRotation":0.0,"angularVelocity":-0.10636458117328547,"angularAcceleration":-0.2571584581283294,"curveRadius":-12.449516001265346},{"acceleration":5.037643510345878,"curvature":-0.07984746728228212,"pose":{"rotation":{"radians":0.030977169251573233},"translation":{"x":4.349427867303395,"y":7.251039400445854}},"time":1.2614639251914388,"velocity":1.3375191299668063,"position":1.5624503172684079,"holonomicRotation":0.0,"angularVelocity":-0.10739847427818264,"angularAcceleration":-0.2510378801755976,"curveRadius":-12.52387876580647},{"acceleration":5.036483245910405,"curvature":-0.0793739819963034,"pose":{"rotation":{"radians":0.030537176427439583},"translation":{"x":4.354937592427801,"y":7.251207704212792}},"time":1.2655231620246763,"velocity":1.3579634082685894,"position":1.5679626123534405,"holonomicRotation":0.0,"angularVelocity":-0.10839299164092576,"angularAcceleration":-0.24500106882158348,"curveRadius":-12.598586776792576},{"acceleration":5.035391769003609,"curvature":-0.07890391633571452,"pose":{"rotation":{"radians":0.030099495844168267},"translation":{"x":4.360451112335698,"y":7.251373708517549}},"time":1.2695257355942409,"velocity":1.3781179342756062,"position":1.573478630772915,"holonomicRotation":0.0,"angularVelocity":-0.10934979099433018,"angularAcceleration":-0.23904603794915344,"curveRadius":-12.673642151617347},{"acceleration":5.034363200598379,"curvature":-0.07843723407991222,"pose":{"rotation":{"radians":0.029664114806888797},"translation":{"x":4.365968392355355,"y":7.251537421768646}},"time":1.2734740386320893,"velocity":1.3979951257941612,"position":1.5789983391749853,"holonomicRotation":0.0,"angularVelocity":-0.11027042076201019,"angularAcceleration":-0.2331710000106,"curveRadius":-12.749047206090863},{"acceleration":5.033392313028692,"curvature":-0.07797389994221293,"pose":{"rotation":{"radians":0.029231020735436264},"translation":{"x":4.371489397815042,"y":7.251698852374603}},"time":1.2773702996035514,"velocity":1.4176065358174723,"position":1.5845217041933806,"holonomicRotation":0.0,"angularVelocity":-0.1111563302932477,"angularAcceleration":-0.2273742795275514,"curveRadius":-12.824804206806482},{"acceleration":5.032474442145508,"curvature":-0.07751387746328556,"pose":{"rotation":{"radians":0.028800201164317585},"translation":{"x":4.377014094043024,"y":7.251858008743942}},"time":1.281216598016885,"velocity":1.4369629342794386,"position":1.5900486924475188,"holonomicRotation":0.0,"angularVelocity":-0.11200887836086659,"angularAcceleration":-0.22165416616231332,"curveRadius":-12.90091571633286},{"acceleration":5.031605413436068,"curvature":-0.07705713270417594,"pose":{"rotation":{"radians":0.028371643741208263},"translation":{"x":4.382542446367571,"y":7.252014899285185}},"time":1.2850148779471982,"velocity":1.4560743801385476,"position":1.5955792705426421,"holonomicRotation":0.0,"angularVelocity":-0.1128293414313969,"angularAcceleration":-0.21600911085631186,"curveRadius":-12.977383986489901},{"acceleration":5.030781479328929,"curvature":-0.07660363055316788,"pose":{"rotation":{"radians":0.02794533622471329},"translation":{"x":4.388074420116951,"y":7.2521695324068505}},"time":1.2887669600227742,"velocity":1.4749502851532779,"position":1.6011134050699316,"holonomicRotation":0.0,"angularVelocity":-0.11361892088395155,"angularAcceleration":-0.21043768143942157,"curveRadius":-13.054211566460094},{"acceleration":5.029999265991381,"curvature":-0.07615333791255818,"pose":{"rotation":{"radians":0.027521266486314477},"translation":{"x":4.393609980619431,"y":7.252321916517463}},"time":1.292474552082165,"velocity":1.4935994704906088,"position":1.6066510626066328,"holonomicRotation":0.0,"angularVelocity":-0.11437874814860255,"angularAcceleration":-0.20493820584346012,"curveRadius":-13.131400768646984},{"acceleration":5.029255728026957,"curvature":-0.07570622050395055,"pose":{"rotation":{"radians":0.027099422505370452},"translation":{"x":4.399149093203279,"y":7.252472060025542}},"time":1.2961392586778204,"velocity":1.512030217128347,"position":1.6121922097161734,"holonomicRotation":0.0,"angularVelocity":-0.11510989213819418,"angularAcceleration":-0.19950955704296147,"curveRadius":-13.208954209354797},{"acceleration":5.02854810904253,"curvature":-0.07526224554043481,"pose":{"rotation":{"radians":0.02667979237161422},"translation":{"x":4.404691723196764,"y":7.252619971339609}},"time":1.2997625895752272,"velocity":1.530250310860937,"position":1.617736812948282,"holonomicRotation":0.0,"angularVelocity":-0.11581336224537665,"angularAcceleration":-0.1941501141079747,"curveRadius":-13.286874352729054},{"acceleration":5.027873908773505,"curvature":-0.07482137903817784,"pose":{"rotation":{"radians":0.026262364281905093},"translation":{"x":4.410237835928155,"y":7.252765658868184}},"time":1.303345967374296,"velocity":1.5482670826021534,"position":1.6232848388391077,"holonomicRotation":0.0,"angularVelocity":-0.11649011438805056,"angularAcceleration":-0.1888587195159178,"curveRadius":-13.365163979265162},{"acceleration":5.027230853417731,"curvature":-0.07438358851022372,"pose":{"rotation":{"radians":0.02584712654086241},"translation":{"x":4.415787396725717,"y":7.25290913101979}},"time":1.3068907343612755,"velocity":1.5660874445672732,"position":1.6288362539113328,"holonomicRotation":0.0,"angularVelocity":-0.11714105400098862,"angularAcceleration":-0.18363396390484202,"curveRadius":-13.443825715165033},{"acceleration":5.026616870953028,"curvature":-0.07394884299134491,"pose":{"rotation":{"radians":0.025434067558096185},"translation":{"x":4.42134037091772,"y":7.253050396202948}},"time":1.3103981586840314,"velocity":1.5837179228416294,"position":1.634391024674292,"holonomicRotation":0.0,"angularVelocity":-0.11776704064185226,"angularAcceleration":-0.17847473908482336,"curveRadius":-13.522862015799781},{"acceleration":5.02603006905432,"curvature":-0.07351710921903042,"pose":{"rotation":{"radians":0.02502317584871694},"translation":{"x":4.4268967238324315,"y":7.253189462826176}},"time":1.3138694399305726,"velocity":1.6011646867648897,"position":1.639949117624083,"holonomicRotation":0.0,"angularVelocity":-0.1183688903884306,"angularAcceleration":-0.17337971308952088,"curveRadius":-13.602275859632726},{"acceleration":5.0254687160881195,"curvature":-0.07308835654407053,"pose":{"rotation":{"radians":0.02461444003250568},"translation":{"x":4.43245642079812,"y":7.253326339298}},"time":1.317305714179806,"velocity":1.6184335755043109,"position":1.645510499243683,"holonomicRotation":0.0,"angularVelocity":-0.11894737921528048,"angularAcceleration":-0.1683476884823589,"curveRadius":-13.682069857420093},{"acceleration":5.02493122440924,"curvature":-0.07266255310284939,"pose":{"rotation":{"radians":0.02420784883109217},"translation":{"x":4.438019427143055,"y":7.253461034026938}},"time":1.3207080585842608,"velocity":1.6355301221384502,"position":1.6510751360030582,"holonomicRotation":0.0,"angularVelocity":-0.11950324631484645,"angularAcceleration":-0.16337766947935767,"curveRadius":-13.762246952492315},{"acceleration":5.024416135777345,"curvature":-0.07223966856684617,"pose":{"rotation":{"radians":0.023803391069097124},"translation":{"x":4.443585708195501,"y":7.253593555421513}},"time":1.324077495536704,"velocity":1.6524595755307907,"position":1.6566429943592704,"holonomicRotation":0.0,"angularVelocity":-0.12003719544351799,"angularAcceleration":-0.15846835427039307,"curveRadius":-13.842809910937799},{"acceleration":5.0239221081101375,"curvature":-0.07181967249426098,"pose":{"rotation":{"radians":0.02340105567220796},"translation":{"x":4.449155229283729,"y":7.253723911890244}},"time":1.3274149964659019,"velocity":1.6692269202348258,"position":1.6622140407565962,"holonomicRotation":0.0,"angularVelocity":-0.1205498980897262,"angularAcceleration":-0.15361872763027068,"curveRadius":-13.923761627845195},{"acceleration":5.0234479047184495,"curvature":-0.07140253376185805,"pose":{"rotation":{"radians":0.023000831666507793},"translation":{"x":4.454727955736006,"y":7.2538521118416535}},"time":1.330721485301052,"velocity":1.6858368946457358,"position":1.6677882416266265,"holonomicRotation":0.0,"angularVelocity":-0.12104199519608859,"angularAcceleration":-0.1488276933316906,"curveRadius":-14.005105243676688},{"acceleration":5.022992383536347,"curvature":-0.07098822392328345,"pose":{"rotation":{"radians":0.022602708177678732},"translation":{"x":4.4603038528806005,"y":7.253978163684263}},"time":1.3339978416395686,"velocity":1.7022940075798554,"position":1.6733655633883795,"holonomicRotation":0.0,"angularVelocity":-0.12151409910721844,"angularAcceleration":-0.14409418950553263,"curveRadius":-14.086843489431345},{"acceleration":5.022554488758197,"curvature":-0.07057671217219998,"pose":{"rotation":{"radians":0.022206674429363193},"translation":{"x":4.465882886045779,"y":7.254102075826591}},"time":1.3372449036486544,"velocity":1.7186025534488658,"position":1.6789459724484013,"holonomicRotation":0.0,"angularVelocity":-0.12196679558547528,"angularAcceleration":-0.13941725688949358,"curveRadius":-14.168979670802772},{"acceleration":5.022133242482569,"curvature":-0.07016796982915255,"pose":{"rotation":{"radians":0.0218127197444713},"translation":{"x":4.471465020559811,"y":7.2542238566771635}},"time":1.340463470727507,"velocity":1.734766626168731,"position":1.68452943520088,"holonomicRotation":0.0,"angularVelocity":-0.12240064452295076,"angularAcceleration":-0.13479567983096155,"curveRadius":-14.251516787999359},{"acceleration":5.021727737867914,"curvature":-0.069761968101176,"pose":{"rotation":{"radians":0.021420833540085393},"translation":{"x":4.4770502217509645,"y":7.254343514644497}},"time":1.3436543059538266,"velocity":1.7507901319317065,"position":1.6901159180277405,"holonomicRotation":0.0,"angularVelocity":-0.12281618340972965,"angularAcceleration":-0.13022887654972276,"curveRadius":-14.334457975005764},{"acceleration":5.0213371326693546,"curvature":-0.06935867807443309,"pose":{"rotation":{"radians":0.021031005332281527},"translation":{"x":4.482638454947507,"y":7.2544610581371165}},"time":1.3468181383356188,"velocity":1.7666768009519414,"position":1.6957053872987533,"holonomicRotation":0.0,"angularVelocity":-0.12321392563250896,"angularAcceleration":-0.1257153271040263,"curveRadius":-14.41780650615685},{"acceleration":5.020960643753275,"curvature":-0.06895807185658596,"pose":{"rotation":{"radians":0.02064322472990643},"translation":{"x":4.488229685477706,"y":7.254576495563541}},"time":1.3499556648868767,"velocity":1.782430198284538,"position":1.7012978093716349,"holonomicRotation":0.0,"angularVelocity":-0.12359436519178851,"angularAcceleration":-0.12125461030027825,"curveRadius":-14.501565561167777},{"acceleration":5.020597541836172,"curvature":-0.06856012028457306,"pose":{"rotation":{"radians":0.020257481437388147},"translation":{"x":4.493823878669833,"y":7.25468983533229}},"time":1.3530675525436915,"velocity":1.7980537338048128,"position":1.7068931505921519,"holonomicRotation":0.0,"angularVelocity":-0.1239579750488524,"angularAcceleration":-0.11684543182901032,"curveRadius":-14.585738704210138},{"acceleration":5.020247146902124,"curvature":-0.06816479753083288,"pose":{"rotation":{"radians":0.019873765252685693},"translation":{"x":4.499420999852151,"y":7.254801085851889}},"time":1.3561544399355159,"velocity":1.8135506714264273,"position":1.7124913772942127,"holonomicRotation":0.0,"angularVelocity":-0.12430520974581871,"angularAcceleration":-0.11248699835502775,"curveRadius":-14.670328912041022},{"acceleration":5.01990882435755,"curvature":-0.06777207476538319,"pose":{"rotation":{"radians":0.019492066065447844},"translation":{"x":4.505021014352932,"y":7.254910255530855}},"time":1.35921693902475,"velocity":1.8289241376290604,"position":1.71809245579998,"holonomicRotation":0.0,"angularVelocity":-0.12463650636817444,"angularAcceleration":-0.10817852110401423,"curveRadius":-14.755339916357153},{"acceleration":5.019581981069068,"curvature":-0.06738192534943634,"pose":{"rotation":{"radians":0.01911237385852793},"translation":{"x":4.510623887500442,"y":7.2550173527777115}},"time":1.3622556366263905,"velocity":1.844177129356173,"position":1.723696352419955,"holonomicRotation":0.0,"angularVelocity":-0.12495228439806653,"angularAcceleration":-0.10391887291503024,"curveRadius":-14.840775101247017},{"acceleration":5.019266062198931,"curvature":-0.06699432194174937,"pose":{"rotation":{"radians":0.01873467870488943},"translation":{"x":4.516229584622949,"y":7.25512238600098}},"time":1.365271095818313,"velocity":1.8593125213401354,"position":1.7293030334530866,"holonomicRotation":0.0,"angularVelocity":-0.12525294809169885,"angularAcceleration":-0.09970743243274527,"curveRadius":-14.926638124190378},{"acceleration":5.018960547866215,"curvature":-0.06660923883819643,"pose":{"rotation":{"radians":0.018358970768149963},"translation":{"x":4.521838071048723,"y":7.25522536360918}},"time":1.36826385725163,"velocity":1.8743330729031287,"position":1.7349124651868615,"holonomicRotation":0.0,"angularVelocity":-0.12553888611263633,"angularAcceleration":-0.09554320560078036,"curveRadius":-15.012932401601915},{"acceleration":5.018664951001881,"curvature":-0.06622664844876182,"pose":{"rotation":{"radians":0.01798524030132098},"translation":{"x":4.52744931210603,"y":7.255326294010834}},"time":1.371234440369648,"velocity":1.8892414342815635,"position":1.7405246138973984,"holonomicRotation":0.0,"angularVelocity":-0.1258104728873353,"angularAcceleration":-0.09142540838250172,"curveRadius":-15.099661894768527},{"acceleration":5.018378814031817,"curvature":-0.06584652660627138,"pose":{"rotation":{"radians":0.01761347764665766},"translation":{"x":4.533063273123138,"y":7.255425185614461}},"time":1.3741833445430955,"velocity":1.904040152510203,"position":1.7461394458495476,"holonomicRotation":0.0,"angularVelocity":-0.1260680689493842,"angularAcceleration":-0.08735314777886873,"curveRadius":-15.18682991404375},{"acceleration":5.018101707436892,"curvature":-0.06546884546695995,"pose":{"rotation":{"radians":0.017243673234296875},"translation":{"x":4.538679919428317,"y":7.255522046828586}},"time":1.377111050128532,"velocity":1.9187316769073541,"position":1.751756927296983,"holonomicRotation":0.0,"angularVelocity":-0.1263120220148981,"angularAcceleration":-0.0833256823115817,"curveRadius":-15.274440733870405},{"acceleration":5.017833227179593,"curvature":-0.06509358122699387,"pose":{"rotation":{"radians":0.016875817580730867},"translation":{"x":4.544299216349833,"y":7.255616886061727}},"time":1.3800180194561946,"velocity":1.9333183641900917,"position":1.7573770244822906,"holonomicRotation":0.0,"angularVelocity":-0.12654266767299566,"angularAcceleration":-0.07934230881032393,"curveRadius":-15.36249782467502},{"acceleration":5.0175729929174375,"curvature":-0.0647207075769372,"pose":{"rotation":{"radians":0.016509901290573836},"translation":{"x":4.549921129215955,"y":7.255709711722406}},"time":1.3829046977529542,"velocity":1.9478024832511536,"position":1.7629997036370662,"holonomicRotation":0.0,"angularVelocity":-0.12676032884155686,"angularAcceleration":-0.07540194860145437,"curveRadius":-15.451005365033176},{"acceleration":5.017320646362389,"curvature":-0.0643502004855042,"pose":{"rotation":{"radians":0.01614591505333518},"translation":{"x":4.55554562335495,"y":7.255800532219145}},"time":1.385771514005498,"velocity":1.962186219624369,"position":1.7686249309820028,"holonomicRotation":0.0,"angularVelocity":-0.12696531803029926,"angularAcceleration":-0.07150412537270437,"curveRadius":-15.539967124504363},{"acceleration":5.017075849789289,"curvature":-0.06398203398943156,"pose":{"rotation":{"radians":0.0157838496433218},"translation":{"x":4.561172664095088,"y":7.255889355960464}},"time":1.3886188817684095,"velocity":1.9764716796631407,"position":1.7742526727269832,"holonomicRotation":0.0,"angularVelocity":-0.12715793678971718,"angularAcceleration":-0.06764800877739997,"curveRadius":-15.629387464693265},{"acceleration":5.016838284156195,"curvature":-0.06361618442182232,"pose":{"rotation":{"radians":0.015423695920367297},"translation":{"x":4.566802216764636,"y":7.255976191354884}},"time":1.3914471999213767,"velocity":1.9906608944527202,"position":1.7798828950711656,"holonomicRotation":0.0,"angularVelocity":-0.12733847589836148,"angularAcceleration":-0.0638326732991107,"curveRadius":-15.719270325445187},{"acceleration":5.0166076486684545,"curvature":-0.06325262800543875,"pose":{"rotation":{"radians":0.015065444826901864},"translation":{"x":4.572434246691862,"y":7.2560610468109275}},"time":1.394256853379389,"velocity":2.004755823480293,"position":1.7855155642030776,"holonomicRotation":0.0,"angularVelocity":-0.1275072171067187,"angularAcceleration":-0.060057658668193646,"curveRadius":-15.809619798153136},{"acceleration":5.016383658362109,"curvature":-0.06289133899766558,"pose":{"rotation":{"radians":0.014709087389186415},"translation":{"x":4.578068719205034,"y":7.256143930737115}},"time":1.3970482137594358,"velocity":2.0187583580753587,"position":1.7911506463006972,"holonomicRotation":0.0,"angularVelocity":-0.12766443210370754,"angularAcceleration":-0.05632199916307914,"curveRadius":-15.900440600209167},{"acceleration":5.016166044251732,"curvature":-0.06253229521324753,"pose":{"rotation":{"radians":0.014354614715342162},"translation":{"x":4.583705599632421,"y":7.256224851541967}},"time":1.3998216400069188,"velocity":2.0326703246442195,"position":1.7967881075315453,"holonomicRotation":0.0,"angularVelocity":-0.12781038405688677,"angularAcceleration":-0.052625143110148556,"curveRadius":-15.991736695251657},{"acceleration":5.015954551259749,"curvature":-0.062175473126521434,"pose":{"rotation":{"radians":0.014002017995331961},"translation":{"x":4.58934485330229,"y":7.256303817634006}},"time":1.402577478984711,"velocity":2.0464934877074152,"position":1.8024279140527673,"holonomicRotation":0.0,"angularVelocity":-0.12794532730380342,"angularAcceleration":-0.04896630318537715,"curveRadius":-16.083512512483676},{"acceleration":5.015748937965357,"curvature":-0.061820847837329614,"pose":{"rotation":{"radians":0.013651288500278191},"translation":{"x":4.594986445542909,"y":7.256380837421752}},"time":1.4053160660275474,"velocity":2.060229552759048,"position":1.808070032011222,"holonomicRotation":0.0,"angularVelocity":-0.12806950794980188,"angularAcceleration":-0.04534478694890468,"curveRadius":-16.175772979227318},{"acceleration":5.0155489752838305,"curvature":-0.061468398055196445,"pose":{"rotation":{"radians":0.013302417581193549},"translation":{"x":4.600630341682546,"y":7.256455919313727}},"time":1.4080377254642054,"velocity":2.073880168957649,"position":1.8137144275435633,"holonomicRotation":0.0,"angularVelocity":-0.12818316442744992,"angularAcceleration":-0.04175999249473145,"curveRadius":-16.268522226690134},{"acceleration":5.015354446202899,"curvature":-0.06111809987541206,"pose":{"rotation":{"radians":0.012955396669270591},"translation":{"x":4.606276507049469,"y":7.256529071718451}},"time":1.4107427711097311,"velocity":2.0874469316631186,"position":1.8193610667763247,"holonomicRotation":0.0,"angularVelocity":-0.12828652725211562,"angularAcceleration":-0.038211120332353084,"curveRadius":-16.361765206027},{"acceleration":5.015165144280811,"curvature":-0.060769931780533096,"pose":{"rotation":{"radians":0.012610217275084601},"translation":{"x":4.6119249069719475,"y":7.256600303044448}},"time":1.4134315067297873,"velocity":2.100931384827011,"position":1.8250099158260031,"holonomicRotation":0.0,"angularVelocity":-0.12837981972313517,"angularAcceleration":-0.034697524860254056,"curveRadius":-16.45550637791464},{"acceleration":5.014980873786186,"curvature":-0.060423870239448986,"pose":{"rotation":{"radians":0.01226687098592727},"translation":{"x":4.617575506778247,"y":7.256669621700234}},"time":1.4161042264790198,"velocity":2.114335023250402,"position":1.8306609407991383,"holonomicRotation":0.0,"angularVelocity":-0.128463258916665,"angularAcceleration":-0.031218833756806702,"curveRadius":-16.54975088548911},{"acceleration":5.014801448130017,"curvature":-0.06007989349105544,"pose":{"rotation":{"radians":0.011925349469885216},"translation":{"x":4.623228271796639,"y":7.256737036094336}},"time":1.4187612153152047,"velocity":2.1276592947137676,"position":1.836314107792398,"holonomicRotation":0.0,"angularVelocity":-0.12853705344597235,"angularAcceleration":-0.027773744587245894,"curveRadius":-16.644503541752744},{"acceleration":5.0146266906415065,"curvature":-0.05973797965600826,"pose":{"rotation":{"radians":0.011585644469115142},"translation":{"x":4.628883167355388,"y":7.2568025546352715}},"time":1.4214027493907802,"velocity":2.140905601993387,"position":1.8419693828926538,"holonomicRotation":0.0,"angularVelocity":-0.12860140776191664,"angularAcceleration":-0.0243624780536924,"curveRadius":-16.73976933532641},{"acceleration":5.014456432160628,"curvature":-0.059398106730449346,"pose":{"rotation":{"radians":0.011247747804247421},"translation":{"x":4.634540158782764,"y":7.256866185731562}},"time":1.4240290964232631,"velocity":2.1540753047635075,"position":1.8476267321770643,"holonomicRotation":0.0,"angularVelocity":-0.12865651823181487,"angularAcceleration":-0.02098369682932809,"curveRadius":-16.83555343839551},{"acceleration":5.014290512401667,"curvature":-0.05906025322758743,"pose":{"rotation":{"radians":0.010911651371593223},"translation":{"x":4.640199211407036,"y":7.25692793779173}},"time":1.426640516045918,"velocity":2.167169721401285,"position":1.8532861217131549,"holonomicRotation":0.0,"angularVelocity":-0.1287025760771925,"angularAcceleration":-0.017637090943965157,"curveRadius":-16.931861029219114},{"acceleration":5.014128778296063,"curvature":-0.05872439883713332,"pose":{"rotation":{"radians":0.010577347142722182},"translation":{"x":4.6458602905564685,"y":7.256987819224296}},"time":1.429237260139946,"velocity":2.180190130693021,"position":1.85894751755889,"holonomicRotation":0.0,"angularVelocity":-0.12873976671011814,"angularAcceleration":-0.014322024650476758,"curveRadius":-17.028697096983613},{"acceleration":5.013971083818002,"curvature":-0.05839051987232192,"pose":{"rotation":{"radians":0.010244827163533365},"translation":{"x":4.651523361559334,"y":7.25704583843778}},"time":1.4318195731493828,"velocity":2.1931377734517046,"position":1.864610885762762,"holonomicRotation":0.0,"angularVelocity":-0.12876827014139788,"angularAcceleration":-0.011037945894081476,"curveRadius":-17.126067762140558},{"acceleration":5.013817289728104,"curvature":-0.05805859772774084,"pose":{"rotation":{"radians":0.009914083555288222},"translation":{"x":4.657188389743897,"y":7.257102003840705}},"time":1.4343876923797716,"velocity":2.206013854051111,"position":1.8702761923638547,"holonomicRotation":0.0,"angularVelocity":-0.12878826042475855,"angularAcceleration":-0.0077840168494199375,"curveRadius":-17.223977828217375},{"acceleration":5.013667263350616,"curvature":-0.057728611075202586,"pose":{"rotation":{"radians":0.009585108511969143},"translation":{"x":4.662855340438426,"y":7.257156323841592}},"time":1.4369418482816378,"velocity":2.2188195418817918,"position":1.8759434033919282,"holonomicRotation":0.0,"angularVelocity":-0.128799907272186,"angularAcceleration":-0.0045599594836508595,"curveRadius":-17.32243304273003},{"acceleration":5.013520877540345,"curvature":-0.05740053844881575,"pose":{"rotation":{"radians":0.009257894300979341},"translation":{"x":4.668524178971191,"y":7.257208806848961}},"time":1.439482264719693,"velocity":2.231555972731628,"position":1.8816124848674958,"holonomicRotation":0.0,"angularVelocity":-0.12880337494600144,"angularAcceleration":-0.0013650021167827178,"curveRadius":-17.421439363181292},{"acceleration":5.013378011152268,"curvature":-0.057074360237503834,"pose":{"rotation":{"radians":0.00893243326244697},"translation":{"x":4.674194870670459,"y":7.257259461271335}},"time":1.4420091592286286,"velocity":2.244224250099227,"position":1.8872834028018917,"holonomicRotation":0.0,"angularVelocity":-0.1287988229747913,"angularAcceleration":0.0018014092768949862,"curveRadius":-17.521002352697337},{"acceleration":5.013238548076842,"curvature":-0.056750056717563134,"pose":{"rotation":{"radians":0.008608717807873756},"translation":{"x":4.679867380864498,"y":7.257308295517233}},"time":1.4445227432563188,"velocity":2.256825446440674,"position":1.8929561231973497,"holonomicRotation":0.0,"angularVelocity":-0.12878640658402252,"angularAcceleration":0.004939715812963413,"curveRadius":-17.621127763393368},{"acceleration":5.013102377695705,"curvature":-0.05642760670149204,"pose":{"rotation":{"radians":0.008286740421168837},"translation":{"x":4.685541674881576,"y":7.257355317995176}},"time":1.447023222395171,"velocity":2.269360604357032,"position":1.8986306120470773,"holonomicRotation":0.0,"angularVelocity":-0.12876627591171605,"angularAcceleration":0.008050725956349728,"curveRadius":-17.721821967217302},{"acceleration":5.012969393740183,"curvature":-0.056106992231214715,"pose":{"rotation":{"radians":0.007966493656865747},"translation":{"x":4.691217718049961,"y":7.257400537113688}},"time":1.4495107966023244,"velocity":2.28183073772215,"position":1.904306835335325,"holonomicRotation":0.0,"angularVelocity":-0.12873857727828047,"angularAcceleration":0.011134796845827381,"curveRadius":-17.823090496083612},{"acceleration":5.012839494524697,"curvature":-0.05578819118193453,"pose":{"rotation":{"radians":0.007647970139114335},"translation":{"x":4.6968954756979215,"y":7.257443961281288}},"time":1.4519856604093508,"velocity":2.2942368327575817,"position":1.9099847590374637,"holonomicRotation":0.0,"angularVelocity":-0.12870345303328826,"angularAcceleration":0.014192395109781977,"curveRadius":-17.92494036486744},{"acceleration":5.012712582843627,"curvature":-0.055471185347883104,"pose":{"rotation":{"radians":0.007331162563211535},"translation":{"x":4.7025749131537244,"y":7.257485598906498}},"time":1.454448003122051,"velocity":2.3065798490568072,"position":1.9156643491200498,"holonomicRotation":0.0,"angularVelocity":-0.12866104067024514,"angularAcceleration":0.017224394810828752,"curveRadius":-18.02737752453963},{"acceleration":5.0125885655025755,"curvature":-0.055155956419945217,"pose":{"rotation":{"radians":0.007016063692565577},"translation":{"x":4.708255995745639,"y":7.257525458397837}},"time":1.4568980090109254,"velocity":2.3188607205607927,"position":1.9213455715409031,"holonomicRotation":0.0,"angularVelocity":-0.12861147480373225,"angularAcceleration":0.0202309172961473,"curveRadius":-18.130408117415676},{"acceleration":5.012467352924051,"curvature":-0.054842483223675895,"pose":{"rotation":{"radians":0.00670266636070771},"translation":{"x":4.7139386888019335,"y":7.257563548163829}},"time":1.4593358574928332,"velocity":2.3310803564877314,"position":1.927028392249172,"holonomicRotation":0.0,"angularVelocity":-0.128554885253821,"angularAcceleration":0.023212906926423933,"curveRadius":-18.234039401926513},{"acceleration":5.012348859486288,"curvature":-0.05453074857125088,"pose":{"rotation":{"radians":0.006390963468594801},"translation":{"x":4.719622957650875,"y":7.2575998766129945}},"time":1.4617617233043403,"velocity":2.3432396422213055,"position":1.9327127771854047,"holonomicRotation":0.0,"angularVelocity":-0.12849139908495794,"angularAcceleration":0.026170519639593538,"curveRadius":-18.338277507659402},{"acceleration":5.012233002797567,"curvature":-0.05422073170168146,"pose":{"rotation":{"radians":0.00608094798536829},"translation":{"x":4.7253087676207315,"y":7.257634452153854}},"time":1.4641757766672108,"velocity":2.3553394401571994,"position":1.9383986922816177,"holonomicRotation":0.0,"angularVelocity":-0.1284211393147832,"angularAcceleration":0.02910448097601396,"curveRadius":-18.443129936016497},{"acceleration":5.0121197040009,"curvature":-0.05391241588255772,"pose":{"rotation":{"radians":0.005772612947550382},"translation":{"x":4.730996084039772,"y":7.257667283194929}},"time":1.4665781834464766,"velocity":2.367380590512583,"position":1.9440861034613675,"holonomicRotation":0.0,"angularVelocity":-0.12834422566528608,"angularAcceleration":0.032015248275569314,"curveRadius":-18.54860301898528},{"acceleration":5.012008887070861,"curvature":-0.05360578218191567,"pose":{"rotation":{"radians":0.005465951458415663},"translation":{"x":4.736684872236264,"y":7.25769837814474}},"time":1.4689691053014822,"velocity":2.379363912098163,"position":1.9497749766398145,"holonomicRotation":0.0,"angularVelocity":-0.12826077460152116,"angularAcceleration":0.03490330041118313,"curveRadius":-18.65470401320546},{"acceleration":5.011900479309411,"curvature":-0.053300811529528286,"pose":{"rotation":{"radians":0.0051609566884471825},"translation":{"x":4.742375097538474,"y":7.25772774541181}},"time":1.4713486998302847,"velocity":2.3912902030576304,"position":1.9554652777237895,"holonomicRotation":0.0,"angularVelocity":-0.1281708989816681,"angularAcceleration":0.03776930009091683,"curveRadius":-18.761440422834966},{"acceleration":5.011794410611934,"curvature":-0.05299748755017285,"pose":{"rotation":{"radians":0.004857621872678131},"translation":{"x":4.748066725274674,"y":7.257755393404658}},"time":1.4737171207077675,"velocity":2.4031602415733753,"position":1.9611569726118685,"holonomicRotation":0.0,"angularVelocity":-0.1280747094627213,"angularAcceleration":0.04061335544764273,"curveRadius":-18.86881899926478},{"acceleration":5.011690613597621,"curvature":-0.05269579092140933,"pose":{"rotation":{"radians":0.004555940312899409},"translation":{"x":4.753759720773128,"y":7.257781330531806}},"time":1.4760745178177843,"velocity":2.4149747865421687,"position":1.9668500271944265,"holonomicRotation":0.0,"angularVelocity":-0.1279723125547439,"angularAcceleration":0.043436427211307665,"curveRadius":-18.97684772378506},{"acceleration":5.011589023498461,"curvature":-0.05239570288156382,"pose":{"rotation":{"radians":0.0042559053754662735},"translation":{"x":4.759454049362107,"y":7.257805565201776}},"time":1.4784210373796642,"velocity":2.4267345782219105,"position":1.9725444073537146,"holonomicRotation":0.0,"angularVelocity":-0.12786381256193816,"angularAcceleration":0.046238690939705285,"curveRadius":-19.08553459546898},{"acceleration":5.01148957807347,"curvature":-0.0520972074031849,"pose":{"rotation":{"radians":0.003957510490868454},"translation":{"x":4.765149676369877,"y":7.257828105823088}},"time":1.48075682206935,"velocity":2.438440338850895,"position":1.978240078963915,"holonomicRotation":0.0,"angularVelocity":-0.12774931093411215,"angularAcceleration":0.04902062605838951,"curveRadius":-19.194886824948437},{"acceleration":5.0113922171806795,"curvature":-0.05180028546576474,"pose":{"rotation":{"radians":0.003660749154828835},"translation":{"x":4.770846567124706,"y":7.257848960804264}},"time":1.4830820111354626,"velocity":2.4500927732402844,"position":1.9839370078912144,"holonomicRotation":0.0,"angularVelocity":-0.12762890569401417,"angularAcceleration":0.05178298911378243,"curveRadius":-19.304912917148087},{"acceleration":5.011296883330502,"curvature":-0.051504922256450085,"pose":{"rotation":{"radians":0.003365614925695315},"translation":{"x":4.776544686954864,"y":7.257868138553824}},"time":1.4853967405105317,"velocity":2.461692569343322,"position":1.9896351599938629,"holonomicRotation":0.0,"angularVelocity":-0.12750269310627396,"angularAcceleration":0.05452585045127938,"curveRadius":-19.415620026001836},{"acceleration":5.0112035205922085,"curvature":-0.05121109776338099,"pose":{"rotation":{"radians":0.0030721014258747736},"translation":{"x":4.782244001188618,"y":7.25788564748029}},"time":1.4877011429176499,"velocity":2.4732403987987337,"position":1.9953345011222365,"holonomicRotation":0.0,"angularVelocity":-0.12737076602328498,"angularAcceleration":0.057250019606587,"curveRadius":-19.527017456654875},{"acceleration":5.011112075604719,"curvature":-0.05091879620021605,"pose":{"rotation":{"radians":0.002780202340314286},"translation":{"x":4.7879444751542355,"y":7.257901495992184}},"time":1.48999534797277,"velocity":2.484736917454359,"position":2.0010349971189036,"holonomicRotation":0.0,"angularVelocity":-0.1272332152302828,"angularAcceleration":0.059955753604153096,"curveRadius":-19.639113149256993},{"acceleration":5.011022496553515,"curvature":-0.05062799945974189,"pose":{"rotation":{"radians":0.002489911415930024},"translation":{"x":4.793646074179985,"y":7.257915692498025}},"time":1.4922794822828624,"velocity":2.4961827658673825,"position":2.006736613818683,"holonomicRotation":0.0,"angularVelocity":-0.1270901291143861,"angularAcceleration":0.0626434773403923,"curveRadius":-19.751916146621095},{"acceleration":5.010934733722059,"curvature":-0.05033869225269297,"pose":{"rotation":{"radians":0.0022012224629022192},"translation":{"x":4.799348763594134,"y":7.257928245406337}},"time":1.494553669540139,"velocity":2.5075785697858572,"position":2.0124393170487096,"holonomicRotation":0.0,"angularVelocity":-0.12694159291593918,"angularAcceleration":0.0653139700663064,"curveRadius":-19.865434623929925},{"acceleration":5.010848738995901,"curvature":-0.050050857697166516,"pose":{"rotation":{"radians":0.0019141293513085245},"translation":{"x":4.805052508724951,"y":7.257939163125638}},"time":1.4968180306125265,"velocity":2.518924940610062,"position":2.0181430726284932,"holonomicRotation":0.0,"angularVelocity":-0.12678769083897823,"angularAcceleration":0.06796710950284596,"curveRadius":-19.979677592150676},{"acceleration":5.010764465992245,"curvature":-0.049764478025397615,"pose":{"rotation":{"radians":0.0016286260143041353},"translation":{"x":4.810757274900705,"y":7.257948454064452}},"time":1.4990726836305788,"velocity":2.5302224758360605,"position":2.0238478463699807,"holonomicRotation":0.0,"angularVelocity":-0.1266285032412776,"angularAcceleration":0.07060403371430225,"curveRadius":-20.094654654865337},{"acceleration":5.010681870111949,"curvature":-0.049479536822517774,"pose":{"rotation":{"radians":0.001344706444140975},"translation":{"x":4.816463027449663,"y":7.2579561266312975}},"time":1.5013177440709893,"velocity":2.541471759482131,"position":2.0295536040776145,"holonomicRotation":0.0,"angularVelocity":-0.1264641098532055,"angularAcceleration":0.07322448211775348,"curveRadius":-20.21037512107242},{"acceleration":5.010600908108338,"curvature":-0.049196019818702856,"pose":{"rotation":{"radians":0.0010623646948917376},"translation":{"x":4.822169731700093,"y":7.257962189234698}},"time":1.5035533248368709,"velocity":2.552673362497807,"position":2.035260311548393,"holonomicRotation":0.0,"angularVelocity":-0.12629458687344575,"angularAcceleration":0.07582950361129087,"curveRadius":-20.326847653228846},{"acceleration":5.010521538365084,"curvature":-0.04891390884153401,"pose":{"rotation":{"radians":0.0007815948795704131},"translation":{"x":4.827877352980264,"y":7.257966650283174}},"time":1.5057795363349513,"velocity":2.563827843157895,"position":2.04096793457193,"holonomicRotation":0.0,"angularVelocity":-0.12612000951545663,"angularAcceleration":0.07841903527119926,"curveRadius":-20.444082750362313},{"acceleration":5.010443720253374,"curvature":-0.04863318937815398,"pose":{"rotation":{"radians":0.000502391171620431},"translation":{"x":4.833585856618443,"y":7.257969518185246}},"time":1.507996486549829,"velocity":2.574935747440143,"position":2.0466764389305134,"holonomicRotation":0.0,"angularVelocity":-0.1259404501175904,"angularAcceleration":0.08099387918647692,"curveRadius":-20.56208965084243},{"acceleration":5.010367415359258,"curvature":-0.04835384296165591,"pose":{"rotation":{"radians":0.00022474780329462263},"translation":{"x":4.8392952079428975,"y":7.257970801349436}},"time":1.510204281115421,"velocity":2.585997609391393,"position":2.052385790399162,"holonomicRotation":0.0,"angularVelocity":-0.12575597958832438,"angularAcceleration":0.08355420931862974,"curveRadius":-20.680879507198416},{"acceleration":5.010292585703359,"curvature":-0.048075856363412106,"pose":{"rotation":{"radians":-0.00005134093409342455},"translation":{"x":4.845005372281897,"y":7.257970508184265}},"time":1.5124030233837402,"velocity":2.597013951476225,"position":2.058095954745687,"holonomicRotation":0.0,"angularVelocity":-0.1255666666194136,"angularAcceleration":0.08610057287683012,"curveRadius":-20.800461513173275},{"acceleration":5.010219195034336,"curvature":-0.047799212381453654,"pose":{"rotation":{"radians":-0.0003258806908457146},"translation":{"x":4.85071631496371,"y":7.257968647098252}},"time":1.5145928144911096,"velocity":2.6079852849154825,"position":2.0638068977307453,"holonomicRotation":0.0,"angularVelocity":-0.12537257815522718,"angularAcceleration":0.08863332376008247,"curveRadius":-20.920846812697803},{"acceleration":5.010147208135504,"curvature":-0.0475238967816167,"pose":{"rotation":{"radians":-0.0005988770584597347},"translation":{"x":4.856428001316602,"y":7.2579652264999215}},"time":1.516773753421942,"velocity":2.618912110010907,"position":2.0695185851078968,"holonomicRotation":0.0,"angularVelocity":-0.12517377894199655,"angularAcceleration":0.09115303983075917,"curveRadius":-21.04204553332887},{"acceleration":5.01007659122364,"curvature":-0.04724989286233318,"pose":{"rotation":{"radians":-0.0008703355713866046},"translation":{"x":4.862140396668844,"y":7.257960254797793}},"time":1.5189459370701859,"velocity":2.629794916458812,"position":2.0752309826236632,"holonomicRotation":0.0,"angularVelocity":-0.12497033257125588,"angularAcceleration":0.09365983898514152,"curveRadius":-21.164069152782847},{"acceleration":5.010007310822662,"curvature":-0.04697718534508899,"pose":{"rotation":{"radians":-0.0011402617062863385},"translation":{"x":4.867853466348701,"y":7.257953740400389}},"time":1.5211094602985415,"velocity":2.6406341836500085,"position":2.08094405601758,"holonomicRotation":0.0,"angularVelocity":-0.12476230038208767,"angularAcceleration":0.0961543589833863,"curveRadius":-21.286928807124465},{"acceleration":5.009939335936663,"curvature":-0.046705758818772175,"pose":{"rotation":{"radians":-0.0014086608826877622},"translation":{"x":4.873567175684443,"y":7.257945691716229}},"time":1.523264415995549,"velocity":2.6514303809636472,"position":2.0866577710222565,"holonomicRotation":0.0,"angularVelocity":-0.12454974214743078,"angularAcceleration":0.0986369394749329,"curveRadius":-21.41063597489558},{"acceleration":5.009872634854466,"curvature":-0.04643560013618067,"pose":{"rotation":{"radians":-0.001675538463323356},"translation":{"x":4.879281490004339,"y":7.257936117153834}},"time":1.5254108951306369,"velocity":2.6621839680438097,"position":2.0923720933634278,"holonomicRotation":0.0,"angularVelocity":-0.12433271596869092,"angularAcceleration":0.10110798432288844,"curveRadius":-21.535201377118458},{"acceleration":5.009807178275068,"curvature":-0.04616669122828677,"pose":{"rotation":{"radians":-0.001940899754313108},"translation":{"x":4.884996374636655,"y":7.257925025121727}},"time":1.5275489868072192,"velocity":2.672895395072962,"position":2.0980869887600084,"holonomicRotation":0.0,"angularVelocity":-0.1241112782469305,"angularAcceleration":0.10356792657010125,"curveRadius":-21.660638295587678},{"acceleration":5.009742937103062,"curvature":-0.04589902030011852,"pose":{"rotation":{"radians":-0.002204750006264966},"translation":{"x":4.89071179490966,"y":7.257912424028427}},"time":1.5296787783139298,"velocity":2.6835651030312078,"position":2.1038024229241494,"holonomicRotation":0.0,"angularVelocity":-0.12388548415208914,"angularAcceleration":0.10601699468230284,"curveRadius":-21.786957400426644},{"acceleration":0.29740015410428305,"curvature":-0.04563257060612194,"pose":{"rotation":{"radians":-0.002467094412737403},"translation":{"x":4.896427716151622,"y":7.257898322282457}},"time":1.5318082552617824,"velocity":2.6841984098036606,"position":2.109518361561289,"holonomicRotation":0.0,"angularVelocity":-0.12319664072296722,"angularAcceleration":0.32348010614369715,"curveRadius":-21.91417197666797},{"acceleration":-4.694552487751353,"curvature":-0.04536732767762052,"pose":{"rotation":{"radians":-0.0027279381131979363},"translation":{"x":4.902144103690809,"y":7.257882728292337}},"time":1.5339458992781705,"velocity":2.6741631277685993,"position":2.115234770370209,"holonomicRotation":0.0,"angularVelocity":-0.12202391907202473,"angularAcceleration":0.5486047452016954,"curveRadius":-22.042294558453683},{"acceleration":-4.98979756910529,"curvature":-0.045103276091892665,"pose":{"rotation":{"radians":-0.00298728619116595},"translation":{"x":4.907860922855488,"y":7.257865650466589}},"time":1.5360923027075633,"velocity":2.663453009154296,"position":2.1209516150430843,"holonomicRotation":0.0,"angularVelocity":-0.12082913883592959,"angularAcceleration":0.5566429030693221,"curveRadius":-22.171338462479238},{"acceleration":-4.98973094204502,"curvature":-0.04484040441114585,"pose":{"rotation":{"radians":-0.003245143675449924},"translation":{"x":4.9135781389739295,"y":7.257847097213733}},"time":1.5382475591181661,"velocity":2.65269885955427,"position":2.1266688612655376,"holonomicRotation":0.0,"angularVelocity":-0.11964120974907345,"angularAcceleration":0.5511776144184367,"curveRadius":-22.30131536796383},{"acceleration":-4.989663040505311,"curvature":-0.04457869530177193,"pose":{"rotation":{"radians":-0.0035015155401421083},"translation":{"x":4.919295717374398,"y":7.2578270769422915}},"time":1.5404117640482868,"velocity":2.6419002062023673,"position":2.1323864747166876,"holonomicRotation":0.0,"angularVelocity":-0.11846006869501283,"angularAcceleration":0.5457621122759161,"curveRadius":-22.432240181785932},{"acceleration":-4.989593833647869,"curvature":-0.04431813457584463,"pose":{"rotation":{"radians":-0.003756406705385018},"translation":{"x":4.925013623385166,"y":7.257805598060785}},"time":1.542585015062983,"velocity":2.6310565663404706,"position":2.13810442106921,"holonomicRotation":0.0,"angularVelocity":-0.11728565339174614,"angularAcceleration":0.540395607927924,"curveRadius":-22.5641266170315},{"acceleration":-4.989523290079158,"curvature":-0.044058708753008276,"pose":{"rotation":{"radians":-0.004009822037202682},"translation":{"x":4.930731822334497,"y":7.257782668977735}},"time":1.5447674118128039,"velocity":2.620167446929046,"position":2.1438226659893744,"holonomicRotation":0.0,"angularVelocity":-0.1161179019527315,"angularAcceleration":0.5350775192963743,"curveRadius":-22.69698836627211},{"acceleration":-4.989451376552872,"curvature":-0.04380040423196553,"pose":{"rotation":{"radians":-0.0042617663480974954},"translation":{"x":4.936450279550662,"y":7.2577582981016615}},"time":1.5469590560947388,"velocity":2.6092323443496315,"position":2.149541175137108,"holonomicRotation":0.0,"angularVelocity":-0.11495675323386705,"angularAcceleration":0.5298071080400397,"curveRadius":-22.830839521572273},{"acceleration":-4.989378059383807,"curvature":-0.04354320643322126,"pose":{"rotation":{"radians":-0.0045122443964071834},"translation":{"x":4.942168960361929,"y":7.257732493841088}},"time":1.5491600519154587,"velocity":2.5982507440929363,"position":2.155259914166039,"holonomicRotation":0.0,"angularVelocity":-0.11380214626112552,"angularAcceleration":0.5245839005563852,"curveRadius":-22.965695039790425},{"acceleration":-4.989303303330327,"curvature":-0.04328710062578992,"pose":{"rotation":{"radians":-0.004761260888756169},"translation":{"x":4.947887830096565,"y":7.2577052646045335}},"time":1.5513705055569655,"velocity":2.5872221204375077,"position":2.160978848723547,"holonomicRotation":0.0,"angularVelocity":-0.11265402163296813,"angularAcceleration":0.5194067889950047,"curveRadius":-23.10157034181708},{"acceleration":-4.9892270724593395,"curvature":-0.04303207450707389,"pose":{"rotation":{"radians":-0.005008820477852005},"translation":{"x":4.953606854082839,"y":7.257676618800519}},"time":1.553590525644762,"velocity":2.57614593611407,"position":2.1666979444508154,"holonomicRotation":0.0,"angularVelocity":-0.11151231939597521,"angularAcceleration":0.5142756334813907,"curveRadius":-23.238479935138},{"acceleration":-4.989149328761711,"curvature":-0.04277811393733158,"pose":{"rotation":{"radians":-0.005254927763841621},"translation":{"x":4.959325997649017,"y":7.257646564837568}},"time":1.5558202232186555,"velocity":2.5650216419599374,"position":2.172417166982878,"holonomicRotation":0.0,"angularVelocity":-0.11037698065924488,"angularAcceleration":0.509189564550569,"curveRadius":-23.376439678125234},{"acceleration":-4.989070033872171,"curvature":-0.042525204628039284,"pose":{"rotation":{"radians":-0.005499587295510366},"translation":{"x":4.96504522612337,"y":7.257615111124199}},"time":1.5580597118063289,"velocity":2.553848676555978,"position":2.1781364819486697,"holonomicRotation":0.0,"angularVelocity":-0.10924794750703821,"angularAcceleration":0.5041477587432855,"curveRadius":-23.515465915962768},{"acceleration":-4.988989147263512,"curvature":-0.042273332135849315,"pose":{"rotation":{"radians":-0.005742803568370647},"translation":{"x":4.970764504834163,"y":7.257582266068935}},"time":1.5603091074998026,"velocity":2.542626465853336,"position":2.1838558549710725,"holonomicRotation":0.0,"angularVelocity":-0.10812516160048523,"angularAcceleration":0.49915002051910395,"curveRadius":-23.655575500563955},{"acceleration":-4.988906627851651,"curvature":-0.04202248450419023,"pose":{"rotation":{"radians":-0.005984581027249192},"translation":{"x":4.976483799109666,"y":7.257548038080296}},"time":1.5625685290349387,"velocity":2.5313544227815847,"position":2.1895752516669673,"holonomicRotation":0.0,"angularVelocity":-0.10700856618328043,"angularAcceleration":0.4941952618582597,"curveRadius":-23.796784311986265},{"acceleration":-4.988822431896405,"curvature":-0.0417726487847635,"pose":{"rotation":{"radians":-0.006224924064525794},"translation":{"x":4.982203074278147,"y":7.257512435566805}},"time":1.564838097874123,"velocity":2.520031946845929,"position":2.1952946376472777,"holonomicRotation":0.0,"angularVelocity":-0.10589810413637242,"angularAcceleration":0.489283262854072,"curveRadius":-23.939109180089826},{"acceleration":-4.988736515433544,"curvature":-0.041523809219518114,"pose":{"rotation":{"radians":-0.006463837022394614},"translation":{"x":4.9879222956678735,"y":7.257475466936981}},"time":1.5671179382922937,"velocity":2.5086584237024394,"position":2.201013978517019,"holonomicRotation":0.0,"angularVelocity":-0.10479371975539999,"angularAcceleration":0.4844130195123679,"curveRadius":-24.082568983819375},{"acceleration":-4.9886488318534,"curvature":-0.0412759534445215,"pose":{"rotation":{"radians":-0.006701324190938607},"translation":{"x":4.993641428607114,"y":7.257437140599346}},"time":1.5694081774664763,"velocity":2.4972332247214886,"position":2.2067332398753465,"holonomicRotation":0.0,"angularVelocity":-0.10369535689596915,"angularAcceleration":0.4795843472648909,"curveRadius":-24.2271811199731},{"acceleration":-4.988559333403518,"curvature":-0.04102906987957071,"pose":{"rotation":{"radians":-0.0069373898097708775},"translation":{"x":4.999360438424136,"y":7.257397464962422}},"time":1.5717089455690019,"velocity":2.4857557065296376,"position":2.212452387315601,"holonomicRotation":0.0,"angularVelocity":-0.10260296053876164,"angularAcceleration":0.47479637604867087,"curveRadius":-24.372962948836488},{"acceleration":-4.9884679703062185,"curvature":-0.04078314320237211,"pose":{"rotation":{"radians":-0.007172038068890885},"translation":{"x":5.005079290447208,"y":7.257356448434729}},"time":1.5740203758645956,"velocity":2.4742252105344726,"position":2.218171386425352,"holonomicRotation":0.0,"angularVelocity":-0.10151647642903688,"angularAcceleration":0.4700483989484324,"curveRadius":-24.519934499355507},{"acceleration":-4.988374691307332,"curvature":-0.04053816155382472,"pose":{"rotation":{"radians":-0.007405273106421362},"translation":{"x":5.010797950004598,"y":7.2573140994247884}},"time":1.5763426048115377,"velocity":2.462641062428126,"position":2.2238902027864507,"holonomicRotation":0.0,"angularVelocity":-0.10043584971998958,"angularAcceleration":0.46534029750611616,"curveRadius":-24.66811423286292},{"acceleration":-4.988279442784519,"curvature":-0.04029411296018045,"pose":{"rotation":{"radians":-0.00763709901149312},"translation":{"x":5.016516382424573,"y":7.257270426341122}},"time":1.5786757721670974,"velocity":2.451002571671811,"position":2.2296088019750684,"holonomicRotation":0.0,"angularVelocity":-0.09936102719735634,"angularAcceleration":0.4606709930481434,"curveRadius":-24.817521134867086},{"acceleration":-4.988182169293382,"curvature":-0.040050982548125745,"pose":{"rotation":{"radians":-0.007867519823058444},"translation":{"x":5.0222345530354024,"y":7.25722543759225}},"time":1.581020021097474,"velocity":2.439309030956921,"position":2.2353271495617473,"holonomicRotation":0.0,"angularVelocity":-0.09829195550845424,"angularAcceleration":0.45604017348547354,"curveRadius":-24.968176468539514},{"acceleration":-4.988082813249115,"curvature":-0.039808756182410886,"pose":{"rotation":{"radians":-0.008096539530267677},"translation":{"x":5.027952427165355,"y":7.257179141586694}},"time":1.5833754982924726,"velocity":2.427559715643549,"position":2.2410452111114427,"holonomicRotation":0.0,"angularVelocity":-0.09722858183281086,"angularAcceleration":0.4514472387596402,"curveRadius":-25.120101603220657},{"acceleration":-4.98798131493424,"curvature":-0.039567425179002684,"pose":{"rotation":{"radians":-0.00832416207331299},"translation":{"x":5.033669970142697,"y":7.257131546732976}},"time":1.5857423540851705,"velocity":2.415753883174428,"position":2.2467629521835666,"holonomicRotation":0.0,"angularVelocity":-0.0961708540704348,"angularAcceleration":0.44689151136258587,"curveRadius":-25.273314992724664},{"acceleration":-4.987877612316699,"curvature":-0.039326973257390166,"pose":{"rotation":{"radians":-0.008550391342692976},"translation":{"x":5.039387147295696,"y":7.257082661439615}},"time":1.5881207425768442,"velocity":2.403890772463417,"position":2.252480338332034,"holonomicRotation":0.0,"angularVelocity":-0.09511872016366164,"angularAcceleration":0.4423726024812496,"curveRadius":-25.427840415155366},{"acceleration":-4.987771640618322,"curvature":-0.03908738960032359,"pose":{"rotation":{"radians":-0.008775231179741105},"translation":{"x":5.045103923952622,"y":7.257032494115134}},"time":1.5905108217674355,"velocity":2.3919696032577535,"position":2.2581973351053075,"holonomicRotation":0.0,"angularVelocity":-0.09407212862788196,"angularAcceleration":0.4378898991713975,"curveRadius":-25.5836987382683},{"acceleration":-4.987663332924696,"curvature":-0.03884866042095312,"pose":{"rotation":{"radians":-0.008998685377758164},"translation":{"x":5.050820265441742,"y":7.2569810531680545}},"time":1.592912753691865,"velocity":2.3799895754700953,"position":2.2639139080464386,"holonomicRotation":0.0,"angularVelocity":-0.09303102879159787,"angularAcceleration":0.43344269073377917,"curveRadius":-25.74091330728736},{"acceleration":-4.987552619257082,"curvature":-0.03861077464032589,"pose":{"rotation":{"radians":-0.009220757680809655},"translation":{"x":5.056536137091324,"y":7.256928347006896}},"time":1.595326704562513,"velocity":2.367949868482437,"position":2.2696300226931125,"holonomicRotation":0.0,"angularVelocity":-0.09199536981126619,"angularAcceleration":0.42903067867892253,"curveRadius":-25.899506272935},{"acceleration":-4.9874394270559845,"curvature":-0.0383737191307153,"pose":{"rotation":{"radians":-0.009441451784694799},"translation":{"x":5.062251504229637,"y":7.256874384040181}},"time":1.5977528449182143,"velocity":2.3558496404168405,"position":2.2753456445776923,"holonomicRotation":0.0,"angularVelocity":-0.09096510157234827,"angularAcceleration":0.4246531889619779,"curveRadius":-26.059501728086985},{"acceleration":-4.987323681068257,"curvature":-0.038137480597541636,"pose":{"rotation":{"radians":-0.009660771336680973},"translation":{"x":5.067966332184948,"y":7.256819172676431}},"time":1.6001913497801314,"velocity":2.3436880273726013,"position":2.2810607392272573,"holonomicRotation":0.0,"angularVelocity":-0.08994017416629228,"angularAcceleration":0.4203097652428763,"curveRadius":-26.22092451656234},{"acceleration":-4.987205302003154,"curvature":-0.037902047535137644,"pose":{"rotation":{"radians":-0.009878719936759595},"translation":{"x":5.073680586285525,"y":7.256762721324166}},"time":1.6026423988149006,"velocity":2.331464142630931,"position":2.2867752721636516,"holonomicRotation":0.0,"angularVelocity":-0.08892053850695471,"angularAcceleration":0.4159996984448839,"curveRadius":-26.383798898276815},{"acceleration":-4.987084208280837,"curvature":-0.03766740732139921,"pose":{"rotation":{"radians":-0.010095301136602508},"translation":{"x":5.079394231859638,"y":7.256705038391907}},"time":1.6051061765054664,"velocity":2.3191770758175956,"position":2.2924892089035227,"holonomicRotation":0.0,"angularVelocity":-0.08790614537676643,"angularAcceleration":0.41172267046354954,"curveRadius":-26.54815053946892},{"acceleration":-4.986960314360003,"curvature":-0.037433548167980314,"pose":{"rotation":{"radians":-0.010310518439887062},"translation":{"x":5.085107234235552,"y":7.256646132288175}},"time":1.6075828723300531,"velocity":2.3068258920296403,"position":2.298202514958361,"holonomicRotation":0.0,"angularVelocity":-0.08689694598264328,"angularAcceleration":0.40747813441787467,"curveRadius":-26.7140051889437},{"acceleration":-4.986833531046627,"curvature":-0.037200456144674675,"pose":{"rotation":{"radians":-0.010524375302927602},"translation":{"x":5.090819558741537,"y":7.2565860114214935}},"time":1.6100726809497545,"velocity":2.2944096309190245,"position":2.303915155834549,"holonomicRotation":0.0,"angularVelocity":-0.0858928920674189,"angularAcceleration":0.40326549891404706,"curveRadius":-26.881390811740147},{"acceleration":-4.986703765705656,"curvature":-0.036968121151178014,"pose":{"rotation":{"radians":-0.01073687513564714},"translation":{"x":5.09653117070586,"y":7.2565246842003805}},"time":1.6125758024052443,"velocity":2.281927305730915,"position":2.3096270970333923,"holonomicRotation":0.0,"angularVelocity":-0.08489393603074495,"angularAcceleration":0.39908412533600995,"curveRadius":-27.050333337487842},{"acceleration":-4.9865709210739215,"curvature":-0.03673653095962943,"pose":{"rotation":{"radians":-0.010948021299062027},"translation":{"x":5.102242035456791,"y":7.25646215903336}},"time":1.6150924423231698,"velocity":2.2693779022973737,"position":2.315338304051172,"holonomicRotation":0.0,"angularVelocity":-0.08390002952386556,"angularAcceleration":0.39493393544304845,"curveRadius":-27.220860921759915},{"acceleration":-4.9864348961207945,"curvature":-0.03650567114169309,"pose":{"rotation":{"radians":-0.011157817108757406},"translation":{"x":5.107952118322595,"y":7.256398444328951}},"time":1.617622812132798,"velocity":2.2567603779785532,"position":2.321048742379174,"holonomicRotation":0.0,"angularVelocity":-0.08291112583508392,"angularAcceleration":0.39081389803925803,"curveRadius":-27.39300412033518},{"acceleration":-4.9862955852221145,"curvature":-0.03627553218813585,"pose":{"rotation":{"radians":-0.011366265832663203},"translation":{"x":5.113661384631543,"y":7.256333548495676}},"time":1.620167129293563,"velocity":2.2440736605524254,"position":2.3267583775037384,"holonomicRotation":0.0,"angularVelocity":-0.08192717760199167,"angularAcceleration":0.38672389129206486,"curveRadius":-27.5667906073355},{"acceleration":-4.9861528776771715,"curvature":-0.036046101396492114,"pose":{"rotation":{"radians":-0.011573370692020468},"translation":{"x":5.119369799711902,"y":7.256267479942056}},"time":1.6227256175341753,"velocity":2.2313166470489936,"position":2.3324671749062955,"holonomicRotation":0.0,"angularVelocity":-0.08094813807223412,"angularAcceleration":0.38266329085150275,"curveRadius":-27.742251207708044},{"acceleration":-4.986006658160312,"curvature":-0.0358173669283208,"pose":{"rotation":{"radians":-0.011779134861985341},"translation":{"x":5.125077328891939,"y":7.256200247076611}},"time":1.6252985071040267,"velocity":2.2184882025230035,"position":2.3381751000634052,"holonomicRotation":0.0,"angularVelocity":-0.0799739609410288,"angularAcceleration":0.37863153654962833,"curveRadius":-27.919416913064588},{"acceleration":-4.985856806032918,"curvature":-0.03558931573972912,"pose":{"rotation":{"radians":-0.011983561470677806},"translation":{"x":5.130783937499923,"y":7.256131858307864}},"time":1.6278860350376736,"velocity":2.2055871587642297,"position":2.3438821184468006,"holonomicRotation":0.0,"angularVelocity":-0.07900459973173776,"angularAcceleration":0.37462830707485073,"curveRadius":-28.098320499140094},{"acceleration":-4.985703194719601,"curvature":-0.035361937764418115,"pose":{"rotation":{"radians":-0.012186653600432251},"translation":{"x":5.136489590864122,"y":7.256062322044334}},"time":1.6304884454332291,"velocity":2.192612312941137,"position":2.3495881955234217,"holonomicRotation":0.0,"angularVelocity":-0.07804000864017895,"angularAcceleration":0.370652950513175,"curveRadius":-28.278993268469012},{"acceleration":-4.985545691846742,"curvature":-0.03513522069752726,"pose":{"rotation":{"radians":-0.012388414287139327},"translation":{"x":5.142194254312804,"y":7.255991646694545}},"time":1.633105989745579,"velocity":2.1795624261714828,"position":2.3552932967554585,"holonomicRotation":0.0,"angularVelocity":-0.0770801417783605,"angularAcceleration":0.36670510496790815,"curveRadius":-28.461469151106762},{"acceleration":-4.985384159002331,"curvature":-0.034909149916041986,"pose":{"rotation":{"radians":-0.01258884652100889},"translation":{"x":5.147897893174237,"y":7.2559198406670165}},"time":1.6357389270953915,"velocity":2.1664362220160824,"position":2.360997387600391,"holonomicRotation":0.0,"angularVelocity":-0.07612495370763143,"angularAcceleration":0.36278420023823515,"curveRadius":-28.645784913268965},{"acceleration":-4.985218450737551,"curvature":-0.03468371810584897,"pose":{"rotation":{"radians":-0.01278795324655313},"translation":{"x":5.15360047277669,"y":7.255846912370268}},"time":1.638387524594967,"velocity":2.153232384892621,"position":2.366700433511023,"holonomicRotation":0.0,"angularVelocity":-0.07517439912109934,"angularAcceleration":0.35888978475756084,"curveRadius":-28.83197230897118},{"acceleration":-4.985048414759264,"curvature":-0.034458910309269106,"pose":{"rotation":{"radians":-0.012985737361610461},"translation":{"x":5.159301958448429,"y":7.255772870212823}},"time":1.6410520576920749,"velocity":2.13994955840081,"position":2.372402399935523,"holonomicRotation":0.0,"angularVelocity":-0.07422843246796797,"angularAcceleration":0.35502154360858623,"curveRadius":-29.020070310552157},{"acceleration":-4.984873891027984,"curvature":-0.034234716782263704,"pose":{"rotation":{"radians":-0.013182201719183162},"translation":{"x":5.165002315517723,"y":7.255697722603203}},"time":1.6437328105329911,"velocity":2.1265863435558274,"position":2.378103252317464,"holonomicRotation":0.0,"angularVelocity":-0.07328700899764741,"angularAcceleration":0.3511787643946973,"curveRadius":-29.210114585147647},{"acceleration":-4.984694711852248,"curvature":-0.034011124363991306,"pose":{"rotation":{"radians":-0.013377349126939109},"translation":{"x":5.170701509312841,"y":7.255621477949927}},"time":1.6464300763460729,"velocity":2.113141296920899,"position":2.38380295609586,"holonomicRotation":0.0,"angularVelocity":-0.0723500838550963,"angularAcceleration":0.3473610713512312,"curveRadius":-29.40214470118291},{"acceleration":-4.984510700869868,"curvature":-0.03378812301310132,"pose":{"rotation":{"radians":-0.013571182346542088},"translation":{"x":5.176399505162051,"y":7.255544144661519}},"time":1.6491441578472987,"velocity":2.099612928635006,"position":2.389501476705203,"holonomicRotation":0.0,"angularVelocity":-0.07141761200444058,"angularAcceleration":0.34356810959234113,"curveRadius":-29.59619862909374},{"acceleration":-4.984321672503092,"curvature":-0.03356570032947182,"pose":{"rotation":{"radians":-0.013763704095021367},"translation":{"x":5.182096268393619,"y":7.255465731146497}},"time":1.6518753676693343,"velocity":2.0859997003268806,"position":2.395198779575499,"holonomicRotation":0.0,"angularVelocity":-0.07048954896324798,"angularAcceleration":0.3397992470973596,"curveRadius":-29.79231746051091},{"acceleration":-4.984127431882651,"curvature":-0.033343845972610454,"pose":{"rotation":{"radians":-0.013954917043603743},"translation":{"x":5.187791764335815,"y":7.255386245813384}},"time":1.6546240288158147,"velocity":2.0723000229057575,"position":2.4008948301323105,"holonomicRotation":0.0,"angularVelocity":-0.06956584984191949,"angularAcceleration":0.33605419951864823,"curveRadius":-29.990541607630604},{"acceleration":-4.983927773925127,"curvature":-0.03312254606329052,"pose":{"rotation":{"radians":-0.01414482381894544},"translation":{"x":5.193485958316906,"y":7.2553056970707015}},"time":1.6573904751426682,"velocity":2.058512254222279,"position":2.4065895937967867,"holonomicRotation":0.0,"angularVelocity":-0.06864647020196911,"angularAcceleration":0.33233236120509113,"curveRadius":-30.190915821784994},{"acceleration":-4.983722482125109,"curvature":-0.032901789910324566,"pose":{"rotation":{"radians":-0.014333427002570787},"translation":{"x":5.199178815665161,"y":7.255224093326969}},"time":1.6601750518684832,"velocity":2.0446346965906326,"position":2.412283035985707,"holonomicRotation":0.0,"angularVelocity":-0.06773136537300668,"angularAcceleration":0.3286333683962648,"curveRadius":-30.39348323375563},{"acceleration":-4.983511328916157,"curvature":-0.03268156552236387,"pose":{"rotation":{"radians":-0.014520729131005439},"translation":{"x":5.204870301708847,"y":7.25514144299071}},"time":1.6629781161160782,"velocity":2.0306655941570635,"position":2.4179751221115096,"holonomicRotation":0.0,"angularVelocity":-0.06682049068099717,"angularAcceleration":0.3249567657220348,"curveRadius":-30.59828940311026},{"acceleration":-4.983294073879483,"curvature":-0.03246186303932329,"pose":{"rotation":{"radians":-0.014706732696450509},"translation":{"x":5.210560381776233,"y":7.255057754470443}},"time":1.6658000374876465,"velocity":2.016603130109173,"position":2.4236658175823362,"holonomicRotation":0.0,"angularVelocity":-0.06591380161017554,"angularAcceleration":0.3213020319973404,"curveRadius":-30.805379185681094},{"acceleration":-4.983070463470232,"curvature":-0.03224267130505958,"pose":{"rotation":{"radians":-0.014891440145819779},"translation":{"x":5.216249021195586,"y":7.254973036174691}},"time":1.6686411986760432,"velocity":2.0024454237093154,"position":2.4293550878020618,"holonomicRotation":0.0,"angularVelocity":-0.06501125318887704,"angularAcceleration":0.3176688548979546,"curveRadius":-31.014799938213496},{"acceleration":-4.98284022988628,"curvature":-0.032023976639273644,"pose":{"rotation":{"radians":-0.015074853881881012},"translation":{"x":5.221936185295176,"y":7.254887296511975}},"time":1.6715019961150352,"velocity":1.9881905271407503,"position":2.4350428981703343,"holonomicRotation":0.0,"angularVelocity":-0.06411280070421782,"angularAcceleration":0.31405665861326465,"curveRadius":-31.22660284399588},{"acceleration":-4.982603089845018,"curvature":-0.0318057698624308,"pose":{"rotation":{"radians":-0.015256976262586264},"translation":{"x":5.227621839403269,"y":7.254800543890816}},"time":1.6743828406715826,"velocity":1.9738364221519342,"position":2.4407292140826056,"holonomicRotation":0.0,"angularVelocity":-0.06321839902515339,"angularAcceleration":0.3104650950471128,"curveRadius":-31.440836185550317},{"acceleration":-4.982358743971632,"curvature":-0.031588038095576275,"pose":{"rotation":{"radians":-0.015437809601899666},"translation":{"x":5.233305948848133,"y":7.254712786719735}},"time":1.677284158383529,"velocity":1.9593810164807786,"position":2.4464140009301727,"holonomicRotation":0.0,"angularVelocity":-0.06232800308935831,"angularAcceleration":0.3068936339266868,"curveRadius":-31.657553310980852},{"acceleration":-4.982106875237598,"curvature":-0.03137077064344945,"pose":{"rotation":{"radians":-0.015617356168954544},"translation":{"x":5.238988478958038,"y":7.254624033407253}},"time":1.6802063912463807,"velocity":1.9448221400437196,"position":2.45209722410021,"holonomicRotation":0.0,"angularVelocity":-0.06144156728141829,"angularAcceleration":0.30334194759378863,"curveRadius":-31.87680696039294},{"acceleration":-4.9818471475864055,"curvature":-0.03115395543468733,"pose":{"rotation":{"radians":-0.015795618188587213},"translation":{"x":5.2446693950612495,"y":7.254534292361891}},"time":1.683149998053229,"velocity":1.9301575408694067,"position":2.457778848975803,"holonomicRotation":0.0,"angularVelocity":-0.06055904586779251,"angularAcceleration":0.2998095437110039,"curveRadius":-32.09865283708352},{"acceleration":-4.981579204754227,"curvature":-0.030937582640579234,"pose":{"rotation":{"radians":-0.015972597841543035},"translation":{"x":5.250348662486038,"y":7.254443571992171}},"time":1.6861154552922697,"velocity":1.9153848807548135,"position":2.4634588409359863,"holonomicRotation":0.0,"angularVelocity":-0.05968039283313736,"angularAcceleration":0.2962959718614499,"curveRadius":-32.3231459813008},{"acceleration":-4.981302668811965,"curvature":-0.030721638592620743,"pose":{"rotation":{"radians":-0.016148297264877876},"translation":{"x":5.256026246560671,"y":7.254351880706613}},"time":1.6891032581068106,"velocity":1.900501730620857,"position":2.469137165355775,"holonomicRotation":0.0,"angularVelocity":-0.058805561893092106,"angularAcceleration":0.2928007617462789,"curveRadius":-32.550347110723365},{"acceleration":-4.981017137963972,"curvature":-0.030506114336965432,"pose":{"rotation":{"radians":-0.01632271855026879},"translation":{"x":5.261702112613415,"y":7.2542592269137405}},"time":1.6921139213231715,"velocity":1.8855055655435256,"position":2.474813787606201,"holonomicRotation":0.0,"angularVelocity":-0.05793450574048028,"angularAcceleration":0.2893236772144532,"curveRadius":-32.78031377428693},{"acceleration":-4.980722185102318,"curvature":-0.030290997045442043,"pose":{"rotation":{"radians":-0.016495863747051587},"translation":{"x":5.267376225972539,"y":7.254165619022071}},"time":1.6951479805524303,"velocity":1.8703937594294417,"position":2.480488673054346,"holonomicRotation":0.0,"angularVelocity":-0.05706717756630461,"angularAcceleration":0.2858639560532068,"curveRadius":-33.01310942323281},{"acceleration":-4.980417355668851,"curvature":-0.03007627617912997,"pose":{"rotation":{"radians":-0.016667734858824446},"translation":{"x":5.273048551966312,"y":7.254071065440129}},"time":1.6982059933726021,"velocity":1.8551635793060002,"position":2.4861617870633794,"holonomicRotation":0.0,"angularVelocity":-0.056203528853486645,"angularAcceleration":0.28242154745755477,"curveRadius":-33.248796960240156},{"acceleration":-4.980102165562176,"curvature":-0.02986194103245375,"pose":{"rotation":{"radians":-0.016838333846012077},"translation":{"x":5.278719055923001,"y":7.253975574576435}},"time":1.7012885405985374,"velocity":1.8398121791906723,"position":2.4918330949925855,"holonomicRotation":0.0,"angularVelocity":-0.055343511285823224,"angularAcceleration":0.27899574755176276,"curveRadius":-33.487441386117766},{"acceleration":-4.979776098136917,"curvature":-0.02964797944100307,"pose":{"rotation":{"radians":-0.017007662626042475},"translation":{"x":5.284387703170874,"y":7.253879154839508}},"time":1.7043962276476305,"velocity":1.8243365935031086,"position":2.497502562197402,"holonomicRotation":0.0,"angularVelocity":-0.054487075872008954,"angularAcceleration":0.2755861192857843,"curveRadius":-33.72911135444876},{"acceleration":-4.979438602223586,"curvature":-0.02943437901647131,"pose":{"rotation":{"radians":-0.017175723070423032},"translation":{"x":5.290054459038199,"y":7.253781814637871}},"time":1.707529686010312,"velocity":1.8087337299735124,"position":2.5031701540294513,"holonomicRotation":0.0,"angularVelocity":-0.053634171872876626,"angularAcceleration":0.27219254268388154,"curveRadius":-33.97387794185859},{"acceleration":-4.979089088377791,"curvature":-0.02922113105621126,"pose":{"rotation":{"radians":-0.017342517008527736},"translation":{"x":5.2957192888532445,"y":7.253683562380044}},"time":1.710689574835316,"velocity":1.7930003620044483,"position":2.508835835836577,"holonomicRotation":0.0,"angularVelocity":-0.052784748876250336,"angularAcceleration":0.26881420317856536,"curveRadius":-34.221810171425226},{"acceleration":-4.978726926486223,"curvature":-0.029008221476517798,"pose":{"rotation":{"radians":-0.0175080462248145},"translation":{"x":5.301382157944279,"y":7.253584406474551}},"time":1.7138765826408608,"velocity":1.77713312042806,"position":2.514499572962874,"holonomicRotation":0.0,"angularVelocity":-0.05193875458941996,"angularAcceleration":0.26545096166958493,"curveRadius":-34.47298555719804},{"acceleration":-4.978351441048172,"curvature":-0.02879564121235954,"pose":{"rotation":{"radians":-0.017672312460894624},"translation":{"x":5.307043031639569,"y":7.253484355329911}},"time":1.7170914291641748,"velocity":1.7611284846059714,"position":2.5201613307487185,"holonomicRotation":0.0,"angularVelocity":-0.05109613628173899,"angularAcceleration":0.26210218794904805,"curveRadius":-34.72747811466634},{"acceleration":-4.9779619080048025,"curvature":-0.028583379732324873,"pose":{"rotation":{"radians":-0.017835317413961604},"translation":{"x":5.312701875267384,"y":7.2533834173546445}},"time":1.720334867363286,"velocity":1.7449827727998286,"position":2.5258210745308083,"holonomicRotation":0.0,"angularVelocity":-0.05025683952037499,"angularAcceleration":0.258767613205645,"curveRadius":-34.985365949188385},{"acceleration":-4.977557549574455,"curvature":-0.02837142227296116,"pose":{"rotation":{"radians":-0.017997062737619807},"translation":{"x":5.318358654155991,"y":7.253281600957274}},"time":1.723607685586665,"velocity":1.7286921317436625,"position":2.531478769642191,"holonomicRotation":0.0,"angularVelocity":-0.049420808801045706,"angularAcceleration":0.25544673191964684,"curveRadius":-35.2467349144153},{"acceleration":-4.97713752982627,"curvature":-0.028159760559043436,"pose":{"rotation":{"radians":-0.01815755004173525},"translation":{"x":5.324013333633659,"y":7.253178914546319}},"time":1.7269107099282481,"velocity":1.71225252533124,"position":2.5371343814122973,"holonomicRotation":0.0,"angularVelocity":-0.048587987104728954,"angularAcceleration":0.25213913377265895,"curveRadius":-35.51166558761284},{"acceleration":-4.9767009485398335,"curvature":-0.027948382088045627,"pose":{"rotation":{"radians":-0.018316780892141615},"translation":{"x":5.3296658790286555,"y":7.253075366530303}},"time":1.730244806787556,"velocity":1.6956597223289989,"position":2.5427878751669692,"holonomicRotation":0.0,"angularVelocity":-0.04775831570754735,"angularAcceleration":0.24884441940113294,"curveRadius":-35.780246486172466},{"acceleration":-4.9762468353086735,"curvature":-0.02773727549172919,"pose":{"rotation":{"radians":-0.01847475681187305},"translation":{"x":5.335316255669248,"y":7.252970965317745}},"time":1.7336108856571717,"velocity":1.6789092830066743,"position":2.5484392162284997,"holonomicRotation":0.0,"angularVelocity":-0.0469317344752145,"angularAcceleration":0.24556205138093362,"curveRadius":-36.05256761062145},{"acceleration":-4.9757741423936395,"curvature":-0.02752642918731849,"pose":{"rotation":{"radians":-0.018631479279002328},"translation":{"x":5.340964428883706,"y":7.252865719317168}},"time":1.737009902162724,"velocity":1.6619965445687774,"position":2.55408836991566,"holonomicRotation":0.0,"angularVelocity":-0.04610818066733898,"angularAcceleration":0.24229179426761174,"curveRadius":-36.32872223254817},{"acceleration":-4.975281736968906,"curvature":-0.027315832779539237,"pose":{"rotation":{"radians":-0.0187869497291393},"translation":{"x":5.3466103640002975,"y":7.252759636937092}},"time":1.7404428613839047,"velocity":1.6449166052518787,"position":2.5597353015437325,"holonomicRotation":0.0,"angularVelocity":-0.04528759012858539,"angularAcceleration":0.23903299919519408,"curveRadius":-36.60880515965979},{"acceleration":-4.9747683920686105,"curvature":-0.027105475689755274,"pose":{"rotation":{"radians":-0.018941169552611825},"translation":{"x":5.352254026347288,"y":7.25265272658604}},"time":1.7439108214889156,"velocity":1.6276643069365153,"position":2.5653799764245386,"holonomicRotation":0.0,"angularVelocity":-0.044469895501302786,"angularAcceleration":0.23578547691511662,"curveRadius":-36.89291460684299},{"acceleration":-4.974232777079546,"curvature":-0.02689534571058897,"pose":{"rotation":{"radians":-0.019094140098184553},"translation":{"x":5.357895381252949,"y":7.25254499667253}},"time":1.7474148977192754,"velocity":1.6102342160980745,"position":2.57102235986648,"holonomicRotation":0.0,"angularVelocity":-0.04365502789219374,"angularAcceleration":0.2325484822644354,"curveRadius":-37.18115434397595},{"acceleration":-4.973673445946856,"curvature":-0.026685430381914226,"pose":{"rotation":{"radians":-0.01924586266872108},"translation":{"x":5.363534394045546,"y":7.252436455605085}},"time":1.750956266767119,"velocity":1.5926206029025165,"position":2.576662417174557,"holonomicRotation":0.0,"angularVelocity":-0.04284291427602348,"angularAcceleration":0.22932193883175372,"curveRadius":-37.47363207893921},{"acceleration":-4.973088824820314,"curvature":-0.02647571990661459,"pose":{"rotation":{"radians":-0.019396338524387602},"translation":{"x":5.369171030053348,"y":7.252327111792226}},"time":1.7545361715933152,"velocity":1.57481741821744,"position":2.5823001136504113,"holonomicRotation":0.0,"angularVelocity":-0.042033479372245844,"angularAcceleration":0.22610514610738824,"curveRadius":-37.77045547872577},{"acceleration":-4.972477197576908,"curvature":-0.02626620136582712,"pose":{"rotation":{"radians":-0.019545568881907727},"translation":{"x":5.374805254604623,"y":7.252216973642474}},"time":1.7581559267418485,"velocity":1.5568182682805465,"position":2.5879354145923505,"holonomicRotation":0.0,"angularVelocity":-0.04122664417801629,"angularAcceleration":0.22289772681350536,"curveRadius":-38.07174041165393},{"acceleration":-4.97183668910172,"curvature":-0.026056864536891423,"pose":{"rotation":{"radians":-0.01969355491293534},"translation":{"x":5.380437033027639,"y":7.252106049564351}},"time":1.7618169242143955,"velocity":1.5386163867278286,"position":2.5935682852953805,"holonomicRotation":0.0,"angularVelocity":-0.040422325373706984,"angularAcceleration":0.21969936071814072,"curveRadius":-38.37760289938936},{"acceleration":-4.9711652467608145,"curvature":-0.02584769750586623,"pose":{"rotation":{"radians":-0.019840297746860358},"translation":{"x":5.386066330650665,"y":7.251994347966377}},"time":1.765520639978967,"velocity":1.5202046036351111,"position":2.599198691051238,"holonomicRotation":0.0,"angularVelocity":-0.039620436138408384,"angularAcceleration":0.21650938848202772,"curveRadius":-38.688165542522555},{"acceleration":-4.9704606187674525,"curvature":-0.025638688106666266,"pose":{"rotation":{"radians":-0.019985798467956783},"translation":{"x":5.391693112801968,"y":7.251881877257074}},"time":1.7692686411982828,"velocity":1.5015753111754093,"position":2.604826597148418,"holonomicRotation":0.0,"angularVelocity":-0.03882088414127703,"angularAcceleration":0.21332757124270668,"curveRadius":-39.003555713913144},{"acceleration":-4.969720329284973,"curvature":-0.02542982851101399,"pose":{"rotation":{"radians":-0.020130058117066696},"translation":{"x":5.3973173448098155,"y":7.2517686458449635}},"time":1.7730625942775764,"velocity":1.4827204254288904,"position":2.6104519688722054,"holonomicRotation":0.0,"angularVelocity":-0.0380235722727416,"angularAcceleration":0.21015332869743242,"curveRadius":-39.323898687200625},{"acceleration":-4.968941650071039,"curvature":-0.025221103048971162,"pose":{"rotation":{"radians":-0.020273077691397745},"translation":{"x":5.402938992002476,"y":7.251654662138566}},"time":1.7769042738482592,"velocity":1.4636313438038975,"position":2.616074771504708,"holonomicRotation":0.0,"angularVelocity":-0.037228397553632726,"angularAcceleration":0.20698621643958134,"curveRadius":-39.64933643299922},{"acceleration":-4.968121567303361,"curvature":-0.02501250190094585,"pose":{"rotation":{"radians":-0.02041485814370514},"translation":{"x":5.408558019708218,"y":7.251539934546401}},"time":1.7807955728239386,"velocity":1.444298897437999,"position":2.6216949703248833,"holonomicRotation":0.0,"angularVelocity":-0.036435250335047666,"angularAcceleration":0.20382582359829565,"curveRadius":-39.980006956528605},{"acceleration":-4.9672567433962325,"curvature":-0.024804013490418705,"pose":{"rotation":{"radians":-0.020555400382701094},"translation":{"x":5.41417439325531,"y":7.251424471476993}},"time":1.784738513689462,"velocity":1.4247132978349155,"position":2.627312530608571,"holonomicRotation":0.0,"angularVelocity":-0.035644013894512216,"angularAcceleration":0.20067164776776875,"curveRadius":-40.31605612479932},{"acceleration":-4.966343472029276,"curvature":-0.024595627586858803,"pose":{"rotation":{"radians":-0.020694705273331948},"translation":{"x":5.41978807797202,"y":7.2513082813388605}},"time":1.7887352612128884,"velocity":1.4048640768625977,"position":2.6329274176285224,"holonomicRotation":0.0,"angularVelocity":-0.034854563570587666,"angularAcceleration":0.19752319086889966,"curveRadius":-40.65763300686379},{"acceleration":-4.965377626165336,"curvature":-0.024387328930352697,"pose":{"rotation":{"radians":-0.02083277363623992},"translation":{"x":5.425399039186614,"y":7.251191372540526}},"time":1.792788136805859,"velocity":1.3847400190716304,"position":2.6385395966544274,"holonomicRotation":0.0,"angularVelocity":-0.034066765618822444,"angularAcceleration":0.1943799985204611,"curveRadius":-41.00490065377314},{"acceleration":-4.964354596210821,"curvature":-0.024179109994908396,"pose":{"rotation":{"radians":-0.020969606247686734},"translation":{"x":5.431007242227362,"y":7.251073753490511}},"time":1.796899634801307,"velocity":1.3643290851006156,"position":2.6441490329529502,"holonomicRotation":0.0,"angularVelocity":-0.033280476263955305,"angularAcceleration":0.19124157563438773,"curveRadius":-41.35801525410069},{"acceleration":-4.96326921763636,"curvature":-0.02397095494682326,"pose":{"rotation":{"radians":-0.021105203840320108},"translation":{"x":5.4366126524225304,"y":7.250955432597334}},"time":1.8010724409708745,"velocity":1.3436183246880387,"position":2.6497556917877523,"holonomicRotation":0.0,"angularVelocity":-0.03249554068010593,"angularAcceleration":0.18810736754895793,"curveRadius":-41.71715320555156},{"acceleration":-4.962115684668575,"curvature":-0.023762855823635482,"pose":{"rotation":{"radians":-0.021239567101144274},"translation":{"x":5.442215235100391,"y":7.25083641826952}},"time":1.8053094536705006,"velocity":1.3225937775150842,"position":2.65535953841953,"holonomicRotation":0.0,"angularVelocity":-0.031711790912504104,"angularAcceleration":0.18497696919128875,"curveRadius":-42.08248400031785},{"acceleration":-4.960887447813545,"curvature":-0.023554801199113046,"pose":{"rotation":{"radians":-0.021372696674216485},"translation":{"x":5.447814955589207,"y":7.250716718915588}},"time":1.8096138080848256,"velocity":1.301240359730118,"position":2.6609605381060324,"holonomicRotation":0.0,"angularVelocity":-0.030929045393926952,"angularAcceleration":0.1818496906230907,"curveRadius":-42.45418976567949},{"acceleration":-4.959577090432574,"curvature":-0.02334677261133099,"pose":{"rotation":{"radians":-0.021504593158418572},"translation":{"x":5.45341177921725,"y":7.250596342944059}},"time":1.8139889041440658,"velocity":1.2795417335462689,"position":2.666558656102104,"holonomicRotation":0.0,"angularVelocity":-0.030147105895772096,"angularAcceleration":0.17872510399021121,"curveRadius":-42.83247267824357},{"acceleration":-4.958176180793604,"curvature":-0.02313876646499279,"pose":{"rotation":{"radians":-0.02163525710761771},"translation":{"x":5.459005671312785,"y":7.250475298763455}},"time":1.818438438816811,"velocity":1.2574801567162477,"position":2.672153857659702,"holonomicRotation":0.0,"angularVelocity":-0.0293657559293768,"angularAcceleration":0.17560262451291472,"curveRadius":-43.21751557123517},{"acceleration":-4.95667509164092,"curvature":-0.022930768852242114,"pose":{"rotation":{"radians":-0.021764689031774864},"translation":{"x":5.464596597204084,"y":7.250353594782297}},"time":1.8229664436472761,"velocity":1.235036307958252,"position":2.6777461080279368,"holonomicRotation":0.0,"angularVelocity":-0.028584758409778647,"angularAcceleration":0.17248160036038435,"curveRadius":-43.60952772424037},{"acceleration":-4.955062780987612,"curvature":-0.022722765498639823,"pose":{"rotation":{"radians":-0.02189288939581502},"translation":{"x":5.470184522219411,"y":7.250231239409106}},"time":1.8275773286168113,"velocity":1.212189083458293,"position":2.6833353724530893,"holonomicRotation":0.0,"angularVelocity":-0.02780385216443103,"angularAcceleration":0.1693614675940034,"curveRadius":-44.00872772549889},{"acceleration":-4.953326521936745,"curvature":-0.022514745283249295,"pose":{"rotation":{"radians":-0.02201985862009792},"translation":{"x":5.475769411687037,"y":7.250108241052402}},"time":1.8322759336825387,"velocity":1.188915358370119,"position":2.688921616178648,"holonomicRotation":0.0,"angularVelocity":-0.027022748774746464,"angularAcceleration":0.16624155015327832,"curveRadius":-44.41533703443619},{"acceleration":-4.951451568545706,"curvature":-0.0223066986246062,"pose":{"rotation":{"radians":-0.022145597078775836},"translation":{"x":5.481351230935229,"y":7.249984608120709}},"time":1.8370675897017938,"velocity":1.1651897056576468,"position":2.694504804445337,"holonomicRotation":0.0,"angularVelocity":-0.02624112794671383,"angularAcceleration":0.16312123092553288,"curveRadius":-44.82958311441543},{"acceleration":-4.949420738842947,"curvature":-0.02209860852377619,"pose":{"rotation":{"radians":-0.022270105103016746},"translation":{"x":5.486929945292254,"y":7.249860349022545}},"time":1.841958190919532,"velocity":1.1409840625651633,"position":2.7000849024911378,"holonomicRotation":0.0,"angularVelocity":-0.02545863354986345,"angularAcceleration":0.15999963235855086,"curveRadius":-45.25171794975627},{"acceleration":-4.947213889875546,"curvature":-0.02189046843912324,"pose":{"rotation":{"radians":-0.022393382976732212},"translation":{"x":5.492505520086382,"y":7.249735472166434}},"time":1.8469542818190487,"velocity":1.116267332271993,"position":2.7056618755513298,"holonomicRotation":0.0,"angularVelocity":-0.0246748660492524,"angularAcceleration":0.15687614904821937,"curveRadius":-45.68198267574634},{"acceleration":-4.944807250876345,"curvature":-0.02168226068426341,"pose":{"rotation":{"radians":-0.022515430940176273},"translation":{"x":5.498077920645881,"y":7.2496099859608965}},"time":1.8520631619748622,"velocity":1.0910049046336683,"position":2.711235688858508,"holonomicRotation":0.0,"angularVelocity":-0.023889376873556318,"angularAcceleration":0.15374977524228386,"curveRadius":-46.12065201880825},{"acceleration":-4.942172567740939,"curvature":-0.02147398011219958,"pose":{"rotation":{"radians":-0.022636249187874213},"translation":{"x":5.503647112299016,"y":7.24948389881445}},"time":1.8572930136889587,"velocity":1.0651580749589076,"position":2.7168063076426154,"holonomicRotation":0.0,"angularVelocity":-0.02310165838398199,"angularAcceleration":0.15061966048695358,"curveRadius":-46.567985756487225},{"acceleration":-4.939275993129885,"curvature":-0.021265606454963427,"pose":{"rotation":{"radians":-0.02275583786706825},"translation":{"x":5.509213060374059,"y":7.2493572191356215}},"time":1.86265305876874,"velocity":1.03868333297425,"position":2.722373697130975,"holonomicRotation":0.0,"angularVelocity":-0.022311133099447402,"angularAcceleration":0.1474848201401407,"curveRadius":-47.02428788559653},{"acceleration":-4.936076629627828,"curvature":-0.02105713598930848,"pose":{"rotation":{"radians":-0.022874197082565217},"translation":{"x":5.514775730199275,"y":7.249229955332927}},"time":1.8681537530147603,"velocity":1.011531484659741,"position":2.727937822548311,"holonomicRotation":0.0,"angularVelocity":-0.02151714132858738,"angularAcceleration":0.14434392012144098,"curveRadius":-47.489839098144145},{"acceleration":-4.932524592099988,"curvature":-0.020848549583255428,"pose":{"rotation":{"radians":-0.022991326890024588},"translation":{"x":5.520335087102933,"y":7.2491021158148925}},"time":1.8738070301325813,"velocity":0.9836465562501325,"position":2.7334986491167834,"holonomicRotation":0.0,"angularVelocity":-0.020718921966541837,"angularAcceleration":0.14119586664684888,"curveRadius":-47.964967347328226},{"acceleration":-4.928558393527001,"curvature":-0.020639837261689657,"pose":{"rotation":{"radians":-0.023107227302229916},"translation":{"x":5.525891096413303,"y":7.248973708990035}},"time":1.8796266113426545,"velocity":0.9549644104304142,"position":2.739056142056013,"holonomicRotation":0.0,"angularVelocity":-0.01991559323971866,"angularAcceleration":0.13803892373435453,"curveRadius":-48.44999441231719},{"acceleration":-4.9241013611747455,"curvature":-0.020430984873309233,"pose":{"rotation":{"radians":-0.02322189828336363},"translation":{"x":5.53144372345865,"y":7.248844743266878}},"time":1.8856284037009465,"velocity":0.9254109765094604,"position":2.744610266583107,"holonomicRotation":0.0,"angularVelocity":-0.01910612268604811,"angularAcceleration":0.13487146927903862,"curveRadius":-48.94526652537375},{"acceleration":-4.919056635523873,"curvature":-0.020221983878616793,"pose":{"rotation":{"radians":-0.023335339753137063},"translation":{"x":5.5369929335672445,"y":7.2487152270539426}},"time":1.8918310203223965,"velocity":0.8948999540601064,"position":2.750160987912695,"holonomicRotation":0.0,"angularVelocity":-0.01828929251908461,"angularAcceleration":0.13169122272344394,"curveRadius":-49.451132292584994},{"acceleration":-4.913300051515466,"curvature":-0.020012817466961513,"pose":{"rotation":{"radians":-0.023447551584305337},"translation":{"x":5.542538692067352,"y":7.248585168759748}},"time":1.8982564714567713,"velocity":0.8633297846705722,"position":2.755708271256946,"holonomicRotation":0.0,"angularVelocity":-0.017463650228069328,"angularAcceleration":0.12849561435433887,"curveRadius":-49.96797685537613},{"acceleration":-4.906669774553362,"curvature":-0.019803474450769104,"pose":{"rotation":{"radians":-0.02355853360259541},"translation":{"x":5.548080964287243,"y":7.248454576792817}},"time":1.9049311004423382,"velocity":0.8305795843707338,"position":2.761252081825607,"holonomicRotation":0.0,"angularVelocity":-0.01662744379201607,"angularAcceleration":0.12528133591566928,"curveRadius":-50.49618956946028},{"acceleration":-4.898950821234794,"curvature":-0.019593943369945344,"pose":{"rotation":{"radians":-0.023668285588046345},"translation":{"x":5.553619715555184,"y":7.24832345956167}},"time":1.9118868797422828,"velocity":0.7965035636569421,"position":2.766792384826024,"holonomicRotation":0.0,"angularVelocity":-0.01577853188237415,"angularAcceleration":0.12204411224615436,"curveRadius":-51.036178941594514},{"acceleration":-4.889851249498557,"curvature":-0.019384212476392184,"pose":{"rotation":{"radians":-0.02377680727290432},"translation":{"x":5.559154911199444,"y":7.248191825474829}},"time":1.9191632523841016,"velocity":0.7609231838025273,"position":2.7723291454631704,"holonomicRotation":0.0,"angularVelocity":-0.014914256072356708,"angularAcceleration":0.11877838760624683,"curveRadius":-51.58837384897059},{"acceleration":-4.878964260329967,"curvature":-0.019174265440856555,"pose":{"rotation":{"radians":-0.023884098343350146},"translation":{"x":5.564686516548292,"y":7.2480596829408155}},"time":1.926809828630708,"velocity":0.7236158115814463,"position":2.777862328939678,"holonomicRotation":0.0,"angularVelocity":-0.014031256210050955,"angularAcceleration":0.11547650004766853,"curveRadius":-52.1532364869216},{"acceleration":-4.865705393117464,"curvature":-0.018964089720691964,"pose":{"rotation":{"radians":-0.023990158437777964},"translation":{"x":5.570214496929992,"y":7.2479270403681495}},"time":1.93489048003901,"velocity":0.6842977424441687,"position":2.7833919004558574,"holonomicRotation":0.0,"angularVelocity":-0.013125191159570601,"angularAcceleration":0.11212772395421776,"curveRadius":-52.7312417694843},{"acceleration":-4.849203298034999,"curvature":-0.01875367242351518,"pose":{"rotation":{"radians":-0.024094987147322833},"translation":{"x":5.575738817672817,"y":7.247793906165352}},"time":1.94348983307825,"velocity":0.6425977313253195,"position":2.7889178252097384,"holonomicRotation":0.0,"angularVelocity":-0.012190301882772198,"angularAcceleration":0.10871623394601812,"curveRadius":-53.32288937424878},{"acceleration":-4.828098225189776,"curvature":-0.018543004734975974,"pose":{"rotation":{"radians":-0.024198584015308278},"translation":{"x":5.581259444105032,"y":7.2476602887409465}},"time":1.9527241438841596,"velocity":0.5980135717124564,"position":2.7944400683970834,"holonomicRotation":0.0,"angularVelocity":-0.011218689749877863,"angularAcceleration":0.10521761215493595,"curveRadius":-53.928692479584576},{"acceleration":-4.8001417112091564,"curvature":-0.01833206867082283,"pose":{"rotation":{"radians":-0.024300948538249934},"translation":{"x":5.586776341554906,"y":7.247526196503451}},"time":1.9627608198429705,"velocity":0.5498361048006782,"position":2.7999585952114225,"holonomicRotation":0.0,"angularVelocity":-0.010199046313913674,"angularAcceleration":0.10159174612677202,"curveRadius":-54.54921743728746},{"acceleration":-4.761321136024971,"curvature":-0.01812085244770029,"pose":{"rotation":{"radians":-0.02440208016344414},"translation":{"x":5.592289475350706,"y":7.24739163786139}},"time":1.9738568510511525,"velocity":0.4970043368831684,"position":2.80547337084408,"holonomicRotation":0.0,"angularVelocity":-0.00911421600181094,"angularAcceleration":0.09776741717370065,"curveRadius":-55.18504181225258},{"acceleration":-4.7036769491754935,"curvature":-0.017909341648971962,"pose":{"rotation":{"radians":-0.024501978291343818},"translation":{"x":5.597798810820703,"y":7.247256621223281}},"time":1.9864449384433673,"velocity":0.4377940403822008,"position":2.810984360484202,"holonomicRotation":0.0,"angularVelocity":-0.007935925831072672,"angularAcceleration":0.09360358996768535,"curveRadius":-55.836781697522774},{"acceleration":-4.60869584559585,"curvature":-0.017697523741787024,"pose":{"rotation":{"radians":-0.024600642272776696},"translation":{"x":5.603304313293162,"y":7.2471211549976475}},"time":2.001368958209548,"velocity":0.3690137724862138,"position":2.816491529318779,"holonomicRotation":0.0,"angularVelocity":-0.0066110862206482076,"angularAcceleration":0.08877230338616197,"curveRadius":-56.50508029204226},{"acceleration":-4.419335180490763,"curvature":-0.01748538583138106,"pose":{"rotation":{"radians":-0.02469807141111957},"translation":{"x":5.608805948096352,"y":7.24698524759301}},"time":2.0208080065814618,"velocity":0.2831061021409535,"position":2.821994842532681,"holonomicRotation":0.0,"angularVelocity":-0.005012032301110167,"angularAcceleration":0.08225988684962629,"curveRadius":-57.190616760958044},{"acceleration":-3.536159133323964,"curvature":-0.01748538583138106,"pose":{"rotation":{"radians":-0.024794264960191548},"translation":{"x":5.614303680558541,"y":7.246848907417889}},"time":2.0677097028236964,"velocity":0.11725424060558934,"position":2.8274942653086783,"holonomicRotation":0.0,"angularVelocity":-0.002050960983909047,"angularAcceleration":0.0631335656157932,"curveRadius":-57.190616760958044}] \ No newline at end of file diff --git a/src/main/deploy/pathplanner/generatedJSON/Blue3(1).wpilib.json b/src/main/deploy/pathplanner/generatedJSON/Blue3(1).wpilib.json new file mode 100644 index 0000000..5dffdae --- /dev/null +++ b/src/main/deploy/pathplanner/generatedJSON/Blue3(1).wpilib.json @@ -0,0 +1 @@ +[{"acceleration":0.0,"curvature":-0.002394723219621367,"pose":{"rotation":{"radians":-1.5708091670536497},"translation":{"x":7.64757694377755,"y":1.8956170898115021}},"time":0.0,"velocity":0,"position":0.0,"holonomicRotation":-90.0,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-417.5847930175878},{"acceleration":1.5000000000000004,"curvature":-0.002394723219621367,"pose":{"rotation":{"radians":-1.5708091670536497},"translation":{"x":7.647576802396737,"y":1.884606344970438}},"time":0.08567669788988448,"velocity":0.12851504683482676,"position":0.011010744841971808,"holonomicRotation":-90.0456,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-417.5847930175878},{"acceleration":5.170925437190575,"curvature":-0.0024921307046337185,"pose":{"rotation":{"radians":-1.5708353264404877},"translation":{"x":7.647576379766392,"y":1.8737695709637463}},"time":0.12068559388456358,"velocity":0.30954343766167214,"position":0.02184751885690472,"holonomicRotation":-90.0912,"angularVelocity":-0.0007472211303666228,"angularAcceleration":-0.02134375018510126,"curveRadius":-401.26306302500905},{"acceleration":3.478875689135106,"curvature":-0.0025943328114735407,"pose":{"rotation":{"radians":-1.5708621181004023},"translation":{"x":7.647575678154655,"y":1.863105369511949}},"time":0.14722255337137705,"velocity":0.4018622208839107,"position":0.03251172033178194,"holonomicRotation":-90.1368,"angularVelocity":-0.001009597950658459,"angularAcceleration":-0.009887222400976808,"curveRadius":-385.45555742789054},{"acceleration":3.3012221864720916,"curvature":-0.0027015862398716284,"pose":{"rotation":{"radians":-1.5708895625186852},"translation":{"x":7.6475746998296685,"y":1.8526123423355667}},"time":0.16932168113538937,"velocity":0.4748163517601496,"position":0.043004747553771705,"holonomicRotation":-90.1824,"angularVelocity":-0.0012418778956304643,"angularAcceleration":-0.010510819587652022,"curveRadius":-370.1529069260869},{"acceleration":3.223738462223704,"curvature":-0.0028142021393836487,"pose":{"rotation":{"radians":-1.5709176810142056},"translation":{"x":7.647573447059575,"y":1.8422890911551204}},"time":0.18855237788694593,"velocity":0.5368110885335029,"position":0.05332799881023248,"holonomicRotation":-90.228,"angularVelocity":-0.0014621672778521633,"angularAcceleration":-0.011455091048839324,"curveRadius":-355.3405016666694},{"acceleration":3.1799740447100064,"curvature":-0.002932479206065729,"pose":{"rotation":{"radians":-1.5709464957806674},"translation":{"x":7.6475719221125145,"y":1.8321342176911313}},"time":0.20572290812112862,"velocity":0.5914129290121123,"position":0.0634828723887215,"holonomicRotation":-90.2736,"angularVelocity":-0.0016781523965059212,"angularAcceleration":-0.012578826379151637,"curveRadius":-341.0083856456801},{"acceleration":3.1518063780389665,"curvature":-0.0030567688914650806,"pose":{"rotation":{"radians":-1.5709760299297972},"translation":{"x":7.647570127256627,"y":1.8221463236641204}},"time":0.22131541078590822,"velocity":0.6405574783605542,"position":0.07347076657700294,"holonomicRotation":-90.3192,"angularVelocity":-0.0018941250012792805,"angularAcceleration":-0.013851054536690824,"curveRadius":-327.14282155649306},{"acceleration":3.132162735629613,"curvature":-0.003187416755199891,"pose":{"rotation":{"radians":-1.571006307536404},"translation":{"x":7.6475680647600575,"y":1.8123240107946086}},"time":0.23564532623281836,"velocity":0.6854411055280893,"position":0.08329307966305707,"holonomicRotation":-90.3648,"angularVelocity":-0.0021128949936209383,"angularAcceleration":-0.015266663167145872,"curveRadius":-313.7336836698932},{"acceleration":3.117695491435902,"curvature":-0.003324814874883205,"pose":{"rotation":{"radians":-1.5710373536882551},"translation":{"x":7.647565736890945,"y":1.802665880803117}},"time":0.24893266818571394,"velocity":0.726866991627799,"position":0.09295120993508812,"holonomicRotation":-90.4104,"angularVelocity":-0.0023365208753701287,"angularAcceleration":-0.016829993729517732,"curveRadius":-300.76862551185746},{"acceleration":3.106610872053033,"curvature":-0.0034693611406703684,"pose":{"rotation":{"radians":-1.5710691945362285},"translation":{"x":7.64756314591743,"y":1.7931705354101666}},"time":0.2613382937644044,"velocity":0.7654064429251779,"position":0.10244655568153517,"holonomicRotation":-90.456,"angularVelocity":-0.0025666458955570536,"angularAcceleration":-0.018550053661317855,"curveRadius":-288.2375052505415},{"acceleration":3.0978598624052247,"curvature":-0.0036214986518977995,"pose":{"rotation":{"radians":-1.5711018573486415},"translation":{"x":7.647560294107657,"y":1.7838365763362785}},"time":0.2729841450720546,"velocity":0.8014836582546869,"position":0.1117805151910808,"holonomicRotation":-90.5016,"angularVelocity":-0.0028046736601840755,"angularAcceleration":-0.020438846275725685,"curveRadius":-276.1287787518471},{"acceleration":3.090787574611619,"curvature":-0.0037816986954909465,"pose":{"rotation":{"radians":-1.5711353705699898},"translation":{"x":7.647557183729766,"y":1.7746626053019734}},"time":0.28396535792553174,"velocity":0.8354242544963795,"position":0.120954486752663,"holonomicRotation":-90.5472,"angularVelocity":-0.003051868841395447,"angularAcceleration":-0.022510735791183432,"curveRadius":-264.43143161890066},{"acceleration":3.0849638632128564,"curvature":-0.003950457618704727,"pose":{"rotation":{"radians":-1.5711697638810191},"translation":{"x":7.647553817051896,"y":1.765647224027773}},"time":0.2943579098710555,"velocity":0.8674849016948827,"position":0.12996986865548463,"holonomicRotation":-90.5928,"angularVelocity":-0.0033094192080708506,"angularAcceleration":-0.02478220633636911,"curveRadius":-253.1352305275152},{"acceleration":3.080094460416772,"curvature":-0.004128313441942387,"pose":{"rotation":{"radians":-1.5712050682632146},"translation":{"x":7.647550196342191,"y":1.7567890342341974}},"time":0.30422366682977103,"velocity":0.8978723650512407,"position":0.1388280591890273,"holonomicRotation":-90.6384,"angularVelocity":-0.0035784767801590044,"angularAcceleration":-0.02727186299176612,"curveRadius":-242.2296693463993},{"acceleration":3.0759712201051173,"curvature":-0.004315843377388311,"pose":{"rotation":{"radians":-1.5712413160691714},"translation":{"x":7.6475463238687915,"y":1.7480866376417685}},"time":0.31361383541234356,"velocity":0.926756253363169,"position":0.14753045664306075,"holonomicRotation":-90.684,"angularVelocity":-0.003860186921890186,"angularAcceleration":-0.030000541444379962,"curveRadius":-231.70442311211485},{"acceleration":3.0724427493195,"curvature":-0.0045136713779565085,"pose":{"rotation":{"radians":-1.571278541093771},"translation":{"x":7.64754220189984,"y":1.7395386359710068}},"time":0.3225713970659919,"velocity":0.9542778487175033,"position":0.1560784593076587,"holonomicRotation":-90.7296,"angularVelocity":-0.004155709560148405,"angularAcceleration":-0.032991415486138924,"curveRadius":-221.54913733501215},{"acceleration":3.0693962983968346,"curvature":-0.004722445535704521,"pose":{"rotation":{"radians":-1.5713167786533013},"translation":{"x":7.647537832703477,"y":1.7311436309424337}},"time":0.3311328690754513,"velocity":0.9805563992121661,"position":0.16447346547320996,"holonomicRotation":-90.7752,"angularVelocity":-0.004466236587353682,"angularAcceleration":-0.036270284696624924,"curveRadius":-211.75469202119962},{"acceleration":3.066746174041756,"curvature":-0.004942896709255865,"pose":{"rotation":{"radians":-1.5713560656671657},"translation":{"x":7.647533218547844,"y":1.7229002242765699}},"time":0.33932960714761784,"velocity":1.0056937143346052,"position":0.172716873430435,"holonomicRotation":-90.8208,"angularVelocity":-0.004793005890691939,"angularAcceleration":-0.03986577348956158,"curveRadius":-202.31051928061558},{"acceleration":3.064426088192769,"curvature":-0.005175775720997717,"pose":{"rotation":{"radians":-1.5713964407460672},"translation":{"x":7.647528361701081,"y":1.7148070176939365}},"time":0.34718878771296663,"velocity":1.0297775922908776,"position":0.18081008147039912,"holonomicRotation":-90.8664,"angularVelocity":-0.005137314070572129,"angularAcceleration":-0.043809679268376756,"curveRadius":-193.20775356302212},{"acceleration":3.062383965882979,"curvature":-0.005421913046842546,"pose":{"rotation":{"radians":-1.571437944284301},"translation":{"x":7.6475232644313325,"y":1.7068626129150544}},"time":0.3547341613889947,"velocity":1.0528844236529415,"position":0.18875448788453003,"holonomicRotation":-90.912,"angularVelocity":-0.005500527875192162,"angularAcceleration":-0.048137285204836844,"curveRadius":-184.4367461005946},{"acceleration":3.060578336615291,"curvature":-0.005682194571484458,"pose":{"rotation":{"radians":-1.5714806185614947},"translation":{"x":7.647517929006737,"y":1.699065611660445}},"time":0.36198663968405703,"velocity":1.0750812016095819,"position":0.19655149096463304,"holonomicRotation":-90.9576,"angularVelocity":-0.0058840958162931075,"angularAcceleration":-0.05288784405767742,"curveRadius":-175.98834172599493},{"acceleration":3.05897577287725,"curvature":-0.005957576164567788,"pose":{"rotation":{"radians":-1.57152450784589},"translation":{"x":7.647512357695437,"y":1.691414615650629}},"time":0.368964758030638,"velocity":1.0964270965720433,"position":0.2042024890029109,"holonomicRotation":-91.0032,"angularVelocity":-0.006289558619588758,"angularAcceleration":-0.05810489062489358,"curveRadius":-167.85349819737442},{"acceleration":3.0575490375743786,"curvature":-0.006249085704717221,"pose":{"rotation":{"radians":-1.571569658508908},"translation":{"x":7.647506552765574,"y":1.6839082266061274}},"time":0.3756850456539189,"velocity":1.1169747055268289,"position":0.2117088802919807,"holonomicRotation":-91.0488,"angularVelocity":-0.006718561101718314,"angularAcceleration":-0.06383692278934225,"curveRadius":-160.0234093837334},{"acceleration":3.056275721500021,"curvature":-0.006557833523294022,"pose":{"rotation":{"radians":-1.5716161191452436},"translation":{"x":7.647500516485289,"y":1.6765450462474616}},"time":0.38216232425929064,"velocity":1.136771054869818,"position":0.21907206312489483,"holonomicRotation":-91.09440000000001,"angularVelocity":-0.007172863661751335,"angularAcceleration":-0.07013787544297684,"curveRadius":-152.48938486283754},{"acceleration":3.055137225984065,"curvature":-0.006885018086884268,"pose":{"rotation":{"radians":-1.5716639407011286},"translation":{"x":7.647494251122724,"y":1.669323676295152}},"time":0.38840995163629405,"velocity":1.1558584138433783,"position":0.22629343579516245,"holonomicRotation":-91.14,"angularVelocity":-0.00765435468527336,"angularAcceleration":-0.07706782022473403,"curveRadius":-145.24290094531008},{"acceleration":3.0541179928641484,"curvature":-0.007231926594596498,"pose":{"rotation":{"radians":-1.5717131766116452},"translation":{"x":7.647487758946021,"y":1.6622427184697204}},"time":0.3944400221383641,"velocity":1.1742749606619898,"position":0.23337439659676978,"holonomicRotation":-91.18560000000001,"angularVelocity":-0.008165063824666858,"angularAcceleration":-0.08469372608797478,"curveRadius":-138.2757397934837},{"acceleration":2.6362502603623192,"curvature":-0.007599963888479407,"pose":{"rotation":{"radians":-1.5717638829473017},"translation":{"x":7.647481042223319,"y":1.6553007744916872}},"time":0.4002752676290066,"velocity":1.1896581281059742,"position":0.24031634382420639,"holonomicRotation":-91.2312,"angularVelocity":-0.00868966622532462,"angularAcceleration":-0.08990237026000414,"curveRadius":-131.57957257084797},{"acceleration":-0.39396669196856715,"curvature":-0.007990637860811906,"pose":{"rotation":{"radians":-1.571816118570597},"translation":{"x":7.647474103222762,"y":1.6484964460815736}},"time":0.4060057114093716,"velocity":1.187400524126312,"position":0.2471206757724881,"holonomicRotation":-91.27680000000001,"angularVelocity":-0.009115458644624111,"angularAcceleration":-0.07430356803402266,"curveRadius":-125.1464548161106},{"acceleration":-3.0085440955552234,"curvature":-0.00840558433135355,"pose":{"rotation":{"radians":-1.5718699453041474},"translation":{"x":7.647466944212489,"y":1.6418283349599008}},"time":0.4117036990889354,"velocity":1.1702578769364138,"position":0.2537887907371843,"holonomicRotation":-91.3224,"angularVelocity":-0.009446621610541404,"angularAcceleration":-0.058119284305410183,"curveRadius":-118.96852860900037},{"acceleration":-3.008654946217408,"curvature":-0.008846582100656327,"pose":{"rotation":{"radians":-1.5719254281091724},"translation":{"x":7.647459567460643,"y":1.6352950428471897}},"time":0.4173689981957788,"velocity":1.1532129467568084,"position":0.26032208701444587,"holonomicRotation":-91.368,"angularVelocity":-0.009793446732223975,"angularAcceleration":-0.06121920751962138,"curveRadius":-113.03800593517468},{"acceleration":-3.008768925615833,"curvature":-0.00931553988043336,"pose":{"rotation":{"radians":-1.57198263527855},"translation":{"x":7.647451975235366,"y":1.6288951714639612}},"time":0.4230013707320801,"velocity":1.136266439292093,"position":0.26672196290103556,"holonomicRotation":-91.4136,"angularVelocity":-0.010156851133144934,"angularAcceleration":-0.06452066133388248,"curveRadius":-107.3475088760481},{"acceleration":-3.008886169319421,"curvature":-0.009814547834656141,"pose":{"rotation":{"radians":-1.572041638642201},"translation":{"x":7.647444169804797,"y":1.6226273225307366}},"time":0.4286005729623332,"velocity":1.1194190771422619,"position":0.2729898166943584,"holonomicRotation":-91.4592,"angularVelocity":-0.010537816143189613,"angularAcceleration":-0.068039158862004,"curveRadius":-101.88956402748387},{"acceleration":-3.009006820595088,"curvature":-0.010345869866074173,"pose":{"rotation":{"radians":-1.5721025137879057},"translation":{"x":7.64743615343708,"y":1.6164900977680365}},"time":0.43416635519125285,"velocity":1.1026716004534958,"position":0.2791270466924968,"holonomicRotation":-91.5048,"angularVelocity":-0.010937392661257306,"angularAcceleration":-0.07179161915310066,"curveRadius":-96.65692812154599},{"acceleration":-3.009131030923737,"curvature":-0.010911966003640564,"pose":{"rotation":{"radians":-1.5721653402988505},"translation":{"x":7.647427928400354,"y":1.6104820988963824}},"time":0.4396984615307987,"velocity":1.0860247676007984,"position":0.28513505119424504,"holonomicRotation":-91.5504,"angularVelocity":-0.011356707027790012,"angularAcceleration":-0.07579651235827961,"curveRadius":-91.64251425145291},{"acceleration":-3.009258960577925,"curvature":-0.011515504397644434,"pose":{"rotation":{"radians":-1.5722302020070948},"translation":{"x":7.647419496962763,"y":1.604601927636295}},"time":0.4451966296557292,"velocity":1.0694793559040874,"position":0.29101522849914807,"holonomicRotation":-91.596,"angularVelocity":-0.011796967057132202,"angularAcceleration":-0.08007394814754895,"curveRadius":-86.83944406330616},{"acceleration":-3.009390779222787,"curvature":-0.012159402395353973,"pose":{"rotation":{"radians":-1.5722971872682105},"translation":{"x":7.647410861392445,"y":1.5988481857082955}},"time":0.45066059054705443,"velocity":1.0530361623796993,"position":0.29676897690754195,"holonomicRotation":-91.6416,"angularVelocity":-0.012259469357120061,"angularAcceleration":-0.08464597554534915,"curveRadius":-82.24088384327945},{"acceleration":-3.0095266665707987,"curvature":-0.012846827032656957,"pose":{"rotation":{"radians":-1.5723663892541602},"translation":{"x":7.647402023957544,"y":1.5932194748329047}},"time":0.4560900682227312,"velocity":1.0366960045291993,"position":0.3023976947205965,"holonomicRotation":-91.6872,"angularVelocity":-0.012745606499062147,"angularAcceleration":-0.0895366315105977,"curveRadius":-77.84023225797117},{"acceleration":-3.0096668131070436,"curvature":-0.013581237245523195,"pose":{"rotation":{"radians":-1.5724379062706682},"translation":{"x":7.647392986926201,"y":1.587714396730644}},"time":0.4614847794549071,"velocity":1.0204597211674236,"position":0.30790278024036155,"holonomicRotation":-91.7328,"angularVelocity":-0.01325687574923939,"angularAcceleration":-0.09477231091218657,"curveRadius":-73.63099413712338},{"acceleration":-3.0098114208430125,"curvature":-0.014366407169861227,"pose":{"rotation":{"radians":-1.5725118420979083},"translation":{"x":7.647383752566558,"y":1.582331553122034}},"time":0.46684443347298593,"velocity":1.0043281732920428,"position":0.313285631769816,"holonomicRotation":-91.7784,"angularVelocity":-0.01379488806380777,"angularAcceleration":-0.10038191136099343,"curveRadius":-69.60682571338117},{"acceleration":-3.0099607041527614,"curvature":-0.015206464696530992,"pose":{"rotation":{"radians":-1.572588306357666},"translation":{"x":7.647374323146755,"y":1.577069545727596}},"time":0.47216873165174933,"velocity":0.9883022449967729,"position":0.3185476476129201,"holonomicRotation":-91.824,"angularVelocity":-0.014361378193035942,"angularAcceleration":-0.10639714572855564,"curveRadius":-65.76150472556104},{"acceleration":-3.0101148906644517,"curvature":-0.016105917104146883,"pose":{"rotation":{"radians":-1.5726674149089988},"translation":{"x":7.647364700934934,"y":1.5719269762678514}},"time":0.4774573671837362,"velocity":0.972382844430642,"position":0.32369022607467046,"holonomicRotation":-91.8696,"angularVelocity":-0.0149582157541931,"angularAcceleration":-0.11285284409321598,"curveRadius":-62.08898217553376},{"acceleration":-3.010274222236268,"curvature":-0.01706969264036463,"pose":{"rotation":{"radians":-1.5727492902770397},"translation":{"x":7.647354888199235,"y":1.56690244646332}},"time":0.4827100247350467,"velocity":0.9565709048056974,"position":0.328714765461162,"holonomicRotation":-91.9152,"angularVelocity":-0.015587417843471047,"angularAcceleration":-0.11978738060336075,"curveRadius":-58.58336298541804},{"acceleration":-3.010438956006057,"curvature":-0.018103209583892266,"pose":{"rotation":{"radians":-1.5728340621133992},"translation":{"x":7.647344887207802,"y":1.561994558034524}},"time":0.4879263800836901,"velocity":0.9408673854557708,"position":0.33362266407964836,"holonomicRotation":-91.9608,"angularVelocity":-0.01625116210334703,"angularAcceleration":-0.12724291493074738,"curveRadius":-55.23882355589432},{"acceleration":-3.010609365521847,"curvature":-0.01921239023850447,"pose":{"rotation":{"radians":-1.5729218676975236},"translation":{"x":7.647334700228774,"y":1.557201912701984}},"time":0.4931060997395811,"velocity":0.9252732729489678,"position":0.3384153202386127,"holonomicRotation":-92.0064,"angularVelocity":-0.01695180240587049,"angularAcceleration":-0.13526606632592758,"curveRadius":-52.049744336123894},{"acceleration":-3.010785741971115,"curvature":-0.02040375635891418,"pose":{"rotation":{"radians":-1.5730128524753093},"translation":{"x":7.647324329530294,"y":1.552523112186221}},"time":0.498248840545232,"velocity":0.909789582256661,"position":0.34309413224784013,"holonomicRotation":-92.052,"angularVelocity":-0.017691884779748195,"angularAcceleration":-0.1439081613960582,"curveRadius":-49.01058326758106},{"acceleration":-3.0109683955268705,"curvature":-0.021684452948740083,"pose":{"rotation":{"radians":-1.5731071706447892},"translation":{"x":7.6473137773805036,"y":1.547956758207756}},"time":0.5033542492561716,"velocity":0.8944173579817744,"position":0.34766049841849583,"holonomicRotation":-92.0976,"angularVelocity":-0.018474166285220795,"angularAcceleration":-0.15322602944527727,"curveRadius":-46.11598929260064},{"acceleration":-3.011157656772879,"curvature":-0.023062363693459344,"pose":{"rotation":{"radians":-1.5732049857919597},"translation":{"x":7.647303046047542,"y":1.5435014524871105}},"time":0.5084219621000834,"velocity":0.879157675649503,"position":0.3521158170632085,"holonomicRotation":-92.14320000000001,"angularVelocity":-0.01930163570494236,"angularAcceleration":-0.16328261786096582,"curveRadius":-43.360689879485655},{"acceleration":-3.0113538782932965,"curvature":-0.02454615481631049,"pose":{"rotation":{"radians":-1.5733064715750977},"translation":{"x":7.647292137799553,"y":1.5391557967448046}},"time":0.5134516043136381,"velocity":0.8640116430632873,"position":0.3564614864961624,"holonomicRotation":-92.1888,"angularVelocity":-0.020177535265742286,"angularAcceleration":-0.17414748874967775,"curveRadius":-40.739578458762004},{"acceleration":-3.0115574363377777,"curvature":-0.026145396834310844,"pose":{"rotation":{"radians":-1.57341181247694},"translation":{"x":7.647281054904677,"y":1.53491839270136}},"time":0.5184427896559582,"velocity":0.848980401729483,"position":0.36069890503319163,"holonomicRotation":-92.23440000000001,"angularVelocity":-0.021105387722060668,"angularAcceleration":-0.1858982170930713,"curveRadius":-38.24765048842903},{"acceleration":-3.011768732715916,"curvature":-0.02787064317995763,"pose":{"rotation":{"radians":-1.5735212046112652},"translation":{"x":7.647269799631055,"y":1.5307878420772978}},"time":0.5233951198976611,"velocity":0.8340651283534389,"position":0.3648294709918861,"holonomicRotation":-92.28,"angularVelocity":-0.022089022538112124,"angularAcceleration":-0.1986206024324499,"curveRadius":-35.88004745865073},{"acceleration":-3.0119881967353166,"curvature":-0.029733573555509207,"pose":{"rotation":{"radians":-1.573634856610025},"translation":{"x":7.647258374246829,"y":1.5267627465931386}},"time":0.5283081842843975,"velocity":0.8192670364107881,"position":0.36885458269170307,"holonomicRotation":-92.32560000000001,"angularVelocity":-0.0231326092665301,"angularAcceleration":-0.21241055403940845,"curveRadius":-33.63201527502618},{"acceleration":-3.0122162874316136,"curvature":-0.03174709347252164,"pose":{"rotation":{"radians":-1.5737529905820233},"translation":{"x":7.64724678102014,"y":1.5228417079694034}},"time":0.5331815589738224,"velocity":0.8045873777965457,"position":0.37277563845408745,"holonomicRotation":-92.3712,"angularVelocity":-0.024240691415498117,"angularAcceleration":-0.22737470840740873,"curveRadius":-31.498946537122823},{"acceleration":-3.0124534958765206,"curvature":-0.033925516147913976,"pose":{"rotation":{"radians":-1.5738758431623658},"translation":{"x":7.64723502221913,"y":1.5190233279266139}},"time":0.5380148064449418,"velocity":0.7900274445557355,"position":0.37659403660260143,"holonomicRotation":-92.41680000000001,"angularVelocity":-0.025418226787805708,"angularAcceleration":-0.24363233609365637,"curveRadius":-29.476338565934785},{"acceleration":-3.0127003477704695,"curvature":-0.036284716994342686,"pose":{"rotation":{"radians":-1.5740036666545132},"translation":{"x":7.6472231001119395,"y":1.5153062081852902}},"time":0.5428074748788236,"velocity":0.7755885706982312,"position":0.38031117546306636,"holonomicRotation":-92.4624,"angularVelocity":-0.026670631175672466,"angularAcceleration":-0.261316718472088,"curveRadius":-27.559812583240333},{"acceleration":-3.01295740619585,"curvature":-0.03884233321690886,"pose":{"rotation":{"radians":-1.5741367302785108},"translation":{"x":7.64721101696671,"y":1.511688950465954}},"time":0.547559097509693,"velocity":0.7612721341011055,"position":0.3839284533637114,"holonomicRotation":-92.50800000000001,"angularVelocity":-0.02800382823608596,"angularAcceleration":-0.28057721834900223,"curveRadius":-25.74510636154781},{"acceleration":-3.013225274649371,"curvature":-0.04161797774871044,"pose":{"rotation":{"radians":-1.5742753215348593},"translation":{"x":7.647198775051584,"y":1.5081701564891261}},"time":0.5522691919455371,"velocity":0.7470795585010346,"position":0.38744726863534,"holonomicRotation":-92.5536,"angularVelocity":-0.029424305231298634,"angularAcceleration":-0.3015814257146836,"curveRadius":-24.028077626404748},{"acceleration":-3.013504600307124,"curvature":-0.04463349599372685,"pose":{"rotation":{"radians":-1.5744197476981352},"translation":{"x":7.647186376634702,"y":1.5047484279753276}},"time":0.5569372594574175,"velocity":0.733012315579439,"position":0.39086901961150455,"holonomicRotation":-92.5992,"angularVelocity":-0.030939176202648418,"angularAcceleration":-0.32451779403241493,"curveRadius":-22.40469803531742},{"acceleration":-3.0137960775709383,"curvature":-0.04791325418883548,"pose":{"rotation":{"radians":-1.5745703374501279},"translation":{"x":7.647173823984205,"y":1.5014223666450792}},"time":0.5615627842368542,"velocity":0.7190719271424653,"position":0.3941951046286994,"holonomicRotation":-92.6448,"angularVelocity":-0.032556252354788005,"angularAcceleration":-0.3495984194763057,"curveRadius":-20.871051589583228},{"acceleration":-3.0141004519444885,"curvature":-0.05148446990534026,"pose":{"rotation":{"radians":-1.5747274426740399},"translation":{"x":7.647161119368236,"y":1.4981905742189026}},"time":0.5661452326208083,"velocity":0.7052599673973771,"position":0.397426922026567,"holonomicRotation":-92.6904,"angularVelocity":-0.03428412297280031,"angularAcceleration":-0.37706275624677776,"curveRadius":-19.4233329359049},{"acceleration":-3.014418524183788,"curvature":-0.055377588170684916,"pose":{"rotation":{"radians":-1.5748914404227001},"translation":{"x":7.647148265054934,"y":1.495051652417318}},"time":0.5706840522840311,"velocity":0.6915780653266287,"position":0.40056587014812506,"holonomicRotation":-92.736,"angularVelocity":-0.036132246008607746,"angularAcceleration":-0.4071814200468094,"curveRadius":-18.05784673969184},{"acceleration":-3.0147511548701043,"curvature":-0.05962670513982233,"pose":{"rotation":{"radians":-1.5750627350783475},"translation":{"x":7.6471352633124425,"y":1.4920042029608471}},"time":0.5751786713988261,"velocity":0.6780279071595993,"position":0.40361334734000903,"holonomicRotation":-92.7816,"angularVelocity":-0.038111050407698806,"angularAcceleration":-0.4402607537037807,"curveRadius":-16.771008856770443},{"acceleration":-3.0150992692712926,"curvature":-0.06427008100226932,"pose":{"rotation":{"radians":-1.5752417607357572},"translation":{"x":7.647122116408902,"y":1.4890468275700104}},"time":0.5796284977626411,"velocity":0.6646112389416763,"position":0.4065707519527395,"holonomicRotation":-92.8272,"angularVelocity":-0.04023205464048559,"angularAcceleration":-0.47664876320439903,"curveRadius":-15.55933934430067},{"acceleration":-3.0154638626973433,"curvature":-0.06935070506251671,"pose":{"rotation":{"radians":-1.575428983819478},"translation":{"x":7.647108826612453,"y":1.4861781279653294}},"time":0.5840329178943341,"velocity":0.6513298691984195,"position":0.40943948234100996,"holonomicRotation":-92.8728,"angularVelocity":-0.042507998356824006,"angularAcceleration":-0.5167408304129234,"curveRadius":-14.419464071757345},{"acceleration":-3.015846006247118,"curvature":-0.07491696159041963,"pose":{"rotation":{"radians":-1.5756249059760972},"translation":{"x":7.647095396191239,"y":1.483396705867325}},"time":0.5883912961005087,"velocity":0.6381856716916134,"position":0.4122209368640036,"holonomicRotation":-92.9184,"angularVelocity":-0.04495299566744048,"angularAcceleration":-0.5609878709361692,"curveRadius":-13.34811207997362},{"acceleration":-3.016246852992305,"curvature":-0.08102339678272329,"pose":{"rotation":{"radians":-1.5758300672638361},"translation":{"x":7.6470818274134,"y":1.4807011629965179}},"time":0.5927029735139503,"velocity":0.6251805882622021,"position":0.41491651388573586,"holonomicRotation":-92.964,"angularVelocity":-0.04758270808928423,"angularAcceleration":-0.6099047237730806,"curveRadius":-12.342114002966994},{"acceleration":-3.016667644728033,"curvature":-0.08773159693822444,"pose":{"rotation":{"radians":-1.576045049680042},"translation":{"x":7.647068122547077,"y":1.4780901010734295}},"time":0.59696726710699,"velocity":0.6123166317524582,"position":0.4175276117754295,"holonomicRotation":-93.0096,"angularVelocity":-0.05041454381958549,"angularAcceleration":-0.6640808538425829,"curveRadius":-11.398401885972083},{"acceleration":-3.017109719111792,"curvature":-0.09511123011520246,"pose":{"rotation":{"radians":-1.5762704810651558},"translation":{"x":7.647054283860412,"y":1.4755621218185806}},"time":0.6011834686835564,"velocity":0.5995958889980652,"position":0.4200556289079259,"holonomicRotation":-93.0552,"angularVelocity":-0.05346788596795644,"angularAcceleration":-0.7241926394936529,"curveRadius":-10.514005536346872},{"acceleration":-3.017574517529694,"curvature":-0.10324123900158415,"pose":{"rotation":{"radians":-1.5765070394284422},"translation":{"x":7.647040313621548,"y":1.473115826952492}},"time":0.6053508438547899,"velocity":0.5870205238763652,"position":0.42250196366413273,"holonomicRotation":-93.1008,"angularVelocity":-0.056764354915610604,"angularAcceleration":-0.7910180418621849,"curveRadius":-9.686051907849109},{"acceleration":-3.01806359330942,"curvature":-0.1122112379514744,"pose":{"rotation":{"radians":-1.5767554577516858},"translation":{"x":7.647026214098624,"y":1.4707498181956853}},"time":0.6094686310044231,"velocity":0.5745927803950599,"position":0.4248680144315155,"holonomicRotation":-93.1464,"angularVelocity":-0.06032811173004807,"angularAcceleration":-0.8654543532574116,"curveRadius":-8.911763369302179},{"acceleration":-3.018578620676812,"curvature":-0.12212315558986371,"pose":{"rotation":{"radians":-1.5770165293186693},"translation":{"x":7.6470119875597815,"y":1.4684626972686812}},"time":0.6135360402516984,"velocity":0.5623149857996914,"position":0.42715517960463867,"holonomicRotation":-93.19200000000001,"angularVelocity":-0.0641862057914146,"angularAcceleration":-0.9485384496165417,"curveRadius":-8.188455294738556},{"acceleration":-3.0191214042192227,"curvature":-0.13309311541694466,"pose":{"rotation":{"radians":-1.5772911136537573},"translation":{"x":7.646997636273163,"y":1.4662530658920008}},"time":0.6175522524214164,"velocity":0.55018955367421,"position":0.42936485758575677,"holonomicRotation":-93.2376,"angularVelocity":-0.06836898138956067,"angularAcceleration":-1.041472766225827,"curveRadius":-7.513536645883381},{"acceleration":-3.019693888966859,"curvature":-0.14525371025850978,"pose":{"rotation":{"radians":-1.5775801431315708},"translation":{"x":7.646983162506909,"y":1.4641195257861652}},"time":0.6215164180328763,"velocity":0.5382189870024321,"position":0.43149844678546656,"holonomicRotation":-93.28320000000001,"angularVelocity":-0.07291054565883007,"angularAcceleration":-1.1456545246597092,"curveRadius":-6.884505726017518},{"acceleration":-3.0202981709850643,"curvature":-0.15875661897692045,"pose":{"rotation":{"radians":-1.5778846303525587},"translation":{"x":7.646968568529162,"y":1.4620606786716952}},"time":0.6254276563219594,"velocity":0.5264058811516276,"position":0.43355734562342535,"holonomicRotation":-93.3288,"angularVelocity":-0.07784931484172926,"angularAcceleration":-1.2627124245239822,"curveRadius":-6.29894996784592},{"acceleration":-3.020936508620292,"curvature":-0.17377571631282254,"pose":{"rotation":{"radians":-1.578205676383658},"translation":{"x":7.646953856608063,"y":1.4600751262691118}},"time":0.6292850543135106,"velocity":0.5147529267306721,"position":0.4355429525291413,"holonomicRotation":-93.37440000000001,"angularVelocity":-0.08322865097212628,"angularAcceleration":-1.394550456597779,"curveRadius":-5.754543967465794},{"acceleration":-3.0216113340911046,"curvature":-0.19051072762295662,"pose":{"rotation":{"radians":-1.5785444799746227},"translation":{"x":7.646939029011752,"y":1.4581614702989363}},"time":0.6330876659645198,"velocity":0.5032629122668356,"position":0.43745666594284804,"holonomicRotation":-93.42,"angularVelocity":-0.08909760503013416,"angularAcceleration":-1.543400850952051,"curveRadius":-5.249048242464954},{"acceleration":-3.022325265621652,"curvature":-0.2091915891879822,"pose":{"rotation":{"radians":-1.5789023478813435},"translation":{"x":7.646924088008372,"y":1.4563183124816896}},"time":0.6368345114024394,"velocity":0.491938726633432,"position":0.4392998843164705,"holonomicRotation":-93.46560000000001,"angularVelocity":-0.09551178788938265,"angularAcceleration":-1.7118888316914214,"curveRadius":-4.7803069133022715},{"acceleration":-3.0230811197534093,"curvature":-0.23008357970168036,"pose":{"rotation":{"radians":-1.5792807064533712},"translation":{"x":7.646909035866065,"y":1.4545442545378926}},"time":0.6405245762873483,"velocity":0.480783361149199,"position":0.4410740061146956,"holonomicRotation":-93.5112,"angularVelocity":-0.10253439541807945,"angularAcceleration":-1.9031122074348679,"curveRadius":-4.34624670433488},{"acceleration":-3.0238819239110963,"curvature":-0.2534934608856432,"pose":{"rotation":{"radians":-1.5796811146413168},"translation":{"x":7.64689387485297,"y":1.4528378981880665}},"time":0.6441568113316284,"velocity":0.46979991125540393,"position":0.4427804298161572,"holonomicRotation":-93.55680000000001,"angularVelocity":-0.11023741114335846,"angularAcceleration":-2.1207371305470377,"curveRadius":-3.9448749348651773},{"acceleration":-3.024730928747504,"curvature":-0.2797767760084927,"pose":{"rotation":{"radians":-1.5801052786367293},"translation":{"x":7.64687860723723,"y":1.4511978451527325}},"time":0.6477301320164044,"velocity":0.45899157766182874,"position":0.44442055391475416,"holonomicRotation":-93.6024,"angularVelocity":-0.11870303083059337,"angularAcceleration":-2.3691183730870735,"curveRadius":-3.5742780879340916},{"acceleration":-3.025631620308893,"curvature":-0.30934658849514945,"pose":{"rotation":{"radians":-1.580555068364272},"translation":{"x":7.646863235286986,"y":1.4496226971524109}},"time":0.6512434185502088,"velocity":0.44836166683394457,"position":0.44599577692111597,"holonomicRotation":-93.64800000000001,"angularVelocity":-0.12802534698345527,"angularAcceleration":-2.653446015052749,"curveRadius":-3.2326201005306383},{"acceleration":-3.026587731308207,"curvature":-0.34268395125027495,"pose":{"rotation":{"radians":-1.5810325360804702},"translation":{"x":7.64684776127038,"y":1.4481110559076236}},"time":0.6546955161222071,"velocity":0.43791359067525576,"position":0.44750749736423107,"holonomicRotation":-93.6936,"angularVelocity":-0.138312346693576,"angularAcceleration":-2.97992727481513,"curveRadius":-2.918140742662508},{"acceleration":-3.0276032514260116,"curvature":-0.38035048033564556,"pose":{"rotation":{"radians":-1.5815399373954193},"translation":{"x":7.646832187455552,"y":1.4466615231388908}},"time":0.6580852355098653,"velocity":0.42765086523576,"position":0.4489571137932695,"holonomicRotation":-93.73920000000001,"angularVelocity":-0.14968829478820836,"angularAcceleration":-3.3560147002290597,"curveRadius":-2.6291540347669238},{"acceleration":-3.028682435674031,"curvature":-0.42300351823568993,"pose":{"rotation":{"radians":-1.5820797550354317},"translation":{"x":7.646816516110645,"y":1.4452727005667345}},"time":0.6614113541090011,"velocity":0.41757710825558875,"position":0.4503460247796118,"holonomicRotation":-93.7848,"angularVelocity":-0.16229656998781972,"angularAcceleration":-3.790687200055742,"curveRadius":-2.3640465312697896},{"acceleration":-3.0298298105363703,"curvature":-0.4714144204227945,"pose":{"rotation":{"radians":-1.5826547257757433},"translation":{"x":7.646800749503799,"y":1.4439431899116748}},"time":0.664672617462835,"velocity":0.4076960353261329,"position":0.4516756289191243,"holonomicRotation":-93.8304,"angularVelocity":-0.1763030696786907,"angularAcceleration":-4.29480792294956,"curveRadius":-2.121275796152218},{"acceleration":-3.031050176575771,"curvature":-0.5264907190793044,"pose":{"rotation":{"radians":-1.5832678709650727},"translation":{"x":7.646784889903157,"y":1.4426715928942333}},"time":0.6678677413755664,"velocity":0.39801145442626706,"position":0.4529473248347026,"holonomicRotation":-93.876,"angularVelocity":-0.19190028495804862,"angularAcceleration":-4.88156819746769,"curveRadius":-1.8993687139418913},{"acceleration":-3.032348606786991,"curvature":-0.589303022703793,"pose":{"rotation":{"radians":-1.5839225311933527},"translation":{"x":7.64676893957686,"y":1.4414565112349307}},"time":0.6709954147051609,"velocity":0.3885272585627863,"position":0.4541625111791299,"holonomicRotation":-93.9216,"angularVelocity":-0.20931221367829114,"angularAcceleration":-5.5670547673531745,"curveRadius":-1.6969198552756102},{"acceleration":-3.0337304392497573,"curvature":-0.6611177259327515,"pose":{"rotation":{"radians":-1.5846224056882},"translation":{"x":7.6467529007930475,"y":1.440296546654288}},"time":0.6740543029389254,"velocity":0.3792474162177519,"position":0.455322586638284,"holonomicRotation":-93.9672,"angularVelocity":-0.22880028342385003,"angularAcceleration":-6.370964957282896,"curveRadius":-1.5125899076282208},{"acceleration":-3.035201262393747,"curvature":-0.7434369483808112,"pose":{"rotation":{"radians":-1.5853715971236095},"translation":{"x":7.646736775819861,"y":1.4391903008728266}},"time":0.6770430526638296,"velocity":0.37017595927974384,"position":0.4564289499347475,"holonomicRotation":-94.0128,"angularVelocity":-0.25067051589060774,"angularAcceleration":-7.317518855634221,"curveRadius":-1.34510398249371},{"acceleration":-3.0367668911955734,"curvature":-0.838047343817873,"pose":{"rotation":{"radians":-1.5861746626403548},"translation":{"x":7.646720566925445,"y":1.4381363756110672}},"time":0.679960297050758,"velocity":0.3613169681119935,"position":0.4574829998318742,"holonomicRotation":-94.0584,"angularVelocity":-0.2752822219295796,"angularAcceleration":-8.436628123873303,"curveRadius":-1.1932500083400097},{"acceleration":-3.038433331916318,"curvature":-0.9470799044337724,"pose":{"rotation":{"radians":-1.5870366719657474},"translation":{"x":7.646704276377939,"y":1.4371333725895312}},"time":0.6828046624773345,"velocity":0.35267455339173304,"position":0.45848613513837494,"holonomicRotation":-94.104,"angularVelocity":-0.30305857234037475,"angularAcceleration":-9.76539447121142,"curveRadius":-1.0558771179902362},{"acceleration":-3.040206732667092,"curvature":-1.073083415692698,"pose":{"rotation":{"radians":-1.5879632736122788},"translation":{"x":7.646687906445484,"y":1.4361798935287389}},"time":0.6855747764168294,"velocity":0.3442528343426257,"position":0.45943975471349807,"holonomicRotation":-94.1496,"angularVelocity":-0.334499470697016,"angularAcceleration":-11.350037956335576,"curveRadius":-0.9318940031837869},{"acceleration":-3.042093316688505,"curvature":-1.21911479696006,"pose":{"rotation":{"radians":-1.588960770326171},"translation":{"x":7.646671459396221,"y":1.435274540149212}},"time":0.6882692767199392,"velocity":0.33605591297872023,"position":0.4603452574728811,"holonomicRotation":-94.1952,"angularVelocity":-0.3701972914016426,"angularAcceleration":-13.248401072149314,"curveRadius":-0.820267297627396},{"acceleration":-3.0440992944597003,"curvature":-1.3888504372313968,"pose":{"rotation":{"radians":-1.5900362049874168},"translation":{"x":7.646654937498293,"y":1.4344159141714714}},"time":0.690886822410928,"velocity":0.32808784398756513,"position":0.46120404239517654,"holonomicRotation":-94.24080000000001,"angularVelocity":-0.41085611798415606,"angularAcceleration":-15.533186955431493,"curveRadius":-0.7200199338911175},{"acceleration":-3.046230750196255,"curvature":-1.5867234794273333,"pose":{"rotation":{"radians":-1.5911974583577884},"translation":{"x":7.64663834301984,"y":1.4336026173160379}},"time":0.6934261061083767,"velocity":0.3203525999049248,"position":0.4620175085295504,"holonomicRotation":-94.2864,"angularVelocity":-0.45731533327224627,"angularAcceleration":-18.2961893288131,"curveRadius":-0.630229534613625},{"acceleration":-3.0484934974714397,"curvature":-1.818093326454663,"pose":{"rotation":{"radians":-1.5924533600780428},"translation":{"x":7.646621678229004,"y":1.4328332513034325}},"time":0.6958858681625251,"velocity":0.31285403127752665,"position":0.4627870550041742,"holonomicRotation":-94.33200000000001,"angularVelocity":-0.510578540772439,"angularAcceleration":-21.65380485090647,"curveRadius":-0.5500267700503748},{"acceleration":-3.0508928973846623,"curvature":-2.089454831533826,"pose":{"rotation":{"radians":-1.5938138144259026},"translation":{"x":7.646604945393927,"y":1.4321064178541765}},"time":0.6982649125745731,"velocity":0.30559582157824655,"position":0.4635140810358452,"holonomicRotation":-94.3776,"angularVelocity":-0.5718490756078937,"angularAcceleration":-25.754262730517244,"curveRadius":-0.4785937388586287},{"acceleration":-3.053433632100081,"curvature":-2.40869631951777,"pose":{"rotation":{"radians":-1.5952899422468798},"translation":{"x":7.646588146782749,"y":1.4314207186887906}},"time":0.7005621247272856,"velocity":0.29858143673108517,"position":0.4641999859408782,"holonomicRotation":-94.42320000000001,"angularVelocity":-0.6425735730303301,"angularAcceleration":-30.787098761830247,"curveRadius":-0.4151623398503817},{"acceleration":-3.056119424107259,"curvature":-2.7854171783437076,"pose":{"rotation":{"radians":-1.596894240285068},"translation":{"x":7.6465712846636125,"y":1.4307747555277963}},"time":0.7027764909100294,"velocity":0.2918140692279158,"position":0.4648461691474253,"holonomicRotation":-94.4688,"angularVelocity":-0.7244953660737669,"angularAcceleration":-36.99559435193809,"curveRadius":-0.35901264908354946},{"acceleration":-3.0589526907588045,"curvature":-3.231317473850418,"pose":{"rotation":{"radians":-1.5986407587318663},"translation":{"x":7.646554361304658,"y":1.430167130091714}},"time":0.7049071195646606,"velocity":0.28529657697182387,"position":0.4654540302093897,"holonomicRotation":-94.51440000000001,"angularVelocity":-0.8197197775416627,"angularAcceleration":-44.69310560566848,"curveRadius":-0.30947129401321444},{"acceleration":-3.061934119704215,"curvature":-3.760673256640255,"pose":{"rotation":{"radians":-1.6005452970144702},"translation":{"x":7.646537378974028,"y":1.4295964441010653}},"time":0.7069532641117371,"velocity":0.27903141716928354,"position":0.46602496882209365,"holonomicRotation":-94.56,"angularVelocity":-0.9307936163772522,"angularAcceleration":-54.28445365420976,"curveRadius":-0.2659098336273408},{"acceleration":-3.065062149477504,"curvature":-4.390911652723339,"pose":{"rotation":{"radians":-1.602625616526404},"translation":{"x":7.646520339939863,"y":1.4290612992763712}},"time":0.7089143471406941,"velocity":0.27302057580524464,"position":0.4665603848398614,"holonomicRotation":-94.60560000000001,"angularVelocity":-1.0608013435514965,"angularAcceleration":-66.29384133898017,"curveRadius":-0.22774313834799617},{"acceleration":-3.06833233343509,"curvature":-5.143298071154777,"pose":{"rotation":{"radians":-1.6049016668734737},"translation":{"x":7.646503246470305,"y":1.4285602973381522}},"time":0.7107899856649733,"velocity":0.2672654934753623,"position":0.4670616782956343,"holonomicRotation":-94.6512,"angularVelocity":-1.213480272241946,"angularAcceleration":-81.4010411463074,"curveRadius":-0.19442777497347716},{"acceleration":-3.0717365620397414,"curvature":-6.043742345014569,"pose":{"rotation":{"radians":-1.6073958188413364},"translation":{"x":7.646486100833494,"y":1.4280920400069295}},"time":0.7125800170572263,"velocity":0.26176698860057995,"position":0.46753024942268484,"holonomicRotation":-94.69680000000001,"angularVelocity":-1.3933565515426707,"angularAcceleration":-100.48777919717261,"curveRadius":-0.16546039571407134},{"acceleration":-3.0752621114933465,"curvature":-7.123718228148556,"pose":{"rotation":{"radians":-1.610133092201358},"translation":{"x":7.646468905297573,"y":1.4276551290032244}},"time":0.7142845251951352,"velocity":0.25652517930533664,"position":0.4679674986783893,"holonomicRotation":-94.7424,"angularVelocity":-1.6059021949754955,"angularAcceleration":-124.69617404911716,"curveRadius":-0.140376130550562},{"acceleration":-3.078890479129253,"curvature":-8.421265862986663,"pose":{"rotation":{"radians":-1.6131413588616903},"translation":{"x":7.646451662130683,"y":1.4272481660475578}},"time":0.7159038662708245,"velocity":0.251539405484934,"position":0.46837482676984554,"holonomicRotation":-94.78800000000001,"angularVelocity":-1.8577103400232657,"angularAcceleration":-155.50037532431904,"curveRadius":-0.1187469931801135},{"acceleration":-3.0825959597286943,"curvature":-9.982003300486346,"pose":{"rotation":{"radians":-1.6164514905191822},"translation":{"x":7.646434373600965,"y":1.4268697528604506}},"time":0.717438693652761,"velocity":0.24680815279849538,"position":0.46875363468084585,"holonomicRotation":-94.8336,"angularVelocity":-2.1566800908356325,"angularAcceleration":-194.79047242116857,"curveRadius":-0.10018029146026006},{"acceleration":-3.086343908240982,"curvature":-11.859996281043767,"pose":{"rotation":{"radians":-1.6200974039271934},"translation":{"x":7.6464170419765605,"y":1.4265184911624242}},"time":0.7188899811452961,"velocity":0.24232898048680337,"position":0.46910532369930513,"holonomicRotation":-94.87920000000001,"angularVelocity":-2.5121923993450035,"angularAcceleration":-244.96339308234948,"curveRadius":-0.08431705847988619},{"acceleration":-3.090088630857614,"curvature":-14.118211259519983,"pose":{"rotation":{"radians":-1.6241159337058262},"translation":{"x":7.646399669525611,"y":1.4261929826739992}},"time":0.7202590439739632,"velocity":0.23809845500500937,"position":0.46943129544361556,"holonomicRotation":-94.9248,"angularVelocity":-2.935241315802261,"angularAcceleration":-309.0062103790581,"curveRadius":-0.07083050264782621},{"acceleration":-3.0937708482715025,"curvature":-16.828079196167916,"pose":{"rotation":{"radians":-1.6285464310085693},"translation":{"x":7.646382258516258,"y":1.4258918291156966}},"time":0.7215475568397018,"velocity":0.23411209146336448,"position":0.4697329518854911,"holonomicRotation":-94.97040000000001,"angularVelocity":-3.4384579467923726,"angularAcceleration":-390.54063360217486,"curveRadius":-0.05942448857904826},{"acceleration":-3.0973146909251277,"curvature":-20.067400329835163,"pose":{"rotation":{"radians":-1.633429943810011},"translation":{"x":7.6463648112166425,"y":1.4256136322080377}},"time":0.722757568435775,"velocity":0.23036430477065736,"position":0.4700116953655849,"holonomicRotation":-95.016,"angularVelocity":-4.0359223145383085,"angularAcceleration":-493.76747271256625,"curveRadius":-0.049832065118731506},{"acceleration":-3.1006242274339164,"curvature":-23.91540202376786,"pose":{"rotation":{"radians":-1.6388077799344014},"translation":{"x":7.646347329894907,"y":1.4253569936715433}},"time":0.7238915119079412,"velocity":0.22684837216831824,"position":0.4702689285963767,"holonomicRotation":-95.06160000000001,"angularVelocity":-4.74259630783609,"angularAcceleration":-623.2003716620824,"curveRadius":-0.04181405769412403},{"acceleration":-3.103579607778474,"curvature":-28.4432178986065,"pose":{"rotation":{"radians":-1.6447191890335198},"translation":{"x":7.6463298168191915,"y":1.425120515226735}},"time":0.7249522108592262,"velocity":0.22355640853311803,"position":0.4705060546444608,"holonomicRotation":-95.1072,"angularVelocity":-5.573126184349263,"angularAcceleration":-783.0024490049682,"curveRadius":-0.03515776602931388},{"acceleration":-3.1060330512550705,"curvature":-33.697468906622944,"pose":{"rotation":{"radians":-1.6511978299878374},"translation":{"x":7.646312274257638,"y":1.424902798594133}},"time":0.7259428806500349,"velocity":0.22047935541998645,"position":0.47072447688137237,"holonomicRotation":-95.15280000000001,"angularVelocity":-6.539657325201543,"angularAcceleration":-975.6340102622316,"curveRadius":-0.029675819355187795},{"acceleration":-3.1078051477878113,"curvature":-39.67420773480023,"pose":{"rotation":{"radians":-1.6582666343402614},"translation":{"x":7.646294704478388,"y":1.424702445494259}},"time":0.7268671249144938,"velocity":0.21760698433708767,"position":0.4709255988885521,"holonomicRotation":-95.1984,"angularVelocity":-7.648199317268557,"angularAcceleration":-1199.403701699994,"curveRadius":-0.025205292231276242},{"acceleration":-3.1086822978522988,"curvature":-46.280757791939905,"pose":{"rotation":{"radians":-1.6659306670335567},"translation":{"x":7.646277109749581,"y":1.4245180576476333}},"time":0.7277289273962871,"velocity":0.2149279142176915,"position":0.4711108242984316,"holonomicRotation":-95.244,"angularVelocity":-8.893026946669945,"angularAcceleration":-1444.4465590433083,"curveRadius":-0.02160725207861995},{"acceleration":-3.108416604645006,"curvature":-53.284847689512645,"pose":{"rotation":{"radians":-1.674167685610966},"translation":{"x":7.646259492339363,"y":1.4243482367747775}},"time":0.7285326393941278,"velocity":0.2124296424982511,"position":0.47128155655080445,"holonomicRotation":-95.28960000000001,"angularVelocity":-10.248719192371698,"angularAcceleration":-1686.7886125179962,"curveRadius":-0.01876706124463253},{"acceleration":-3.1067300994994898,"curvature":-60.25525701303009,"pose":{"rotation":{"radians":-1.6829163994623189},"translation":{"x":7.64624185451587,"y":1.4241915845962123}},"time":0.7292829632955266,"velocity":0.21009858864940179,"position":0.47143919854351823,"holonomicRotation":-95.3352,"angularVelocity":-11.659916250893533,"angularAcceleration":-1880.7838266795502,"curveRadius":-0.016596062311770604},{"acceleration":-3.1033256875893036,"curvature":-66.50726866604991,"pose":{"rotation":{"radians":-1.6920630472731544},"translation":{"x":7.646224198547248,"y":1.4240467028324593}},"time":0.7299849328708834,"velocity":0.20792014843429074,"position":0.4715851521618228,"holonomicRotation":-95.38080000000001,"angularVelocity":-13.029977554491406,"angularAcceleration":-1951.7388668895098,"curveRadius":-0.01503595050672216},{"acceleration":-3.0979073340848373,"curvature":-71.07942287779109,"pose":{"rotation":{"radians":-1.7014279415941598},"translation":{"x":7.6462065267016355,"y":1.4239121932040386}},"time":0.7306438912100552,"velocity":0.20587875656251392,"position":0.471720817685318,"holonomicRotation":-95.4264,"angularVelocity":-14.211663718794224,"angularAcceleration":-1793.2638439448522,"curveRadius":-0.014068769265604885},{"acceleration":-3.090211279471001,"curvature":-72.78128021240819,"pose":{"rotation":{"radians":-1.7107550506933853},"translation":{"x":7.646188841247174,"y":1.4237866574314721}},"time":0.7312654674254431,"velocity":0.20395795473067155,"position":0.4718475930989177,"holonomicRotation":-95.47200000000001,"angularVelocity":-15.005575934732132,"angularAcceleration":-1277.256426941221,"curveRadius":-0.013739796786777515},{"acceleration":-0.0938254940183062,"curvature":-70.35431295762751,"pose":{"rotation":{"radians":-1.7197092047670761},"translation":{"x":7.646171144452006,"y":1.4236686972352803}},"time":0.7318504526240345,"velocity":0.2039030682054203,"position":0.47196687337576526,"holonomicRotation":-95.5176,"angularVelocity":-15.306633561416076,"angularAcceleration":-514.6414429097799,"curveRadius":-0.014213769674678975},{"acceleration":3.0941024721396935,"curvature":-62.763613933682755,"pose":{"rotation":{"radians":-1.7278863951050392},"translation":{"x":7.646153438584273,"y":1.4235569143359845}},"time":0.7324009051910512,"velocity":0.2056062248538223,"position":0.47208004985003066,"holonomicRotation":-95.56320000000001,"angularVelocity":-14.855395047535684,"angularAcceleration":819.7591235262789,"curveRadius":-0.015932798277942046},{"acceleration":3.077491502036263,"curvature":-49.576465202272544,"pose":{"rotation":{"radians":-1.7348417618914596},"translation":{"x":7.6461357259121145,"y":1.4234499104541056}},"time":0.732924317741615,"velocity":0.20721702253024174,"position":0.47218850984031346,"holonomicRotation":-95.6088,"angularVelocity":-13.288498296281517,"angularAcceleration":2993.6170799996025,"curveRadius":-0.020170861232643122},{"acceleration":3.059063646682841,"curvature":-31.30065342028308,"pose":{"rotation":{"radians":-1.7401362084567458},"translation":{"x":7.646118008703675,"y":1.4233462873101645}},"time":0.7334279013043865,"velocity":0.20875751670018297,"position":0.47229363669432867,"holonomicRotation":-95.65440000000001,"angularVelocity":-10.513541260457844,"angularAcceleration":5510.420198291835,"curveRadius":-0.03194821483669066},{"acceleration":3.0393159105670624,"curvature":-9.504558470980953,"pose":{"rotation":{"radians":-1.7433961813535577},"translation":{"x":7.646100289227092,"y":1.4232446466246822}},"time":0.7339186227599797,"velocity":0.21024897422782385,"position":0.4723968103769987,"holonomicRotation":-95.7,"angularVelocity":-6.64322470447415,"angularAcceleration":7886.992736654554,"curveRadius":-0.10521267274573264},{"acceleration":1.4912475711705517,"curvature":13.411665541644323,"pose":{"rotation":{"radians":-1.744374066993176},"translation":{"x":7.64608256975051,"y":1.4231435901181804}},"time":0.7344049298212045,"velocity":0.21097417845171854,"position":0.4724994086097159,"holonomicRotation":-95.74560000000001,"angularVelocity":-2.0108398943566264,"angularAcceleration":9525.637564155008,"curveRadius":0.07456195480679993},{"acceleration":-1.5221163342670543,"curvature":34.76754013590046,"pose":{"rotation":{"radians":-1.7429926784790464},"translation":{"x":7.64606485254207,"y":1.4230417195111793}},"time":0.7348967816450995,"velocity":0.21022552275652892,"position":0.472602808416513,"holonomicRotation":-95.7912,"angularVelocity":2.808546084449453,"angularAcceleration":9798.450965661077,"curveRadius":0.028762460504573182},{"acceleration":-2.9585765673684805,"curvature":52.270202700063784,"pose":{"rotation":{"radians":-1.7393598302288913},"translation":{"x":7.6460471398699115,"y":1.4229376365242001}},"time":0.7354026020129408,"velocity":0.20872901446893594,"position":0.4727083878033908,"holonomicRotation":-95.83680000000001,"angularVelocity":7.1820916695368435,"angularAcceleration":8646.440244690884,"curveRadius":0.019131358754014928},{"acceleration":-2.940303007752071,"curvature":64.52241472585507,"pose":{"rotation":{"radians":-1.733748124333255},"translation":{"x":7.646029434002179,"y":1.4228299428777642}},"time":0.7359293873822135,"velocity":0.2071801058632238,"position":0.4728175272519639,"holonomicRotation":-95.8824,"angularVelocity":10.652736812688156,"angularAcceleration":6588.34763756518,"curveRadius":0.01549849000922908},{"acceleration":-2.9237549351519383,"curvature":71.19000804487023,"pose":{"rotation":{"radians":-1.7265466663036966},"translation":{"x":7.646011737207011,"y":1.4227172402923922}},"time":0.7364843832135548,"velocity":0.20555743406235083,"position":0.47293161077096973,"holonomicRotation":-95.92800000000001,"angularVelocity":12.975697514977368,"angularAcceleration":4185.546216941857,"curveRadius":0.01404691511440358},{"acceleration":-2.9092404094871114,"curvature":72.83355234896774,"pose":{"rotation":{"radians":-1.7181996443533327},"translation":{"x":7.645994051752549,"y":1.4225981304886053}},"time":0.737075122551903,"velocity":0.2038388313077546,"position":0.47305202638730615,"holonomicRotation":-95.9736,"angularVelocity":14.129788569191254,"angularAcceleration":1953.6383973359998,"curveRadius":0.013729935829694194},{"acceleration":0.09002689857826927,"curvature":70.55128231323656,"pose":{"rotation":{"radians":-1.7091480293005743},"translation":{"x":7.645976379906936,"y":1.4224712151869245}},"time":0.7377035806456311,"velocity":0.20389540944081935,"position":0.47318016610764324,"holonomicRotation":-96.01920000000001,"angularVelocity":14.402893594801991,"angularAcceleration":434.5636221989376,"curveRadius":0.014174086809083893},{"acceleration":2.91368234001572,"curvature":65.60817753297384,"pose":{"rotation":{"radians":-1.6997858716241288},"translation":{"x":7.645958723938314,"y":1.422335096107871}},"time":0.7383704115976155,"velocity":0.20583834300939213,"position":0.4733174254858671,"holonomicRotation":-96.0648,"angularVelocity":14.039776720899342,"angularAcceleration":-544.5411206874381,"curveRadius":0.015242002408882837},{"acceleration":2.9072239531546518,"curvature":59.16493614838092,"pose":{"rotation":{"radians":-1.6904354629186233},"translation":{"x":7.645941086114822,"y":1.4221883749719655}},"time":0.7390812056583274,"velocity":0.20790478052845365,"position":0.4734652029690603,"holonomicRotation":-96.11040000000001,"angularVelocity":13.154877372133996,"angularAcceleration":-1244.9447704714162,"curveRadius":0.01690190280087652},{"acceleration":2.902779305529579,"curvature":52.138192647366985,"pose":{"rotation":{"radians":-1.681339600764126},"translation":{"x":7.645923468704603,"y":1.4220296534997294}},"time":0.7398412618459789,"velocity":0.21011105590100818,"position":0.47362489917719186,"holonomicRotation":-96.156,"angularVelocity":11.967354917012893,"angularAcceleration":-1562.4140351918059,"curveRadius":0.019179797941279438},{"acceleration":2.900073963114864,"curvature":45.1677062898287,"pose":{"rotation":{"radians":-1.6726660395007666},"translation":{"x":7.645905873975797,"y":1.4218575334116834}},"time":0.7406555647410458,"velocity":0.21247259452508074,"position":0.473797916226036,"holonomicRotation":-96.20160000000001,"angularVelocity":10.651517163827233,"angularAcceleration":-1615.90700605032,"curveRadius":0.022139711801685835},{"acceleration":2.898828614025848,"curvature":38.64734433296537,"pose":{"rotation":{"radians":-1.6645187116991185},"translation":{"x":7.645888304196546,"y":1.4216706164283484}},"time":0.7415287627370948,"velocity":0.21500384586173765,"position":0.4739856571533853,"holonomicRotation":-96.2472,"angularVelocity":9.33044720500121,"angularAcceleration":-1512.9099755193092,"curveRadius":0.025874999104324517},{"acceleration":2.8987787727092624,"curvature":32.781958290087516,"pose":{"rotation":{"radians":-1.656951364917231},"translation":{"x":7.645870761634993,"y":1.421467504270246}},"time":0.7424651488330516,"velocity":0.21771822199975735,"position":0.4741895254693023,"holonomicRotation":-96.29280000000001,"angularVelocity":8.081438644339475,"angularAcceleration":-1333.8606436541386,"curveRadius":0.030504583989492053},{"acceleration":2.8996858679500264,"curvature":27.646009255908723,"pose":{"rotation":{"radians":-1.649980797180337},"translation":{"x":7.645853248559277,"y":1.4212467986578967}},"time":0.7434686448146043,"velocity":0.22062804511601034,"position":0.47441092482599406,"holonomicRotation":-96.33840000000001,"angularVelocity":6.946283657367928,"angularAcceleration":-1131.2003314802905,"curveRadius":0.036171585950918836},{"acceleration":2.9013419629858177,"curvature":23.232480421046503,"pose":{"rotation":{"radians":-1.6435982444611517},"translation":{"x":7.645835767237542,"y":1.421007101311822}},"time":0.7445427894645905,"velocity":0.2237445060633321,"position":0.4746512587901458,"holonomicRotation":-96.38400000000001,"angularVelocity":5.941986229943273,"angularAcceleration":-934.9741000316196,"curveRadius":0.04304318703284439},{"acceleration":2.9035702831508545,"curvature":19.488929232912774,"pose":{"rotation":{"radians":-1.6377784316694814},"translation":{"x":7.645818319937926,"y":1.4207470139525422}},"time":0.7456907312487063,"velocity":0.22707763571447795,"position":0.4749119306964207,"holonomicRotation":-96.42960000000001,"angularVelocity":5.069780429808852,"angularAcceleration":-759.799679916892,"curveRadius":0.0513111822639905},{"acceleration":2.9062233011100456,"curvature":16.34175790722024,"pose":{"rotation":{"radians":-1.6324863551250903},"translation":{"x":7.645800908928574,"y":1.420465138300579}},"time":0.746915225733209,"velocity":0.23063629011742037,"position":0.4751943435615956,"holonomicRotation":-96.4752,"angularVelocity":4.321845962859081,"angularAcceleration":-610.8108092079641,"curveRadius":0.06119292708149668},{"acceleration":2.9091796205449816,"curvature":13.711304506844849,"pose":{"rotation":{"radians":-1.627682124133364},"translation":{"x":7.645783536477624,"y":1.420160076076453}},"time":0.7482186378035809,"velocity":0.23442814994971858,"position":0.47549990004187503,"holonomicRotation":-96.52080000000001,"angularVelocity":3.68588806328571,"angularAcceleration":-487.9177614121104,"curveRadius":0.07293252071681348},{"acceleration":2.9123404594632696,"curvature":11.52045323231498,"pose":{"rotation":{"radians":-1.6233242645876764},"translation":{"x":7.64576620485322,"y":1.4198304290006858}},"time":0.7496029485711952,"velocity":0.23845973420671254,"position":0.47583000241957984,"holonomicRotation":-96.5664,"angularVelocity":3.1480355767207957,"angularAcceleration":-388.5344961173836,"curveRadius":0.0868021404917465},{"acceleration":2.91562619713032,"curvature":9.698994667874206,"pose":{"rotation":{"radians":-1.6193718677247233},"translation":{"x":7.645748916323502,"y":1.4194747987937975}},"time":0.7510697666871861,"velocity":0.24273642753212069,"position":0.47618605260889485,"holonomicRotation":-96.61200000000001,"angularVelocity":2.6945378025164017,"angularAcceleration":-309.17110257945274,"curveRadius":0.10310346940516224},{"acceleration":2.9189732240230035,"curvature":8.185369916164523,"pose":{"rotation":{"radians":-1.6157859061866393},"translation":{"x":7.645731673156611,"y":1.4190917871763102}},"time":0.7526203436372816,"velocity":0.24726252013123678,"position":0.4765694521732329,"holonomicRotation":-96.6576,"angularVelocity":2.312662740061413,"angularAcceleration":-246.2793364956587,"curveRadius":0.12216918847188486},{"acceleration":2.9223311888666412,"curvature":6.926910135517035,"pose":{"rotation":{"radians":-1.612529970287616},"translation":{"x":7.6457144776206905,"y":1.4186799958687442}},"time":0.7542555924762029,"velocity":0.25204125881477446,"position":0.47698160234907,"holonomicRotation":-96.70320000000001,"angularVelocity":1.9910950685469953,"angularAcceleration":-196.64754614749742,"curveRadius":0.14436451180052134},{"acceleration":2.9256606566389225,"curvature":5.879283649067886,"pose":{"rotation":{"radians":-1.609570613441912},"translation":{"x":7.64569733198388,"y":1.4182380265916206}},"time":0.7559761093796946,"velocity":0.25707490742840244,"position":0.47742390407276414,"holonomicRotation":-96.7488,"angularVelocity":1.7200393903122333,"angularAcceleration":-157.54316489693508,"curveRadius":0.17008874884928238},{"acceleration":2.9289311482685556,"curvature":5.005583920975984,"pose":{"rotation":{"radians":-1.606877443132201},"translation":{"x":7.645680238514322,"y":1.4177644810654604}},"time":0.7577821973485649,"velocity":0.2623648147369397,"position":0.4778977580081154,"holonomicRotation":-96.79440000000001,"angularVelocity":1.4911623111003074,"angularAcceleration":-126.72532188733356,"curveRadius":0.1997768923240869},{"acceleration":2.9321195147121912,"curvature":4.275309126224458,"pose":{"rotation":{"radians":-1.6044230532972703},"translation":{"x":7.645663199480157,"y":1.417257961010785}},"time":0.7596738913904854,"velocity":0.26791148775311946,"position":0.47840456457326,"holonomicRotation":-96.84,"angularVelocity":1.2974560264719215,"angularAcceleration":-102.39831618422468,"curveRadius":0.23390121520478308},{"acceleration":2.9352085942540738,"curvature":3.6633675371551417,"pose":{"rotation":{"radians":-1.6021828636149316},"translation":{"x":7.645646217149526,"y":1.416717068148115}},"time":0.7616509845281841,"velocity":0.2737146685225337,"position":0.4789457239660834,"holonomicRotation":-96.88560000000001,"angularVelocity":1.1330724079828587,"angularAcceleration":-83.14409440538319,"curveRadius":0.27297288351705196},{"acceleration":2.938186104893591,"curvature":3.149174085742462,"pose":{"rotation":{"radians":-1.6001349096277915},"translation":{"x":7.645629293790572,"y":1.4161404041979715}},"time":0.763713054031197,"velocity":0.27977341248361104,"position":0.47952263618771973,"holonomicRotation":-96.9312,"angularVelocity":0.9931546847222165,"angularAcceleration":-67.8530588111638,"curveRadius":0.31754357579893394},{"acceleration":2.941043729407284,"curvature":2.7158628431114673,"pose":{"rotation":{"radians":-1.598259612245494},"translation":{"x":7.645612431671435,"y":1.415526570880876}},"time":0.7658594873360246,"velocity":0.2860861666953651,"position":0.4801367010639651,"holonomicRotation":-96.97680000000001,"angularVelocity":0.8736807139918036,"angularAcceleration":-55.661627343231814,"curveRadius":0.36820710682662294},{"acceleration":2.943776358255704,"curvature":2.3496182146323386,"pose":{"rotation":{"radians":-1.5965395446396418},"translation":{"x":7.645595633060258,"y":1.4148741699173488}},"time":0.7680895071994365,"velocity":0.29265084644771755,"position":0.4807893182645878,"holonomicRotation":-97.0224,"angularVelocity":0.7713238944968576,"angularAcceleration":-45.899510212587465,"curveRadius":0.4256010588326483},{"acceleration":2.946381461240773,"curvature":2.0391167227523486,"pose":{"rotation":{"radians":-1.594959207409799},"translation":{"x":7.64557890022518,"y":1.4141818030279114}},"time":0.7704021957154152,"velocity":0.2994649090168218,"position":0.48148188732060965,"holonomicRotation":-97.06800000000001,"angularVelocity":0.6833333667391996,"angularAcceleration":-38.0468563534242,"curveRadius":0.4904084149975609},{"acceleration":2.948858565186404,"curvature":1.7750664381187364,"pose":{"rotation":{"radians":-1.593504818111791},"translation":{"x":7.645562235434344,"y":1.4134480719330846}},"time":0.7727965169123356,"velocity":0.3065254235861679,"position":0.482215807639697,"holonomicRotation":-97.1136,"angularVelocity":0.6074328289281095,"angularAcceleration":-31.70023216129656,"curveRadius":0.5633591951971257},{"acceleration":2.95120881938194,"curvature":1.5498299050178026,"pose":{"rotation":{"radians":-1.592164118141584},"translation":{"x":7.645545640955891,"y":1.4126715783533896}},"time":0.775271337728899,"velocity":0.3138291366063997,"position":0.48299247851981464,"holonomicRotation":-97.15920000000001,"angularVelocity":0.5417361779220761,"angularAcceleration":-26.546023278268073,"curveRadius":0.6452320972529648},{"acceleration":2.953434633778103,"curvature":1.3571170193391433,"pose":{"rotation":{"radians":-1.590926197995171},"translation":{"x":7.645529119057963,"y":1.4118509240093473}},"time":0.7778254472420253,"velocity":0.32137253210092903,"position":0.4838132991613111,"holonomicRotation":-97.2048,"angularVelocity":0.4846777869355151,"angularAcceleration":-22.339837306631438,"curveRadius":0.7368561338114795},{"acceleration":2.955539378602419,"curvature":1.1917356337182616,"pose":{"rotation":{"radians":-1.5897813406937198},"translation":{"x":7.6455126720087,"y":1.410984710621479}},"time":0.7804575740851779,"velocity":0.32915188663534306,"position":0.4846796686775983,"holonomicRotation":-97.25040000000001,"angularVelocity":0.4349552167022277,"angularAcceleration":-18.890643649123106,"curveRadius":0.839112276000308},{"acceleration":2.9575271354426125,"curvature":1.04938940446402,"pose":{"rotation":{"radians":-1.5887208824705565},"translation":{"x":7.645496302076245,"y":1.4100715399103054}},"time":0.783166402050524,"velocity":0.33716331884809997,"position":0.48559298610458296,"holonomicRotation":-97.296,"angularVelocity":0.39148230774698084,"angularAcceleration":-16.048604603685988,"curveRadius":0.9529351027807968},{"acceleration":2.9594024920862867,"curvature":0.9265140608110379,"pose":{"rotation":{"radians":-1.5877370894502736},"translation":{"x":7.645480011528739,"y":1.4091100135963472}},"time":0.7859505839126543,"velocity":0.3454028335893097,"position":0.4865546504089907,"holonomicRotation":-97.34160000000001,"angularVelocity":0.35335084739408007,"angularAcceleration":-13.69575057992992,"curveRadius":1.079314434931117},{"acceleration":2.9611703744808557,"curvature":0.8201447307899613,"pose":{"rotation":{"radians":-1.5868230488347939},"translation":{"x":7.645463802634323,"y":1.4080987334001263}},"time":0.7888087535458042,"velocity":0.35386636083223394,"position":0.48756606049571466,"holonomicRotation":-97.3872,"angularVelocity":0.3197992886350821,"angularAcceleration":-11.738826964592013,"curveRadius":1.219296988028933},{"acceleration":2.9628359100526387,"curvature":0.727808385867498,"pose":{"rotation":{"radians":-1.585972573156888},"translation":{"x":7.645447677661137,"y":1.4070363010421632}},"time":0.7917395364314764,"velocity":0.36254978961047146,"position":0.4886286152143091,"holonomicRotation":-97.43280000000001,"angularVelocity":0.2901871994897576,"angularAcceleration":-10.103815362812849,"curveRadius":1.3739880158265396},{"acceleration":2.964404317819152,"curvature":0.6474365231786842,"pose":{"rotation":{"radians":-1.5851801161255512},"translation":{"x":7.645431638877325,"y":1.4059213182429786}},"time":0.7947415586701461,"velocity":0.37144899729697284,"position":0.48974371336472616,"holonomicRotation":-97.47840000000001,"angularVelocity":0.2639744040297598,"angularAcceleration":-8.731712617696715,"curveRadius":1.5445529626446681},{"acceleration":2.9658808209963223,"curvature":0.5772941763630063,"pose":{"rotation":{"radians":-1.584440698766505},"translation":{"x":7.645415688551028,"y":1.4047523867230942}},"time":0.7978134546206923,"velocity":0.3805598745807942,"position":0.4909127537023913,"holonomicRotation":-97.52400000000002,"angularVelocity":0.24070390760298183,"angularAcceleration":-7.575287965935181,"curveRadius":1.7322191023995253},{"acceleration":2.9672705785328253,"curvature":0.515922083072044,"pose":{"rotation":{"radians":-1.5837498445819946},"translation":{"x":7.645399828950385,"y":1.4035281082030309}},"time":0.8009538732954957,"velocity":0.3898783465188134,"position":0.49213713494270045,"holonomicRotation":-97.56960000000001,"angularVelocity":0.2199879239202273,"angularAcceleration":-6.596567473300772,"curveRadius":1.9382771794638585},{"acceleration":2.9685786326209165,"curvature":0.46208946547476587,"pose":{"rotation":{"radians":-1.5831035226492496},"translation":{"x":7.645384062343539,"y":1.4022470844033093}},"time":0.8041614836389835,"velocity":0.3994003900462652,"position":0.4934182557650059,"holonomicRotation":-97.61520000000002,"angularVelocity":0.2014963987309848,"angularAcceleration":-5.764891370544594,"curveRadius":2.164083093676605},{"acceleration":2.9698098693022463,"curvature":0.41475541780476727,"pose":{"rotation":{"radians":-1.5824980976728655},"translation":{"x":7.645368390998632,"y":1.4009079170444507}},"time":0.8074349788139203,"velocity":0.4091220483239058,"position":0.4947575148161545,"holonomicRotation":-97.66080000000001,"angularVelocity":0.18494756950290556,"angularAcceleration":-5.055400525647247,"curveRadius":2.41105952344839},{"acceleration":2.970968990076891,"curvature":0.37303723728386634,"pose":{"rotation":{"radians":-1.5819302861014695},"translation":{"x":7.645352817183804,"y":1.3995092078469762}},"time":0.8107730796138095,"velocity":0.4190394422861274,"position":0.4961563107136349,"holonomicRotation":-97.7064,"angularVelocity":0.17010018733254662,"angularAcceleration":-4.44785315376094,"curveRadius":2.680697528432102},{"acceleration":2.9720604923715186,"curvature":0.33618436462710405,"pose":{"rotation":{"radians":-1.5813971175440695},"translation":{"x":7.645337343167198,"y":1.3980495585314066}},"time":0.814174537112186,"velocity":0.42914877973353305,"position":0.49761604204837867,"holonomicRotation":-97.75200000000001,"angularVelocity":0.15674708787465688,"angularAcceleration":-3.9256993404336504,"curveRadius":2.9745583234044832},{"acceleration":2.973088657198771,"curvature":0.303556950000233,"pose":{"rotation":{"radians":-1.580895900828578},"translation":{"x":7.645321971216954,"y":1.3965275708182632}},"time":0.8176381346510269,"velocity":0.43944636228936235,"position":0.49913810738725667,"holonomicRotation":-97.79760000000002,"angularVelocity":0.14470986015868864,"angularAcceleration":-3.4753540447417897,"curveRadius":3.294274764584479},{"acceleration":2.9740575427350184,"curvature":0.27460809699575295,"pose":{"rotation":{"radians":-1.580424194085733},"translation":{"x":7.645306703601214,"y":1.3949418464280667}},"time":0.8211626892614469,"velocity":0.44992859051326345,"position":0.50072390527531,"holonomicRotation":-97.84320000000001,"angularVelocity":0.13383442590171435,"angularAcceleration":-3.085619449567364,"curveRadius":3.641553220535467},{"acceleration":2.9749709823571027,"curvature":0.248869205859774,"pose":{"rotation":{"radians":-1.5799797783815386},"translation":{"x":7.64529154258812,"y":1.3932909870813386}},"time":0.8247470526006869,"velocity":0.46059196743772723,"position":0.5023748342377422,"holonomicRotation":-97.8888,"angularVelocity":0.12398734785875105,"angularAcceleration":-2.7472321053956064,"curveRadius":4.018174914591292},{"acceleration":2.9758325863852426,"curvature":0.22593774755813442,"pose":{"rotation":{"radians":-1.579560634418252},"translation":{"x":7.645276490445812,"y":1.3915735944985992}},"time":0.8283901114804577,"velocity":0.47143310076626926,"position":0.5040922927817066,"holonomicRotation":-97.93440000000001,"angularVelocity":0.11505275569769098,"angularAcceleration":-2.4524973259894756,"curveRadius":4.425997916716848},{"acceleration":2.9766457463501297,"curvature":0.20546712914437124,"pose":{"rotation":{"radians":-1.5791649219440416},"translation":{"x":7.6452615494424325,"y":1.3897882704003703}},"time":0.8320907880531153,"velocity":0.4824487039448881,"position":0.5058776793979045,"holonomicRotation":-97.98,"angularVelocity":0.10692976444744115,"angularAcceleration":-2.195001668145344,"curveRadius":4.866958545458389},{"acceleration":2.977413641620025,"curvature":0.18715820948304432,"pose":{"rotation":{"radians":-1.5787909615167175},"translation":{"x":7.645246721846122,"y":1.3879336165071725}},"time":0.8358480397141396,"velocity":0.4936355962954212,"position":0.5077323925620262,"holonomicRotation":-98.02560000000001,"angularVelocity":0.09953031126536979,"angularAcceleration":-1.9693791764947193,"curveRadius":5.343073129210479},{"acceleration":2.9781392471358803,"curvature":0.17075221035708774,"pose":{"rotation":{"radians":-1.578437218335095},"translation":{"x":7.645232009925023,"y":1.3860082345395268}},"time":0.8396608587719274,"velocity":0.5049907023736468,"position":0.5096578307360421,"holonomicRotation":-98.0712,"angularVelocity":0.09277733253561457,"angularAcceleration":-1.7711248888042461,"curveRadius":5.856439561799741},{"acceleration":2.978825342457523,"curvature":0.1560247601718547,"pose":{"rotation":{"radians":-1.5781022878902222},"translation":{"x":7.645217415947275,"y":1.3840107262179542}},"time":0.8435282719291757,"velocity":0.5165110506962116,"position":0.5116553923693687,"holonomicRotation":-98.11680000000001,"angularVelocity":0.08660322320232025,"angularAcceleration":-1.5964442076024081,"curveRadius":6.409239141906336},{"acceleration":2.979474521265981,"curvature":0.14278089618538423,"pose":{"rotation":{"radians":-1.5777848831990209},"translation":{"x":7.6452029421810215,"y":1.381939693262976}},"time":0.8474493396139905,"velocity":0.5281937719592767,"position":0.5137264758999187,"holonomicRotation":-98.1624,"angularVelocity":0.08094853665254438,"angularAcceleration":-1.4421292883249295,"curveRadius":7.0037380820303685},{"acceleration":2.980089201342407,"curvature":0.1308508419666578,"pose":{"rotation":{"radians":-1.5774838234440969},"translation":{"x":7.645188590894403,"y":1.379793737395113}},"time":0.8514231551934073,"velocity":0.5400360968556229,"position":0.515872479755051,"holonomicRotation":-98.20800000000001,"angularVelocity":0.07576087740040255,"angularAcceleration":-1.3054604946974409,"curveRadius":7.642289380566697},{"acceleration":2.9806716345142186,"curvature":0.12008645727408525,"pose":{"rotation":{"radians":-1.5771980238440504},"translation":{"x":7.645174364355561,"y":1.3775714603348863}},"time":0.8554488440971426,"velocity":0.5520353535803655,"position":0.5180948023524291,"holonomicRotation":-98.2536,"angularVelocity":0.07099396075571107,"angularAcceleration":-1.1841244464440295,"curveRadius":8.327333678581263},{"acceleration":2.981223916700321,"curvature":0.11035819590148707,"pose":{"rotation":{"radians":-1.5769264866071433},"translation":{"x":7.645160264832636,"y":1.375271463802817}},"time":0.859525562875131,"velocity":0.5641889651029659,"position":0.5203948421007982,"holonomicRotation":-98.29920000000001,"angularVelocity":0.06660681094148899,"angularAcceleration":-1.07614727753844,"curveRadius":9.061402207885541},{"acceleration":2.9817479976696655,"curvature":0.10155256217246375,"pose":{"rotation":{"radians":-1.576668292844202},"translation":{"x":7.645146294593772,"y":1.372892349519426}},"time":0.863652498208655,"velocity":0.5764944462702131,"position":0.5227739974006911,"holonomicRotation":-98.3448,"angularVelocity":0.06256307455170883,"angularAcceleration":-0.9798400175869177,"curveRadius":9.847117380472678},{"acceleration":2.9822456905708865,"curvature":0.09356992333230645,"pose":{"rotation":{"radians":-1.5764225953297064},"translation":{"x":7.645132455907107,"y":1.3704327192052341}},"time":0.8678288658916143,"velocity":0.5889494007949582,"position":0.5252336666450694,"holonomicRotation":-98.39040000000001,"angularVelocity":0.05883043188415955,"angularAcceleration":-0.8937533643839362,"curveRadius":10.687194820589692},{"acceleration":2.9827186809680746,"curvature":0.08632264657971163,"pose":{"rotation":{"radians":-1.5761886120058373},"translation":{"x":7.645118751040784,"y":1.367891174580763}},"time":0.8720539097956569,"velocity":0.6015515181754562,"position":0.5277752482199042,"holonomicRotation":-98.436,"angularVelocity":0.05538009288974968,"angularAcceleration":-0.8166397965968021,"curveRadius":11.58444556118405},{"acceleration":2.9831685356723954,"curvature":0.07973352100935058,"pose":{"rotation":{"radians":-1.575965620158942},"translation":{"x":7.645105182262945,"y":1.3652663173665331}},"time":0.8763269008304727,"velocity":0.6142985705837289,"position":0.5304001405047086,"holonomicRotation":-98.48160000000001,"angularVelocity":0.05218635964323711,"angularAcceleration":-0.7474233436228661,"curveRadius":12.541776499280989},{"acceleration":2.983596710954599,"curvature":0.07373439024856385,"pose":{"rotation":{"radians":-1.575752951176943},"translation":{"x":7.645091751841731,"y":1.3625567492830657}},"time":0.880647135908445,"velocity":0.6271884097529178,"position":0.5331097418730208,"holonomicRotation":-98.52720000000001,"angularVelocity":0.04922625231283134,"angularAcceleration":-0.685172745691212,"curveRadius":13.562192575661495},{"acceleration":2.984004560361139,"curvature":0.06826498071140348,"pose":{"rotation":{"radians":-1.5755499858334572},"translation":{"x":7.645078462045283,"y":1.3597610720508817}},"time":0.8850139369210894,"velocity":0.6402189638888384,"position":0.5359054506928448,"holonomicRotation":-98.57280000000002,"angularVelocity":0.04647918302165546,"angularAcceleration":-0.6290804832236514,"curveRadius":14.648799275687084},{"acceleration":2.984393342119298,"curvature":0.06327190422772135,"pose":{"rotation":{"radians":-1.575356150036436},"translation":{"x":7.645065315141742,"y":1.3568778873905023}},"time":0.8894266497331896,"velocity":0.6533882346259547,"position":0.5387886653270543,"holonomicRotation":-98.61840000000001,"angularVelocity":0.043926673970201745,"angularAcceleration":-0.578444408268406,"curveRadius":15.804803288374394},{"acceleration":2.984764225999407,"curvature":0.058707791181675364,"pose":{"rotation":{"radians":-1.575170910990959},"translation":{"x":7.64505231339925,"y":1.3539057970224482}},"time":0.8938846431992556,"velocity":0.6666942940432077,"position":0.5417607841337624,"holonomicRotation":-98.66400000000002,"angularVelocity":0.04155211237676257,"angularAcceleration":-0.5326525513135454,"curveRadius":17.033514289533226},{"acceleration":2.985118299786243,"curvature":0.054530541545606555,"pose":{"rotation":{"radians":-1.5749937737332154},"translation":{"x":7.6450394590859485,"y":1.3508434026672405}},"time":0.8983873082058508,"velocity":0.680135281752202,"position":0.5448232054666587,"holonomicRotation":-98.70960000000001,"angularVelocity":0.039340536656458605,"angularAcceleration":-0.49117038843987504,"curveRadius":18.338347129079054},{"acceleration":2.9854565752947457,"curvature":0.050702683111438815,"pose":{"rotation":{"radians":-1.5748242779910537},"translation":{"x":7.6450267544699795,"y":1.3476893060454007}},"time":0.9029340567424324,"velocity":0.6937094020669514,"position":0.5479773276753196,"holonomicRotation":-98.75520000000002,"angularVelocity":0.03727845091891974,"angularAcceleration":-0.45352975229397413,"curveRadius":19.722822119731063},{"acceleration":2.985779993993479,"curvature":0.047190803146920715,"pose":{"rotation":{"radians":-1.5746619953456857},"translation":{"x":7.645014201819483,"y":1.3444421088774494}},"time":0.9075243210025944,"velocity":0.7074149212620863,"position":0.5512245491054942,"holonomicRotation":-98.80080000000001,"angularVelocity":0.03535366074158638,"angularAcceleration":-0.41932012368835747,"curveRadius":21.19056963041435},{"acceleration":2.986089432154908,"curvature":0.04396507458718547,"pose":{"rotation":{"radians":-1.5745065266502776},"translation":{"x":7.6450018034026,"y":1.3411004128839075}},"time":0.9121575525169654,"velocity":0.7212501649238766,"position":0.5545662680993648,"holonomicRotation":-98.84640000000002,"angularVelocity":0.033555132077027976,"angularAcceleration":-0.38818018460330816,"curveRadius":22.745327044013948},{"acceleration":2.9863857057754695,"curvature":0.04099881978434532,"pose":{"rotation":{"radians":-1.5743574996924377},"translation":{"x":7.644989561487474,"y":1.3376628197852964}},"time":0.9168332213185141,"velocity":0.7352135153977619,"position":0.5580038829957871,"holonomicRotation":-98.89200000000001,"angularVelocity":0.031872864431833604,"angularAcceleration":-0.35979187504409377,"curveRadius":24.390946014056546},{"acceleration":2.9866695749671037,"curvature":0.038268152074974866,"pose":{"rotation":{"radians":-1.5742145670662655},"translation":{"x":7.644977478342245,"y":1.3341279313021368}},"time":0.9215508151405845,"velocity":0.7493034093331923,"position":0.5615387921305136,"holonomicRotation":-98.9376,"angularVelocity":0.03029778136122503,"angularAcceleration":-0.33387424395034726,"curveRadius":26.131389831440057},{"acceleration":2.986941748158312,"curvature":0.03575164954966028,"pose":{"rotation":{"radians":-1.5740774042344707},"translation":{"x":7.6449655562350545,"y":1.33049434915495}},"time":0.9263098386476327,"velocity":0.7635183353268615,"position":0.5651723938363965,"holonomicRotation":-98.98320000000001,"angularVelocity":0.028821633595973135,"angularAcceleration":-0.3101787085240642,"curveRadius":27.970737367263723},{"acceleration":2.987202885911613,"curvature":0.03343007994230435,"pose":{"rotation":{"radians":-1.573945707765926},"translation":{"x":7.644953797434044,"y":1.326760675064257}},"time":0.9311098126983782,"velocity":0.7778568316635494,"position":0.5689060864435767,"holonomicRotation":-99.02880000000002,"angularVelocity":0.027436912606696943,"angularAcceleration":-0.2884850990103008,"curveRadius":29.913180038033424},{"acceleration":2.987453604457532,"curvature":0.031286142621033707,"pose":{"rotation":{"radians":-1.57381919372542},"translation":{"x":7.644942204207355,"y":1.3229255107505786}},"time":0.9359502736408508,"velocity":0.792317484153375,"position":0.5727412682796592,"holonomicRotation":-99.07440000000001,"angularVelocity":0.026136775404158905,"angularAcceleration":-0.2685978087603173,"curveRadius":31.963032711092318},{"acceleration":2.9876944789868105,"curvature":0.029304258917430184,"pose":{"rotation":{"radians":-1.5736975962045427},"translation":{"x":7.644930778823129,"y":1.3189874579344358}},"time":0.9408307726386435,"velocity":0.8068989240637807,"position":0.5766793376698724,"holonomicRotation":-99.12,"angularVelocity":0.024914977122678532,"angularAcceleration":-0.2503429018288849,"curveRadius":34.124732613702086},{"acceleration":2.9879260466575026,"curvature":0.027470398357114525,"pose":{"rotation":{"radians":-1.5735806659783735},"translation":{"x":7.6449195235495075,"y":1.3149451183363499}},"time":0.9457508750275624,"velocity":0.8215998261438534,"position":0.5807216929372182,"holonomicRotation":-99.16560000000001,"angularVelocity":0.023765811547450735,"angularAcceleration":-0.23356537819537046,"curveRadius":36.40282121140086},{"acceleration":2.9881488094035364,"curvature":0.02577187526942369,"pose":{"rotation":{"radians":-1.5734681692774242},"translation":{"x":7.644908440654631,"y":1.3107970936768418}},"time":0.9507101597017529,"velocity":0.8364189067385289,"position":0.5848697324026098,"holonomicRotation":-99.21120000000002,"angularVelocity":0.022684057951913108,"angularAcceleration":-0.21812694100166846,"curveRadius":38.80198819627307},{"acceleration":2.9883632364900636,"curvature":0.02419724163196055,"pose":{"rotation":{"radians":-1.5733598866602696},"translation":{"x":7.644897532406643,"y":1.3065419856764324}},"time":0.9557082185283184,"velocity":0.8513549219896521,"position":0.5891248543850002,"holonomicRotation":-99.25680000000001,"angularVelocity":0.02166493450997886,"angularAcceleration":-0.2039038509345719,"curveRadius":41.32702459271909},{"acceleration":2.988569766920364,"curvature":0.02273612212782537,"pose":{"rotation":{"radians":-1.5732556119843215},"translation":{"x":7.644886801073681,"y":1.3021783960556428}},"time":0.9607446557893984,"velocity":0.8664066661211068,"position":0.5934884572015006,"holonomicRotation":-99.3024,"angularVelocity":0.02070405537539277,"angularAcceleration":-0.1907854867986687,"curveRadius":43.98287422885367},{"acceleration":2.988768811602093,"curvature":0.021379137654402865,"pose":{"rotation":{"radians":-1.573155151454543},"translation":{"x":7.64487624892389,"y":1.2977049265349945}},"time":0.9658190876506443,"velocity":0.8815729698045985,"position":0.5979619391674902,"holonomicRotation":-99.34800000000001,"angularVelocity":0.01979739457056336,"angularAcceleration":-0.17867237744459613,"curveRadius":46.77457136789883},{"acceleration":2.9889607553743756,"curvature":0.020117760938519906,"pose":{"rotation":{"radians":-1.5730583227587713},"translation":{"x":7.64486587822541,"y":1.2931201788350077}},"time":0.9709311416550221,"velocity":0.8968526986030384,"position":0.6025466985967209,"holonomicRotation":-99.3936,"angularVelocity":0.018941250559703308,"angularAcceleration":-0.16747554116737948,"curveRadius":49.70732096161252},{"acceleration":2.9891459588925526,"curvature":0.018944266607008178,"pose":{"rotation":{"radians":-1.5729649542625133},"translation":{"x":7.6448556912463825,"y":1.2884227546762035}},"time":0.9760804562408565,"velocity":0.9122447514883516,"position":0.6072441338014107,"holonomicRotation":-99.43920000000001,"angularVelocity":0.0181322183179345,"angularAcceleration":-0.15711454957411974,"curveRadius":52.78641927632413},{"acceleration":2.9893247603494757,"curvature":0.017851615968977396,"pose":{"rotation":{"radians":-1.5728748842765334},"translation":{"x":7.644845690254949,"y":1.283611255779104}},"time":0.9812666802830551,"velocity":0.9277480594304156,"position":0.6120556430923318,"holonomicRotation":-99.4848,"angularVelocity":0.01736716062533241,"angularAcceleration":-0.14751728548112608,"curveRadius":56.01733768740061},{"acceleration":2.9894974770406653,"curvature":0.016833414857659875,"pose":{"rotation":{"radians":-1.5727879603771022},"translation":{"x":7.644835877519251,"y":1.2786842838642292}},"time":0.9864894726564658,"velocity":0.9433615840538342,"position":0.6169826247788969,"holonomicRotation":-99.53040000000001,"angularVelocity":0.0166431849509743,"angularAcceleration":-0.13861850569512874,"curveRadius":59.405652890741905},{"acceleration":2.9896644068720786,"curvature":0.01588383640370599,"pose":{"rotation":{"radians":-1.572704038780282},"translation":{"x":7.6448262553074295,"y":1.2736404406521}},"time":0.9917485018203256,"velocity":0.959084316359728,"position":0.6220264771692332,"holonomicRotation":-99.57600000000001,"angularVelocity":0.01595762149351796,"angularAcceleration":-0.1303593184399041,"curveRadius":62.95708257022099},{"acceleration":2.989825829701803,"curvature":0.014997566696651058,"pose":{"rotation":{"radians":-1.5726229837668058},"translation":{"x":7.644816825887626,"y":1.268478327863238}},"time":0.99704344542281,"velocity":0.9749152755092502,"position":0.6271885985702552,"holonomicRotation":-99.62160000000002,"angularVelocity":0.015308003174610889,"angularAcceleration":-0.1226865416663306,"curveRadius":66.67748310286221},{"acceleration":2.989982008570448,"curvature":0.01416975208576853,"pose":{"rotation":{"radians":-1.5725446671472953},"translation":{"x":7.644807591527983,"y":1.263196547218164}},"time":1.0023739899247115,"velocity":0.9908535076658198,"position":0.6324703872877331,"holonomicRotation":-99.66720000000001,"angularVelocity":0.014692048717063148,"angularAcceleration":-0.11555188355111148,"curveRadius":70.5728649271398},{"acceleration":2.9901331909100173,"curvature":0.013395963753770238,"pose":{"rotation":{"radians":-1.572468967771365},"translation":{"x":7.64479855449664,"y":1.2577937004373991}},"time":1.0077398302413034,"velocity":1.0068980848935845,"position":0.6378732416263543,"holonomicRotation":-99.71280000000002,"angularVelocity":0.014107646046837058,"angularAcceleration":-0.10891167752775543,"curveRadius":74.64935098219821},{"acceleration":2.9902796095435105,"curvature":0.012672146704233217,"pose":{"rotation":{"radians":-1.5723957710708447},"translation":{"x":7.644789717061739,"y":1.2522683892414643}},"time":1.0131406694014935,"velocity":1.023048104108725,"position":0.6433985598897829,"holonomicRotation":-99.75840000000001,"angularVelocity":0.013552838429228465,"angularAcceleration":-0.10272618775580572,"curveRadius":78.91322783265626},{"acceleration":2.99042148377848,"curvature":0.011994585338619593,"pose":{"rotation":{"radians":-1.5723249686385312},"translation":{"x":7.644781081491422,"y":1.2466192153508808}},"time":1.0185762182233955,"velocity":1.0393026860818675,"position":0.6490477403807148,"holonomicRotation":-99.80400000000002,"angularVelocity":0.013025811124758533,"angularAcceleration":-0.09695935437951127,"curveRadius":83.3709521228923},{"acceleration":2.9905590202043397,"curvature":0.011359884266997028,"pose":{"rotation":{"radians":-1.572256457837554},"translation":{"x":7.64477265005383,"y":1.240844780486169}},"time":1.0240461950054927,"velocity":1.0556609744878764,"position":0.6548221814009295,"holonomicRotation":-99.84960000000001,"angularVelocity":0.012524879667036542,"angularAcceleration":-0.09157835173295527,"curveRadius":88.02906583346284},{"acceleration":2.9906924136285964,"curvature":0.010764923640023339,"pose":{"rotation":{"radians":-1.5721901414391404},"translation":{"x":7.6447644250171045,"y":1.2349436863678507}},"time":1.0295503252325944,"velocity":1.0721221350016934,"position":0.6607232812513372,"holonomicRotation":-99.89520000000002,"angularVelocity":0.012048479174249197,"angularAcceleration":-0.08655327420154436,"curveRadius":92.89429571818421},{"acceleration":2.9908218478172146,"curvature":0.010206838935609024,"pose":{"rotation":{"radians":-1.5721259272854473},"translation":{"x":7.644756408649387,"y":1.2289145347164465}},"time":1.0350883412958352,"velocity":1.0886853544371966,"position":0.6667524382320253,"holonomicRotation":-99.94080000000001,"angularVelocity":0.011595154827970616,"angularAcceleration":-0.08185681318036878,"curveRadius":97.97352601609676},{"acceleration":2.990947496256273,"curvature":0.00968300251583921,"pose":{"rotation":{"radians":-1.5720637279785104},"translation":{"x":7.644748603218819,"y":1.2227559272524773}},"time":1.0406599822259872,"velocity":1.1053498399272739,"position":0.6729110506423012,"holonomicRotation":-99.98640000000002,"angularVelocity":0.011163552661901954,"angularAcceleration":-0.07746410285217055,"curveRadius":103.27375195495668},{"acceleration":2.9910695227966526,"curvature":0.009190992071659824,"pose":{"rotation":{"radians":-1.5720034605888555},"translation":{"x":7.644741010993541,"y":1.2164664656964643}},"time":1.0462649934394028,"velocity":1.1221148181426548,"position":0.6792005167807306,"holonomicRotation":-100.03200000000001,"angularVelocity":0.01075241196851863,"angularAcceleration":-0.07335234091936467,"curveRadius":108.80218285504488},{"acceleration":2.9911880822578993,"curvature":0.00872858179678227,"pose":{"rotation":{"radians":-1.5719450463866398},"translation":{"x":7.644733634241695,"y":1.2100447517689288}},"time":1.0519031264959346,"velocity":1.138979534547537,"position":0.6856222349451763,"holonomicRotation":-100.07760000000002,"angularVelocity":0.010360557587068194,"angularAcceleration":-0.06950073322524189,"curveRadius":114.56614869194937},{"acceleration":2.9913033211090685,"curvature":0.008293725807878127,"pose":{"rotation":{"radians":-1.5718884105898967},"translation":{"x":7.644726475231423,"y":1.2034893871903916}},"time":1.0575741388682096,"velocity":1.1559432526907738,"position":0.6921776034328334,"holonomicRotation":-100.12320000000001,"angularVelocity":0.009986893525391423,"angularAcceleration":-0.06589018629258832,"curveRadius":120.57307212279792},{"acceleration":1.4677038524578674,"curvature":0.007884528631892457,"pose":{"rotation":{"radians":-1.5718334821306366},"translation":{"x":7.644719536230865,"y":1.1967989736813733}},"time":1.0633200610292923,"velocity":1.164376564782518,"position":0.6988680205402626,"holonomicRotation":-100.16880000000002,"angularVelocity":0.009559555058398018,"angularAcceleration":-0.07437247756117893,"curveRadius":126.83066378312822},{"acceleration":-1.5123901295761657,"curvature":0.007499245978504141,"pose":{"rotation":{"radians":-1.5717801934373874},"translation":{"x":7.644712819508164,"y":1.1899721129623955}},"time":1.0692285114809148,"velocity":1.1554406826383943,"position":0.7056948845634204,"holonomicRotation":-100.21440000000001,"angularVelocity":0.009019064082111714,"angularAcceleration":-0.09147761849096743,"curveRadius":133.3467395077322},{"acceleration":-2.947346061763929,"curvature":0.0071362717421586275,"pose":{"rotation":{"radians":-1.57172848023097},"translation":{"x":7.64470632733146,"y":1.1830074067539793}},"time":1.0753519092719104,"velocity":1.1373929102744895,"position":0.7126595937976893,"holonomicRotation":-100.26000000000002,"angularVelocity":0.00844518161037112,"angularAcceleration":-0.09371961308548091,"curveRadius":140.12919296393179},{"acceleration":-2.946406844743225,"curvature":0.006794114933091941,"pose":{"rotation":{"radians":-1.5716782813357169},"translation":{"x":7.644700061968895,"y":1.175903456776645}},"time":1.0817021949607921,"velocity":1.1186823850546934,"position":0.7197635465379062,"holonomicRotation":-100.30560000000001,"angularVelocity":0.007904982187010785,"angularAcceleration":-0.08506694813843273,"curveRadius":147.18620598090308},{"acceleration":-2.9453578121056703,"curvature":0.006471397337512276,"pose":{"rotation":{"radians":-1.5716295385018064},"translation":{"x":7.644694025688611,"y":1.1686588647509142}},"time":1.0882925551149112,"velocity":1.099271416290169,"position":0.727008141078387,"holonomicRotation":-100.3512,"angularVelocity":0.007396080452441777,"angularAcceleration":-0.07721910831397238,"curveRadius":154.52613212348638},{"acceleration":-2.944185029631766,"curvature":0.0061668542044161015,"pose":{"rotation":{"radians":-1.5715821962398753},"translation":{"x":7.644688220758748,"y":1.1612722323973084}},"time":1.095137619998094,"velocity":1.079118278734244,"position":0.7343947757129514,"holonomicRotation":-100.39680000000001,"angularVelocity":0.006916261969621538,"angularAcceleration":-0.07009699557400437,"curveRadius":162.15723071317257},{"acceleration":-2.942871900603161,"curvature":0.00587929744632905,"pose":{"rotation":{"radians":-1.571536201666273},"translation":{"x":7.644682649447447,"y":1.1537421614363474}},"time":1.1022537037755393,"velocity":1.058176555743262,"position":0.741924848734949,"holonomicRotation":-100.44240000000002,"angularVelocity":0.006463467131738432,"angularAcceleration":-0.06362977896891195,"curveRadius":170.08834969293582},{"acceleration":-2.941398508130143,"curvature":0.00560763962252815,"pose":{"rotation":{"radians":-1.5714915043581694},"translation":{"x":7.644677314022852,"y":1.1460672535885528}},"time":1.1096590990260125,"velocity":1.0363943372014064,"position":0.7495997584372776,"holonomicRotation":-100.48800000000001,"angularVelocity":0.0060357761593860205,"angularAcceleration":-0.05775396962438798,"curveRadius":178.32815004419982},{"acceleration":-2.9397407520107977,"curvature":0.005350863984424803,"pose":{"rotation":{"radians":-1.5714480562182844},"translation":{"x":7.644672216753103,"y":1.1382461105744461}},"time":1.1173744414306706,"velocity":1.013713230718716,"position":0.7574209031124046,"holonomicRotation":-100.5336,"angularVelocity":0.005631394902028246,"angularAcceleration":-0.052412613225516914,"curveRadius":186.8857072261193},{"acceleration":-2.9378692004238176,"curvature":0.005108032871285825,"pose":{"rotation":{"radians":-1.5714058113482707},"translation":{"x":7.64466735990634,"y":1.1302773341145476}},"time":1.125423166310221,"velocity":0.9900671297923999,"position":0.7653896810523898,"holonomicRotation":-100.57920000000001,"angularVelocity":0.005248641324668609,"angularAcceleration":-0.04755456088853366,"curveRadius":195.77007924545208},{"acceleration":-2.935747540695325,"curvature":0.0048782724660273395,"pose":{"rotation":{"radians":-1.5713647259280776},"translation":{"x":7.644662745750708,"y":1.1221595259293786}},"time":1.133832087082946,"velocity":0.9653806613139708,"position":0.7735074905488998,"holonomicRotation":-100.62480000000001,"angularVelocity":0.004885932606995534,"angularAcceleration":-0.04313380128988168,"curveRadius":204.99060004624098},{"acceleration":-2.9333304552553323,"curvature":0.004660776427068075,"pose":{"rotation":{"radians":-1.5713247581070924},"translation":{"x":7.644658376554345,"y":1.1138912877394604}},"time":1.1426321381199052,"velocity":0.939567203599457,"position":0.7817757298932281,"holonomicRotation":-100.67040000000001,"angularVelocity":0.004541771498528068,"angularAcceleration":-0.03910899005267437,"curveRadius":214.55652628870328},{"acceleration":-2.9305606575735252,"curvature":0.004454776395249074,"pose":{"rotation":{"radians":-1.5712858678971333},"translation":{"x":7.644654254585393,"y":1.1054712212653142}},"time":1.1518593431919601,"velocity":0.9125263194359298,"position":0.790195797376311,"holonomicRotation":-100.71600000000001,"angularVelocity":0.004214733459955773,"angularAcceleration":-0.03544280592210357,"curveRadius":224.47815811057976},{"acceleration":-2.927364672611401,"curvature":0.004259584640704084,"pose":{"rotation":{"radians":-1.5712480170753134},"translation":{"x":7.644650382111993,"y":1.0968979282274596}},"time":1.161556099650667,"velocity":0.8841403771397947,"position":0.7987690912887448,"holonomicRotation":-100.76160000000002,"angularVelocity":0.0039034518378528796,"angularAcceleration":-0.03210162320034209,"curveRadius":234.76467410557336},{"acceleration":-2.9236466936920733,"curvature":0.004074539717656737,"pose":{"rotation":{"radians":-1.571211169091324},"translation":{"x":7.644646761402289,"y":1.0881700103464191}},"time":1.1717729145054359,"velocity":0.8542700201695859,"position":0.8074970099207971,"holonomicRotation":-100.80720000000001,"angularVelocity":0.0036066019119645114,"angularAcceleration":-0.029055036242514595,"curveRadius":245.42649459681763},{"acceleration":-2.9192794068569885,"curvature":0.003899034177561706,"pose":{"rotation":{"radians":-1.571175288981526},"translation":{"x":7.644643394724419,"y":1.079286069342713}},"time":1.182570804059891,"velocity":0.8227479635557488,"position":0.816380951562425,"holonomicRotation":-100.85280000000002,"angularVelocity":0.0033228817184125306,"angularAcceleration":-0.026275522834452336,"curveRadius":256.473771313633},{"acceleration":-2.914089876641989,"curvature":0.0037325016760228636,"pose":{"rotation":{"radians":-1.5711403432858777},"translation":{"x":7.6446402843465275,"y":1.070244706936863}},"time":1.1940246971958453,"velocity":0.7893702895201253,"position":0.8254223145032857,"holonomicRotation":-100.89840000000001,"angularVelocity":0.0030509884485153084,"angularAcceleration":-0.023738065884667467,"curveRadius":267.91682544280644},{"acceleration":-2.9078370794221593,"curvature":0.0035744145226519752,"pose":{"rotation":{"radians":-1.5711062999731187},"translation":{"x":7.644637432536754,"y":1.0610445248493896}},"time":1.2062284102213496,"velocity":0.7538838802779365,"position":0.8346224970327514,"holonomicRotation":-100.94400000000002,"angularVelocity":0.002789586471582692,"angularAcceleration":-0.021419872491783107,"curveRadius":279.7660969825255},{"acceleration":-2.9001746702575835,"curvature":0.0034242717742514125,"pose":{"rotation":{"radians":-1.5710731283669688},"translation":{"x":7.6446348415632395,"y":1.051684124800814}},"time":1.2193021858917008,"velocity":0.7159676472341542,"position":0.8439828974399198,"holonomicRotation":-100.98960000000001,"angularVelocity":0.0025372629136610797,"angularAcceleration":-0.01929997609595167,"curveRadius":292.03289514559987},{"acceleration":-2.890586224822042,"curvature":0.0032816214082050043,"pose":{"rotation":{"radians":-1.571040799078446},"translation":{"x":7.644632513694127,"y":1.0421621085116568}},"time":1.2334046292752716,"velocity":0.6752033186532717,"position":0.8535049140136267,"holonomicRotation":-101.03520000000002,"angularVelocity":0.0022924600825107093,"angularAcceleration":-0.017358894802269733,"curveRadius":304.7274123394339},{"acceleration":-2.878265761519957,"curvature":0.0031460293289813515,"pose":{"rotation":{"radians":-1.571009283942832},"translation":{"x":7.644630451197557,"y":1.0324770777024392}},"time":1.2487526598699161,"velocity":0.6310276076859456,"position":0.8631899450424559,"holonomicRotation":-101.08080000000001,"angularVelocity":0.0020533667443335874,"angularAcceleration":-0.015578111908413203,"curveRadius":317.86099092845666},{"acceleration":-2.861880372760804,"curvature":0.0030170875325300985,"pose":{"rotation":{"radians":-1.5709785559581322},"translation":{"x":7.64462865634167,"y":1.0226276340936828}},"time":1.2656572620306001,"velocity":0.5826486585529541,"position":0.8730393888147499,"holonomicRotation":-101.12640000000002,"angularVelocity":0.0018177289478776173,"angularAcceleration":-0.01393926897635049,"curveRadius":331.4454715741742},{"acceleration":-2.839051071950871,"curvature":0.002894417240408088,"pose":{"rotation":{"radians":-1.5709485892281485},"translation":{"x":7.64462713139461,"y":1.0126123794059083}},"time":1.2845937341130917,"velocity":0.5288870471881886,"position":0.8830546436186204,"holonomicRotation":-101.17200000000001,"angularVelocity":0.0015824874798819476,"angularAcceleration":-0.012422666005098736,"curveRadius":345.492690562819},{"acceleration":-2.8050581950552345,"curvature":0.002777676526327184,"pose":{"rotation":{"radians":-1.5709193589099009},"translation":{"x":7.644625878624516,"y":1.0024299153596363}},"time":1.3063588233875445,"velocity":0.4678347051527761,"position":0.8932371077419579,"holonomicRotation":-101.21760000000002,"angularVelocity":0.0013429909649831477,"angularAcceleration":-0.011003700094164747,"curveRadius":360.013122666325},{"acceleration":-2.748922147929171,"curvature":0.0026665263827622457,"pose":{"rotation":{"radians":-1.5708908411614555},"translation":{"x":7.6446249002995295,"y":0.9920788436753883}},"time":1.3324994711179168,"velocity":0.3959760996455413,"position":0.9035881794724387,"holonomicRotation":-101.26320000000001,"angularVelocity":0.0010909350349506731,"angularAcceleration":-0.009642298562465077,"curveRadius":375.0197284619038},{"acceleration":-2.636802850076001,"curvature":0.002560662056697967,"pose":{"rotation":{"radians":-1.570863013094744},"translation":{"x":7.644624198687793,"y":0.9815577660736853}},"time":1.366991794560753,"velocity":0.3050266428857274,"position":0.9141092570975358,"holonomicRotation":-101.30880000000002,"angularVelocity":0.0008067901473074386,"angularAcceleration":-0.008237916709616405,"curveRadius":390.5240042840808},{"acceleration":-2.1128018652314693,"curvature":0.002560662056697967,"pose":{"rotation":{"radians":-1.5708358527303687},"translation":{"x":7.644623776057447,"y":0.970865284275048}},"time":1.451421180467911,"velocity":0.1266440788607367,"position":0.9248017389045254,"holonomicRotation":-101.35440000000001,"angularVelocity":0.0003216932597993836,"angularAcceleration":-0.0057455929863269185,"curveRadius":390.5240042840808}] \ No newline at end of file diff --git a/src/main/deploy/pathplanner/generatedJSON/Blue3(2).wpilib.json b/src/main/deploy/pathplanner/generatedJSON/Blue3(2).wpilib.json new file mode 100644 index 0000000..260639d --- /dev/null +++ b/src/main/deploy/pathplanner/generatedJSON/Blue3(2).wpilib.json @@ -0,0 +1 @@ +[{"acceleration":0.0,"curvature":-1.2366562116737734,"pose":{"rotation":{"radians":2.2963725864182423},"translation":{"x":7.64,"y":0.96}},"time":0.0,"velocity":0,"position":0.0,"holonomicRotation":-101.4,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-0.8086321732428231},{"acceleration":1.4999999999999998,"curvature":-1.2366562116737734,"pose":{"rotation":{"radians":2.2963725864182423},"translation":{"x":7.635124399710297,"y":0.9654968407029728}},"time":0.06998841173198542,"velocity":0.10498261759797811,"position":0.00734756666514887,"holonomicRotation":-101.72203660973199,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-0.8086321732428231},{"acceleration":5.120554912531448,"curvature":-1.2229852672818682,"pose":{"rotation":{"radians":2.28728501587032},"translation":{"x":7.630297757753251,"y":0.9710391336309265}},"time":0.0989846899639804,"velocity":0.2534596525439487,"position":0.01469695327089798,"holonomicRotation":-102.04407321946398,"angularVelocity":-0.31340472302045064,"angularAcceleration":-10.808446536239765,"curveRadius":-0.8176713381204815},{"acceleration":3.4543679184550697,"curvature":-1.2091564202008829,"pose":{"rotation":{"radians":2.2782954205314128},"translation":{"x":7.625519673245971,"y":0.9766262986687353}},"time":0.12123966915048631,"velocity":0.33033653867170004,"position":0.02204858606357907,"holonomicRotation":-102.36610982919596,"angularVelocity":-0.40393636244593517,"angularAcceleration":-4.067927391294865,"curveRadius":-0.8270228593202733},{"acceleration":3.2787694956322775,"curvature":-1.1951859998137149,"pose":{"rotation":{"radians":2.2694045130191607},"translation":{"x":7.620789745305569,"y":0.9822577557012735}},"time":0.1400068387369498,"velocity":0.39186976183115435,"position":0.029402872339671402,"holonomicRotation":-102.68814643892794,"angularVelocity":-0.4737479176756079,"angularAcceleration":-3.71987661261541,"curveRadius":-0.8366898542618998},{"acceleration":3.2020172270954714,"curvature":-1.1810898792732192,"pose":{"rotation":{"radians":2.26061292683797},"translation":{"x":7.616107573049155,"y":0.9879329246134153}},"time":0.15654648001175325,"velocity":0.4448299781230543,"position":0.03676020060610539,"holonomicRotation":-103.01018304865994,"angularVelocity":-0.5315463639821394,"angularAcceleration":-3.4945405009830433,"curveRadius":-0.8466756150813413},{"acceleration":3.158552036563686,"curvature":-1.1668834545567464,"pose":{"rotation":{"radians":2.2519212186575226},"translation":{"x":7.61147275559384,"y":0.9936512252900352}},"time":0.17150498680880727,"velocity":0.492077200230841,"position":0.04412094075043373,"holonomicRotation":-103.33221965839192,"angularVelocity":-0.5810545329403585,"angularAcceleration":-3.309699933951255,"curveRadius":-0.8569836139975616},{"acceleration":3.1304867558456606,"curvature":-1.152581626265162,"pose":{"rotation":{"radians":2.243329870666302},"translation":{"x":7.606884892056736,"y":0.9994120776160075}},"time":0.1852663743914641,"velocity":0.5351570418004071,"position":0.051485444220237216,"holonomicRotation":-103.6542562681239,"angularVelocity":-0.6243082639463066,"angularAcceleration":-3.1431227952957173,"curveRadius":-0.8676175094343738},{"acceleration":3.1108388853406366,"curvature":-1.138198785179899,"pose":{"rotation":{"radians":2.234839292989364},"translation":{"x":7.602343581554952,"y":1.0052149014762062}},"time":0.19808086599694863,"velocity":0.5750208605826196,"position":0.05885404421115169,"holonomicRotation":-103.9762928778559,"angularVelocity":-0.6625762408946467,"angularAcceleration":-2.986304734240231,"curveRadius":-0.8785811520980883},{"acceleration":3.09630296853465,"curvature":-1.1237487996139905,"pose":{"rotation":{"radians":2.226449826154608},"translation":{"x":7.597848423205599,"y":1.0110591167555059}},"time":0.21012227529525476,"velocity":0.6123047119383056,"position":0.06622705586288226,"holonomicRotation":-104.29832948758788,"angularVelocity":-0.6967180192052844,"angularAcceleration":-2.83536398978153,"curveRadius":-0.8898785923895994},{"acceleration":3.0851075905282483,"curvature":-1.109245006354742,"pose":{"rotation":{"radians":2.218161743602195},"translation":{"x":7.593399016125789,"y":1.0169441433387805}},"time":0.2215171572927846,"velocity":0.6474591488820586,"position":0.07360477646261442,"holonomicRotation":-104.62036609731986,"angularVelocity":-0.7273513279215561,"angularAcceleration":-2.6883392669544386,"curveRadius":-0.9015140877543829},{"acceleration":3.076216677566432,"curvature":-1.0947002036538875,"pose":{"rotation":{"radians":2.2099752542225435},"translation":{"x":7.5889949594326325,"y":1.0228694011109047}},"time":0.23236104902389176,"velocity":0.6808173094750152,"position":0.08098748565522516,"holonomicRotation":-104.94240270705185,"angularVelocity":-0.7549401619501296,"angularAcceleration":-2.5441819885965096,"curveRadius":-0.913492111047575},{"acceleration":3.068983329186816,"curvature":-1.0801266467446549,"pose":{"rotation":{"radians":2.2018905049149287},"translation":{"x":7.58463585224324,"y":1.0288343099567527}},"time":0.24272816847894055,"velocity":0.7126338262542482,"position":0.08837544565971144,"holonomicRotation":-105.26443931678384,"angularVelocity":-0.779845292867495,"angularAcceleration":-2.402319277341467,"curveRadius":-0.9258173594863668},{"acceleration":3.062982574599219,"curvature":-1.0655360455620526,"pose":{"rotation":{"radians":2.1939075831573556},"translation":{"x":7.580321293674723,"y":1.0348382897611987}},"time":0.25267753031783424,"velocity":0.743108548195162,"position":0.09576890149128008,"holonomicRotation":-105.58647592651582,"angularVelocity":-0.8023551547162086,"angularAcceleration":-2.2624427790653616,"curveRadius":-0.9384947643629612},{"acceleration":3.0579236250719,"curvature":-1.0509395646611155,"pose":{"rotation":{"radians":2.1860265195790625},"translation":{"x":7.576050882844192,"y":1.0408807604091168}},"time":0.26225697472587023,"velocity":0.7724017575655582,"position":0.10316808118854863,"holonomicRotation":-105.90851253624781,"angularVelocity":-0.8227057063645413,"angularAcceleration":-2.124397906757634,"curveRadius":-0.9515295014347077},{"acceleration":3.053600740645045,"curvature":-1.0363478248872358,"pose":{"rotation":{"radians":2.1782472905266466},"translation":{"x":7.571824218868757,"y":1.0469611417853817}},"time":0.2715059189598219,"velocity":0.8006443405285377,"position":0.11057319604532609,"holonomicRotation":-106.2305491459798,"angularVelocity":-0.8410937352027018,"angularAcceleration":-1.9881219275450295,"curveRadius":-0.9649270022917348},{"acceleration":3.0498642278157515,"curvature":-1.0217709068685223,"pose":{"rotation":{"radians":2.1705698206187733},"translation":{"x":7.5676409008655305,"y":1.0530788537748674}},"time":0.28045729424930943,"velocity":0.8279448198136996,"position":0.11798444084646564,"holonomicRotation":-106.55258575571179,"angularVelocity":-0.8576860716463998,"angularAcceleration":-1.853607508019907,"curveRadius":-0.9786929665718855},{"acceleration":3.0466025547760713,"curvature":-1.007218356263893,"pose":{"rotation":{"radians":2.162993985280157},"translation":{"x":7.563500527951622,"y":1.0592333162624485}},"time":0.2891389448083128,"velocity":0.8543943585864324,"position":0.12540199410729688,"holonomicRotation":-106.87462236544377,"angularVelocity":-0.8726261541084002,"angularAcceleration":-1.7208804201992045,"curveRadius":-0.9928333749886488},{"acceleration":3.0437309081274555,"curvature":-0.9926991902750605,"pose":{"rotation":{"radians":2.1555196132499876},"translation":{"x":7.559402699244142,"y":1.065423949132999}},"time":0.2975746610137365,"velocity":0.8800704087330721,"position":0.13282601831616028,"holonomicRotation":-107.19665897517575,"angularVelocity":-0.8860388197227365,"angularAcceleration":-1.5899854010869585,"curveRadius":-1.0073545035560234},{"acceleration":3.041183636359014,"curvature":-0.9782219054433549,"pose":{"rotation":{"radians":2.1481464890581217},"translation":{"x":7.555347013860203,"y":1.0716501722713934}},"time":0.3057849573143315,"velocity":0.9050394274921005,"position":0.1402566601795913,"holonomicRotation":-107.51869558490775,"angularVelocity":-0.8980338737996151,"angularAcceleration":-1.4609770022562205,"curveRadius":-1.0222629389461226},{"acceleration":3.038909121776545,"curvature":-0.9637944870455708,"pose":{"rotation":{"radians":2.1408743554666056},"translation":{"x":7.551333070916915,"y":1.0779114055625056}},"time":0.3137876679855624,"velocity":0.9293589379498427,"position":0.14769405086972634,"holonomicRotation":-107.84073219463973,"angularVelocity":-0.9087087975901372,"angularAcceleration":-1.3339134986970858,"curveRadius":-1.0375655945754723},{"acceleration":3.036866216300398,"curvature":-0.949424418867153,"pose":{"rotation":{"radians":2.1337029158672824},"translation":{"x":7.547360469531387,"y":1.0842070688912104}},"time":0.3215984103127224,"velocity":0.9530791174474225,"position":0.15513830627350522,"holonomicRotation":-108.16276880437171,"angularVelocity":-0.9181508362382182,"angularAcceleration":-1.2088529172507165,"curveRadius":-1.0532697286143045},{"acceleration":3.0350217114528806,"curvature":-0.935118694417566,"pose":{"rotation":{"radians":2.1266318366360197},"translation":{"x":7.543428808820733,"y":1.0905365821423818}},"time":0.32923094958127624,"velocity":0.976244039841,"position":0.1625895272432833,"holonomicRotation":-108.4848054141037,"angularVelocity":-0.926438631032748,"angularAcceleration":-1.085850265936477,"curveRadius":-1.0693829627936644},{"acceleration":3.033348508453673,"curvature":-0.9208838286861232,"pose":{"rotation":{"radians":2.119660749437562},"translation":{"x":7.539537687902062,"y":1.096899365200894}},"time":0.3366974901881299,"velocity":0.9988926596541083,"position":0.17004779984847873,"holonomicRotation":-108.80684202383569,"angularVelocity":-0.9336435125068479,"angularAcceleration":-0.964955774497007,"curveRadius":-1.0859133029046197},{"acceleration":3.031824272350315,"curvature":-0.9067258706468788,"pose":{"rotation":{"radians":2.1127892534786255},"translation":{"x":7.535686705892484,"y":1.1032948379516216}},"time":0.34400891037675096,"velocity":1.0210596008473218,"position":0.17751319562789922,"holonomicRotation":-109.12887863356767,"angularVelocity":-0.9398305365667119,"angularAcceleration":-0.8462137177525435,"curveRadius":-1.102869160760327},{"acceleration":3.03043042702346,"curvature":-0.8926504161365612,"pose":{"rotation":{"radians":2.1060169177055106},"translation":{"x":7.531875461909113,"y":1.109722420279439}},"time":0.35117495339921245,"velocity":1.0427757956639483,"position":0.18498577184240858,"holonomicRotation":-109.45091524329966,"angularVelocity":-0.9450593237980053,"angularAcceleration":-0.7296617135710877,"curveRadius":-1.120259378053117},{"acceleration":3.029151394443584,"curvature":-0.8786626215491476,"pose":{"rotation":{"radians":2.0993432829471734},"translation":{"x":7.528103555069058,"y":1.1161815320692194}},"time":0.3582043846071015,"velocity":1.0640690070094707,"position":0.1924655717276285,"holonomicRotation":-109.77295185303164,"angularVelocity":-0.9493847455036465,"angularAcceleration":-0.6153302561360618,"curveRadius":-1.1380932515792301},{"acceleration":3.0279740115902096,"curvature":-0.8647672175483748,"pose":{"rotation":{"radians":2.0927678639968876},"translation":{"x":7.524370584489429,"y":1.1226715932058386}},"time":0.3651051216169293,"velocity":1.084964259336048,"position":0.19995262474636916,"holonomicRotation":-110.09498846276364,"angularVelocity":-0.952857490572573,"angularAcceleration":-0.5032426339361592,"curveRadius":-1.1563805608115114},{"acceleration":3.0268870784228112,"curvature":-0.8509685229641967,"pose":{"rotation":{"radians":2.0862901516358074},"translation":{"x":7.520676149287337,"y":1.1291920235741701}},"time":0.37188434298897194,"velocity":1.1054841969088516,"position":0.20744694684050902,"holonomicRotation":-110.41702507249562,"angularVelocity":-0.9555245367549364,"angularAcceleration":-0.39341482391507543,"curveRadius":-1.1751315977195946},{"acceleration":3.0258810037987782,"curvature":-0.8372704594022868,"pose":{"rotation":{"radians":2.079909614595336},"translation":{"x":7.517019848579894,"y":1.1357422430590884}},"time":0.37854857960555705,"velocity":1.1256493838917967,"position":0.2149485406820772,"holonomicRotation":-110.7390616822276,"angularVelocity":-0.9574295463327617,"angularAcceleration":-0.2858556331995024,"curveRadius":-1.1943571981673438},{"acceleration":3.0249475254114397,"curvature":-0.823676565331511,"pose":{"rotation":{"radians":2.0736257014566624},"translation":{"x":7.51340128148421,"y":1.1423216715454674}},"time":0.3851037920035584,"velocity":1.1454785574136772,"position":0.22245739592328,"holonomicRotation":-111.06109829195958,"angularVelocity":-0.9586132007850386,"angularAcceleration":-0.18056691078962836,"curveRadius":-1.2140687766168543},{"acceleration":3.0240794863258325,"curvature":-0.8101900106217934,"pose":{"rotation":{"radians":2.067437842488893},"translation":{"x":7.509820047117396,"y":1.148929728918182}},"time":0.391555436215835,"velocity":1.1649888423290957,"position":0.22997348944525936,"holonomicRotation":-111.38313490169158,"angularVelocity":-0.9591134855196836,"angularAcceleration":-0.07754375755763822,"curveRadius":-1.2342783629639347},{"acceleration":3.0232706551797004,"curvature":-0.7968136107415061,"pose":{"rotation":{"radians":2.0613454514235574},"translation":{"x":7.5062757445965635,"y":1.1555658350621059}},"time":0.397908520144485,"velocity":1.1841959345404771,"position":0.23749678560536117,"holonomicRotation":-111.70517151142356,"angularVelocity":-0.9589659343017701,"angularAcceleration":0.023225132797007823,"curveRadius":-1.254998642743327},{"acceleration":3.0225155804308983,"curvature":-0.7835498413366366,"pose":{"rotation":{"radians":2.055347927168695},"translation":{"x":7.5027679730388215,"y":1.1622294098621138}},"time":0.40416765208078287,"velocity":1.20311425833791,"position":0.24502723648273927,"holonomicRotation":-112.02720812115555,"angularVelocity":-0.9582038397499988,"angularAcceleration":0.12175722760400955,"curveRadius":-1.2762429997996385},{"acceleration":3.0218094713185497,"curvature":-0.7704008518168564,"pose":{"rotation":{"radians":2.0494446554571137},"translation":{"x":7.4992963315612835,"y":1.1689198732030797}},"time":0.4103370826707354,"velocity":1.2217571021272708,"position":0.252564782122095,"holonomicRotation":-112.34924473088753,"angularVelocity":-0.9568584370160926,"angularAcceleration":0.21807567396856162,"curveRadius":-1.2980255637590146},{"acceleration":3.0211481000767133,"curvature":-0.75736847993688,"pose":{"rotation":{"radians":2.043635010437709},"translation":{"x":7.495860419281058,"y":1.1756366449698783}},"time":0.4164207413785688,"velocity":1.240136736073957,"position":0.26010935077541547,"holonomicRotation":-112.67128134061952,"angularVelocity":-0.9549590630263505,"angularAcceleration":0.31220916243978053,"curveRadius":-1.3203612594008947},{"acceleration":3.0205277209720807,"curvature":-0.7444542649090218,"pose":{"rotation":{"radians":2.0379183562009144},"translation":{"x":7.492459835315258,"y":1.1823791450473837}},"time":0.4224222683062829,"velocity":1.2582645145272777,"position":0.267660859141538,"holonomicRotation":-112.99331795035151,"angularVelocity":-0.9525332978839126,"angularAcceleration":0.4041913285827452,"curveRadius":-1.3432658621711409},{"acceleration":3.0199450030327557,"curvature":-0.7316594612518992,"pose":{"rotation":{"radians":2.032294048247862},"translation":{"x":7.489094178780992,"y":1.18914679332047}},"time":0.4283450420735034,"velocity":1.2761509655696888,"position":0.27521921260342724,"holonomicRotation":-113.31535456008349,"angularVelocity":-0.9496070885199278,"angularAcceleration":0.4940606342555003,"curveRadius":-1.3667560565525376},{"acceleration":3.019396973703083,"curvature":-0.7189850517554549,"pose":{"rotation":{"radians":2.0267614348975487},"translation":{"x":7.485763048795372,"y":1.1959390096740117}},"time":0.43419220433891587,"velocity":1.293805869618626,"position":0.28278430546303046,"holonomicRotation":-113.63739116981547,"angularVelocity":-0.9462048595846521,"angularAcceleration":0.581859845997577,"curveRadius":-1.390849500359467},{"acceleration":3.018880971528853,"curvature":-0.7064317600519301,"pose":{"rotation":{"radians":2.0213198586373586},"translation":{"x":7.482466044475509,"y":1.2027552139928828}},"time":0.4399666814457709,"velocity":1.3112383286770397,"position":0.29035602117360687,"holonomicRotation":-113.95942777954747,"angularVelocity":-0.9423496118341537,"angularAcceleration":0.6676358186478446,"curveRadius":-1.4155648946566184},{"acceleration":3.018394606094818,"curvature":-0.6940000636481496,"pose":{"rotation":{"radians":2.01596865741741},"translation":{"x":7.479202764938513,"y":1.209594826161958}},"time":0.44567120359403967,"velocity":1.3284568275597226,"position":0.2979342325694402,"holonomicRotation":-114.28146438927945,"angularVelocity":-0.9380630105140019,"angularAcceleration":0.7514391580463413,"curveRadius":-1.4409220580518405},{"acceleration":3.0179357241121942,"curvature":-0.6816902053993698,"pose":{"rotation":{"radians":2.010707165886834},"translation":{"x":7.4759728093014965,"y":1.2164572660661115}},"time":0.45130832187676684,"velocity":1.345469288206211,"position":0.30551880209283533,"holonomicRotation":-114.60350099901143,"angularVelocity":-0.9333654655957138,"angularAcceleration":0.8333238159436834,"curveRadius":-1.4669420098447032},{"acceleration":3.0175023804183785,"curvature":-0.6695022056743744,"pose":{"rotation":{"radians":2.0055347165792337},"translation":{"x":7.472775776681568,"y":1.2233419535902172}},"time":0.4568804234650032,"velocity":1.3622831180126471,"position":0.31310958201834116,"holonomicRotation":-114.92553760874343,"angularVelocity":-0.928276203456221,"angularAcceleration":0.9133469767021277,"curveRadius":-1.4936470582538601},{"acceleration":3.017092813200036,"curvature":-0.6574358732086418,"pose":{"rotation":{"radians":2.0004506410426663},"translation":{"x":7.469611266195841,"y":1.2302483086191498}},"time":0.4623897451819348,"velocity":1.3789052529704084,"position":0.32070641467412214,"holonomicRotation":-115.2475742184754,"angularVelocity":-0.9228133330719409,"angularAcceleration":0.9915685931883741,"curveRadius":-1.52106089848651},{"acceleration":3.016705422656735,"curvature":-0.6454908164153572,"pose":{"rotation":{"radians":1.9954542709213274},"translation":{"x":7.466478876961424,"y":1.2371757510377839}},"time":0.46783838567068814,"velocity":1.3953421962789376,"position":0.32830913266043354,"holonomicRotation":-115.5696108282074,"angularVelocity":-0.9169939054801006,"angularAcceleration":1.0680513063492294,"curveRadius":-1.5492087177217484},{"acceleration":3.0163387526392005,"curvature":-0.6336664536081454,"pose":{"rotation":{"radians":1.990544938985468},"translation":{"x":7.4633782080954285,"y":1.2441237007309929}},"time":0.47322831633025025,"velocity":1.411600053001413,"position":0.33591755906514537,"holonomicRotation":-115.89164743793938,"angularVelocity":-0.9108339691068231,"angularAcceleration":1.1428600407593998,"curveRadius":-1.5781173112540885},{"acceleration":3.0159914746955727,"curvature":-0.6219620230107552,"pose":{"rotation":{"radians":1.9857219801150958},"translation":{"x":7.460308858714967,"y":1.251091577583652}},"time":0.47856139116891466,"velocity":1.4276845612487383,"position":0.34353150767629065,"holonomicRotation":-116.21368404767136,"angularVelocity":-0.9043486199379749,"angularAcceleration":1.2160619089441476,"curveRadius":-1.607815208972506},{"acceleration":3.0156623742633095,"curvature":-0.610376592676686,"pose":{"rotation":{"radians":1.9809847322380645},"translation":{"x":7.457270427937148,"y":1.2580788014806346}},"time":0.48383935570365894,"velocity":1.4436011203088628,"position":0.3511507831915979,"holonomicRotation":-116.53572065740336,"angularVelocity":-0.89755204792426,"angularAcceleration":1.2877259725740409,"curveRadius":-1.6383328128863814},{"acceleration":3.0153503385605442,"curvature":-0.5989090693100034,"pose":{"rotation":{"radians":1.976332537221407},"translation":{"x":7.454262514879083,"y":1.2650847923068158}},"time":0.489063855016223,"velocity":1.4593548160798122,"position":0.358775181424994,"holonomicRotation":-116.85775726713534,"angularVelocity":-0.8904575803981465,"angularAcceleration":1.3579229514017703,"curveRadius":-1.669702549590857},{"acceleration":3.0150543461057935,"curvature":-0.5875582071242625,"pose":{"rotation":{"radians":1.971764741723065},"translation":{"x":7.4512847186578846,"y":1.2721089699470693}},"time":0.49423644106173703,"velocity":1.4749504441169454,"position":0.366404489510058,"holonomicRotation":-117.17979387686732,"angularVelocity":-0.8830777213079569,"angularAcceleration":1.4267252444432188,"curveRadius":-1.7019590363555424},{"acceleration":3.0147734573881717,"curvature":-0.5763226165523577,"pose":{"rotation":{"radians":1.967280698001458},"translation":{"x":7.448336638390661,"y":1.2791507542862697}},"time":0.4993585793131219,"velocity":1.4903925305622931,"position":0.3740384861004294,"holonomicRotation":-117.50183048659932,"angularVelocity":-0.8754241884030752,"angularAcceleration":1.4942066241207814,"curveRadius":-1.7351392627659477},{"acceleration":3.0145068068022973,"curvature":-0.565200771491694,"pose":{"rotation":{"radians":1.9628797646846727},"translation":{"x":7.445417873194524,"y":1.2862095652092913}},"time":0.5044316548137152,"velocity":1.5056853511902537,"position":0.3816769415671549,"holonomicRotation":-117.8238670963313,"angularVelocity":-0.8675079478455733,"angularAcceleration":1.5604420940662327,"curveRadius":-1.7692827937243814},{"acceleration":3.014253595429603,"curvature":-0.5541910175289863,"pose":{"rotation":{"radians":1.9585613075049382},"translation":{"x":7.442528022186584,"y":1.2932848226010083}},"time":0.5094569777014168,"velocity":1.520832948772703,"position":0.38931961819299316,"holonomicRotation":-118.14590370606328,"angularVelocity":-0.8593392457036,"angularAcceleration":1.6255079175040448,"curveRadius":-1.8044319889174245},{"acceleration":3.0140130846919497,"curvature":-0.5432915785018908,"pose":{"rotation":{"radians":1.9543246999950064},"translation":{"x":7.439666684483953,"y":1.300375946346295}},"time":0.5144357882597721,"velocity":1.5358391489417882,"position":0.3969662703636799,"holonomicRotation":-118.46794031579527,"angularVelocity":-0.8509276382934692,"angularAcceleration":1.6894813151737145,"curveRadius":-1.8406322489987204},{"acceleration":3.0137845907505203,"curvature":-0.5325005633850203,"pose":{"rotation":{"radians":1.9501693241514793},"translation":{"x":7.436833459203742,"y":1.3074823563300255}},"time":0.519369261544662,"velocity":1.5507075747066688,"position":0.40461664475617165,"holonomicRotation":-118.78997692552726,"angularVelocity":-0.842282019901487,"angularAcceleration":1.7524405003796661,"curveRadius":-1.87793228544804},{"acceleration":3.013567479468726,"curvature":-0.5218159725940514,"pose":{"rotation":{"radians":1.9460945710663753},"translation":{"x":7.434027945463061,"y":1.3146034724370748}},"time":0.524258511629451,"velocity":1.5654416597611787,"position":0.41227048052389126,"holonomicRotation":-119.11201353525925,"angularVelocity":-0.8334106487579676,"angularAcceleration":1.8144645885714086,"curveRadius":-1.9163844200260876},{"acceleration":3.0133611620024605,"curvature":-0.5112357039882067,"pose":{"rotation":{"radians":1.9420998415268609},"translation":{"x":7.431249742379022,"y":1.321738714552316}},"time":0.5291045955064042,"velocity":1.5800446607037957,"position":0.4199275094789939,"holonomicRotation":-119.43405014499123,"angularVelocity":-0.8243211716809921,"angularAcceleration":1.8756334615260963,"curveRadius":-1.9560449166575975},{"acceleration":3.0131650907693555,"curvature":-0.5007575580338062,"pose":{"rotation":{"radians":1.9381845465864442},"translation":{"x":7.428498449068734,"y":1.3288875025606248}},"time":0.5339085166778369,"velocity":1.5945196682763645,"position":0.42758745627169253,"holonomicRotation":-119.75608675472321,"angularVelocity":-0.8150206468206835,"angularAcceleration":1.9360277840559976,"curveRadius":-1.996974352072565},{"acceleration":3.0129787559413654,"curvature":-0.4903792434844151,"pose":{"rotation":{"radians":1.934348108109106},"translation":{"x":7.4257736646493075,"y":1.3360492563468742}},"time":0.5386712284666552,"velocity":1.6088696177167454,"position":0.4352500385666636,"holonomicRotation":-120.0781233644552,"angularVelocity":-0.805515564965579,"angularAcceleration":1.99572896210522,"curveRadius":-2.0392380250323163},{"acceleration":3.012801682207112,"curvature":-0.48009838156337614,"pose":{"rotation":{"radians":1.9305899592866775},"translation":{"x":7.423074988237855,"y":1.3432233957959396}},"time":0.5433936370726616,"velocity":1.623097298308991,"position":0.44291496721658385,"holonomicRotation":-120.40015997418719,"angularVelocity":-0.7958118697413231,"angularAcceleration":2.0548190624406413,"curveRadius":-2.0829064175214125},{"acceleration":3.0126334259286573,"curvature":-0.4699125108811592,"pose":{"rotation":{"radians":1.9269095451330225},"translation":{"x":7.420402018951487,"y":1.3504093407926945}},"time":0.5480766043980976,"velocity":1.637205362206131,"position":0.4505819464328237,"holonomicRotation":-120.72219658391917,"angularVelocity":-0.7859149761017057,"angularAcceleration":2.113380886913647,"curveRadius":-2.1280557057841345},{"acceleration":3.0124735725784944,"curvature":-0.4598190912525009,"pose":{"rotation":{"radians":1.9233063229544303},"translation":{"x":7.417754355907314,"y":1.3576065112220133}},"time":0.5527209506633847,"velocity":1.651196332592212,"position":0.45825067395335406,"holonomicRotation":-121.04423319365117,"angularVelocity":-0.7758297880421884,"angularAcceleration":2.1714978779459897,"curveRadius":-2.174768336121279},{"acceleration":3.0123217343585655,"curvature":-0.4498155074706552,"pose":{"rotation":{"radians":1.9197797627988582},"translation":{"x":7.415131598222447,"y":1.3648143269687707}},"time":0.5573274568317989,"velocity":1.665072611242783,"position":0.46592084120790145,"holonomicRotation":-121.36626980338315,"angularVelocity":-0.7655607149194609,"angularAcceleration":2.2292541781752795,"curveRadius":-2.2231336701197155},{"acceleration":3.0121775481202526,"curvature":-0.4398990728505413,"pose":{"rotation":{"radians":1.9163293478858583},"translation":{"x":7.412533345013998,"y":1.3720322079178404}},"time":0.5618968668598677,"velocity":1.6788364855374875,"position":0.47359213348040435,"holonomicRotation":-121.68830641311513,"angularVelocity":-0.7551116865864026,"angularAcceleration":2.286734670093557,"curveRadius":-2.2732487102553107},{"acceleration":3.012040673505308,"curvature":-0.4300670321760193,"pose":{"rotation":{"radians":1.9129545750171697},"translation":{"x":7.409959195399074,"y":1.3792595739540974}},"time":0.5664298897885622,"velocity":1.6924901349726476,"position":0.4812642300688246,"holonomicRotation":-122.01034302284711,"angularVelocity":-0.7444861677901357,"angularAcceleration":2.34402493951802,"curveRadius":-2.325218919804847},{"acceleration":3.0119107911139684,"curvature":-0.4203165643114979,"pose":{"rotation":{"radians":1.9096549549701218},"translation":{"x":7.407408748494792,"y":1.3864958449624156}},"time":0.57092720168883,"velocity":1.7060356372160694,"position":0.48893680444235743,"holonomicRotation":-122.3323796325791,"angularVelocity":-0.7336871714081874,"angularAcceleration":2.401211350563698,"curveRadius":-2.37915915028963},{"acceleration":3.011787601062875,"curvature":-0.41064478519929754,"pose":{"rotation":{"radians":1.9064300128775382},"translation":{"x":7.404881603418257,"y":1.393740440827669}},"time":0.5753894474736849,"velocity":1.7194749737437904,"position":0.4966095243961091,"holonomicRotation":-122.65441624231109,"angularVelocity":-0.7227172701981716,"angularAcceleration":2.4583812140622827,"curveRadius":-2.4351946890417024},{"acceleration":3.011670821399523,"curvature":-0.40104874957394393,"pose":{"rotation":{"radians":1.9032792885887941},"translation":{"x":7.402377359286582,"y":1.4009927814347325}},"time":0.5798172425878605,"velocity":1.7328100350922884,"position":0.5042820522032851,"holonomicRotation":-122.97645285204308,"angularVelocity":-0.7115786091043476,"angularAcceleration":2.515622517890138,"curveRadius":-2.49346245577964},{"acceleration":3.0115601870096436,"curvature":-0.3915254527298125,"pose":{"rotation":{"radians":1.9002023370218764},"translation":{"x":7.399895615216879,"y":1.4082522866684801}},"time":0.5842111745849866,"velocity":1.7460426257592612,"position":0.5119540447649549,"holonomicRotation":-123.29848946177506,"angularVelocity":-0.7002729147675213,"angularAcceleration":2.573024421912043,"curveRadius":-2.5541123649248143},{"acceleration":3.0114554481897686,"curvature":-0.3820718327023614,"pose":{"rotation":{"radians":1.8971987285016931},"translation":{"x":7.397435970326258,"y":1.415518376413786}},"time":0.588571804601304,"velocity":1.75917446877944,"position":0.5196251537574537,"holonomicRotation":-123.62052607150704,"angularVelocity":-0.688801505503515,"angularAcceleration":2.6306770400333264,"curveRadius":-2.6173088786134415},{"acceleration":3.011356369746582,"curvature":-0.3726847711903614,"pose":{"rotation":{"radians":1.8942680490873476},"translation":{"x":7.394998023731829,"y":1.4227904705555243}},"time":0.5928996687340843,"velocity":1.7722072100030857,"position":0.5272950257774807,"holonomicRotation":-123.94256268123902,"angularVelocity":-0.6771653001183348,"angularAcceleration":2.6886716006273907,"curveRadius":-2.683232794315644},{"acceleration":3.011262729926103,"curvature":-0.36336109453845034,"pose":{"rotation":{"radians":1.8914099008899186},"translation":{"x":7.392581374550704,"y":1.43006798897857}},"time":0.5971952793321769,"velocity":1.7851424220993974,"position":0.5349633024849555,"holonomicRotation":-124.26459929097102,"angularVelocity":-0.6653648258289874,"angularAcceleration":2.7471005622779816,"curveRadius":-2.752083299589966},{"acceleration":3.0111743194970244,"curvature":-0.3540975748632094,"pose":{"rotation":{"radians":1.8886239023833054},"translation":{"x":7.390185621899993,"y":1.4373503515677968}},"time":0.6014591262054304,"velocity":1.7979816083064062,"position":0.5426296207437001,"holonomicRotation":-124.586635900703,"angularVelocity":-0.6534002250618685,"angularAcceleration":2.806057797753251,"curveRadius":-2.824080341093292},{"acceleration":3.0110909409439377,"curvature":-0.34489093021555334,"pose":{"rotation":{"radians":1.885909688705218},"translation":{"x":7.387810364896807,"y":1.4446369782080792}},"time":0.6056916777591326,"velocity":1.810726205946837,"position":0.5502936127600097,"holonomicRotation":-124.908672510435,"angularVelocity":-0.6412712624169303,"angularAcceleration":2.865638490411073,"curveRadius":-2.899467374729194},{"acceleration":3.0110124076660245,"curvature":-0.3357378251783617,"pose":{"rotation":{"radians":1.883266911954627},"translation":{"x":7.385455202658258,"y":1.4519272887842913}},"time":0.6098933820590717,"velocity":1.8233775897272975,"position":0.5579549062191795,"holonomicRotation":-125.23070912016698,"angularVelocity":-0.6289773296586483,"angularAcceleration":2.9259395427850734,"curveRadius":-2.9785145581042203},{"acceleration":3.0109385432924265,"curvature":-0.32663487097534627,"pose":{"rotation":{"radians":1.8806952414819884},"translation":{"x":7.383119734301455,"y":1.4592207031813078}},"time":0.6140646678323359,"velocity":1.835937074837106,"position":0.5656131244200558,"holonomicRotation":-125.55274572989896,"angularVelocity":-0.6165174510750878,"angularAcceleration":2.9870594490125524,"curveRadius":-3.0615224792562885},{"acceleration":3.010869181016438,"curvature":-0.3175786247719062,"pose":{"rotation":{"radians":1.8781943641765024},"translation":{"x":7.3808035589435095,"y":1.4665166412840027}},"time":0.6182059454085267,"velocity":1.8484059198612932,"position":0.5732678864076757,"holonomicRotation":-125.87478233963095,"angularVelocity":-0.6038902873509737,"angularAcceleration":3.0490986155361375,"curveRadius":-3.1488265330143923},{"acceleration":3.010804163000566,"curvature":-0.30856558967977255,"pose":{"rotation":{"radians":1.875763984749688},"translation":{"x":7.378506275701533,"y":1.4738145229772501}},"time":0.6223176076056709,"velocity":1.860785329521307,"position":0.580918807104069,"holonomicRotation":-126.19681894936294,"angularVelocity":-0.5910941391300062,"angularAcceleration":3.1121594156872168,"curveRadius":-3.2408020642800572},{"acceleration":3.010743339803381,"curvature":-0.29959221409569975,"pose":{"rotation":{"radians":1.8734038260178427},"translation":{"x":7.376227483692637,"y":1.4811137681459248}},"time":0.6264000305647572,"velocity":1.8730764572556367,"position":0.5885654974372935,"holonomicRotation":-126.51885555909493,"angularVelocity":-0.5781269494853063,"angularAcceleration":3.1763464429472035,"curveRadius":-3.337870455073197},{"acceleration":3.010686569912378,"curvature":-0.2906548907314153,"pose":{"rotation":{"radians":1.8711136291823707},"translation":{"x":7.373966782033929,"y":1.4884137966749007}},"time":0.6304535745364959,"velocity":1.8852804076518994,"position":0.5962075644687678,"holonomicRotation":-126.84089216882691,"angularVelocity":-0.5649863061655025,"angularAcceleration":3.2417665656079167,"curveRadius":-3.4405063595646403},{"acceleration":3.0106337191711128,"curvature":-0.28174995501395944,"pose":{"rotation":{"radians":1.8688931541093619},"translation":{"x":7.371723769842524,"y":1.495714028449052}},"time":0.6344785846236143,"velocity":1.897398238740182,"position":0.6038446115189777,"holonomicRotation":-127.16292877855889,"angularVelocity":-0.5516694430444274,"angularAcceleration":3.3085291298260686,"curveRadius":-3.549246351966425},{"acceleration":3.0105846604553888,"curvature":-0.27287368473798024,"pose":{"rotation":{"radians":1.8667421796132642},"translation":{"x":7.369498046235529,"y":1.5030138833532534}},"time":0.6384753914817358,"velocity":1.9094309641580456,"position":0.6114762382916342,"holonomicRotation":-127.48496538829087,"angularVelocity":-0.5381732399019723,"angularAcceleration":3.3767463931940496,"curveRadius":-3.6646992946946266},{"acceleration":3.0105392731707457,"curvature":-0.26402229728115484,"pose":{"rotation":{"radians":1.864660503737129},"translation":{"x":7.367289210330058,"y":1.510312781272379}},"time":0.6424443119816381,"velocity":1.9213795551950938,"position":0.6191020409963411,"holonomicRotation":-127.80700199802287,"angularVelocity":-0.52449422360219,"angularAcceleration":3.4465332072333315,"curveRadius":-3.787558892933613},{"acceleration":3.010497442888555,"curvature":-0.25519194894680164,"pose":{"rotation":{"radians":1.8626479440406485},"translation":{"x":7.36509686124322,"y":1.517610142091303}},"time":0.6463856498354852,"velocity":1.9332449427256604,"position":0.6267216124698642,"holonomicRotation":-128.12903860775486,"angularVelocity":-0.5106285660124733,"angularAcceleration":3.518007870394209,"curveRadius":-3.9186189224506616},{"acceleration":3.0104590610913076,"curvature":-0.24637873192908843,"pose":{"rotation":{"radians":1.8607043378879997},"translation":{"x":7.362920598092128,"y":1.5249053856948998}},"time":0.6502996961894119,"velocity":1.9450280190373703,"position":0.6343345422960627,"holonomicRotation":-128.45107521748685,"angularVelocity":-0.4965720834396594,"angularAcceleration":3.591291799268568,"curveRadius":-4.05879189396841},{"acceleration":3.0104240245974796,"curvature":-0.23757867278612818,"pose":{"rotation":{"radians":1.858829542742253},"translation":{"x":7.360760019993889,"y":1.5321979319680437}},"time":0.6541867301846708,"velocity":1.956729639561125,"position":0.6419404169245675,"holonomicRotation":-128.77311182721883,"angularVelocity":-0.4823202338938774,"angularAcceleration":3.6665101368203237,"curveRadius":-4.20913202465869},{"acceleration":3.0103922355710107,"curvature":-0.22878772964218502,"pose":{"rotation":{"radians":1.8570234364631484},"translation":{"x":7.358614726065617,"y":1.539487200795609}},"time":0.6580470194893748,"velocity":1.9683506245110638,"position":0.6495388197882751,"holonomicRotation":-129.0951484369508,"angularVelocity":-0.46786811467827666,"angularAcceleration":3.7437917406837196,"curveRadius":-4.3708637764969325},{"acceleration":3.010363600974154,"curvature":-0.22000178921307773,"pose":{"rotation":{"radians":1.8552859176133305},"translation":{"x":7.356484315424423,"y":1.5467726120624696}},"time":0.6618808208027283,"velocity":1.9798917604381499,"position":0.6571293314197405,"holonomicRotation":-129.4171850466828,"angularVelocity":-0.45321045818570843,"angularAcceleration":3.823269724884929,"curveRadius":-4.54541757854284},{"acceleration":3.0103380324196274,"curvature":-0.21121666454402882,"pose":{"rotation":{"radians":1.8536169057703207},"translation":{"x":7.3543683871874155,"y":1.5540535856535005}},"time":0.6656883803334949,"velocity":1.9913538017043184,"position":0.6647115295665481,"holonomicRotation":-129.73922165641477,"angularVelocity":-0.43834162789144576,"angularAcceleration":3.9050815027622123,"curveRadius":-4.734474915408707},{"acceleration":3.0103154459198525,"curvature":-0.20242809120546015,"pose":{"rotation":{"radians":1.8520163418456113},"translation":{"x":7.352266540471705,"y":1.5613295414535757}},"time":0.6694699342543214,"velocity":2.0027374718817614,"position":0.6722849893057289,"holonomicRotation":-130.06125826614678,"angularVelocity":-0.42325561349117746,"angularAcceleration":3.9893691101912907,"curveRadius":-4.940025833593528},{"acceleration":3.0102957615360313,"curvature":-0.19363172402629505,"pose":{"rotation":{"radians":1.850484188413057},"translation":{"x":7.350178374394407,"y":1.5685998993475692}},"time":0.6732257091334295,"velocity":2.014043465081624,"position":0.6798492831573142,"holonomicRotation":-130.38329487587876,"angularVelocity":-0.4079460249540229,"angularAcceleration":4.076279604061468,"curveRadius":-5.164442991088592},{"acceleration":3.010278903388651,"curvature":-0.18482313364730707,"pose":{"rotation":{"radians":1.8490204300497837},"translation":{"x":7.348103488072627,"y":1.5758640792203555}},"time":0.6769559223450765,"velocity":2.0252724472177865,"position":0.6874039811971107,"holonomicRotation":-130.70533148561074,"angularVelocity":-0.39240608518111575,"angularAcceleration":4.165965560463425,"curveRadius":-5.410578103865897},{"acceleration":3.0102647991492737,"curvature":-0.17599780232146225,"pose":{"rotation":{"radians":1.8476250736807294},"translation":{"x":7.346041480623478,"y":1.5831215009568091}},"time":0.6806607824600828,"velocity":2.036425057207762,"position":0.694948651168759,"holonomicRotation":-131.02736809534272,"angularVelocity":-0.3766286244931394,"angularAcceleration":4.258584723366731,"curveRadius":-5.681889130487477},{"acceleration":3.0102533801034457,"curvature":-0.16715111987741527,"pose":{"rotation":{"radians":1.8462981489418717},"translation":{"x":7.343991951164072,"y":1.5903715844418038}},"time":0.6843404896176469,"velocity":2.0475019081166104,"position":0.702482858595182,"holonomicRotation":-131.3494047050747,"angularVelocity":-0.3606060705482953,"angularAcceleration":4.354301377463544,"curveRadius":-5.982610231587899},{"acceleration":3.0102445808074294,"curvature":-0.15827837976709477,"pose":{"rotation":{"radians":1.8450397085503711},"translation":{"x":7.3419544988115195,"y":1.5976137495602147}},"time":0.687995235879577,"velocity":2.0585035882458116,"position":0.710006166889493,"holonomicRotation":-131.6714413148067,"angularVelocity":-0.34433044083229947,"angularAcceleration":4.453285823295611,"curveRadius":-6.317982288367439},{"acceleration":3.010238339019461,"curvature":-0.14937477331905819,"pose":{"rotation":{"radians":1.8438498286910985},"translation":{"x":7.339928722682929,"y":1.6048474161969153}},"time":0.6916252055679925,"velocity":2.0694306621713583,"position":0.7175181374654526,"holonomicRotation":-131.9934779245387,"angularVelocity":-0.32779333201321137,"angularAcceleration":4.555715402215073,"curveRadius":-6.694570828663568},{"acceleration":3.0102345953882916,"curvature":-0.14043538574366898,"pose":{"rotation":{"radians":1.8427286094131998},"translation":{"x":7.337914221895414,"y":1.6120720042367802}},"time":0.6952305755874865,"velocity":2.080283671733215,"position":0.7250183298475624,"holonomicRotation":-132.31551453427068,"angularVelocity":-0.31098591041593276,"angularAcceleration":4.661774382768456,"curveRadius":-7.1207124522394905},{"acceleration":3.0102332934903204,"curvature":-0.1314551905867435,"pose":{"rotation":{"radians":1.8416761750459862},"translation":{"x":7.335910595566085,"y":1.6192869335646836}},"time":0.6988115157326682,"velocity":2.091063136980237,"position":0.7325063017808846,"holonomicRotation":-132.63755114400266,"angularVelocity":-0.29389889932387375,"angularAcceleration":4.771655040101724,"curveRadius":-7.607154921281932},{"acceleration":3.010234379513192,"curvature":-0.12242904443449312,"pose":{"rotation":{"radians":1.8406926746272838},"translation":{"x":7.33391744281205,"y":1.6264916240654999}},"time":0.7023681889819493,"velocity":2.101769557071918,"position":0.7399816093406757,"holonomicRotation":-132.95958775373464,"angularVelocity":-0.27652256751480403,"angularAcceleration":4.885557539642395,"curveRadius":-8.167996447403949},{"acceleration":2.664630929185663,"curvature":-0.11335168049057802,"pose":{"rotation":{"radians":1.839778282347744},"translation":{"x":7.331934362750422,"y":1.6336854956241034}},"time":0.7059027855547872,"velocity":2.1111879524220956,"position":0.7474438070419236,"holonomicRotation":-133.28162436346662,"angularVelocity":-0.2586977780057235,"angularAcceleration":5.042948789702724,"curveRadius":-8.822101231071926},{"acceleration":-0.3432996561693943,"curvature":-0.1042177031367976,"pose":{"rotation":{"radians":1.838933198015875},"translation":{"x":7.329960954498313,"y":1.6408679681253684}},"time":0.709432987216786,"velocity":2.1099760354053227,"position":0.7548924479488891,"holonomicRotation":-133.60366097319863,"angularVelocity":-0.239386984875686,"angularAcceleration":5.470167140282791,"curveRadius":-9.59529878227489},{"acceleration":-2.9952705767771217,"curvature":-0.09502158092543035,"pose":{"rotation":{"radians":1.83815764753834},"translation":{"x":7.327996817172833,"y":1.6480384614541688}},"time":0.7129743546289631,"velocity":2.0993686817940715,"position":0.7623270837847397,"holonomicRotation":-133.9256975829306,"angularVelocity":-0.2189974626377708,"angularAcceleration":5.757528057610057,"curveRadius":-10.523925094287428},{"acceleration":-2.9953043577149043,"curvature":-0.08575764105219817,"pose":{"rotation":{"radians":1.837451883420647},"translation":{"x":7.326041549891091,"y":1.6551963954953794}},"time":0.7165268428503934,"velocity":2.0887278983436905,"position":0.7697472650413785,"holonomicRotation":-134.2477341926626,"angularVelocity":-0.19866754615415003,"angularAcceleration":5.722725936424264,"curveRadius":-11.660768506812463},{"acceleration":-2.9953382579282652,"curvature":-0.0764200603115024,"pose":{"rotation":{"radians":1.8368161852870402},"translation":{"x":7.3240947517701995,"y":1.6623411901338747}},"time":0.7200904060133854,"velocity":2.0780538212670367,"position":0.7771525410895604,"holonomicRotation":-134.56977080239457,"angularVelocity":-0.17838834462334258,"angularAcceleration":5.690709159138587,"curveRadius":-13.085569363905416},{"acceleration":-2.9953722670675518,"curvature":-0.06700285886395788,"pose":{"rotation":{"radians":1.8362508604240009},"translation":{"x":7.322156021927269,"y":1.6694722652545282}},"time":0.7236649973457214,"velocity":2.0673465895240573,"position":0.7845424602894077,"holonomicRotation":-134.89180741212655,"angularVelocity":-0.15815090746886423,"angularAcceleration":5.661468759074284,"curveRadius":-14.924736301631441},{"acceleration":-2.995406374754156,"curvature":-0.05749989292923822,"pose":{"rotation":{"radians":1.8357562443427415},"translation":{"x":7.320224959479412,"y":1.6765890407422146}},"time":0.7272505691936477,"velocity":2.05660634475364,"position":0.7919165701014229,"holonomicRotation":-135.21384402185856,"angularVelocity":-0.137946219525735,"angularAcceleration":5.6349973728220135,"curveRadius":-17.39133673223778},{"acceleration":-2.9954405703817693,"curvature":-0.047904845124937076,"pose":{"rotation":{"radians":1.835332701367179},"translation":{"x":7.318301163543737,"y":1.6836909364818085}},"time":0.7308470730457017,"velocity":2.045833231203663,"position":0.799274417198107,"holonomicRotation":-135.53588063159054,"angularVelocity":-0.1177651944737062,"angularAcceleration":5.611289708616087,"curveRadius":-20.874715227488455},{"acceleration":-2.995474843204596,"curvature":-0.038211217731001904,"pose":{"rotation":{"radians":1.8349806252442695},"translation":{"x":7.316384233237355,"y":1.6907773723581836}},"time":0.7344544595574745,"velocity":2.035027395657932,"position":0.8066155475762914,"holonomicRotation":-135.85791724132253,"angularVelocity":-0.09759866921951307,"angularAcceleration":5.590342257027231,"curveRadius":-26.170325348952964},{"acceleration":-2.9955091822233757,"curvature":-0.028412320509840917,"pose":{"rotation":{"radians":1.834700439780875},"translation":{"x":7.314473767677379,"y":1.6978477682562145}},"time":0.7380726785774098,"velocity":2.0241889873604206,"position":0.8139395066703025,"holonomicRotation":-136.1799538510545,"angularVelocity":-0.07743739719755476,"angularAcceleration":5.572153568060892,"curveRadius":-35.19599885034519},{"acceleration":-2.9955435762136235,"curvature":-0.018501265907322133,"pose":{"rotation":{"radians":1.8344925995070018},"translation":{"x":7.312569365980917,"y":1.7049015440607758}},"time":0.7417016791737474,"velocity":2.013318157935986,"position":0.8212458394660695,"holonomicRotation":-136.5019904607865,"angularVelocity":-0.05727204180758952,"angularAcceleration":5.556724187457,"curveRadius":-54.0503555275229},{"acceleration":-2.9955780135294523,"curvature":-0.00847095525789901,"pose":{"rotation":{"radians":1.834357590363699},"translation":{"x":7.310670627265081,"y":1.7119381196567414}},"time":0.745341409662722,"velocity":2.002415061308041,"position":0.8285340906162943,"holonomicRotation":-136.82402707051847,"angularVelocity":-0.037093170417904615,"angularAcceleration":5.5440564763820825,"curveRadius":-118.05044054122685},{"acceleration":-2.9956124822949035,"curvature":0.0016859266472644644,"pose":{"rotation":{"radians":1.8342959304238184},"translation":{"x":7.308777150646981,"y":1.7189569149289852}},"time":0.7489918176381454,"velocity":1.9914798536113938,"position":0.8358038045568124,"holonomicRotation":-137.14606368025045,"angularVelocity":-0.016891246210215212,"angularAcceleration":5.534155180379908,"curveRadius":593.1456161646006},{"acceleration":-2.995646970087119,"curvature":0.011976937804887105,"pose":{"rotation":{"radians":1.8343081706377355},"translation":{"x":7.306888535243731,"y":1.7259573497623824}},"time":0.7526528500024972,"velocity":1.9805126931017325,"position":0.8430545256242673,"holonomicRotation":-137.46810028998246,"angularVelocity":0.0033433776866570245,"angularAcceleration":5.527026773622901,"curveRadius":83.49379585088577},{"acceleration":-2.995681464121223,"curvature":0.022409863784463854,"pose":{"rotation":{"radians":1.8343948956141058},"translation":{"x":7.305004380172439,"y":1.7329388440418068}},"time":0.7563244529996637,"velocity":1.9695137400595089,"position":0.8502857981752304,"holonomicRotation":-137.79013689971444,"angularVelocity":0.023620466710924007,"angularAcceleration":5.522680159024663,"curveRadius":44.62320742410191},{"acceleration":-2.9957159510922375,"curvature":0.03299275173000253,"pose":{"rotation":{"radians":1.8345567244282015},"translation":{"x":7.303124284550216,"y":1.7399008176521327}},"time":0.7600065722494725,"velocity":1.9584831566890326,"position":0.8574971667069016,"holonomicRotation":-138.11217350944642,"angularVelocity":0.04394991121052217,"angularAcceleration":5.521126047358017,"curveRadius":30.30968766059706},{"acceleration":-2.995750417039477,"curvature":0.0437339135274464,"pose":{"rotation":{"radians":1.8347943114669016},"translation":{"x":7.3012478474941735,"y":1.7468426904782344}},"time":0.7636991527841793,"velocity":1.947421107012233,"position":0.8646881759795321,"holonomicRotation":-138.4342101191784,"angularVelocity":0.06434173512724864,"angularAcceleration":5.522377569036755,"curveRadius":22.86555030965667},{"acceleration":-2.9957848474194906,"curvature":0.05464194245693692,"pose":{"rotation":{"radians":1.8351083473065284},"translation":{"x":7.2993746681214215,"y":1.753763882404986}},"time":0.7674021390870741,"velocity":1.9363277567558188,"position":0.8718583711407139,"holonomicRotation":-138.7562467289104,"angularVelocity":0.08480610349037801,"angularAcceleration":5.526449921548857,"curveRadius":18.300959940948214},{"acceleration":-2.9958192269851067,"curvature":0.06572572320707244,"pose":{"rotation":{"radians":1.8354995596255101},"translation":{"x":7.297504345549072,"y":1.7606638133172625}},"time":0.7711154751333863,"velocity":1.92520327323202,"position":0.8790072978516845,"holonomicRotation":-139.0782833386424,"angularVelocity":0.10535333029454279,"angularAcceleration":5.533360446752664,"curveRadius":15.214743196502319},{"acceleration":-2.995853539731548,"curvature":0.07699444906744785,"pose":{"rotation":{"radians":1.8359687141560674},"translation":{"x":7.295636478894236,"y":1.767541903099937}},"time":0.7748391044336771,"velocity":1.9140478252120956,"position":0.8861345024158022,"holonomicRotation":-139.40031994837437,"angularVelocity":0.12599388734014236,"angularAcceleration":5.543128861937904,"curveRadius":12.987949288707693},{"acceleration":-2.9958877687563326,"curvature":0.08845763478976121,"pose":{"rotation":{"radians":1.8365166156723123},"translation":{"x":7.293770667274023,"y":1.774397571637885}},"time":0.7785729700799277,"velocity":1.902861582792314,"position":0.8932395319093603,"holonomicRotation":-139.72235655810636,"angularVelocity":0.14673841218551326,"angularAcceleration":5.555776991119639,"curveRadius":11.30484669160234},{"acceleration":-2.995921896322508,"curvature":0.10012513380667103,"pose":{"rotation":{"radians":1.8371441090176028},"translation":{"x":7.2919065098055444,"y":1.7812302388159806}},"time":0.7823170147945324,"velocity":1.8916447172510191,"position":0.900321934314894,"holonomicRotation":-140.04439316783834,"angularVelocity":0.16759771667331522,"angularAcceleration":5.571328891034342,"curveRadius":9.987502258232919},{"acceleration":-2.9959559036004917,"curvature":0.11200715357724667,"pose":{"rotation":{"radians":1.8378520801748417},"translation":{"x":7.290043605605912,"y":1.7880393245190973}},"time":0.786071180982437,"velocity":1.880397400897269,"position":0.9073812586571662,"holonomicRotation":-140.36642977757032,"angularVelocity":0.18858279623311558,"angularAcceleration":5.589811028454588,"curveRadius":8.928001186195145},{"acceleration":-2.9959897707467547,"curvature":0.12411427210959608,"pose":{"rotation":{"radians":1.838641457377136},"translation":{"x":7.288181553792235,"y":1.7948242486321098}},"time":0.7898354107866676,"velocity":1.869119806909054,"position":0.9144170551420111,"holonomicRotation":-140.6884663873023,"angularVelocity":0.20970483826652464,"angularAcceleration":5.611252004239993,"curveRadius":8.057091122582376},{"acceleration":-2.996023476682163,"curvature":0.13645745687847424,"pose":{"rotation":{"radians":1.8395132122621207},"translation":{"x":7.286319953481625,"y":1.8015844310398927}},"time":0.7936096461475136,"velocity":1.8578121091614355,"position":0.921428875298216,"holonomicRotation":-141.0105029970343,"angularVelocity":0.23097523117620566,"angularAcceleration":5.635682694921642,"curveRadius":7.328291343510645},{"acceleration":-2.996056999075461,"curvature":0.14904808279908568,"pose":{"rotation":{"radians":1.840468361072461},"translation":{"x":7.284458403791193,"y":1.8083192916273199}},"time":0.7973938288656506,"velocity":1.8464744820429808,"position":0.928416272122644,"holonomicRotation":-141.3325396067663,"angularVelocity":0.2524055738012969,"angularAcceleration":5.663136328586659,"curveRadius":6.709244300364354},{"acceleration":-2.996090314227564,"curvature":0.16189795110935423,"pose":{"rotation":{"radians":1.8415079659018778},"translation":{"x":7.282596503838049,"y":1.8150282502792658}},"time":0.8011879006695096,"velocity":1.8351071002599548,"position":0.9353788002288018,"holonomicRotation":-141.65457621649827,"angularVelocity":0.2740076843984283,"angularAcceleration":5.693648331894869,"curveRadius":6.176730422762104},{"acceleration":-2.996123396869328,"curvature":0.1750193106518636,"pose":{"rotation":{"radians":1.842633135988344},"translation":{"x":7.2807338527393055,"y":1.821710726880605}},"time":0.8049918032872123,"velocity":1.8237101386276433,"position":0.9423160159990585,"holonomicRotation":-141.97661282623025,"angularVelocity":0.29579360976013,"angularAcceleration":5.727256334143217,"curveRadius":5.713655231959697},{"acceleration":-2.9961562202263807,"curvature":0.18842487806976033,"pose":{"rotation":{"radians":1.843845029058299},"translation":{"x":7.278870049612072,"y":1.8283661413162116}},"time":0.8088054785234262,"velocity":1.8122837718467377,"position":0.9492274777407427,"holonomicRotation":-142.29864943596223,"angularVelocity":0.3177756350218434,"angularAcceleration":5.764000314703378,"curveRadius":5.307154820765075},{"acceleration":-2.9961887556540594,"curvature":0.20212786011298917,"pose":{"rotation":{"radians":1.8451448527194139},"translation":{"x":7.27700469357346,"y":1.8349939134709594}},"time":0.8126288683415094,"velocity":1.8008281742653147,"position":0.956112745846346,"holonomicRotation":-142.62068604569424,"angularVelocity":0.3399662924683065,"angularAcceleration":5.803922305151778,"curveRadius":4.947363512585556},{"acceleration":-2.996220972741088,"curvature":0.21614197627153417,"pose":{"rotation":{"radians":1.8465338659062362},"translation":{"x":7.275137383740579,"y":1.8415934632297235}},"time":0.8164619149513475,"velocity":1.7893435196234238,"position":0.9629713829580743,"holonomicRotation":-142.94272265542622,"angularVelocity":0.36237837109970944,"angularAcceleration":5.84706655376406,"curveRadius":4.6265885842726036},{"acceleration":-2.9962528389638234,"curvature":0.23048148325489606,"pose":{"rotation":{"radians":1.8480133803787708},"translation":{"x":7.2732677192305415,"y":1.8481642104773779}},"time":0.8203045609033074,"velocity":1.777829980780731,"position":0.9698029541369944,"holonomicRotation":-143.2647592651582,"angularVelocity":0.3850249258014413,"angularAcceleration":5.893479385000602,"curveRadius":4.338743337980307},{"acceleration":-2.996284319664273,"curvature":0.24516119899862243,"pose":{"rotation":{"radians":1.849584762276323},"translation":{"x":7.271395299160458,"y":1.8547055750987964}},"time":0.8241567491887725,"velocity":1.7662877294245976,"position":0.9766070270370445,"holonomicRotation":-143.58679587489019,"angularVelocity":0.40791928667695554,"angularAcceleration":5.943209204466542,"curveRadius":4.078948887852433},{"acceleration":-2.9963153778151583,"curvature":0.2601965291390388,"pose":{"rotation":{"radians":1.8512494337257912},"translation":{"x":7.269519722647439,"y":1.861216976978854}},"time":0.8280184233477489,"velocity":1.754716935757945,"position":0.9833831720841792,"holonomicRotation":-143.90883248462217,"angularVelocity":0.4310750676875787,"angularAcceleration":5.996306279958334,"curveRadius":3.843248806234611},{"acceleration":-2.9963459738821285,"curvature":0.2756034934110805,"pose":{"rotation":{"radians":1.8530088745072997},"translation":{"x":7.267640588808595,"y":1.8676978360024243}},"time":0.8318895275840702,"velocity":1.7431177681649657,"position":0.9901309626609296,"holonomicRotation":-144.23086909435415,"angularVelocity":0.4545061755248568,"angularAcceleration":6.0528227624127595,"curveRadius":3.628401032306347},{"acceleration":-2.9963760655601317,"curvature":0.29139875399918874,"pose":{"rotation":{"radians":1.8548646237791235},"translation":{"x":7.2657574967610365,"y":1.8741475720543823}},"time":0.8357700068887733,"velocity":1.7314903928534517,"position":0.9968499752966897,"holonomicRotation":-144.55290570408613,"angularVelocity":0.478226818417686,"angularAcceleration":6.112812627058667,"curveRadius":3.431723664826597},{"acceleration":-2.996405607711253,"curvature":0.3075996437295386,"pose":{"rotation":{"radians":1.8568182818592538},"translation":{"x":7.263870045621876,"y":1.880565605019602}},"time":0.839659807172248,"velocity":1.7198349734711715,"position":1.0035397898640275,"holonomicRotation":-144.87494231381814,"angularVelocity":0.5022515136394411,"angularAcceleration":6.176331294905101,"curveRadius":3.2509790579577666},{"acceleration":-2.9964345519632967,"curvature":0.3242241968020308,"pose":{"rotation":{"radians":1.8588715120694113},"translation":{"x":7.261977834508223,"y":1.8869513547829577}},"time":0.8435588754058198,"velocity":1.7081516706956346,"position":1.0101999897813594,"holonomicRotation":-145.19697892355012,"angularVelocity":0.5265950958433427,"angularAcceleration":6.243435801994539,"curveRadius":3.084285534094772},{"acceleration":-2.996462846665952,"curvature":0.3412911793240649,"pose":{"rotation":{"radians":1.8610260426376002},"translation":{"x":7.260080462537189,"y":1.8933042412293235}},"time":0.8474671597734654,"velocity":1.696440641793779,"position":1.0168301622223208,"holonomicRotation":-145.5190155332821,"angularVelocity":0.5512727236597686,"angularAcceleration":6.314184305706379,"curveRadius":2.930049355452207},{"acceleration":-2.996490436451137,"curvature":0.35882012148167947,"pose":{"rotation":{"radians":1.863283668662856},"translation":{"x":7.258177528825884,"y":1.899623684243574}},"time":0.8513846098344171,"velocity":1.6847020401508623,"position":1.0234298983321952,"holonomicRotation":-145.84105214301408,"angularVelocity":0.5762998864387204,"angularAcceleration":6.388636074373304,"curveRadius":2.7869117146237232},{"acceleration":-2.996517262111793,"curvature":0.37683135084241415,"pose":{"rotation":{"radians":1.8656462541412004},"translation":{"x":7.2562686324914205,"y":1.905909103710583}},"time":0.8553111766974653,"velocity":1.6729360147649024,"position":1.029998793451771,"holonomicRotation":-146.1630887527461,"angularVelocity":0.6016924098703357,"angularAcceleration":6.46685114942963,"curveRadius":2.653707017116489},{"acceleration":-2.9965432603033477,"curvature":0.3953460260346808,"pose":{"rotation":{"radians":1.8681157340541314},"translation":{"x":7.2543533726509075,"y":1.9121599195152257}},"time":0.8592468132078369,"velocity":1.6611427097047444,"position":1.0365364473490226,"holonomicRotation":-146.48512536247807,"angularVelocity":0.62746646099637,"angularAcceleration":6.548890137112903,"curveRadius":2.5294297505150016},{"acceleration":-2.9965683630992985,"curvature":0.41438617207093753,"pose":{"rotation":{"radians":1.8706941165170448},"translation":{"x":7.252431348421456,"y":1.9183755515423755}},"time":0.8631914741475799,"velocity":1.649322263529557,"position":1.0430424644590162,"holonomicRotation":-146.80716197221005,"angularVelocity":0.6536385515256218,"angularAcceleration":6.634813721393484,"curveRadius":2.4132079383884775},{"acceleration":-2.9965924978151843,"curvature":0.43397471659607595,"pose":{"rotation":{"radians":1.8733834849896753},"translation":{"x":7.250502158920178,"y":1.924555419676907}},"time":0.8671451164504702,"velocity":1.6374748086656712,"position":1.049516454132474,"holonomicRotation":-147.12919858194203,"angularVelocity":0.6802255405514336,"angularAcceleration":6.724682454549677,"curveRadius":2.304281705265228},{"acceleration":-2.9966155866670023,"curvature":0.4541355261006816,"pose":{"rotation":{"radians":1.8761860005483089},"translation":{"x":7.248565403264184,"y":1.9306989438036946}},"time":0.8711076994325255,"velocity":1.6256004707381828,"position":1.0559580308934422,"holonomicRotation":-147.45123519167402,"angularVelocity":0.7072446359671996,"angularAcceleration":6.818556365411853,"curveRadius":2.2019858445919085},{"acceleration":-2.9966375461383143,"curvature":0.4748934441971376,"pose":{"rotation":{"radians":1.8791039042133455},"translation":{"x":7.246620680570585,"y":1.9368055438076124}},"time":0.8750791850392919,"velocity":1.6136993678549987,"position":1.0623668147065264,"holonomicRotation":-147.773271801406,"angularVelocity":0.734713392909007,"angularAcceleration":6.916494143906136,"curveRadius":2.105735533348151},{"acceleration":-2.9966582869934415,"curvature":0.4962743294894637,"pose":{"rotation":{"radians":1.8821395193386647},"translation":{"x":7.2446675899564905,"y":1.942874639573535}},"time":0.8790595381111692,"velocity":1.6017716098369978,"position":1.0687424312541869,"holonomicRotation":-148.09530841113798,"angularVelocity":0.7626497123501519,"angularAcceleration":7.0185531124175355,"curveRadius":2.0150145606538588},{"acceleration":-2.996677713415115,"curvature":0.5183050947344165,"pose":{"rotation":{"radians":1.8852952540525882},"translation":{"x":7.242705730539012,"y":1.9489056509863363}},"time":0.8830487266681253,"velocity":1.589817297393757,"position":1.0750845122246009,"holonomicRotation":-148.41734502087,"angularVelocity":0.791071835504177,"angularAcceleration":7.124788098688549,"curveRadius":1.9293655612480667},{"acceleration":-2.9966957228512547,"curvature":0.5410137458241167,"pose":{"rotation":{"radians":1.8885736037537182},"translation":{"x":7.240734701435261,"y":1.9548979979308907}},"time":0.8870467222152678,"velocity":1.5778365212376566,"position":1.081392695610628,"holonomicRotation":-148.73938163060197,"angularVelocity":0.8199983372850593,"angularAcceleration":7.235251125168664,"curveRadius":1.848381871474851},{"acceleration":-2.9967122053977215,"curvature":0.5644294215509958,"pose":{"rotation":{"radians":1.8919771536540264},"translation":{"x":7.238754101762348,"y":1.9608511002920728}},"time":0.8910535000708455,"velocity":1.5658293611335297,"position":1.087666626020431,"holonomicRotation":-149.06141824033395,"angularVelocity":0.8494481159144552,"angularAcceleration":7.349990364052752,"curveRadius":1.7717006977632377},{"acceleration":-2.996727043168511,"curvature":0.5885824326365259,"pose":{"rotation":{"radians":1.895508581368475},"translation":{"x":7.236763530637383,"y":1.9667643779547563}},"time":0.8950690397183816,"velocity":1.553795884878843,"position":1.0939059550003405,"holonomicRotation":-149.38345485006593,"angularVelocity":0.879440380227738,"angularAcceleration":7.469049479236438,"curveRadius":1.6989973613730698},{"acceleration":-2.996740109902081,"curvature":0.6135043017688654,"pose":{"rotation":{"radians":1.8991706595407727},"translation":{"x":7.234762587177478,"y":1.9726372508038161}},"time":0.8990933251847727,"velocity":1.5417361472080127,"position":1.1001103413705595,"holonomicRotation":-149.70549145979794,"angularVelocity":0.909994632061142,"angularAcceleration":7.592466311989635,"curveRadius":1.6299804208654838},{"acceleration":-2.996751270296364,"curvature":0.63922780126053,"pose":{"rotation":{"radians":1.902966258507148},"translation":{"x":7.232750870499744,"y":1.9784691387241264}},"time":0.9031263454463359,"velocity":1.5296501886160423,"position":1.106279451574352,"holonomicRotation":-150.02752806952992,"angularVelocity":0.9411306465651733,"angularAcceleration":7.7202722735549445,"curveRadius":1.5643875282458657},{"acceleration":-2.9967603791803947,"curvature":0.665786991523138,"pose":{"rotation":{"radians":1.90689834898153},"translation":{"x":7.230727979721291,"y":1.9842594616005613}},"time":0.9071680948649375,"velocity":1.5175380340958013,"position":1.1124129600413646,"holonomicRotation":-150.3495646792619,"angularVelocity":0.9728684456005693,"angularAcceleration":7.852490530295214,"curveRadius":1.501981884194334},{"acceleration":-2.996767281070731,"curvature":0.693217257351192,"pose":{"rotation":{"radians":1.9109700047614795},"translation":{"x":7.2286935139592305,"y":1.9900076393179948}},"time":0.9112185736565188,"velocity":1.5053996917805197,"position":1.1185105495657746,"holonomicRotation":-150.67160128899388,"angularVelocity":1.005228267930235,"angularAcceleration":7.989135110872322,"curveRadius":1.442549199973809},{"acceleration":-2.996771809207564,"curvature":0.7215553421254193,"pose":{"rotation":{"radians":1.9151844054409823},"translation":{"x":7.226647072330671,"y":1.9957130917613017}},"time":0.9152777883945119,"velocity":1.4932351514861821,"position":1.1245719116999766,"holonomicRotation":-150.99363789872586,"angularVelocity":1.038230532634124,"angularAcceleration":8.13020912517814,"curveRadius":1.3858950819411744},{"acceleration":-2.996773784878003,"curvature":0.7508393809691852,"pose":{"rotation":{"radians":1.9195448391171097},"translation":{"x":7.224588253952727,"y":2.0013752388153563}},"time":0.9193457525508419,"velocity":1.481044383144669,"position":1.130596747164543,"holonomicRotation":-151.31567450845785,"angularVelocity":1.071895795675149,"angularAcceleration":8.275702967696875,"curveRadius":1.33184276870134},{"acceleration":-2.996773016407628,"curvature":0.7811089290392483,"pose":{"rotation":{"radians":1.924054705085479},"translation":{"x":7.222516657942507,"y":2.0069935003650325}},"time":0.923422487077444,"velocity":1.4688273351202905,"position":1.1365847662752449,"holonomicRotation":-151.63771111818983,"angularVelocity":1.1062447012286272,"angularAcceleration":8.425592917404867,"curveRadius":1.2802311724050885},{"acceleration":-2.996769298393652,"curvature":0.8124049879566265,"pose":{"rotation":{"radians":1.9287175164965078},"translation":{"x":7.220431883417123,"y":2.012567296295205}},"time":0.9275080210314444,"velocity":1.4565839323993974,"position":1.142535689387914,"holonomicRotation":-151.95974772792184,"angularVelocity":1.1412979217718067,"angularAcceleration":8.57983826296612,"curveRadius":1.2309131711699792},{"acceleration":-2.996762410578644,"curvature":0.8447700264946634,"pose":{"rotation":{"radians":1.9335369029678284},"translation":{"x":7.218333529493685,"y":2.0180960464907476}},"time":0.9316023922474341,"velocity":1.4443140746443641,"position":1.1484492473619867,"holonomicRotation":-152.28178433765382,"angularVelocity":1.1770760922945769,"angularAcceleration":8.73837974999569,"curveRadius":1.1837541208102005},{"acceleration":-2.996752116776235,"curvature":0.878247996451253,"pose":{"rotation":{"radians":1.938516613124657},"translation":{"x":7.216221195289304,"y":2.023579170836535}},"time":0.9357056480605402,"velocity":1.432017634100764,"position":1.1543251820435811,"holonomicRotation":-152.6038209473858,"angularVelocity":1.2135997324180834,"angularAcceleration":8.901136508927186,"curveRadius":1.1386305508702688},{"acceleration":-2.996738163903135,"curvature":0.912884341496053,"pose":{"rotation":{"radians":1.9436605170505705},"translation":{"x":7.214094479921091,"y":2.0290160892174414}},"time":0.9398178460843116,"velocity":1.4196944533454012,"position":1.1601632467689873,"holonomicRotation":-152.92585755711778,"angularVelocity":1.2508891585906625,"angularAcceleration":9.068003524397446,"curveRadius":1.0954290204618693},{"acceleration":-2.996720280448707,"curvature":0.9487259990043875,"pose":{"rotation":{"radians":1.9489726086203494},"translation":{"x":7.211952982506157,"y":2.034406221518341}},"time":0.9439390550477789,"velocity":1.407344342864612,"position":1.1659632068894858,"holonomicRotation":-153.24789416684976,"angularVelocity":1.2889643832351825,"angularAcceleration":9.238848353005297,"curveRadius":1.0540451100206176},{"acceleration":-2.9966981755402298,"curvature":0.985821392005402,"pose":{"rotation":{"radians":1.954457007689257},"translation":{"x":7.209796302161611,"y":2.0397489876241086}},"time":0.9480693556964203,"velocity":1.3949670784463957,"position":1.1717248403184264,"holonomicRotation":-153.56993077658177,"angularVelocity":1.3278450009956388,"angularAcceleration":9.413507893970289,"curveRadius":1.0143825322817912},{"acceleration":-2.996671537126648,"curvature":1.0242204111865714,"pose":{"rotation":{"radians":1.9601179621035354},"translation":{"x":7.207624038004567,"y":2.0450438074196176}},"time":0.9522088417621665,"velocity":1.3825623983748416,"position":1.1774479381015237,"holonomicRotation":-153.89196738631375,"angularVelocity":1.3675500592023406,"angularAcceleration":9.591784481473857,"curveRadius":0.9763523447472486},{"acceleration":-2.9966400308795365,"curvature":1.0639743845825318,"pose":{"rotation":{"radians":1.9659598495002462},"translation":{"x":7.205435789152135,"y":2.0502901007897427}},"time":0.9563576210080346,"velocity":1.370130000407391,"position":1.1831323050113551,"holonomicRotation":-154.21400399604573,"angularVelocity":1.40809791278456,"angularAcceleration":9.773442060722415,"curveRadius":0.9398722511466916},{"acceleration":-2.9966032982670705,"curvature":1.1051360318316912,"pose":{"rotation":{"radians":1.97198717885382},"translation":{"x":7.203231154721424,"y":2.0554872876193584}},"time":0.9605158163534581,"velocity":1.3576695385204562,"position":1.1887777601670542,"holonomicRotation":-154.5360406057777,"angularVelocity":1.4495060604133034,"angularAcceleration":9.958201620882738,"curveRadius":0.9048659813783874},{"acceleration":-2.996560955054165,"curvature":1.147759404490877,"pose":{"rotation":{"radians":1.978204591721479},"translation":{"x":7.201009733829546,"y":2.0606347877933393}},"time":0.9646835670869219,"velocity":1.34518061940216,"position":1.194384137680209,"holonomicRotation":-154.8580772155097,"angularVelocity":1.4917909599866395,"angularAcceleration":10.14573622021596,"curveRadius":0.8712627368482159},{"acceleration":-2.996512589389654,"curvature":1.1918998053188585,"pose":{"rotation":{"radians":1.9846168631475505},"translation":{"x":7.198771125593612,"y":2.0657320211965584}},"time":0.9688610301731088,"velocity":1.3326627986726907,"position":1.1999512873279985,"holonomicRotation":-155.18011382524168,"angularVelocity":1.5349678246767173,"angularAcceleration":10.335666360008352,"curveRadius":0.838996697153146},{"acceleration":-2.9964577598353297,"curvature":1.237613687284388,"pose":{"rotation":{"radians":1.9912289021600167},"translation":{"x":7.196514929130732,"y":2.070778407713891}},"time":0.9730483816624053,"velocity":1.3201155768094301,"position":1.205479075254595,"holonomicRotation":-155.50215043497366,"angularVelocity":1.5790503924419954,"angularAcceleration":10.52755372410455,"curveRadius":0.8080065777183124},{"acceleration":-2.996395993299322,"curvature":1.284958528875479,"pose":{"rotation":{"radians":1.9980457518047123},"translation":{"x":7.1942407435580185,"y":2.075773367230212}},"time":0.9772458182113298,"velocity":1.3075383947521044,"position":1.2109673847018496,"holonomicRotation":-155.82418704470567,"angularVelocity":1.6240506712227,"angularAcceleration":10.720895540930625,"curveRadius":0.778235232910701},{"acceleration":-2.9963267828837394,"curvature":1.3339926806231515,"pose":{"rotation":{"radians":2.005072588650177},"translation":{"x":7.191948167992581,"y":2.080716319630394}},"time":0.9814535587232495,"velocity":1.2949306291608147,"position":1.2164161167702952,"holonomicRotation":-156.14622365443765,"angularVelocity":1.669978656135977,"angularAcceleration":10.915118169281776,"curveRadius":0.749629300464278},{"acceleration":-2.9962495853861495,"curvature":1.384775182216893,"pose":{"rotation":{"radians":2.0123147216831345},"translation":{"x":7.189636801551529,"y":2.085606684799312}},"time":0.9856718461196228,"velocity":1.2822915872983915,"position":1.2218251912114715,"holonomicRotation":-156.46826026416963,"angularVelocity":1.7168420148859902,"angularAcceleration":11.109569914630304,"curveRadius":0.7221388806225537},{"acceleration":-2.9961638189104147,"curvature":1.4373655447388596,"pose":{"rotation":{"radians":2.0197775905197695},"translation":{"x":7.187306243351977,"y":2.090443882621841}},"time":0.9899009492529688,"velocity":1.2696205015038196,"position":1.2271945472525416,"holonomicRotation":-156.7902968739016,"angularVelocity":1.7646457419756543,"angularAcceleration":11.303514145289327,"curveRadius":0.6957172471959315},{"acceleration":-2.9960688600683985,"curvature":1.491823493231987,"pose":{"rotation":{"radians":2.0274667628406515},"translation":{"x":7.184956092511033,"y":2.0952273329828546}},"time":0.99414116497386,"velocity":1.256916523222485,"position":1.2325241444541575,"holonomicRotation":-157.11233348363362,"angularVelocity":1.8133917769792198,"angularAcceleration":11.496121474055697,"curveRadius":0.6703205872120519},{"acceleration":-2.9959640412069186,"curvature":1.5482086679911866,"pose":{"rotation":{"radians":2.035387930948043},"translation":{"x":7.182585948145809,"y":2.0999564557672277}},"time":0.9983928203654167,"velocity":1.2441787165537777,"position":1.2378139636024534,"holonomicRotation":-157.4343700933656,"angularVelocity":1.863078584196209,"angularAcceleration":11.686461540524071,"curveRadius":0.6459077646797496},{"acceleration":-2.99584864726154,"curvature":1.6065802764446286,"pose":{"rotation":{"radians":2.0435469073483814},"translation":{"x":7.1801954093734155,"y":2.1046306708598337}},"time":1.0026562751601382,"velocity":1.2314060512743503,"position":1.2430640076360082,"holonomicRotation":-157.75640670309758,"angularVelocity":1.9137006941974826,"angularAcceleration":11.87349519078918,"curveRadius":0.6224401075139586},{"acceleration":-2.9957219126297625,"curvature":1.666996693902621,"pose":{"rotation":{"radians":2.0519496192353643},"translation":{"x":7.177784075310963,"y":2.109249398145548}},"time":1.0069319243553927,"velocity":1.2185973952894087,"position":1.2482743026085166,"holonomicRotation":-158.07844331282956,"angularVelocity":1.965248200509312,"angularAcceleration":12.056065396815473,"curveRadius":0.5998812137166817},{"acceleration":-2.99558301767385,"curvature":1.729515005247142,"pose":{"rotation":{"radians":2.0606021017584877},"translation":{"x":7.1753515450755625,"y":2.1138120575092434}},"time":1.0112202010455653,"velocity":1.205751506461241,"position":1.2534448986878148,"holonomicRotation":-158.40047992256154,"angularVelocity":2.017706213536105,"angularAcceleration":12.232889064040599,"curveRadius":0.5781967759551778},{"acceleration":-2.995431084982091,"curvature":1.7941904843374985,"pose":{"rotation":{"radians":2.0695104899377785},"translation":{"x":7.172897417784326,"y":2.118318068835795}},"time":1.0155215794907628,"velocity":1.1928670237582244,"position":1.2585758711917954,"holonomicRotation":-158.72251653229353,"angularVelocity":2.0710542661590408,"angularAcceleration":12.402547997723623,"curveRadius":0.5573544218016785},{"acceleration":-2.9952651756457964,"curvature":1.8610760036545053,"pose":{"rotation":{"radians":2.0786810090867327},"translation":{"x":7.170421292554363,"y":2.122766852010078}},"time":1.0198365784440822,"velocity":1.179942457660399,"position":1.263667321661577,"holonomicRotation":-159.0445531420255,"angularVelocity":2.1252656717100056,"angularAcceleration":12.563480579586821,"curveRadius":0.5373235687507378},{"acceleration":-2.99508428486493,"curvature":1.9302213703393725,"pose":{"rotation":{"radians":2.088119963589415},"translation":{"x":7.167922768502784,"y":2.127157826916965}},"time":1.0241657647618618,"velocity":1.1669761797537648,"position":1.2687193789721418,"holonomicRotation":-159.36658975175752,"angularVelocity":2.180306831313163,"angularAcceleration":12.713973380426511,"curveRadius":0.5180752919672522},{"acceleration":-2.994887337774044,"curvature":2.0016725819543324,"pose":{"rotation":{"radians":2.097833723874352},"translation":{"x":7.1654014447467,"y":2.1314904134413317}},"time":1.0285097573240678,"velocity":1.1539664114338295,"position":1.2737322004804459,"holonomicRotation":-159.6886263614895,"angularVelocity":2.2361364909897596,"angularAcceleration":12.852153606875689,"curveRadius":0.49958220391051683},{"acceleration":-2.9946731845847285,"curvature":2.075470996528412,"pose":{"rotation":{"radians":2.107828711417565},"translation":{"x":7.1628569204032235,"y":2.1357640314680517}},"time":1.0328692312950476,"velocity":1.1409112116340412,"position":1.2787059732107635,"holonomicRotation":-160.01066297122148,"angularVelocity":2.2927049478326,"angularAcceleration":12.975982244510693,"curveRadius":0.48181834469027746},{"acceleration":-2.9944405955348627,"curvature":2.151652412397245,"pose":{"rotation":{"radians":2.118111381599233},"translation":{"x":7.160288794589465,"y":2.139978100881999}},"time":1.0372449227584435,"velocity":1.1278084634825132,"position":1.2836409150767696,"holonomicRotation":-160.33269958095346,"angularVelocity":2.349953205724399,"angularAcceleration":13.083248298171757,"curveRadius":0.464759082014487},{"acceleration":-2.994188255652403,"curvature":2.230246052970266,"pose":{"rotation":{"radians":2.1286882042341873},"translation":{"x":7.157696666422533,"y":2.144132041568048}},"time":1.0416376337641005,"velocity":1.1146558597789,"position":1.2885372761395404,"holonomicRotation":-160.65473619068547,"angularVelocity":2.40781208263721,"angularAcceleration":13.17156463020209,"curveRadius":0.4483810199633305},{"acceleration":-2.9939147588036104,"curvature":2.3112734535080874,"pose":{"rotation":{"radians":2.1395656415926787},"translation":{"x":7.155080135019539,"y":2.1482252734110743}},"time":1.0460482378294638,"velocity":1.1014508871723696,"position":1.2933953399003009,"holonomicRotation":-160.97677280041745,"angularVelocity":2.466201272499723,"angularAcceleration":13.23836576514461,"curveRadius":0.43266191565614365},{"acceleration":-2.993618601668452,"curvature":2.3947472453167205,"pose":{"rotation":{"radians":2.150750123729416},"translation":{"x":7.152438799497596,"y":2.1522572162959506}},"time":1.0504776859433618,"velocity":1.0881908089034793,"position":1.2982154246263595,"holonomicRotation":-161.29880941014943,"angularVelocity":2.52502836677202,"angularAcceleration":13.280908311741799,"curveRadius":0.41758060352951515},{"acceleration":-2.993298176929655,"curvature":2.480669839154114,"pose":{"rotation":{"radians":2.1622480209307917},"translation":{"x":7.149772258973814,"y":2.156227290107552}},"time":1.0549270131262964,"velocity":1.0748726459582374,"position":1.3029978847082144,"holonomicRotation":-161.6208460198814,"angularVelocity":2.5841878397874956,"angularAcceleration":13.2962739270739,"curveRadius":0.4031169260077717},{"acceleration":-2.9929517660729505,"curvature":2.5690320049345265,"pose":{"rotation":{"radians":2.174065613108602},"translation":{"x":7.147080112565302,"y":2.1601349147307527}},"time":1.0593973456086256,"velocity":1.061493156460317,"position":1.3077431120453091,"holonomicRotation":-161.9428826296134,"angularVelocity":2.6435600091321874,"angularAcceleration":13.281376626768676,"curveRadius":0.38925167069901323},{"acceleration":-2.992577531426788,"curvature":2.6598113553866622,"pose":{"rotation":{"radians":2.1862090559628227},"translation":{"x":7.1443619593891725,"y":2.163979510050426}},"time":1.063889908696516,"velocity":1.0480488131049792,"position":1.3124515374573718,"holonomicRotation":-162.26491923934537,"angularVelocity":2.703009978191208,"angularAcceleration":13.232973671369997,"curveRadius":0.37596651280354726},{"acceleration":-2.992173507522117,"curvature":2.752970733953824,"pose":{"rotation":{"radians":2.198684343768827},"translation":{"x":7.141617398562537,"y":2.1677604959514483}},"time":1.0684060354055265,"velocity":1.0345357784096647,"position":1.3171236321176747,"holonomicRotation":-162.58695584907736,"angularVelocity":2.7623865781076167,"angularAcceleration":13.14768245938286,"curveRadius":0.3632439632090812},{"acceleration":-2.9917375915012965,"curvature":2.848456519415962,"pose":{"rotation":{"radians":2.2114972686429066},"translation":{"x":7.138846029202504,"y":2.171477292318692}},"time":1.0729471759534028,"velocity":1.0209498775242922,"position":1.3217599090038497,"holonomicRotation":-162.90899245880937,"angularVelocity":2.8215213202488796,"angularAcceleration":13.022002185974408,"curveRadius":0.35106732126107254},{"acceleration":-2.9912675322830675,"curvature":2.94619686046173,"pose":{"rotation":{"radians":2.224653376182541},"translation":{"x":7.1360474504261875,"y":2.1751293190370316}},"time":1.0775149082176214,"velocity":1.0072865683061734,"position":1.3263609243612158,"holonomicRotation":-163.23102906854135,"angularVelocity":2.880227381690712,"angularAcceleration":12.85234292335991,"curveRadius":0.3394206318729426},{"acceleration":-2.990760918725731,"curvature":3.046099853582616,"pose":{"rotation":{"radians":2.238157917411031},"translation":{"x":7.133221261350695,"y":2.1787159959913422}},"time":1.0821109492797782,"velocity":0.993540908316616,"position":1.3309272791727715,"holonomicRotation":-163.55306567827333,"angularVelocity":2.938298645694073,"angularAcceleration":12.635062049708766,"curveRadius":0.3282886471445996},{"acceleration":-2.990215165777601,"curvature":3.148051691516538,"pose":{"rotation":{"radians":2.252015796986834},"translation":{"x":7.130367061093139,"y":2.1822367430664977}},"time":1.0867371681987281,"velocity":0.9797075183449648,"position":1.3354596206291764,"holonomicRotation":-163.8751022880053,"angularVelocity":2.9955088201811133,"angularAcceleration":12.366508262870259,"curveRadius":0.3176567915624859},{"acceleration":-2.9896274989059344,"curvature":3.251914805393465,"pose":{"rotation":{"radians":2.2662315177088543},"translation":{"x":7.127484448770631,"y":2.1856909801473723}},"time":1.0913956001782268,"velocity":0.9657805419972728,"position":1.339958643591194,"holonomicRotation":-164.19713889773732,"angularVelocity":3.0516106674053547,"angularAcceleration":12.043075324731687,"curveRadius":0.3075111310854299},{"acceleration":-2.988994935892174,"curvature":3.3575260374223888,"pose":{"rotation":{"radians":2.280809121393012},"translation":{"x":7.124573023500281,"y":2.1890781271188406}},"time":1.0960884623235578,"velocity":0.9517536008100382,"position":1.344425092036118,"holonomicRotation":-164.5191755074693,"angularVelocity":3.106335373320347,"angularAcceleration":11.6612643244674,"curveRadius":0.2978383455121949},{"acceleration":-2.988314265681112,"curvature":3.464694882609279,"pose":{"rotation":{"radians":2.295752126282114},"translation":{"x":7.121632384399199,"y":2.1923976038657766}},"time":1.1008181712165677,"velocity":0.9376197442525381,"position":1.3488597604787709,"holonomicRotation":-164.84121211720128,"angularVelocity":3.159392095185055,"angularAcceleration":11.217756328116046,"curveRadius":0.28862570410439575},{"acceleration":-2.980347528323872,"curvature":3.573201846564347,"pose":{"rotation":{"radians":2.3110634612290255},"translation":{"x":7.118662130584497,"y":2.195648830273054}},"time":1.1055871815964693,"velocity":0.9234064359542474,"position":1.3532634953567046,"holonomicRotation":-165.16324872693326,"angularVelocity":3.210589562027216,"angularAcceleration":10.735448817206633,"curveRadius":0.27986104422326585},{"acceleration":-2.908324744740049,"curvature":3.6827969731774846,"pose":{"rotation":{"radians":2.326745396987921},"translation":{"x":7.115661861173286,"y":2.198831226225549}},"time":1.1103965152651147,"velocity":0.9094193318400144,"position":1.3576371963682399,"holonomicRotation":-165.48528533666524,"angularVelocity":3.2607294147907147,"angularAcceleration":10.425530066750516,"curveRadius":0.2715327527645948},{"acceleration":-2.7806466529234304,"curvature":3.7931985994613635,"pose":{"rotation":{"radians":2.342799475058612},"translation":{"x":7.112631175282676,"y":2.201944211608134}},"time":1.1152457734481283,"velocity":0.8959352583042564,"position":1.3619818177510221,"holonomicRotation":-165.80732194639722,"angularVelocity":3.3106255564875267,"angularAcceleration":10.28943805706064,"curveRadius":0.26362975040167963},{"acceleration":-2.654342782158857,"curvature":3.9040924070266096,"pose":{"rotation":{"radians":2.3592264346344947},"translation":{"x":7.109569672029778,"y":2.204987206305684}},"time":1.1201345081692617,"velocity":0.8829588805833263,"position":1.366298369487863,"holonomicRotation":-166.1293585561292,"angularVelocity":3.3601658737731803,"angularAcceleration":10.133566272576834,"curveRadius":0.2561414781576875},{"acceleration":-2.5293149528969185,"curvature":4.015130835036642,"pose":{"rotation":{"radians":2.3760261383463535},"translation":{"x":7.106476950531704,"y":2.2079596302030735}},"time":1.1250622196637106,"velocity":0.8704951462168549,"position":1.3705879184257377,"holonomicRotation":-166.4513951658612,"angularVelocity":3.409230376166311,"angularAcceleration":9.956853693322543,"curveRadius":0.24905788655100555},{"acceleration":-2.4054698797089937,"curvature":4.1259329313001025,"pose":{"rotation":{"radians":2.3931974976020522},"translation":{"x":7.103352609905563,"y":2.2108609031851763}},"time":1.130028353893179,"velocity":0.8585492599092767,"position":1.374851589293058,"holonomicRotation":-166.7734317755932,"angularVelocity":3.457691327351961,"angularAcceleration":9.758284602556374,"curveRadius":0.2423694269031404},{"acceleration":-2.2827188686706563,"curvature":4.236084715212355,"pose":{"rotation":{"radians":2.410738398472547},"translation":{"x":7.100196249268468,"y":2.213690445136867}},"time":1.1350323001983174,"velocity":0.8471266572607226,"position":1.379090565599642,"holonomicRotation":-167.09546838532518,"angularVelocity":3.5054134878470875,"angularAcceleration":9.536904991590832,"curveRadius":0.236067044742723},{"acceleration":-2.160977505351077,"curvature":4.3451401231849145,"pose":{"rotation":{"radians":2.4286456292033165},"translation":{"x":7.0970074677375266,"y":2.21644767594302}},"time":1.1400733891259005,"velocity":0.836232977485741,"position":1.3833060904033252,"holonomicRotation":-167.41750499505716,"angularVelocity":3.552254480730811,"angularAcceleration":9.291840226706867,"curveRadius":0.2301421753153997},{"acceleration":-2.040165388097039,"curvature":4.452622609804108,"pose":{"rotation":{"radians":2.446914810547547},"translation":{"x":7.093785864429853,"y":2.219132015488509}},"time":1.145150890470935,"velocity":0.8258740349835852,"position":1.3874994669267835,"holonomicRotation":-167.73954160478917,"angularVelocity":3.5980652889626974,"angularAcceleration":9.022313362198444,"curveRadius":0.22458674081161228},{"acceleration":-1.9202058781483107,"curvature":4.558027460721524,"pose":{"rotation":{"radians":2.465540330256674},"translation":{"x":7.090531038462556,"y":2.221742883658209}},"time":1.1502640115755747,"velocity":0.8160557897827722,"position":1.391672059008085,"holonomicRotation":-168.06157821452115,"angularVelocity":3.6426908981730217,"angularAcceleration":8.72766521603247,"curveRadius":0.21939314947472968},{"acceleration":-1.8010258542539903,"curvature":4.660824869974148,"pose":{"rotation":{"radians":2.4845152831423687},"translation":{"x":7.087242588952747,"y":2.224279700336994}},"time":1.15541189592724,"velocity":0.8067843169707135,"position":1.3958252913685876,"holonomicRotation":-168.38361482425313,"angularVelocity":3.6859710882115677,"angularAcceleration":8.40737419140849,"curveRadius":0.21455429626677794},{"acceleration":-1.6825555149752232,"curvature":4.760463814964758,"pose":{"rotation":{"radians":2.5038314182167136},"translation":{"x":7.083920115017537,"y":2.226741885409738}},"time":1.1605936220995883,"velocity":0.7980657750223373,"position":1.3999606496822763,"holonomicRotation":-168.7056514339851,"angularVelocity":3.7277413803575943,"angularAcceleration":8.061076706239051,"curveRadius":0.21006356499474896},{"acceleration":-1.5647281742013888,"curvature":4.856376740337784,"pose":{"rotation":{"radians":2.5234790944686663},"translation":{"x":7.080563215774037,"y":2.229128858761316}},"time":1.1658082030785706,"velocity":0.789906373247869,"position":1.4040796804313915,"holonomicRotation":-169.0276880437171,"angularVelocity":3.7678341425981885,"angularAcceleration":7.68858752068298,"curveRadius":0.20591483187328774},{"acceleration":-1.447480077941956,"curvature":4.9479850431314025,"pose":{"rotation":{"radians":2.543447246834471},"translation":{"x":7.077171490339358,"y":2.2314400402766017}},"time":1.171054586014254,"velocity":0.7823123384672126,"position":1.4081839905343005,"holonomicRotation":-169.34972465344907,"angularVelocity":3.806079847887335,"angularAcceleration":7.289918741732883,"curveRadius":0.2021024702546667},{"acceleration":-1.3307502423566024,"curvature":5.034705319093987,"pose":{"rotation":{"radians":2.563723363906406},"translation":{"x":7.07374453783061,"y":2.2336748498404693}},"time":1.176331652436487,"velocity":0.7752898810468941,"position":1.4122752467330701,"holonomicRotation":-169.67176126318105,"angularVelocity":3.842308481566319,"angularAcceleration":6.8652980236040895,"curveRadius":0.19862135648883486},{"acceleration":-1.214480304437972,"curvature":5.115956304097939,"pose":{"rotation":{"radians":2.584293478832671},"translation":{"x":7.070281957364903,"y":2.235832707337794}},"time":1.1816382189683483,"velocity":0.7688451605097589,"position":1.4163551747300147,"holonomicRotation":-169.99379787291304,"angularVelocity":3.8763510836545283,"angularAcceleration":6.415184259692916,"curveRadius":0.19546687668129392},{"acceleration":-1.0986143785178457,"curvature":5.191166407366568,"pose":{"rotation":{"radians":2.6051421747453163},"translation":{"x":7.06678334805935,"y":2.2379130326534487}},"time":1.1869730385658135,"velocity":0.7629842509931849,"position":1.4204255580647704,"holonomicRotation":-170.31583448264504,"angularVelocity":3.9080414120378975,"angularAcceleration":5.940281166850836,"curveRadius":0.19263493433401435},{"acceleration":-0.9830989299751816,"curvature":5.259781708289867,"pose":{"rotation":{"radians":2.6262526058500457},"translation":{"x":7.063248309031062,"y":2.2399152456723086}},"time":1.192334802305654,"velocity":0.757713106797768,"position":1.4244882367260006,"holonomicRotation":-170.63787109237703,"angularVelocity":3.9372177009346725,"angularAcceleration":5.441546907406879,"curveRadius":0.19012195856415756},{"acceleration":-0.8678826627854379,"curvature":5.32127425045976,"pose":{"rotation":{"radians":2.647606535090352},"translation":{"x":7.0596764393971485,"y":2.2418387662792485}},"time":1.1977221417359796,"velocity":0.753037528307648,"position":1.4285451054947673,"holonomicRotation":-170.959907702109,"angularVelocity":3.9637244908133864,"angularAcceleration":4.920200448018108,"curveRadius":0.18792491289348592},{"acceleration":-0.7529164034082402,"curvature":5.375150444531233,"pose":{"rotation":{"radians":2.669184388989669},"translation":{"x":7.05606733827472,"y":2.2436830143591413}},"time":1.203133631794532,"velocity":0.7489631286756833,"position":1.4325981120198181,"holonomicRotation":-171.28194431184102,"angularVelocity":3.9874144950547525,"angularAcceleration":4.37772295338986,"curveRadius":0.1860413043912876},{"acceleration":-0.6381530127691244,"curvature":5.420959369027576,"pose":{"rotation":{"radians":2.690965329941524},"translation":{"x":7.052420604780888,"y":2.245447409796862}},"time":1.2085677942908886,"velocity":0.7454953015067564,"position":1.4366492546284761,"holonomicRotation":-171.603980921573,"angularVelocity":4.008150467796795,"angularAcceleration":3.8158543760782164,"curveRadius":0.18446919298334127},{"acceleration":-0.5235472914945066,"curvature":5.45830073871972,"pose":{"rotation":{"radians":2.712927345842111},"translation":{"x":7.048735838032763,"y":2.2471313724772854}},"time":1.2140231019378689,"velocity":0.7426391899639105,"position":1.4407005798804335,"holonomicRotation":-171.92601753130498,"angularVelocity":4.025807034502174,"angularAcceleration":3.236584964214186,"curveRadius":0.18320720089794035},{"acceleration":-0.40905589305717466,"curvature":5.486832310808212,"pose":{"rotation":{"radians":2.735047356537781},"translation":{"x":7.045012637147456,"y":2.2487343222852854}},"time":1.2194979829067545,"velocity":0.7403996576398013,"position":1.444754179875415,"holonomicRotation":-172.24805414103696,"angularVelocity":4.040272440876885,"angularAcceleration":2.642140798479418,"curveRadius":0.18225452198168232},{"acceleration":-0.29463724901488153,"curvature":5.506276496635432,"pose":{"rotation":{"radians":2.7573013361544363},"translation":{"x":7.041250601242078,"y":2.250255679105736}},"time":1.2249908258704887,"velocity":0.7387812614996959,"position":1.4488121893293824,"holonomicRotation":-172.57009075076894,"angularVelocity":4.051450180459282,"angularAcceleration":2.034964344729442,"curveRadius":0.18161093083702612},{"acceleration":-0.18025149443295832,"curvature":5.516425965174217,"pose":{"rotation":{"radians":2.7796644499415555},"translation":{"x":7.037449329433741,"y":2.251694862823512}},"time":1.230499985488377,"velocity":0.7377882272455019,"position":1.4528767824374766,"holonomicRotation":-172.89212736050092,"angularVelocity":4.059260456804741,"angularAcceleration":1.417689246123613,"curveRadius":0.18127679158808732},{"acceleration":-0.06586039671404756,"curvature":5.517148045296719,"pose":{"rotation":{"radians":2.8021112038716574},"translation":{"x":7.0336084208395535,"y":2.2530512933234865}},"time":1.2360237882761005,"velocity":0.7374244274025322,"position":1.4569501695452982,"holonomicRotation":-173.2141639702329,"angularVelocity":4.063641442809808,"angularAcceleration":0.793110502569672,"curveRadius":0.1812530662200526},{"acceleration":0.048572707509591646,"curvature":5.508387772999522,"pose":{"rotation":{"radians":2.8246156048603384},"translation":{"x":7.029727474576628,"y":2.2543243904905355}},"time":1.2415605387962758,"velocity":0.7376933623661023,"position":1.4610345936531086,"holonomicRotation":-173.53620057996488,"angularVelocity":4.064550300158437,"angularAcceleration":0.16414995498127535,"curveRadius":0.18154132229065326},{"acceleration":0.16308298250283118,"curvature":5.490169465449957,"pose":{"rotation":{"radians":2.84715132916968},"translation":{"x":7.0258060897620735,"y":2.2555135742095316}},"time":1.2471085260971568,"velocity":0.7385981446820178,"position":1.4651323267802587,"holonomicRotation":-173.85823718969687,"angularVelocity":4.061963931633936,"angularAcceleration":-0.46618140674021447,"curveRadius":0.18214374005995154},{"acceleration":0.2777041519904984,"curvature":5.462596763218019,"pose":{"rotation":{"radians":2.869691896293592},"translation":{"x":7.021843865513004,"y":2.2566182643653505}},"time":1.2526660303216974,"velocity":0.7401414866798774,"position":1.46924566621924,"holonomicRotation":-174.18027379942887,"angularVelocity":4.055879440339047,"angularAcceleration":-1.0948244120123387,"curveRadius":0.18306311875945597},{"acceleration":0.39246856073119724,"curvature":5.425851122445107,"pose":{"rotation":{"radians":2.8922108454783864},"translation":{"x":7.017840400946527,"y":2.2576378808428665}},"time":1.258231329405297,"velocity":0.7423256916012564,"position":1.4733769307104407,"holonomicRotation":-174.50231040916086,"angularVelocity":4.046314285454347,"angularAcceleration":-1.7187135392036321,"curveRadius":0.184302882153051},{"acceleration":0.507407242846165,"curvature":5.380188804845341,"pose":{"rotation":{"radians":2.914681911924525},"translation":{"x":7.013795295179755,"y":2.2585718435269526}},"time":1.263802705778356,"velocity":0.7451526483255686,"position":1.4775284565696443,"holonomicRotation":-174.82434701889287,"angularVelocity":4.033306124281855,"angularAcceleration":-2.3348200339496707,"curveRadius":0.18586708315875655},{"acceleration":0.6225499715571824,"curvature":5.325936457532602,"pose":{"rotation":{"radians":2.937079199746966},"translation":{"x":7.0097081473298,"y":2.259419572302484}},"time":1.269378452990928,"velocity":0.7486238295941653,"position":1.4817025938007689,"holonomicRotation":-175.14638362862485,"angularVelocity":4.016912347091427,"angularAcceleration":-2.9401937651447962,"curveRadius":0.18776040757784027},{"acceleration":0.7379253273072149,"curvature":5.263485423927997,"pose":{"rotation":{"radians":2.959377348861391},"translation":{"x":7.005578556513771,"y":2.2601804870543347}},"time":1.274956882178268,"velocity":0.7527402937780933,"position":1.4859017022260674,"holonomicRotation":-175.46842023835683,"angularVelocity":3.9972093156671664,"angularAcceleration":-3.532003501805855,"curveRadius":0.1899881769319553},{"acceleration":0.853560758427159,"curvature":5.193284969287618,"pose":{"rotation":{"radians":2.9815516931481336},"translation":{"x":7.001406121848778,"y":2.2608540076673793}},"time":1.280536328290769,"velocity":0.757502690033483,"position":1.4901281476651838,"holonomicRotation":-175.7904568480888,"angularVelocity":3.974291325631845,"angularAcceleration":-4.107574403124499,"curveRadius":0.19255635034739363},{"acceleration":0.9694826385683496,"curvature":5.115834632359243,"pose":{"rotation":{"radians":3.003578407514482},"translation":{"x":6.997190442451934,"y":2.2614395540264915}},"time":1.2861151560179873,"velocity":0.762911266658585,"position":1.494384298193026,"holonomicRotation":-176.1124934578208,"angularVelocity":3.9482693216860922,"angularAcceleration":-4.664421491058904,"curveRadius":0.19547152554046401},{"acceleration":1.085716325202286,"curvature":5.031675937306214,"pose":{"rotation":{"radians":3.025434641797363},"translation":{"x":6.992931117440349,"y":2.261936546016547}},"time":1.291691765344053,"velocity":0.7689658824431698,"position":1.4986725205044849,"holonomicRotation":-176.43453006755277,"angularVelocity":3.9192693991890324,"angularAcceleration":-5.200278664225467,"curveRadius":0.19874093889587127},{"acceleration":1.2022862253379618,"curvature":4.941383706505425,"pose":{"rotation":{"radians":3.047098639828428},"translation":{"x":6.988627745931134,"y":2.2623444035224183}},"time":1.297264596680273,"velocity":0.7756660207948388,"position":1.5029951764116114,"holonomicRotation":-176.75656667728475,"angularVelocity":3.8874311322257986,"angularAcceleration":-5.71312229679454,"curveRadius":0.20237246475789386},{"acceleration":1.319215849222996,"curvature":4.8455572194285015,"pose":{"rotation":{"radians":3.0685498423817217},"translation":{"x":6.984279927041399,"y":2.262662546428981}},"time":1.3028321355309314,"velocity":0.7830108062877922,"position":1.507354619496104,"holonomicRotation":-177.07860328701673,"angularVelocity":3.852905768364197,"angularAcceleration":-6.201189571855201,"curveRadius":0.20637461384016897},{"acceleration":1.4365278670387054,"curvature":4.744811443474515,"pose":{"rotation":{"radians":3.0897689731626},"translation":{"x":6.9798872598882555,"y":2.2628903946211087}},"time":1.3083929166583563,"velocity":0.7909990233398411,"position":1.5117531919369038,"holonomicRotation":-177.40063989674871,"angularVelocity":3.815854336763722,"angularAcceleration":-6.662990459693247,"curveRadius":0.21075653098402647},{"acceleration":1.554244170363973,"curvature":4.639768550708871,"pose":{"rotation":{"radians":3.1107381073980163},"translation":{"x":6.9754493435888145,"y":2.2630273679836757}},"time":1.3139455277235217,"velocity":0.7996291367181728,"position":1.5161932215294738,"holonomicRotation":-177.72267650648072,"angularVelocity":3.7764457098332107,"angularAcceleration":-7.097314482864431,"curveRadius":0.21552799219849414},{"acceleration":1.6723859206384766,"curvature":4.531049902698091,"pose":{"rotation":{"radians":3.131440723006267},"translation":{"x":6.970965777260187,"y":2.2630728864015563}},"time":1.319488612389136,"velocity":0.8088993134698533,"position":1.5206770189099945,"holonomicRotation":-178.0447131162127,"angularVelocity":3.734854662544831,"angularAcceleration":-7.503231467197882,"curveRadius":0.22069940112655415},{"acceleration":1.790973604472017,"curvature":4.419268656620069,"pose":{"rotation":{"radians":-3.131323572489665},"translation":{"x":6.966436160019483,"y":2.263026369759625}},"time":1.3250208728816364,"velocity":0.8188074459849848,"position":1.5252068749943823,"holonomicRotation":-178.3667497259447,"angularVelocity":-1132.0443612490576,"angularAcceleration":-205301.10927554715,"curveRadius":0.22628178499670956},{"acceleration":1.9100270835742397,"curvature":4.305023111274032,"pose":{"rotation":{"radians":-3.111197795552586},"translation":{"x":6.961860090983815,"y":2.2628872379427563}},"time":1.3305410720177067,"velocity":0.8293511758416021,"position":1.529785058638762,"holonomicRotation":-178.6887863356767,"angularVelocity":3.645842557666582,"angularAcceleration":205733.55703526334,"curveRadius":0.2322867901408453},{"acceleration":2.029565639787156,"curvature":4.188890877053761,"pose":{"rotation":{"radians":-3.0913794274591933},"translation":{"x":6.957237169270291,"y":2.2626549108358245}},"time":1.336048034709271,"velocity":0.8405279180999907,"position":1.5344138145249568,"holonomicRotation":-179.01082294540868,"angularVelocity":3.598783794876797,"angularAcceleration":-8.545320792143933,"curveRadius":0.23872667714451085},{"acceleration":2.1496080233923993,"curvature":4.07142391884588,"pose":{"rotation":{"radians":-3.0718791975862083},"translation":{"x":6.952566993996025,"y":2.262328808323703}},"time":1.341540648967736,"velocity":0.8523348857793867,"position":1.5390953612715759,"holonomicRotation":-179.33285955514066,"angularVelocity":3.550263855309307,"angularAcceleration":-8.833669594166835,"curveRadius":0.24561431576092635},{"acceleration":2.270172491875998,"curvature":3.9531444919530827,"pose":{"rotation":{"radians":-3.052706415489551},"translation":{"x":6.947849164278125,"y":2.261908350291267}},"time":1.347017866434606,"velocity":0.8647691142046977,"position":1.5438318897687076,"holonomicRotation":-179.65489616487264,"angularVelocity":3.500460263377815,"angularAcceleration":-9.09286370912575,"curveRadius":0.25296317957402614},{"acceleration":2.391276846416348,"curvature":3.834541959626503,"pose":{"rotation":{"radians":-3.03386900721519},"translation":{"x":6.943083279233704,"y":2.261392956623391}},"time":1.352478702470271,"velocity":0.8778274849788593,"position":1.5486255617317772,"holonomicRotation":-179.97693277460462,"angularVelocity":3.4495465806578163,"angularAcceleration":-9.323422711738539,"curveRadius":0.26078734058171665},{"acceleration":2.512938475481102,"curvature":3.7160704595155027,"pose":{"rotation":{"radians":-3.0153735614778236},"translation":{"x":6.938268937979871,"y":2.260782047204948}},"time":1.3579222358361498,"velocity":0.8915067494165415,"position":1.5534785084681324,"holonomicRotation":-180.2989693843366,"angularVelocity":3.397691259375629,"angularAcceleration":-9.526040862948767,"curveRadius":0.26910146373553395},{"acceleration":2.6351743778853467,"curvature":3.5981473674183575,"pose":{"rotation":{"radians":-2.9972253841399588},"translation":{"x":6.93340573963374,"y":2.2600750419208135}},"time":1.363347608008405,"velocity":0.9058035511553607,"position":1.5583928298481007,"holonomicRotation":-180.62100599406858,"angularVelocity":3.345056663701829,"angularAcceleration":-9.701564059138171,"curveRadius":0.2779208014255103},{"acceleration":2.7580011981748718,"curvature":3.481152488655477,"pose":{"rotation":{"radians":-2.979428559442473},"translation":{"x":6.9284932833124175,"y":2.2592713606558616}},"time":1.3687540221624583,"velocity":0.9207144478700693,"position":1.5633705934709068,"holonomicRotation":-180.94304260380056,"angularVelocity":3.2917982585819705,"angularAcceleration":-9.850966574569522,"curveRadius":0.28726118814353613},{"acceleration":2.912712029070569,"curvature":3.326862298565089,"pose":{"rotation":{"radians":-2.961986016503454},"translation":{"x":6.923531168133017,"y":2.258370423294966}},"time":1.3741397886506914,"velocity":0.9364016347061109,"position":1.5684138340146336,"holonomicRotation":-181.26507921353257,"angularVelocity":3.2386370588342106,"angularAcceleration":-9.870684119689827,"curveRadius":0.30058352593412435},{"acceleration":2.254086743084202,"curvature":1.4358131324229562,"pose":{"rotation":{"radians":-2.9364784217189537},"translation":{"x":6.9134563576684265,"y":2.2562744598248425}},"time":1.3848529457329888,"velocity":0.960550020061896,"position":1.5787043572649606,"holonomicRotation":178.09084756700352,"angularVelocity":2.3809596544280813,"angularAcceleration":-80.05832434057862,"curveRadius":0.6964694620897394},{"acceleration":2.7705038823128803,"curvature":-0.01719734277298267,"pose":{"rotation":{"radians":-2.9200503113757543},"translation":{"x":6.901171557749045,"y":2.253507438252807}},"time":1.397501262552154,"velocity":0.9955922309141163,"position":1.5912969232242618,"holonomicRotation":178.14372390663158,"angularVelocity":1.298837669713252,"angularAcceleration":-85.55462360613588,"curveRadius":-58.14851824498246},{"acceleration":3.065680518884025,"curvature":-0.017452667583007554,"pose":{"rotation":{"radians":-2.9202661985073517},"translation":{"x":6.888962353885816,"y":2.250760213292275}},"time":1.4096189806944581,"velocity":1.0327412833563059,"position":1.603811391009895,"holonomicRotation":178.19660024625966,"angularVelocity":-0.01781582382607871,"angularAcceleration":-108.65523344223986,"curveRadius":-57.297831133484166},{"acceleration":3.0614554234635705,"curvature":-0.01771168515861627,"pose":{"rotation":{"radians":-2.9204839314053577},"translation":{"x":6.876828350694748,"y":2.248032685032641}},"time":1.4212597723176652,"velocity":1.0683790480045825,"position":1.6162481688823167,"holonomicRotation":178.24947658588772,"angularVelocity":-0.018704303371593827,"angularAcceleration":-0.07632466710802073,"curveRadius":-56.45990153079964},{"acceleration":3.0578013621241333,"curvature":-0.01797443790097832,"pose":{"rotation":{"radians":-2.9207035233100846},"translation":{"x":6.864769152791852,"y":2.245324753563299}},"time":1.4324686387748031,"velocity":1.1026535351250863,"position":1.6286076651060248,"holonomicRotation":178.30235292551578,"angularVelocity":-0.019590910960237247,"angularAcceleration":-0.07909877346061331,"curveRadius":-55.63456312286526},{"acceleration":3.054609996844024,"curvature":-0.018240964425123476,"pose":{"rotation":{"radians":-2.920924987425226},"translation":{"x":6.852784364793138,"y":2.2426363189736414}},"time":1.4432837626450055,"velocity":1.1356895206161128,"position":1.6408902879495788,"holonomicRotation":178.35522926514386,"angularVelocity":-0.020477261083565484,"angularAcceleration":-0.08195468992919219,"curveRadius":-54.821662752803206},{"acceleration":3.051798771660241,"curvature":-0.018511306543599372,"pose":{"rotation":{"radians":-2.9211483369124482},"translation":{"x":6.840873591314614,"y":2.239967281353063}},"time":1.453737879571476,"velocity":1.167593381811108,"position":1.6530964456856052,"holonomicRotation":178.40810560477192,"angularVelocity":-0.021364739728213934,"angularAcceleration":-0.0848927413850996,"curveRadius":-54.02103831216433},{"acceleration":3.0493036697326197,"curvature":-0.01878550430312596,"pose":{"rotation":{"radians":-2.921373584885046},"translation":{"x":6.829036436972293,"y":2.237317540790957}},"time":1.4638593139268459,"velocity":1.1984567087338953,"position":1.665226546590808,"holonomicRotation":178.4609819444,"angularVelocity":-0.02225455055966697,"angularAcceleration":-0.08791351109054478,"curveRadius":-53.232534185073604},{"acceleration":3.047074283240302,"curvature":-0.01906359845083211,"pose":{"rotation":{"radians":-2.921600744402765},"translation":{"x":6.817272506382184,"y":2.2346869973767176}},"time":1.4736727738864133,"velocity":1.2283590502063015,"position":1.6772809989459798,"holonomicRotation":178.51385828402806,"angularVelocity":-0.023147749993856694,"angularAcceleration":-0.09101778963482905,"curveRadius":-52.455993687611006},{"acceleration":3.0450703778036976,"curvature":-0.019345627484636422,"pose":{"rotation":{"radians":-2.921829828464789},"translation":{"x":6.805581404160296,"y":2.2320755511997374}},"time":1.4831999709324444,"velocity":1.2573700357146698,"position":1.6892602110360087,"holonomicRotation":178.56673462365612,"angularVelocity":-0.024045273853076872,"angularAcceleration":-0.09420649692493487,"curveRadius":-51.691267227913016},{"acceleration":3.0432594479946573,"curvature":-0.019631631820862243,"pose":{"rotation":{"radians":-2.9220608500042844},"translation":{"x":6.793962734922641,"y":2.229483102349412}},"time":1.4924601090042626,"velocity":1.2855510383914657,"position":1.701164591149883,"holonomicRotation":178.6196109632842,"angularVelocity":-0.024947958410951553,"angularAcceleration":-0.09748068018789674,"curveRadius":-50.93820061036978},{"acceleration":3.0416149455788535,"curvature":-0.019921649570402444,"pose":{"rotation":{"radians":-2.922293821880782},"translation":{"x":6.782416103285226,"y":2.226909550915134}},"time":1.5014702753545157,"velocity":1.3129564950245471,"position":1.7129945475806994,"holonomicRotation":178.67248730291226,"angularVelocity":-0.02585655663182821,"angularAcceleration":-0.10084144793299352,"curveRadius":-50.196646440649076},{"acceleration":3.040114974009502,"curvature":-0.020215720312596133,"pose":{"rotation":{"radians":-2.9225287568743363},"translation":{"x":6.770941113864065,"y":2.2243547969862973}},"time":1.5102457562461895,"velocity":1.339634965887459,"position":1.7247504886256628,"holonomicRotation":178.72536364254032,"angularVelocity":-0.02677175148057499,"angularAcceleration":-0.10428999390963507,"curveRadius":-49.466454053428606},{"acceleration":3.0387413117972275,"curvature":-0.020513881254071983,"pose":{"rotation":{"radians":-2.92276566767796},"translation":{"x":6.759537371275165,"y":2.2218187406522953}},"time":1.5188002944499657,"velocity":1.3656299945306212,"position":1.7364328225860977,"holonomicRotation":178.7782399821684,"angularVelocity":-0.02769416629867642,"angularAcceleration":-0.10782754090621231,"curveRadius":-48.747479212472335},{"acceleration":3.037478672206547,"curvature":-0.020816169741813897,"pose":{"rotation":{"radians":-2.9230045668906284},"translation":{"x":6.748204480134536,"y":2.219301282002523}},"time":1.527146301154075,"velocity":1.3909808118924458,"position":1.7480419577674393,"holonomicRotation":178.83111632179646,"angularVelocity":-0.028624373444447668,"angularAcceleration":-0.11145535568684029,"curveRadius":-48.039577520896074},{"acceleration":3.0363141349160916,"curvature":-0.02112262324804816,"pose":{"rotation":{"radians":-2.9232454670093984},"translation":{"x":6.736942045058191,"y":2.2168023211263725}},"time":1.5352950317890923,"velocity":1.415722917901173,"position":1.7595783024792369,"holonomicRotation":178.88399266142451,"angularVelocity":-0.029562901212461933,"angularAcceleration":-0.11517471984914353,"curveRadius":-47.34260457409831},{"acceleration":3.0352367048887063,"curvature":-0.02143327761911806,"pose":{"rotation":{"radians":-2.923488380422552},"translation":{"x":6.725749670662136,"y":2.214321758113239}},"time":1.543256733013125,"velocity":1.4398885656897145,"position":1.7710422650351594,"holonomicRotation":178.9368690010526,"angularVelocity":-0.030510239748810154,"angularAcceleration":-0.11898694885568441,"curveRadius":-46.656419879898344},{"acceleration":3.034236966455498,"curvature":-0.021748168764309656,"pose":{"rotation":{"radians":-2.923733319400612},"translation":{"x":6.714626961562384,"y":2.211859493052515}},"time":1.5510407664428723,"velocity":1.4635071676703788,"position":1.7824342537529803,"holonomicRotation":178.98974534068066,"angularVelocity":-0.03146684559756058,"angularAcceleration":-0.12289333767435916,"curveRadius":-45.98088284293037},{"acceleration":3.033306809273121,"curvature":-0.022067331762575245,"pose":{"rotation":{"radians":-2.923980296089142},"translation":{"x":6.703573522374945,"y":2.209415426033595}},"time":1.5586557134802104,"velocity":1.4866056383709907,"position":1.7937546769545836,"holonomicRotation":179.0426216803087,"angularVelocity":-0.032433145932441294,"angularAcceleration":-0.12689521412856694,"curveRadius":-45.31585471044283},{"acceleration":3.03243920957437,"curvature":-0.022390799945522864,"pose":{"rotation":{"radians":-2.924229322499565},"translation":{"x":6.6925889577158255,"y":2.2069894571458724}},"time":1.5661094646532974,"velocity":1.5092086856866707,"position":1.8050039429659537,"holonomicRotation":179.0954980199368,"angularVelocity":-0.03340954167105208,"angularAcceleration":-0.13099387354601089,"curveRadius":-44.661200244431384},{"acceleration":3.031628053866683,"curvature":-0.022718606163043043,"pose":{"rotation":{"radians":-2.9244804105009656},"translation":{"x":6.681672872201039,"y":2.2045814864787414}},"time":1.573409296183161,"velocity":1.5313390597411056,"position":1.8161824601171634,"holonomicRotation":179.14837435956485,"angularVelocity":-0.03439641043408118,"angularAcceleration":-0.13519062172761448,"curveRadius":-44.016784868903024},{"acceleration":3.030867995991831,"curvature":-0.02305078319527449,"pose":{"rotation":{"radians":-2.9247335718108696},"translation":{"x":6.670824870446596,"y":2.2021914141215952}},"time":1.5805619359427099,"velocity":1.5530177666751812,"position":1.8272906367423702,"holonomicRotation":179.20125069919294,"angularVelocity":-0.03539410880660687,"angularAcceleration":-0.13948673581578586,"curveRadius":-43.38247388509577},{"acceleration":3.030154340243041,"curvature":-0.023387361948290344,"pose":{"rotation":{"radians":-2.924988817986395},"translation":{"x":6.660044557068504,"y":2.199819140163828}},"time":1.5875736205533362,"velocity":1.5742642532304858,"position":1.8383288811798055,"holonomicRotation":179.254127038821,"angularVelocity":-0.03640297442052452,"angularAcceleration":-0.14388348448940544,"curveRadius":-42.758135877445625},{"acceleration":3.0294829451482794,"curvature":-0.023728372285284113,"pose":{"rotation":{"radians":-2.9252461604143494},"translation":{"x":6.649331536682775,"y":2.1974645646948328}},"time":1.5944501450345374,"velocity":1.5950965668681796,"position":1.8492976017717546,"holonomicRotation":179.30700337844905,"angularVelocity":-0.03742332753382905,"angularAcceleration":-0.14838209564932495,"curveRadius":-42.14364086912869},{"acceleration":3.0288501440506255,"curvature":-0.02407384343039963,"pose":{"rotation":{"radians":-2.9255056103019488},"translation":{"x":6.638685413905418,"y":2.1951275878040044}},"time":1.601196906162146,"velocity":1.6155314952814122,"position":1.8601972068645467,"holonomicRotation":179.35987971807714,"angularVelocity":-0.03845547258783217,"angularAcceleration":-0.1529837850312272,"curveRadius":-41.538859504969366},{"acceleration":3.0282526786887853,"curvature":-0.02442380302884696,"pose":{"rotation":{"radians":-2.9257671786664337},"translation":{"x":6.628105793352443,"y":2.192808109580736}},"time":1.6078189404844492,"velocity":1.6355846884562957,"position":1.8710281048085378,"holonomicRotation":179.4127560577052,"angularVelocity":-0.039499699299943174,"angularAcceleration":-0.15768971607320587,"curveRadius":-40.94366462171758},{"acceleration":3.027687643859291,"curvature":-0.02477827663443619,"pose":{"rotation":{"radians":-2.9260308763250653},"translation":{"x":6.61759227963986,"y":2.190506030114421}},"time":1.614320957780576,"velocity":1.655270765883938,"position":1.8817907039580881,"holonomicRotation":179.46563239733325,"angularVelocity":-0.040556283784225024,"angularAcceleration":-0.16250102639856948,"curveRadius":-40.35793185916032},{"acceleration":3.027152440716995,"curvature":-0.025137290827619476,"pose":{"rotation":{"radians":-2.926296713884593},"translation":{"x":6.607144477383679,"y":2.188221249494454}},"time":1.620707370612841,"velocity":1.6746034110765555,"position":1.8924854126715422,"holonomicRotation":179.51850873696134,"angularVelocity":-0.04162548938030513,"angularAcceleration":-0.16741880366366715,"curveRadius":-39.781534408682376},{"acceleration":3.0266447372871648,"curvature":-0.025500867722737904,"pose":{"rotation":{"radians":-2.9265647017299705},"translation":{"x":6.596761991199911,"y":2.185953667810228}},"time":1.6269823205172878,"velocity":1.69359545518159,"position":1.9031126393112054,"holonomicRotation":179.5713850765894,"angularVelocity":-0.04270756730465762,"angularAcceleration":-0.17244407379024207,"curveRadius":-39.21435187510689},{"acceleration":3.02616243504284,"curvature":-0.025869030358618747,"pose":{"rotation":{"radians":-2.926834850013862},"translation":{"x":6.586444425704565,"y":2.1837031851511366}},"time":1.6331497012891838,"velocity":1.7122589511961073,"position":1.9136727922433192,"holonomicRotation":179.62426141621745,"angularVelocity":-0.043802757423769115,"angularAcceleration":-0.1775778340299878,"curveRadius":-38.65626141131461},{"acceleration":3.025703640209834,"curvature":-0.02624179761342615,"pose":{"rotation":{"radians":-2.9271071686448464},"translation":{"x":6.576191385513652,"y":2.1814697016065745}},"time":1.6392131797485743,"velocity":1.730605240043019,"position":1.9241662798380283,"holonomicRotation":179.67713775584554,"angularVelocity":-0.04491128859587147,"angularAcceleration":-0.1828209961537142,"curveRadius":-38.10714550623497},{"acceleration":3.025266639376772,"curvature":-0.026619189652631974,"pose":{"rotation":{"radians":-2.927381667275493},"translation":{"x":6.566002475243181,"y":2.1792531172659344}},"time":1.6451762143120316,"velocity":1.7486450095772972,"position":1.934593510469355,"holonomicRotation":179.7300140954736,"angularVelocity":-0.04603337910010427,"angularAcceleration":-0.1881744089006608,"curveRadius":-37.56688362979994},{"acceleration":3.0248498783758393,"curvature":-0.02700122280383119,"pose":{"rotation":{"radians":-2.927658355290966},"translation":{"x":6.555877299509161,"y":2.177053332218611}},"time":1.651042071647937,"velocity":1.7663883474263806,"position":1.9449548925151638,"holonomicRotation":179.78289043510168,"angularVelocity":-0.04716923710015097,"angularAcceleration":-0.1936388723765947,"curveRadius":-37.03535974148958},{"acceleration":3.024451944118721,"curvature":-0.02738791178321364,"pose":{"rotation":{"radians":-2.9279372417957203},"translation":{"x":6.545815462927606,"y":2.174870246553997}},"time":1.6568138416520874,"velocity":1.7838447884364395,"position":1.9552508343571213,"holonomicRotation":179.83576677472973,"angularVelocity":-0.04831906062676235,"angularAcceleration":-0.19921506327947167,"curveRadius":-36.51245877799677},{"acceleration":3.0240715489057757,"curvature":-0.027779269631357913,"pose":{"rotation":{"radians":-2.9282183356022093},"translation":{"x":6.535816570114522,"y":2.172703760361488}},"time":1.6624944509465738,"velocity":1.8010233573843453,"position":1.9654817443806658,"holonomicRotation":179.8886431143578,"angularVelocity":-0.049483038159626645,"angularAcceleration":-0.20490364193750651,"curveRadius":-35.99806666159343},{"acceleration":3.0237075166932272,"curvature":-0.028175307173809113,"pose":{"rotation":{"radians":-2.9285016452162265},"translation":{"x":6.5258802256859205,"y":2.1705537737304748}},"time":1.6680866750764651,"velocity":1.817932607520931,"position":1.9756480309749607,"holonomicRotation":179.94151945398588,"angularVelocity":-0.050661348228657,"angularAcceleration":-0.2107050865025406,"curveRadius":-35.49207090560378},{"acceleration":3.0233587711347214,"curvature":-0.028576032941255564,"pose":{"rotation":{"radians":-2.9287871788253823},"translation":{"x":6.516006034257812,"y":2.1684201867503536}},"time":1.6735931495549614,"velocity":1.8345806554335222,"position":1.9857501025328483,"holonomicRotation":179.99439579361393,"angularVelocity":-0.05185416009297757,"angularAcceleration":-0.21661988427962545,"curveRadius":-34.994360555774975},{"acceleration":3.023024325235772,"curvature":-0.0289814530872548,"pose":{"rotation":{"radians":-2.9290749442839865},"translation":{"x":6.506193600446206,"y":2.166302899510517}},"time":1.6790163798874662,"velocity":1.8509752126500407,"position":1.9957883674508066,"holonomicRotation":180.047272133242,"angularVelocity":-0.05306163318925395,"angularAcceleration":-0.22264831516360956,"curveRadius":-34.50482613791959},{"acceleration":3.0227032721359413,"curvature":-0.029391571303473585,"pose":{"rotation":{"radians":-2.929364949100348},"translation":{"x":6.496442528867112,"y":2.16420181210036}},"time":1.684358750687896,"velocity":1.8671236143494636,"position":2.0057632341289002,"holonomicRotation":180.10014847287007,"angularVelocity":-0.0542839176079504,"angularAcceleration":-0.22879063703292524,"curveRadius":-34.02335961132561},{"acceleration":3.022394777066623,"curvature":-0.029806389215021812,"pose":{"rotation":{"radians":-2.929657200421309},"translation":{"x":6.486752424136541,"y":2.1621168246092743}},"time":1.689622533985953,"velocity":1.8830328454971212,"position":2.0156751109707205,"holonomicRotation":180.15302481249813,"angularVelocity":-0.0555211535909494,"angularAcceleration":-0.23504690693777658,"curveRadius":-33.549853784235644},{"acceleration":3.022098070335484,"curvature":-0.030225905332410426,"pose":{"rotation":{"radians":-2.9299517050192034},"translation":{"x":6.477122890870502,"y":2.1600478371266556}},"time":1.6948098968116423,"velocity":1.898709564682767,"position":2.0255244063833366,"holonomicRotation":180.2059011521262,"angularVelocity":-0.05677347195301277,"angularAcceleration":-0.24141715244238002,"curveRadius":-33.084203401104645},{"acceleration":3.021812440870055,"curvature":-0.030650115922095406,"pose":{"rotation":{"radians":-2.9302484692752593},"translation":{"x":6.467553533685007,"y":2.1579947497418965}},"time":1.699922908132614,"velocity":1.9141601259027885,"position":2.03531152877723,"holonomicRotation":180.25877749175427,"angularVelocity":-0.058040993345473996,"angularAcceleration":-0.24790115117921419,"curveRadius":-32.626304009477124},{"acceleration":3.021537230823119,"curvature":-0.031079013453407092,"pose":{"rotation":{"radians":-2.930547499165748},"translation":{"x":6.458043957196064,"y":2.155957462544391}},"time":1.7049635452107461,"velocity":1.9293905985014324,"position":2.045036886566236,"holonomicRotation":180.31165383138233,"angularVelocity":-0.05932382868548158,"angularAcceleration":-0.25449865168292274,"curveRadius":-32.176053512740225},{"acceleration":3.0212718305738346,"curvature":-0.031512587460762125,"pose":{"rotation":{"radians":-2.930848800245575},"translation":{"x":6.448593766019684,"y":2.153935875623533}},"time":1.709933699436455,"velocity":1.9444067854571738,"position":2.054700888167473,"holonomicRotation":180.36453017101041,"angularVelocity":-0.06062207853998013,"angularAcceleration":-0.26120916887914225,"curveRadius":-31.733351037744814},{"acceleration":3.0210156742974963,"curvature":-0.03195082543277132,"pose":{"rotation":{"radians":-2.931152377632918},"translation":{"x":6.439202564771876,"y":2.1519298890687164}},"time":1.7148351816923837,"velocity":1.9592142401796258,"position":2.0643039420012763,"holonomicRotation":180.41740651063847,"angularVelocity":-0.061935833181031255,"angularAcceleration":-0.2680321120130581,"curveRadius":-31.298095947603287},{"acceleration":3.0207682360538946,"curvature":-0.03239371124086689,"pose":{"rotation":{"radians":-2.9314582359924035},"translation":{"x":6.429869958068652,"y":2.1499394029693346}},"time":1.7196697272921708,"velocity":1.9738182819632168,"position":2.073846456491121,"holonomicRotation":180.47028285026653,"angularVelocity":-0.06326517211859131,"angularAcceleration":-0.27496667683072185,"curveRadius":-30.870189357569853},{"acceleration":3.0205290262580884,"curvature":-0.03284122401927583,"pose":{"rotation":{"radians":-2.9317663795192397},"translation":{"x":6.420595550526019,"y":2.1479643174147816}},"time":1.7244390005348502,"velocity":1.988224010226886,"position":2.083328840063549,"holonomicRotation":180.5231591898946,"angularVelocity":-0.06461016409767552,"angularAcceleration":-0.2820119357071236,"curveRadius":-30.449534993368694},{"acceleration":3.020297588603067,"curvature":-0.0332933405306814,"pose":{"rotation":{"radians":-2.932076811921572},"translation":{"x":6.41137894675999,"y":2.1460045324944503}},"time":1.729144598910915,"velocity":2.0024363176550493,"position":2.0927515011480797,"holonomicRotation":180.57603552952267,"angularVelocity":-0.06597086651326586,"angularAcceleration":-0.28916671310318054,"curveRadius":-30.03603675871613},{"acceleration":3.0200734970663956,"curvature":-0.0337500335625049,"pose":{"rotation":{"radians":-2.932389536404066},"translation":{"x":6.402219751386575,"y":2.1440599482977354}},"time":1.7337880569921715,"velocity":2.0164599023409906,"position":2.1021148481771346,"holonomicRotation":180.62891186915073,"angularVelocity":-0.06734732542464755,"angularAcceleration":-0.29642970546839625,"curveRadius":-29.62960016463405},{"acceleration":3.019856353603399,"curvature":-0.03421127281422397,"pose":{"rotation":{"radians":-2.9327045556496083},"translation":{"x":6.393117569021781,"y":2.1421304649140307}},"time":1.7383708500340298,"velocity":2.0302992790256957,"position":2.1114192895859434,"holonomicRotation":180.6817882087788,"angularVelocity":-0.0687395748978395,"angularAcceleration":-0.3037993338288306,"curveRadius":-29.23013140815479},{"acceleration":3.019645785587822,"curvature":-0.03467702274725662,"pose":{"rotation":{"radians":-2.933021871801601},"translation":{"x":6.384072004281621,"y":2.14021598243273}},"time":1.7428943973158786,"velocity":2.0439587895112377,"position":2.120665233812448,"holonomicRotation":180.73466454840687,"angularVelocity":-0.07014763684813267,"angularAcceleration":-0.3112738438577129,"curveRadius":-28.83753911887122},{"acceleration":3.0194414439691166,"curvature":-0.0351472439628508,"pose":{"rotation":{"radians":-2.9333414864459346},"translation":{"x":6.375082661782103,"y":2.1383164009432254}},"time":1.7473600652425219,"velocity":2.057442612323948,"position":2.129853089297212,"holonomicRotation":180.78754088803493,"angularVelocity":-0.07157152067374578,"angularAcceleration":-0.3188512556246887,"curveRadius":-28.451732973912808},{"acceleration":3.0192430012765303,"curvature":-0.03562189359247742,"pose":{"rotation":{"radians":-2.9336634005924727},"translation":{"x":6.3661491461392385,"y":2.1364316205349128}},"time":1.7517691702272917,"velocity":2.070754771691108,"position":2.1389832644833113,"holonomicRotation":180.840417227663,"angularVelocity":-0.07301122283320727,"angularAcceleration":-0.32652934426251357,"curveRadius":-28.07262329847559},{"acceleration":3.0190501498804547,"curvature":-0.03610092362376964,"pose":{"rotation":{"radians":-2.9339876146556394},"translation":{"x":6.357271061969037,"y":2.134561541297185}},"time":1.7561229813754058,"velocity":2.083899145890373,"position":2.148056167816234,"holonomicRotation":180.89329356729107,"angularVelocity":-0.07446672630878319,"angularAcceleration":-0.3343056062976922,"curveRadius":-27.700122313257882},{"acceleration":3.0188626006882866,"curvature":-0.036584281784102085,"pose":{"rotation":{"radians":-2.9343141284357297},"translation":{"x":6.3484480138875075,"y":2.1327060633194357}},"time":1.7604227229842662,"velocity":2.0968794750259847,"position":2.1570722077437687,"holonomicRotation":180.94616990691915,"angularVelocity":-0.07593800041785286,"angularAcceleration":-0.34217733131633893,"curveRadius":-27.334143277743827},{"acceleration":3.018680081288061,"curvature":-0.03707191035320334,"pose":{"rotation":{"radians":-2.9346429410991504},"translation":{"x":6.339679606510662,"y":2.130865086691059}},"time":1.764669576875792,"velocity":2.1096993682764746,"position":2.1660317927158834,"holonomicRotation":180.9990462465472,"angularVelocity":-0.0774250002046857,"angularAcceleration":-0.3501414988163319,"curveRadius":-26.974601267441592},{"acceleration":3.0185023353235385,"curvature":-0.03756374863545514,"pose":{"rotation":{"radians":-2.93497405115866},"translation":{"x":6.3309654444545105,"y":2.129038511501448}},"time":1.7688646845744185,"velocity":2.122362310661712,"position":2.174935331184615,"holonomicRotation":181.05192258617527,"angularVelocity":-0.07892766605682174,"angularAcceleration":-0.35819482122664964,"curveRadius":-26.621411236261284},{"acceleration":3.018329120697568,"curvature":-0.038059728078462786,"pose":{"rotation":{"radians":-2.9353074564531596},"translation":{"x":6.322305132335061,"y":2.127226237839997}},"time":1.773009149343097,"velocity":2.13487166936272,"position":2.1837832316039387,"holonomicRotation":181.10479892580335,"angularVelocity":-0.08044592320324118,"angularAcceleration":-0.3663337080082169,"curveRadius":-26.274491450344318},{"acceleration":3.018160208879943,"curvature":-0.038559777379562676,"pose":{"rotation":{"radians":-2.9356431541271406},"translation":{"x":6.313698274768325,"y":2.1254281657960994}},"time":1.7771040380884937,"velocity":2.1472306996338664,"position":2.1925759024296396,"holonomicRotation":181.1576752654314,"angularVelocity":-0.08197968122049391,"angularAcceleration":-0.37455425839760376,"curveRadius":-25.933759683218934},{"acceleration":3.0179953838424325,"curvature":-0.03906381755761448,"pose":{"rotation":{"radians":-2.9359811406101617},"translation":{"x":6.3051444763703115,"y":2.1236441954591494}},"time":1.7811503831455426,"velocity":2.1594425503374737,"position":2.201313752119179,"holonomicRotation":181.21055160505946,"angularVelocity":-0.08352883361548497,"angularAcceleration":-0.3828522711606994,"curveRadius":-25.599136554565334},{"acceleration":3.0178344412184157,"curvature":-0.03957176658641348,"pose":{"rotation":{"radians":-2.9363214115955034},"translation":{"x":6.296643341757032,"y":2.1218742269185404}},"time":1.7851491839505922,"velocity":2.171510269130524,"position":2.2099971891315513,"holonomicRotation":181.26342794468755,"angularVelocity":-0.08509325718651595,"angularAcceleration":-0.3912231809735259,"curveRadius":-25.27054226442695},{"acceleration":3.017677187453379,"curvature":-0.040083534947631366,"pose":{"rotation":{"radians":-2.9366639620191504},"translation":{"x":6.288194475544495,"y":2.120118160263666}},"time":1.7891014086115613,"velocity":2.1834368073296213,"position":2.218626621927147,"holonomicRotation":181.3163042843156,"angularVelocity":-0.08667281165209667,"angularAcceleration":-0.3996621146514997,"curveRadius":-24.94789946312089},{"acceleration":3.0175234389279577,"curvature":-0.0405990270457963,"pose":{"rotation":{"radians":-2.937008786038006},"translation":{"x":6.279797482348711,"y":2.1183758955839203}},"time":1.793007995382769,"velocity":2.195225024477946,"position":2.2272024589675965,"holonomicRotation":181.36918062394366,"angularVelocity":-0.08826733899703028,"angularAcceleration":-0.40816381110119676,"curveRadius":-24.63113214195959},{"acceleration":3.0173730214979035,"curvature":-0.041118143225917905,"pose":{"rotation":{"radians":-2.937355877007942},"translation":{"x":6.271451966785691,"y":2.116647332968697}},"time":1.7968698540514425,"velocity":2.2068776926376397,"position":2.2357251087156116,"holonomicRotation":181.42205696357175,"angularVelocity":-0.08987666295290321,"angularAcceleration":-0.41672264418357596,"curveRadius":-24.320164325165155},{"acceleration":3.0172257699161715,"curvature":-0.04164077577633269,"pose":{"rotation":{"radians":-2.9377052274619255},"translation":{"x":6.263157533471444,"y":2.1149323725073894}},"time":1.8006878672423134,"velocity":2.2183975004270153,"position":2.244194979634837,"holonomicRotation":181.4749333031998,"angularVelocity":-0.09150058853092963,"angularAcceleration":-0.42533262637994657,"curveRadius":-24.014922425349447},{"acceleration":3.0170815268129685,"curvature":-0.042166810358671765,"pose":{"rotation":{"radians":-2.9380568290875275},"translation":{"x":6.254913787021981,"y":2.113230914289392}},"time":1.8044628916461425,"velocity":2.229787056819076,"position":2.252612480189671,"holonomicRotation":181.52780964282786,"angularVelocity":-0.09313890136587226,"angularAcceleration":-0.43398734940120554,"curveRadius":-23.715334204650038},{"acceleration":3.0169401426841884,"curvature":-0.042696126931998514,"pose":{"rotation":{"radians":-2.938410672704224},"translation":{"x":6.246720332053311,"y":2.111542858404098}},"time":1.8081957591775617,"velocity":2.241048894721937,"position":2.2609780188451016,"holonomicRotation":181.58068598245595,"angularVelocity":-0.0947913671509308,"angularAcceleration":-0.4426799963164725,"curveRadius":-23.421328159172027},{"acceleration":3.0168014751219205,"curvature":-0.043228599022307385,"pose":{"rotation":{"radians":-2.9387667482407034},"translation":{"x":6.238576773181443,"y":2.109868104940901}},"time":1.8118872780671464,"velocity":2.252185474353477,"position":2.269292004066526,"holonomicRotation":181.633562322084,"angularVelocity":-0.09645773112090761,"angularAcceleration":-0.4514033436692665,"curveRadius":-23.13283387888576},{"acceleration":3.01666538835399,"curvature":-0.043764092400434385,"pose":{"rotation":{"radians":-2.9391250447121187},"translation":{"x":6.23048271502239,"y":2.108206553989196}},"time":1.8155382338922454,"velocity":2.2631991864254624,"position":2.2775548443195652,"holonomicRotation":181.6864386617121,"angularVelocity":-0.0981377175127996,"angularAcceleration":-0.4601497449908013,"curveRadius":-22.84978266772132},{"acceleration":3.0165317530164786,"curvature":-0.04430246542602401,"pose":{"rotation":{"radians":-2.9394855501960255},"translation":{"x":6.22243776219216,"y":2.1065581056383746}},"time":1.8191493905507317,"velocity":2.274092355150903,"position":2.285766948069881,"holonomicRotation":181.73931500134015,"angularVelocity":-0.09983102867046283,"angularAcceleration":-0.46891102153764314,"curveRadius":-22.57210722662363},{"acceleration":3.016400445460264,"curvature":-0.044843570556449636,"pose":{"rotation":{"radians":-2.9398482518103535},"translation":{"x":6.214441519306764,"y":2.104922659977832}},"time":1.8227214911814968,"velocity":2.284867241084772,"position":2.2939287237829746,"holonomicRotation":181.7921913409682,"angularVelocity":-0.10153734505801082,"angularAcceleration":-0.4776787005528679,"curveRadius":-22.299740800995938},{"acceleration":3.0162713477097687,"curvature":-0.04538725129162528,"pose":{"rotation":{"radians":-2.940213135688611},"translation":{"x":6.20649359098221,"y":2.103300117096962}},"time":1.826255259035224,"velocity":2.2955260438114267,"position":2.3020405799239887,"holonomicRotation":181.8450676805963,"angularVelocity":-0.10325632394687807,"angularAcceleration":-0.486443637505574,"curveRadius":-22.032618665861285},{"acceleration":3.0161443469951226,"curvature":-0.04593334482322118,"pose":{"rotation":{"radians":-2.940580186956898},"translation":{"x":6.198593581834511,"y":2.101690377085158}},"time":1.829751398298687,"velocity":2.3060709044872287,"position":2.3101029249574965,"holonomicRotation":181.89794402022434,"angularVelocity":-0.10498759935655128,"angularAcceleration":-0.4951963520921828,"curveRadius":-21.77067670226487},{"acceleration":3.0160193353282567,"curvature":-0.046481680105437836,"pose":{"rotation":{"radians":-2.9409493897100236},"translation":{"x":6.190741096479674,"y":2.100093340031813}},"time":1.8332105948755928,"velocity":2.3165039082478778,"position":2.3181161673472963,"holonomicRotation":181.9508203598524,"angularVelocity":-0.10673078124276945,"angularAcceleration":-0.5039268071250977,"curveRadius":-21.513852290442728},{"acceleration":3.0158962093011237,"curvature":-0.04703207703317058,"pose":{"rotation":{"radians":-2.941320726987579},"translation":{"x":6.182935739533712,"y":2.0985089060263222}},"time":1.8366335171267252,"velocity":2.3268270864898004,"position":2.32608071555618,"holonomicRotation":182.00369669948049,"angularVelocity":-0.1084854549158146,"angularAcceleration":-0.5126244607117956,"curveRadius":-21.26208458313938},{"acceleration":3.015774870153843,"curvature":-0.047584350337807536,"pose":{"rotation":{"radians":-2.9416941807500274},"translation":{"x":6.175177115612633,"y":2.0969369751580786}},"time":1.8400208165719827,"velocity":2.337042419034494,"position":2.3339969780457186,"holonomicRotation":182.05657303910854,"angularVelocity":-0.11025118047095146,"angularAcceleration":-0.5212782582918735,"curveRadius":-21.015312658486856},{"acceleration":3.0156552227649733,"curvature":-0.04813830229528387,"pose":{"rotation":{"radians":-2.942069731854573},"translation":{"x":6.167464829332448,"y":2.095377447516476}},"time":1.8433731285566692,"velocity":2.3471518361794517,"position":2.341865363276022,"holonomicRotation":182.1094493787366,"angularVelocity":-0.11202749214902899,"angularAcceleration":-0.5298766004452347,"curveRadius":-20.77347875431765},{"acceleration":3.0155371761906604,"curvature":-0.04869373047678306,"pose":{"rotation":{"radians":-2.942447360031387},"translation":{"x":6.1597984853091665,"y":2.0938302231909076}},"time":1.8466910728842572,"velocity":2.357157220647824,"position":2.3496862797055034,"holonomicRotation":182.16232571836468,"angularVelocity":-0.11381389786262613,"angularAcceleration":-0.5384073803600639,"curveRadius":-20.536524727280757},{"acceleration":3.0154206430805823,"curvature":-0.049250422198953335,"pose":{"rotation":{"radians":-2.9428270438595336},"translation":{"x":6.1521776881587975,"y":2.092295202270768}},"time":1.8499752544176609,"velocity":2.3670604094392735,"position":2.357460135790635,"holonomicRotation":182.21520205799274,"angularVelocity":-0.1156098785298204,"angularAcceleration":-0.5468579154127685,"curveRadius":-20.304394467125032},{"acceleration":3.0153055394875206,"curvature":-0.04980815576060102,"pose":{"rotation":{"radians":-2.9432087607424653},"translation":{"x":6.144602042497354,"y":2.0907722848454506}},"time":1.8532262636509205,"velocity":2.3768631955892463,"position":2.3651873399856904,"holonomicRotation":182.26807839762083,"angularVelocity":-0.11741488736066198,"angularAcceleration":-0.5552149198394634,"curveRadius":-20.077033263516547},{"acceleration":3.015191784748809,"curvature":-0.05036670173491397,"pose":{"rotation":{"radians":-2.9435924868850925},"translation":{"x":6.137071152940843,"y":2.0892613710043495}},"time":1.8564446772530683,"velocity":2.386567329842366,"position":2.3728683007424967,"holonomicRotation":182.32095473724888,"angularVelocity":-0.11922834975936017,"angularAcceleration":-0.5634646825653402,"curveRadius":-19.854387235104667},{"acceleration":3.0150793012580146,"curvature":-0.05092582123151887,"pose":{"rotation":{"radians":-2.9439781972686982},"translation":{"x":6.129584624105275,"y":2.087762360836858}},"time":1.8596310585858062,"velocity":2.3961745222446194,"position":2.3805034265101592,"holonomicRotation":182.37383107687694,"angularVelocity":-0.12104966208622861,"angularAcceleration":-0.5715927055420703,"curveRadius":-19.6364040052256},{"acceleration":3.0149680145097077,"curvature":-0.05148526595739196,"pose":{"rotation":{"radians":-2.9443658656281295},"translation":{"x":6.122142060606663,"y":2.086275154432369}},"time":1.8627859581965338,"velocity":2.405686443659952,"position":2.3880931257347946,"holonomicRotation":182.42670741650502,"angularVelocity":-0.12287819178559153,"angularAcceleration":-0.5795841151792582,"curveRadius":-19.42303261728467},{"acceleration":3.0148578524583844,"curvature":-0.05204477859898494,"pose":{"rotation":{"radians":-2.9447554644280296},"translation":{"x":6.114743067061014,"y":2.0847996518802785}},"time":1.865909914288146,"velocity":2.415104727213484,"position":2.3956378068592543,"holonomicRotation":182.47958375613308,"angularVelocity":-0.12471327652336898,"angularAcceleration":-0.5874233452591427,"curveRadius":-19.21422334611495},{"acceleration":3.0147487460190603,"curvature":-0.05260409291071606,"pose":{"rotation":{"radians":-2.945146964838631},"translation":{"x":6.107387248084338,"y":2.083335753269978}},"time":1.8690034531669237,"velocity":2.4244309696690407,"position":2.4031378783228385,"holonomicRotation":182.53246009576114,"angularVelocity":-0.1265542234775795,"angularAcceleration":-0.5950941708991275,"curveRadius":-19.009927643791542},{"acceleration":3.014640628448832,"curvature":-0.05316293285984907,"pose":{"rotation":{"radians":-2.9455403367137727},"translation":{"x":6.1000742082926465,"y":2.0818833586908627}},"time":1.8720670896697589,"velocity":2.4336667327412864,"position":2.4105937485610003,"holonomicRotation":182.58533643538922,"angularVelocity":-0.12840030949416611,"angularAcceleration":-0.6025799780353241,"curveRadius":-18.81009843148144},{"acceleration":3.0145334356352502,"curvature":-0.05372101238030397,"pose":{"rotation":{"radians":-2.9459355485666707},"translation":{"x":6.092803552301949,"y":2.0804423682323256}},"time":1.8751013275718702,"velocity":2.4428135443488728,"position":2.4180058260050545,"holonomicRotation":182.63821277501728,"angularVelocity":-0.13025077981625457,"angularAcceleration":-0.6098632941078351,"curveRadius":-18.61469014993164},{"acceleration":3.0144271052213147,"curvature":-0.05427803737806369,"pose":{"rotation":{"radians":-2.9463325675482963},"translation":{"x":6.0855748847282545,"y":2.0790126819837607}},"time":1.8781066599760874,"velocity":2.451872899808345,"position":2.4253745190818705,"holonomicRotation":182.69108911464534,"angularVelocity":-0.13210484839163697,"angularAcceleration":-0.6169262916743258,"curveRadius":-18.42365804486783},{"acceleration":3.0143215776139773,"curvature":-0.05483370263580636,"pose":{"rotation":{"radians":-2.9467313594242333},"translation":{"x":6.078387810187575,"y":2.0775942000345617}},"time":1.8810835696847104,"velocity":2.4608462629776557,"position":2.4327002362135572,"holonomicRotation":182.74396545427342,"angularVelocity":-0.13396169685019213,"angularAcceleration":-0.623750345257897,"curveRadius":-18.236959240957784},{"acceleration":3.014216794869313,"curvature":-0.055387693493013215,"pose":{"rotation":{"radians":-2.947131888553027},"translation":{"x":6.071241933295919,"y":2.076186822474122}},"time":1.8840325295548963,"velocity":2.469735067345766,"position":2.439983385817151,"holonomicRotation":182.79684179390148,"angularVelocity":-0.13582047448084436,"angularAcceleration":-0.6303163530451915,"curveRadius":-18.054552138484397},{"acceleration":3.014112701328726,"curvature":-0.05593968595994439,"pose":{"rotation":{"radians":-2.9475341178647545},"translation":{"x":6.064136858669297,"y":2.0747904493918363}},"time":1.8869540028384493,"velocity":2.4785407170763154,"position":2.4472243763042876,"holonomicRotation":182.84971813352956,"angularVelocity":-0.1376802978113996,"angularAcceleration":-0.6366045998180061,"curveRadius":-17.876396387281293},{"acceleration":3.014009243099971,"curvature":-0.056489345515027524,"pose":{"rotation":{"radians":-2.9479380088390603},"translation":{"x":6.057072190923719,"y":2.0734049808770973}},"time":1.889848443506846,"velocity":2.487264588004468,"position":2.454423616080871,"holonomicRotation":182.90259447315762,"angularVelocity":-0.13954024994042336,"angularAcceleration":-0.642594664085461,"curveRadius":-17.70245328358382},{"acceleration":3.013906367815557,"curvature":-0.05703632886521967,"pose":{"rotation":{"radians":-2.948343521485686},"translation":{"x":6.050047534675196,"y":2.0720303170192995}},"time":1.8927162965622768,"velocity":2.49590802859019,"position":2.4615815135467374,"holonomicRotation":182.95547081278568,"angularVelocity":-0.14139938092640725,"angularAcceleration":-0.6482657758434871,"curveRadius":-17.5326852182766},{"acceleration":3.013804025397413,"curvature":-0.05758028208539716,"pose":{"rotation":{"radians":-2.948750614323293},"translation":{"x":6.043062494539736,"y":2.0706663579078364}},"time":1.8955579983354225,"velocity":2.5044723608330752,"position":2.468698477095311,"holonomicRotation":183.00834715241376,"angularVelocity":-0.1432567067572121,"angularAcceleration":-0.6535963232865397,"curveRadius":-17.367056287027264},{"acceleration":3.013702166949804,"curvature":-0.05812084173594405,"pose":{"rotation":{"radians":-2.949159244360439},"translation":{"x":6.03611667513335,"y":2.0693130036321015}},"time":1.8983739767706593,"velocity":2.5129588811454324,"position":2.4757749151132535,"holonomicRotation":183.06122349204182,"angularVelocity":-0.14511120967138488,"angularAcceleration":-0.6585643167458406,"curveRadius":-17.205531959485775},{"acceleration":3.0136007456853036,"curvature":-0.05865763398476725,"pose":{"rotation":{"radians":-2.9495693670765495},"translation":{"x":6.029209681072048,"y":2.067970154281489}},"time":1.9011646516993277,"velocity":2.5213688611914327,"position":2.4828112359801056,"holonomicRotation":183.11409983166988,"angularVelocity":-0.14696183776099234,"angularAcceleration":-0.6631471371302026,"curveRadius":-17.04807937291997},{"acceleration":3.0134997156170438,"curvature":-0.059190276455789545,"pose":{"rotation":{"radians":-2.9499809364036333},"translation":{"x":6.022341116971841,"y":2.066637709945392}},"time":1.9039304351016757,"velocity":2.5297035486878667,"position":2.4898078480679273,"holonomicRotation":183.16697617129796,"angularVelocity":-0.14880750485900632,"angularAcceleration":-0.667321633518772,"curveRadius":-16.894666824996516},{"acceleration":3.0133990330014244,"curvature":-0.059718375301684834,"pose":{"rotation":{"radians":-2.9503939047088075},"translation":{"x":6.015510587448738,"y":2.0653155707132043}},"time":1.9066717313580375,"velocity":2.5379641681759577,"position":2.4967651597409284,"holonomicRotation":183.21985251092602,"angularVelocity":-0.15064709048346733,"angularAcceleration":-0.6710641435386124,"curveRadius":-16.745264668507936},{"acceleration":3.0132986550365417,"curvature":-0.060241529156568024,"pose":{"rotation":{"radians":-2.950808222777623},"translation":{"x":6.008717697118749,"y":2.0640036366743204}},"time":1.9093889374897852,"velocity":2.5461519217582103,"position":2.503683579355091,"holonomicRotation":183.27272885055407,"angularVelocity":-0.15247943980934794,"angularAcceleration":-0.6743505045390186,"curveRadius":-16.599844227077888},{"acceleration":3.0131985403290504,"curvature":-0.060759324801783345,"pose":{"rotation":{"radians":-2.9512238397979167},"translation":{"x":6.001962050597884,"y":2.0627018079181334}},"time":1.9120824433905597,"velocity":2.5542679898067915,"position":2.510563515257795,"holonomicRotation":183.32560519018216,"angularVelocity":-0.15430336357321614,"angularAcceleration":-0.6771560304894002,"curveRadius":-16.458379076171845},{"acceleration":3.013098649237174,"curvature":-0.06127134189408131,"pose":{"rotation":{"radians":-2.9516407033450545},"translation":{"x":5.995243252502154,"y":2.0614099845340372}},"time":1.914752632048244,"velocity":2.5623135316444685,"position":2.517405375787423,"holonomicRotation":183.37848152981022,"angularVelocity":-0.1561176383317007,"angularAcceleration":-0.6794556456763484,"curveRadius":-16.320843792334145},{"acceleration":3.012998942886676,"curvature":-0.06177714858881348,"pose":{"rotation":{"radians":-2.952058759367848},"translation":{"x":5.988560907447567,"y":2.060128066611426}},"time":1.9173998797581413,"velocity":2.5702896861959483,"position":2.524209569272978,"holonomicRotation":183.43135786943827,"angularVelocity":-0.1579210064967955,"angularAcceleration":-0.6812238077881809,"curveRadius":-16.187215221860832},{"acceleration":3.01289938377526,"curvature":-0.062276306012241295,"pose":{"rotation":{"radians":-2.9524779521750997},"translation":{"x":5.981914620050135,"y":2.0588559542396925}},"time":1.9200245563277638,"velocity":2.5781975726151733,"position":2.5309765040336787,"holonomicRotation":183.48423420906636,"angularVelocity":-0.15971217638910046,"angularAcceleration":-0.6824345189939249,"curveRadius":-16.057471356818045},{"acceleration":3.012799935926286,"curvature":-0.06276836455826859,"pose":{"rotation":{"radians":-2.9528982244242754},"translation":{"x":5.975303994925868,"y":2.057593547508232}},"time":1.9226270252736393,"velocity":2.586038290888557,"position":2.537706588378561,"holonomicRotation":183.53711054869441,"angularVelocity":-0.161489822901367,"angularAcceleration":-0.6830615654737571,"curveRadius":-15.931592403872312},{"acceleration":3.012700564001747,"curvature":-0.06325286700702233,"pose":{"rotation":{"radians":-2.9533195171096103},"translation":{"x":5.968728636690774,"y":2.0563407465064367}},"time":1.9252076440105081,"velocity":2.5938129224125954,"position":2.5444002306060716,"holonomicRotation":183.5899868883225,"angularVelocity":-0.16325258718613572,"angularAcceleration":-0.6830781547015881,"curveRadius":-15.809560061348366},{"acceleration":3.0126012343606954,"curvature":-0.06372934697546147,"pose":{"rotation":{"radians":-2.953741769553263},"translation":{"x":5.962188149960865,"y":2.055097451323701}},"time":1.9277667640332616,"velocity":2.6015225305520198,"position":2.5510578390036516,"holonomicRotation":183.64286322795056,"angularVelocity":-0.16499907776824294,"angularAcceleration":-0.6824574723260037,"curveRadius":-15.691358023565545},{"acceleration":3.0125019140932503,"curvature":-0.064197329918438,"pose":{"rotation":{"radians":-2.954164919396312},"translation":{"x":5.955682139352151,"y":2.053863562049419}},"time":1.930304731091963,"velocity":2.609168161174263,"position":2.5576798218473242,"holonomicRotation":183.6957395675786,"angularVelocity":-0.16672787048136983,"angularAcceleration":-0.6811722426419123,"curveRadius":-15.576971834661798},{"acceleration":3.012402571438902,"curvature":-0.06465633418769207,"pose":{"rotation":{"radians":-2.9545889025913254},"translation":{"x":5.949210209480642,"y":2.052638978772983}},"time":1.9328218853602617,"velocity":2.6167508431647946,"position":2.5642665874012707,"holonomicRotation":183.7486159072067,"angularVelocity":-0.16843750911621008,"angularAcceleration":-0.6791950165198956,"curveRadius":-15.466388754690014},{"acceleration":3.01230317570438,"curvature":-0.06510586833292595,"pose":{"rotation":{"radians":-2.9550136533971476},"translation":{"x":5.942771964962346,"y":2.0514236015837883}},"time":1.935318561597506,"velocity":2.624271588922951,"position":2.57081854391741,"holonomicRotation":183.80149224683475,"angularVelocity":-0.17012650638714202,"angularAcceleration":-0.6764983163360412,"curveRadius":-15.35959853705339},{"acceleration":3.012203697456291,"curvature":-0.06554543596826279,"pose":{"rotation":{"radians":-2.9554391043734505},"translation":{"x":5.936367010413274,"y":2.0502173305712286}},"time":1.9377950893048292,"velocity":2.6317313948398033,"position":2.5773360996349632,"holonomicRotation":183.8543685864628,"angularVelocity":-0.17179334398107826,"angularAcceleration":-0.6730542884730293,"curveRadius":-15.256592396215074},{"acceleration":3.0121041079772026,"curvature":-0.06597453157481374,"pose":{"rotation":{"radians":-2.955865186378053},"translation":{"x":5.929994950449439,"y":2.049020065824697}},"time":1.940251792875488,"velocity":2.639131241757067,"position":2.583819662780025,"holonomicRotation":183.9072449260909,"angularVelocity":-0.173436473855261,"angularAcceleration":-0.668835220417773,"curveRadius":-15.157364154469532},{"acceleration":3.012004379252033,"curvature":-0.0663926439241678,"pose":{"rotation":{"radians":-2.9562918285658517},"translation":{"x":5.923655389686847,"y":2.0478317074335872}},"time":1.942688991739702,"velocity":2.646472095409188,"position":2.5902696415651305,"holonomicRotation":183.96012126571895,"angularVelocity":-0.1750543191460591,"angularAcceleration":-0.6638134107779666,"curveRadius":-15.061909586582782},{"acceleration":3.011904485112959,"curvature":-0.0667992561301775,"pose":{"rotation":{"radians":-2.956718958388013},"translation":{"x":5.917347932741509,"y":2.046652155487293}},"time":1.945107000504232,"velocity":2.6537549068521176,"position":2.596686444188813,"holonomicRotation":184.012997605347,"angularVelocity":-0.17664527458578388,"angularAcceleration":-0.6579609896633947,"curveRadius":-14.970226585326241},{"acceleration":3.0118043998541744,"curvature":-0.06719384370577526,"pose":{"rotation":{"radians":-2.9571465015941047},"translation":{"x":5.911072184229437,"y":2.0454813100752087}},"time":1.9475061290869295,"velocity":2.6609806128733022,"position":2.6030704788351615,"holonomicRotation":184.0658739449751,"angularVelocity":-0.178207708071695,"angularAcceleration":-0.6512504153296691,"curveRadius":-14.882315772539304},{"acceleration":3.011704098010247,"curvature":-0.06757587896958646,"pose":{"rotation":{"radians":-2.9575743822354346},"translation":{"x":5.904827748766639,"y":2.044319071286728}},"time":1.9498866828464807,"velocity":2.668150136386476,"position":2.6094221536733833,"holonomicRotation":184.11875028460315,"angularVelocity":-0.17973996160056901,"angularAcceleration":-0.6436542433567702,"curveRadius":-14.798179694415298},{"acceleration":3.011603556481902,"curvature":-0.06794482796247048,"pose":{"rotation":{"radians":-2.958002522669729},"translation":{"x":5.898614230969126,"y":2.0431653392112437}},"time":1.9522489627075335,"velocity":2.675264386817428,"position":2.6157418768573537,"holonomicRotation":184.17162662423124,"angularVelocity":-0.1812403523194273,"angularAcceleration":-0.6351452017161279,"curveRadius":-14.71782371061934},{"acceleration":3.0115027517686586,"curvature":-0.06830015253430459,"pose":{"rotation":{"radians":-2.958430843568663},"translation":{"x":5.892431235452907,"y":2.04202001393815}},"time":1.9545932652814204,"velocity":2.682324260469667,"position":2.622030056525172,"holonomicRotation":184.2245029638593,"angularVelocity":-0.18270717428074554,"angularAcceleration":-0.6256965195777481,"curveRadius":-14.641255735084012},{"acceleration":3.011401662135885,"curvature":-0.06864131088991784,"pose":{"rotation":{"radians":-2.958859263926063},"translation":{"x":5.886278366833993,"y":2.0408829955568413}},"time":1.9569198829826517,"velocity":2.68933064088231,"position":2.6282871007987127,"holonomicRotation":184.27737930348735,"angularVelocity":-0.184138699354682,"angularAcceleration":-0.6152816052155216,"curveRadius":-14.568486339133738},{"acceleration":3.011300266267658,"curvature":-0.0689677577454651,"pose":{"rotation":{"radians":-2.9592877010687357},"translation":{"x":5.880155229728394,"y":2.0397541841567106}},"time":1.9592291041413603,"velocity":2.6962843991724,"position":2.6345134177831775,"holonomicRotation":184.33025564311544,"angularVelocity":-0.18553317903608765,"angularAcceleration":-0.6038744605066398,"curveRadius":-14.499528949319133},{"acceleration":3.011198543717326,"curvature":-0.06927894533908792,"pose":{"rotation":{"radians":-2.959716070669196},"translation":{"x":5.874061428752119,"y":2.038633479827152}},"time":1.961521213111863,"velocity":2.7031863943664187,"position":2.6407094155666453,"holonomicRotation":184.3831319827435,"angularVelocity":-0.18688884602480532,"angularAcceleration":-0.5914496239768289,"curveRadius":-14.434399875827634},{"acceleration":3.0110964749199547,"curvature":-0.06957432492755804,"pose":{"rotation":{"radians":-2.9601442867600625},"translation":{"x":5.867996568521179,"y":2.037520782657559}},"time":1.9637964903774998,"velocity":2.7100374737204436,"position":2.6468755022196255,"holonomicRotation":184.43600832237155,"angularVelocity":-0.1882039157748696,"angularAcceleration":-0.5779821958077541,"curveRadius":-14.373118259375378},{"acceleration":3.0109940416725656,"curvature":-0.06985334447395404,"pose":{"rotation":{"radians":-2.9605722617512016},"translation":{"x":5.861960253651585,"y":2.0364159927373255}},"time":1.9660552126519002,"velocity":2.7168384730304562,"position":2.6530120857946073,"holonomicRotation":184.48888466199963,"angularVelocity":-0.1894765885959691,"angularAcceleration":-0.5634481208794694,"curveRadius":-14.315706821637816},{"acceleration":3.0108912259500755,"curvature":-0.07011545274518598,"pose":{"rotation":{"radians":-2.960999906448079},"translation":{"x":5.855952088759344,"y":2.0353190101558454}},"time":1.968297652976824,"velocity":2.7235902169294857,"position":2.6591195743256177,"holonomicRotation":184.5417610016277,"angularVelocity":-0.19070505115534905,"angularAcceleration":-0.547823969149207,"curveRadius":-14.262191298032494},{"acceleration":3.0107880107730103,"curvature":-0.0703600979143676,"pose":{"rotation":{"radians":-2.9614271300728245},"translation":{"x":5.84997167846047,"y":2.034229735002512}},"time":1.9705240808167082,"velocity":2.7302935191766604,"position":2.665198375827768,"holonomicRotation":184.59463734125575,"angularVelocity":-0.19188747871917397,"angularAcceleration":-0.5310873061515397,"curveRadius":-14.212601028740167},{"acceleration":3.01068438018737,"curvature":-0.07058672963891961,"pose":{"rotation":{"radians":-2.961853840287956},"translation":{"x":5.8440186273709696,"y":2.0331480673667195}},"time":1.9727347621500613,"velocity":2.7369491829365584,"position":2.671248898296822,"holonomicRotation":184.64751368088383,"angularVelocity":-0.19302203745684435,"angularAcceleration":-0.5132167719304447,"curveRadius":-14.16696884974576},{"acceleration":3.010580318785647,"curvature":-0.07079479810114274,"pose":{"rotation":{"radians":-2.962279943220921},"translation":{"x":5.838092540106855,"y":2.0320739073378613}},"time":1.9749299595578138,"velocity":2.7435580010481875,"position":2.677271549708742,"holonomicRotation":184.7003900205119,"angularVelocity":-0.19410688599578113,"angularAcceleration":-0.4941917911826717,"curveRadius":-14.125331617887028},{"acceleration":3.0104758123285467,"curvature":-0.0709837575403735,"pose":{"rotation":{"radians":-2.9627053434926394},"translation":{"x":5.832193021284135,"y":2.031007155005331}},"time":1.9771099323087613,"velocity":2.7501207562864503,"position":2.6832667380192614,"holonomicRotation":184.75326636013997,"angularVelocity":-0.19514017848775367,"angularAcceleration":-0.4739933063490946,"curveRadius":-14.087729850469369},{"acceleration":3.0103708467689985,"curvature":-0.07115306261841507,"pose":{"rotation":{"radians":-2.9631299442472736},"translation":{"x":5.826319675518819,"y":2.0299477104585235}},"time":1.9792749364421989,"velocity":2.756638221612885,"position":2.6892348711634453,"holonomicRotation":184.80614269976803,"angularVelocity":-0.19612006650540004,"angularAcceleration":-0.45260330108031505,"curveRadius":-14.0542088168836},{"acceleration":3.0102654097638295,"curvature":-0.07130217526568934,"pose":{"rotation":{"radians":-2.963553647183915},"translation":{"x":5.820472107426919,"y":2.0288954737868306}},"time":1.9814252248478639,"velocity":2.7631111604214746,"position":2.695176357055263,"holonomicRotation":184.8590190393961,"angularVelocity":-0.1970447013178059,"angularAcceleration":-0.430005021637978,"curveRadius":-14.024817563752515},{"acceleration":3.010159489176143,"curvature":-0.07143056016995092,"pose":{"rotation":{"radians":-2.9639763525931055},"translation":{"x":5.814649921624444,"y":2.027850345079648}},"time":1.9835610473432845,"velocity":2.769540326773261,"position":2.70109160358716,"holonomicRotation":184.91189537902417,"angularVelocity":-0.19791223760253754,"angularAcceleration":-0.4061837004674701,"curveRadius":-13.999610217542092},{"acceleration":3.010053073460579,"curvature":-0.0715376894910044,"pose":{"rotation":{"radians":-2.9643979593918632},"translation":{"x":5.808852722727404,"y":2.026812224426368}},"time":1.9856826507486387,"velocity":2.7759264656242117,"position":2.7069810186296412,"holonomicRotation":184.96477171865223,"angularVelocity":-0.198720834296224,"angularAcceleration":-0.38112528083517205,"curveRadius":-13.978645482053851},{"acceleration":3.00994615280523,"curvature":-0.0716230401508607,"pose":{"rotation":{"radians":-2.96481836516508},"translation":{"x":5.803080115351809,"y":2.0257810119163855}},"time":1.98779027895921,"velocity":2.7822703130481643,"position":2.7128450100308563,"holonomicRotation":185.0176480582803,"angularVelocity":-0.19946865918204595,"angularAcceleration":-0.35481821797179286,"curveRadius":-13.961987621492817},{"acceleration":3.0098387172426455,"curvature":-0.07168609873708655,"pose":{"rotation":{"radians":-2.9652374662064442},"translation":{"x":5.797331704113669,"y":2.0247566076390933}},"time":1.9898841730155339,"velocity":2.7885725964486925,"position":2.718683985616188,"holonomicRotation":185.07052439790837,"angularVelocity":-0.2001538903548349,"angularAcceleration":-0.32725207405762513,"curveRadius":-13.949705976713357},{"acceleration":3.0097307578398427,"curvature":-0.07172635881388015,"pose":{"rotation":{"radians":-2.9656551575637877},"translation":{"x":5.791607093628994,"y":2.0237389116838855}},"time":1.991964571171325,"velocity":2.79483403476673,"position":2.724498353187859,"holonomicRotation":185.12340073753643,"angularVelocity":-0.20077472006057223,"angularAcceleration":-0.29841869644478913,"curveRadius":-13.941875992825175},{"acceleration":3.009622267091626,"curvature":-0.07174332502850876,"pose":{"rotation":{"radians":-2.9660713330852984},"translation":{"x":5.785905888513795,"y":2.022727824140156}},"time":1.9940317089592545,"velocity":2.8010553386824295,"position":2.7302885205245313,"holonomicRotation":185.17627707716449,"angularVelocity":-0.20132935692084325,"angularAcceleration":-0.2683115095228091,"curveRadius":-13.93857894936746},{"acceleration":3.00951323736274,"curvature":-0.07173651140540463,"pose":{"rotation":{"radians":-2.966485885469671},"translation":{"x":5.780227693384081,"y":2.021723245097298}},"time":1.9960858192546704,"velocity":2.807237210807487,"position":2.7360548953809256,"holonomicRotation":185.22915341679257,"angularVelocity":-0.2018160296931203,"angularAcceleration":-0.2369263098301647,"curveRadius":-13.93990285293773},{"acceleration":3.009403662356949,"curvature":-0.07170544410793854,"pose":{"rotation":{"radians":-2.966898706317642},"translation":{"x":5.774572112855862,"y":2.020725074644706}},"time":1.9981271323373266,"velocity":2.8133803458744495,"position":2.741797885487447,"holonomicRotation":185.28202975642063,"angularVelocity":-0.2022329898724095,"angularAcceleration":-0.20426076863557746,"curveRadius":-13.945942493497359},{"acceleration":3.0092935367793925,"curvature":-0.07164966177785002,"pose":{"rotation":{"radians":-2.9673096861865025},"translation":{"x":5.768938751545147,"y":2.019733212871773}},"time":2.0001558759511933,"velocity":2.819485430919441,"position":2.7475178985498148,"holonomicRotation":185.3349060960487,"angularVelocity":-0.20257851512197747,"angularAcceleration":-0.17031489203774705,"curveRadius":-13.956800006963087},{"acceleration":3.009182855186999,"curvature":-0.0715687174500262,"pose":{"rotation":{"radians":-2.9677187146472126},"translation":{"x":5.763327214067949,"y":2.0187475598678937}},"time":2.0021722753624216,"velocity":2.8255531454569183,"position":2.7532153422487085,"holonomicRotation":185.38778243567677,"angularVelocity":-0.20285091258826868,"angularAcceleration":-0.13509102649721125,"curveRadius":-13.972585168907953},{"acceleration":3.0090716142241907,"curvature":-0.07146217630963082,"pose":{"rotation":{"radians":-2.9681256803431397},"translation":{"x":5.757737105040276,"y":2.017768015722461}},"time":2.004176553415524,"velocity":2.8315841616535207,"position":2.7588906242394224,"holonomicRotation":185.44065877530483,"angularVelocity":-0.20304852178430552,"angularAcceleration":-0.09859370346892839,"curveRadius":-13.99341654062153},{"acceleration":3.0089598101524104,"curvature":-0.07132962351929778,"pose":{"rotation":{"radians":-2.968530471052598},"translation":{"x":5.752168029078138,"y":2.0167944805248688}},"time":2.0061689305878345,"velocity":2.8375791444916687,"position":2.7645441521515326,"holonomicRotation":185.4935351149329,"angularVelocity":-0.20316971860752558,"angularAcceleration":-0.06083026090863327,"curveRadius":-14.01942069313539},{"acceleration":3.008847440686899,"curvature":-0.071170655633149,"pose":{"rotation":{"radians":-2.9689329737523558},"translation":{"x":5.746619590797545,"y":2.015826854364511}},"time":2.0081496250423116,"velocity":2.843538751931805,"position":2.7701763335885747,"holonomicRotation":185.54641145456097,"angularVelocity":-0.20321291799843325,"angularAcceleration":-0.021810224595729018,"curveRadius":-14.050734689793025},{"acceleration":3.0087345040183475,"curvature":-0.07098489184536416,"pose":{"rotation":{"radians":-2.9693330746844793},"translation":{"x":5.741091394814508,"y":2.0148650373307815}},"time":2.010118852678734,"velocity":2.849463635067776,"position":2.775787576127731,"holonomicRotation":185.59928779418902,"angularVelocity":-0.20317657782335946,"angularAcceleration":0.018454024512780103,"curveRadius":-14.087504735210882},{"acceleration":3.008621000018916,"curvature":-0.07077196695998422,"pose":{"rotation":{"radians":-2.9697306594248003},"translation":{"x":5.735583045745037,"y":2.0139089295130734}},"time":2.0120768271833556,"velocity":2.8553544382798814,"position":2.7813782873195407,"holonomicRotation":185.6521641338171,"angularVelocity":-0.2030592019368022,"angularAcceleration":0.059947607223793546,"curveRadius":-14.129888470747444},{"acceleration":3.008506926897469,"curvature":-0.07053153687784866,"pose":{"rotation":{"radians":-2.9701256129548943},"translation":{"x":5.730094148205141,"y":2.012958431000781}},"time":2.0140237600770643,"velocity":2.8612117993768087,"position":2.786948874687615,"holonomicRotation":185.70504047344517,"angularVelocity":-0.2028593442384392,"angularAcceleration":0.10265258705568082,"curveRadius":-14.178054871140386},{"acceleration":3.008392287208684,"curvature":-0.07026327754771469,"pose":{"rotation":{"radians":-2.970517819734405},"translation":{"x":5.72462430681083,"y":2.0120134418832984}},"time":2.0159598607620968,"velocity":2.86703634974492,"position":2.792499745728369,"holonomicRotation":185.75791681307322,"angularVelocity":-0.20257561114596442,"angularAcceleration":0.1465487278984292,"curveRadius":-14.232185501465054},{"acceleration":3.0082770814535396,"curvature":-0.06996688672301346,"pose":{"rotation":{"radians":-2.970907163776901},"translation":{"x":5.719173126178116,"y":2.011073862250018}},"time":2.0178853365673604,"velocity":2.8728287144807876,"position":2.7980313079107684,"holonomicRotation":185.8107931527013,"angularVelocity":-0.20220666571435894,"angularAcceleration":0.1916126032832577,"curveRadius":-14.292475295618388},{"acceleration":3.0081613112430112,"curvature":-0.06964208582751631,"pose":{"rotation":{"radians":-2.9712935287286593},"translation":{"x":5.713740210923005,"y":2.0101395921903356}},"time":2.0198003927924124,"velocity":2.8785895125258443,"position":2.8035439686761006,"holonomicRotation":185.86366949232936,"angularVelocity":-0.20175123148035187,"angularAcceleration":0.23781768286969632,"curveRadius":-14.35913339064422},{"acceleration":3.008044980867626,"curvature":-0.0692886195137141,"pose":{"rotation":{"radians":-2.9716767979460625},"translation":{"x":5.708325165661511,"y":2.0092105317936433}},"time":2.021705232750127,"velocity":2.884319356800004,"position":2.809038135437743,"holonomicRotation":185.91654583195742,"angularVelocity":-0.20120809407165005,"angularAcceleration":0.285135455344744,"curveRadius":-14.432384524590981},{"acceleration":3.0079280933092942,"curvature":-0.06890625574564346,"pose":{"rotation":{"radians":-2.972056854579587},"translation":{"x":5.702927595009643,"y":2.008286581149335}},"time":2.023600057808113,"velocity":2.8900188543238263,"position":2.8145142155809677,"holonomicRotation":185.9694221715855,"angularVelocity":-0.20057610697228329,"angularAcceleration":0.3335332181212039,"curveRadius":-14.512470445228395},{"acceleration":3.0078106529579216,"curvature":-0.0684947908446537,"pose":{"rotation":{"radians":-2.9724335816564826},"translation":{"x":5.6975471035834095,"y":2.007367640346805}},"time":2.025485067428911,"velocity":2.895688606342191,"position":2.819972616462758,"holonomicRotation":186.02229851121356,"angularVelocity":-0.1998541931771335,"angularAcceleration":0.38297618600172184,"curveRadius":-14.59965039192545},{"acceleration":3.007692664870122,"curvature":-0.06805404415517174,"pose":{"rotation":{"radians":-2.972806862165555},"translation":{"x":5.692183295998822,"y":2.0064536094754466}},"time":2.0273604592090098,"velocity":2.9013292084429514,"position":2.825413745411632,"holonomicRotation":186.07517485084165,"angularVelocity":-0.19904134860424336,"angularAcceleration":0.4334265413317376,"curveRadius":-14.69420388478126},{"acceleration":3.007574136284028,"curvature":-0.06758386570803815,"pose":{"rotation":{"radians":-2.973176579145247},"translation":{"x":5.686835776871891,"y":2.005544388624654}},"time":2.0292264289167257,"velocity":2.9069412506749672,"position":2.8308380097275014,"holonomicRotation":186.1280511904697,"angularVelocity":-0.1981366461434614,"angularAcceleration":0.4848430588347403,"curveRadius":-14.79643091621887},{"acceleration":3.0074550725776,"curvature":-0.0670841307940692,"pose":{"rotation":{"radians":-2.9735426157720832},"translation":{"x":5.681504150818625,"y":2.0046398778838204}},"time":2.0310831705289814,"velocity":2.9125253176552115,"position":2.83624581668154,"holonomicRotation":186.18092753009776,"angularVelocity":-0.19713923812567272,"angularAcceleration":0.5371819165387147,"curveRadius":-14.906655093583002},{"acceleration":3.007335481307424,"curvature":-0.06655474662749288,"pose":{"rotation":{"radians":-2.9739048554505625},"translation":{"x":5.676188022455034,"y":2.00373997734234}},"time":2.0329308762670135,"velocity":2.918081988680211,"position":2.841637573516073,"holonomicRotation":186.23380386972585,"angularVelocity":-0.19604835933726622,"angularAcceleration":0.5903963850695713,"curveRadius":-15.0252243554769},{"acceleration":3.0072153718597914,"curvature":-0.06599564604985941,"pose":{"rotation":{"radians":-2.974263181905277},"translation":{"x":5.6708869963971305,"y":2.0028445870896063}},"time":2.034769736631047,"velocity":2.9236118378336364,"position":2.8470136874444845,"holonomicRotation":186.2866802093539,"angularVelocity":-0.19486333042095602,"angularAcceleration":0.6444365975189184,"curveRadius":-15.152514746874429},{"acceleration":3.007094751754019,"curvature":-0.06540679642178687,"pose":{"rotation":{"radians":-2.974617479273557},"translation":{"x":5.6656006772609215,"y":2.001953607215013}},"time":2.036599940433974,"velocity":2.9291154340840584,"position":2.852374565651157,"holonomicRotation":186.33955654898196,"angularVelocity":-0.19358356031899332,"angularAcceleration":0.6992500506861654,"curveRadius":-15.288931039388164},{"acceleration":1.1080524843244695,"curvature":-0.06478819322392294,"pose":{"rotation":{"radians":-2.974967632199958},"translation":{"x":5.660328669662419,"y":2.001066937807954}},"time":2.0384238233671144,"velocity":2.9311363920992415,"position":2.8577206152914134,"holonomicRotation":186.39243288861005,"angularVelocity":-0.19198212782114782,"angularAcceleration":0.8780346966064432,"curveRadius":-15.434911057694869},{"acceleration":-1.8977506375244644,"curvature":-0.06413986580538766,"pose":{"rotation":{"radians":-2.975313525930653},"translation":{"x":5.655070578217631,"y":2.0001844789578236}},"time":2.040244933430136,"velocity":2.9276803793161403,"position":2.8630522434914965,"holonomicRotation":186.4453092282381,"angularVelocity":-0.18993565392811437,"angularAcceleration":1.1237508015512827,"curveRadius":-15.590927536926673},{"acceleration":-3.0011477388743106,"curvature":-0.06346187349959494,"pose":{"rotation":{"radians":-2.9756550464102633},"translation":{"x":5.64982600754257,"y":1.9993061307540143}},"time":2.0420646511195057,"velocity":2.922219137687298,"position":2.8683698573485614,"holonomicRotation":186.49818556786616,"angularVelocity":-0.18767772693822143,"angularAcceleration":1.240811694628695,"curveRadius":-15.757492567665572},{"acceleration":-3.001039760795317,"curvature":-0.06275431017243084,"pose":{"rotation":{"radians":-2.975992080378627},"translation":{"x":5.6445945622532445,"y":1.9984317932859208}},"time":2.043883108302077,"velocity":2.9167618753790974,"position":2.873673863930695,"holonomicRotation":186.55106190749424,"angularVelocity":-0.185340612687462,"angularAcceleration":1.2852181910901874,"curveRadius":-15.93516042567095},{"acceleration":-3.000930751654289,"curvature":-0.06201730166523397,"pose":{"rotation":{"radians":-2.976324515467583},"translation":{"x":5.639375846965666,"y":1.9975613666429366}},"time":2.0457004378293235,"velocity":2.9113081953148945,"position":2.878964670276955,"holonomicRotation":186.6039382471223,"angularVelocity":-0.18292504687329078,"angularAcceleration":1.3291842662300972,"curveRadius":-16.124532560251424},{"acceleration":-3.0008207280327186,"curvature":-0.06125100752553082,"pose":{"rotation":{"radians":-2.9766522402996323},"translation":{"x":5.634169466295843,"y":1.996694750914455}},"time":2.047516773544975,"velocity":2.905857697450301,"position":2.884242683397435,"holonomicRotation":186.6568145867504,"angularVelocity":-0.18043186026978494,"angularAcceleration":1.3726463571804526,"curveRadius":-16.32626205508827},{"acceleration":-3.000709704109035,"curvature":-0.060455622111557986,"pose":{"rotation":{"radians":-2.976975144586052},"translation":{"x":5.628975024859785,"y":1.9958318461898703}},"time":2.049332250292912,"velocity":2.900409978755183,"position":2.889508310273349,"holonomicRotation":186.70969092637844,"angularVelocity":-0.17786197856108169,"angularAcceleration":1.415540965547366,"curveRadius":-16.541058797719636},{"acceleration":-3.0005976973924957,"curvature":-0.05963137176372053,"pose":{"rotation":{"radians":-2.977293119224984},"translation":{"x":5.623792127273504,"y":1.9949725525585762}},"time":2.051147003925329,"velocity":2.894964633184418,"position":2.894761957857139,"holonomicRotation":186.7625672660065,"angularVelocity":-0.17521642235736853,"angularAcceleration":1.4578046057909164,"curveRadius":-16.7696963934074},{"acceleration":-3.0004847237638095,"curvature":-0.058778519798064394,"pose":{"rotation":{"radians":-2.977606056400415},"translation":{"x":5.6186203781530075,"y":1.9941167701099665}},"time":2.0529611713111784,"velocity":2.889521251656826,"position":2.900004033072614,"holonomicRotation":186.81544360563458,"angularVelocity":-0.1724963076020535,"angularAcceleration":1.4993736391315122,"curveRadius":-17.013017739057297},{"acceleration":-3.0003708007310825,"curvature":-0.05789736370894879,"pose":{"rotation":{"radians":-2.977913849680029},"translation":{"x":5.613459382114309,"y":1.9932643989334344}},"time":2.054774890344897,"velocity":2.8840794220273263,"position":2.905234942815101,"holonomicRotation":186.86831994526264,"angularVelocity":-0.1697028447580277,"angularAcceleration":1.5401849967348247,"curveRadius":-17.271943590161033},{"acceleration":-3.0002559457830724,"curvature":-0.0569882319670505,"pose":{"rotation":{"radians":-2.9782163941139483},"translation":{"x":5.608308743773415,"y":1.9924153391183739}},"time":2.05658829995543,"velocity":2.878638729061185,"position":2.910455093951633,"holonomicRotation":186.9211962848907,"angularVelocity":-0.1668373389895067,"angularAcceleration":1.5801756822491568,"curveRadius":-17.54748244476475},{"acceleration":-3.0001401776159127,"curvature":-0.056051491764947434,"pose":{"rotation":{"radians":-2.978513586331728},"translation":{"x":5.603168067746338,"y":1.9915694907541792}},"time":2.0584015401155566,"velocity":2.873198754405122,"position":2.9156648933211464,"holonomicRotation":186.97407262451878,"angularVelocity":-0.16390118877518806,"angularAcceleration":1.6192836883302972,"curveRadius":-17.84073837309293},{"acceleration":-3.0000235142448415,"curvature":-0.05508754074520612,"pose":{"rotation":{"radians":-2.978805324639168},"translation":{"x":5.598036958649087,"y":1.9907267539302436}},"time":2.0602147518515315,"velocity":2.8677590765608927,"position":2.920864747734715,"holonomicRotation":187.02694896414684,"angularVelocity":-0.16089588526904638,"angularAcceleration":1.6574476364316941,"curveRadius":-18.15292508019652},{"acceleration":-2.9999059748597845,"curvature":-0.05409681500330614,"pose":{"rotation":{"radians":-2.9790915091153254},"translation":{"x":5.592915021097672,"y":1.989887028735961}},"time":2.0620280772530473,"velocity":2.8623192708545204,"position":2.9260550639758036,"holonomicRotation":187.0798253037749,"angularVelocity":-0.15782301175411856,"angularAcceleration":1.6946067773380034,"curveRadius":-18.48537663333571},{"acceleration":-2.9997875784846113,"curvature":-0.05307978317005739,"pose":{"rotation":{"radians":-2.979372041706799},"translation":{"x":5.587801859708104,"y":1.989050215260725}},"time":2.063841659483529,"velocity":2.8568789094069604,"position":2.9312362488005426,"holonomicRotation":187.13270164340298,"angularVelocity":-0.15468424136417944,"angularAcceleration":1.7307019980588976,"curveRadius":-18.83956452490005},{"acceleration":-2.999668345811761,"curvature":-0.05203694539107802,"pose":{"rotation":{"radians":-2.9796468263223272},"translation":{"x":5.582697079096391,"y":1.9882162135939294}},"time":2.0656556427907753,"velocity":2.8514375611003833,"position":2.9364087089380333,"holonomicRotation":187.18557798303104,"angularVelocity":-0.15148133636652414,"angularAcceleration":1.765675011925951,"curveRadius":-19.21711569510102},{"acceleration":-2.99954829623535,"curvature":-0.0509688361073707,"pose":{"rotation":{"radians":-2.9799157689253892},"translation":{"x":5.577600283878544,"y":1.9873849238249681}},"time":2.067470172517946,"velocity":2.8459947915487804,"position":2.941572851090671,"holonomicRotation":187.2384543226591,"angularVelocity":-0.14821614605419162,"angularAcceleration":1.7994691756436643,"curveRadius":-19.619831967388954},{"acceleration":-2.9994274504577065,"curvature":-0.04987602422878399,"pose":{"rotation":{"radians":-2.980178777625193},"translation":{"x":5.5725110786705745,"y":1.9865562460432344}},"time":2.0692853951149166,"velocity":2.8405501630627352,"position":2.9467290819344916,"holonomicRotation":187.29133066228718,"angularVelocity":-0.14489060473508844,"angularAcceleration":1.832029484787618,"curveRadius":-20.049713574060085},{"acceleration":-2.999305829915438,"curvature":-0.0487591091680837,"pose":{"rotation":{"radians":-2.9804357627671108},"translation":{"x":5.567429068088491,"y":1.9857300803381228}},"time":2.071101458150011,"velocity":2.835103234614083,"position":2.9518778081195505,"holonomicRotation":187.34420700191524,"angularVelocity":-0.14150673019138252,"angularAcceleration":1.863302362481169,"curveRadius":-20.50898831134862},{"acceleration":-2.9991834544316514,"curvature":-0.047618721597278015,"pose":{"rotation":{"radians":-2.9806866370193608},"translation":{"x":5.562353856748303,"y":1.9849063267990263}},"time":2.072918510322111,"velocity":2.8296535618036818,"position":2.957019436270316,"holonomicRotation":187.39708334154332,"angularVelocity":-0.13806662026664887,"angularAcceleration":1.8932367367074445,"curveRadius":-21.000143776584757},{"acceleration":-2.9990603472992574,"curvature":-0.04645552436094055,"pose":{"rotation":{"radians":-2.980931315459857},"translation":{"x":5.557285049266023,"y":1.984084885515339}},"time":2.07473670147317,"velocity":2.82420069681873,"position":2.962154372986087,"holonomicRotation":187.44995968117138,"angularVelocity":-0.13457245150138086,"angularAcceleration":1.9217829562269557,"curveRadius":-21.525965184041542},{"acceleration":-2.998936528988081,"curvature":-0.04527021245059497,"pose":{"rotation":{"radians":-2.9811697156594663},"translation":{"x":5.552222250257659,"y":1.9832656565764548}},"time":2.0765561826011334,"velocity":2.818744188400276,"position":2.967283024841438,"holonomicRotation":187.50283602079944,"angularVelocity":-0.1310264755954075,"angularAcceleration":1.9488940288940018,"curveRadius":-22.089580451855323},{"acceleration":-2.9988120221563093,"curvature":-0.04406350480797115,"pose":{"rotation":{"radians":-2.9814017577633525},"translation":{"x":5.547165064339219,"y":1.982448540071767}},"time":2.07837710587328,"velocity":2.8132835818003383,"position":2.9724057983866863,"holonomicRotation":187.55571236042752,"angularVelocity":-0.1274310166911169,"angularAcceleration":1.9745252088804157,"curveRadius":-22.694517931744244},{"acceleration":-2.9986868494597125,"curvature":-0.04283615398909604,"pose":{"rotation":{"radians":-2.9816273645701057},"translation":{"x":5.542113096126717,"y":1.9816334360906698}},"time":2.0801996246399947,"velocity":2.8078184187416975,"position":2.97752310014837,"holonomicRotation":187.60858870005558,"angularVelocity":-0.12378846839524894,"angularAcceleration":1.9986341772678091,"curveRadius":-23.344766205074112},{"acceleration":-2.9985610325808043,"curvature":-0.04158893654221479,"pose":{"rotation":{"radians":-2.981846461608171},"translation":{"x":5.537065950236162,"y":1.9808202447225567}},"time":2.0820238934489916,"velocity":2.802348237378087,"position":2.9826353366297664,"holonomicRotation":187.66146503968363,"angularVelocity":-0.12010129043733593,"angularAcceleration":2.0211812753299694,"curveRadius":-24.044856232016212},{"acceleration":-2.9984345947415365,"curvature":-0.04032265701569884,"pose":{"rotation":{"radians":-2.982058977209157},"translation":{"x":5.5320232312835635,"y":1.980008866056821}},"time":2.083850068059995,"velocity":2.796872572248416,"position":2.987742914311418,"holonomicRotation":187.71434137931172,"angularVelocity":-0.1163720050129661,"angularAcceleration":2.042129707586355,"curveRadius":-24.799953029153546},{"acceleration":-2.998307559468702,"curvature":-0.039038144869958886,"pose":{"rotation":{"radians":-2.9822648425792453},"translation":{"x":5.5269845438849305,"y":1.9791992001828573}},"time":2.085678305459894,"velocity":2.791390954231795,"position":2.9928462396516844,"holonomicRotation":187.76721771893978,"angularVelocity":-0.1126031937097647,"angularAcceleration":2.0614452496210744,"curveRadius":-25.615971336013263},{"acceleration":-2.9981799487532443,"curvature":-0.03773625358839024,"pose":{"rotation":{"radians":-2.9824639918655502},"translation":{"x":5.521949492656275,"y":1.978391147190059}},"time":2.0875087638783825,"velocity":2.7859029105044564,"position":2.997945719087309,"holonomicRotation":187.82009405856786,"angularVelocity":-0.10879749263541376,"angularAcceleration":2.079097255589936,"curveRadius":-26.499715920598316},{"acceleration":-2.998051786992571,"curvature":-0.036417861140805474,"pose":{"rotation":{"radians":-2.982656362222182},"translation":{"x":5.516917682213605,"y":1.9775846071678198}},"time":2.0893416028041067,"velocity":2.780407964487919,"position":3.003041759034016,"holonomicRotation":187.87297039819592,"angularVelocity":-0.10495759007069234,"angularAcceleration":2.0950572965401255,"curveRadius":-27.459053570818313},{"acceleration":-2.997923096681979,"curvature":-0.03508386469353477,"pose":{"rotation":{"radians":-2.982841893870354},"translation":{"x":5.5118887171729325,"y":1.9767794802055334}},"time":2.0911769830013234,"velocity":2.7749056358034907,"position":3.0081347658871147,"holonomicRotation":187.92584673782397,"angularVelocity":-0.10108622096564568,"angularAcceleration":2.1093009017519266,"curveRadius":-28.503131246663347},{"acceleration":-2.9977939016562893,"curvature":-0.033735181951192864,"pose":{"rotation":{"radians":-2.9830205301568284},"translation":{"x":5.506862202150267,"y":1.9759756663925936}},"time":2.0930150665270952,"velocity":2.769395440219197,"position":3.0132251460221293,"holonomicRotation":187.97872307745206,"angularVelocity":-0.09718616372431574,"angularAcceleration":2.1218063198146564,"curveRadius":-29.64264433038401},{"acceleration":-2.9976642256779025,"curvature":-0.03237275137687268,"pose":{"rotation":{"radians":-2.983192217607971},"translation":{"x":5.501837741761617,"y":1.9751730658183941}},"time":2.094856016749035,"velocity":2.763876889597634,"position":3.0183133057954485,"holonomicRotation":188.03159941708012,"angularVelocity":-0.09326023544606606,"angularAcceleration":2.132555368125498,"curveRadius":-30.890176381931102},{"acceleration":-2.9975340921421654,"curvature":-0.03099752754317262,"pose":{"rotation":{"radians":-2.983356905980234},"translation":{"x":5.496814940622994,"y":1.9743715785723288}},"time":2.0966999983636097,"velocity":2.7583494918426634,"position":3.0233996515449775,"holonomicRotation":188.08447575670817,"angularVelocity":-0.0893112875754021,"angularAcceleration":2.1415332123986834,"curveRadius":-32.2606375172092},{"acceleration":-2.9974035242539907,"curvature":-0.02961048248320636,"pose":{"rotation":{"radians":-2.98351454830759},"translation":{"x":5.4917934033504086,"y":1.9735711047437912}},"time":2.0985471774150333,"velocity":2.752812750843998,"position":3.0284845895908283,"holonomicRotation":188.13735209633626,"angularVelocity":-0.0853422017938319,"angularAcceleration":2.1487282342831016,"curveRadius":-33.77182389942993},{"acceleration":-2.9972725467775256,"curvature":-0.02821259642586811,"pose":{"rotation":{"radians":-2.9836651009444215},"translation":{"x":5.486772734559869,"y":1.9727715444221754}},"time":2.100397721314757,"velocity":2.74726616641675,"position":3.033568526236008,"holonomicRotation":188.19022843596431,"angularVelocity":-0.0813558850746466,"angularAcceleration":2.1541324795270604,"curveRadius":-35.4451602009626},{"acceleration":-2.9971411818257385,"curvature":-0.02680487342401615,"pose":{"rotation":{"radians":-2.9838085236044467},"translation":{"x":5.481752538867386,"y":1.9719727976968746}},"time":2.1022517988615745,"velocity":2.7417092342468843,"position":3.0386518677671277,"holonomicRotation":188.24310477559237,"angularVelocity":-0.07735526503267157,"angularAcceleration":2.157741486509939,"curveRadius":-37.30664883886517},{"acceleration":-2.9970094537266534,"curvature":-0.02538831876277781,"pose":{"rotation":{"radians":-2.983944779396623},"translation":{"x":5.47673242088897,"y":1.9711747646572828}},"time":2.1041095802623686,"velocity":2.736141445825747,"position":3.0437350204551246,"holonomicRotation":188.29598111522046,"angularVelocity":-0.07334328576979161,"angularAcceleration":2.159554004128323,"curveRadius":-39.38819302466435},{"acceleration":-2.996877386029655,"curvature":-0.023963952715664545,"pose":{"rotation":{"radians":-2.9840738348561606},"translation":{"x":5.471711985240631,"y":1.9703773453927942}},"time":2.105971237153513,"velocity":2.7305622883881298,"position":3.0488183905560016,"holonomicRotation":188.3488574548485,"angularVelocity":-0.06932290270648958,"angularAcceleration":2.1595725197409728,"curveRadius":-41.729342895353355},{"acceleration":-2.996745002358774,"curvature":-0.022532804016480154,"pose":{"rotation":{"radians":-2.9841956599712316},"translation":{"x":5.466690836538379,"y":1.9695804399928019}},"time":2.10783694262295,"velocity":2.7249712448467207,"position":3.053902384311571,"holonomicRotation":188.40173379447657,"angularVelocity":-0.0652970777363528,"angularAcceleration":2.157803059531912,"curveRadius":-44.37974072239811},{"acceleration":-2.996612324626266,"curvature":-0.021095903529514223,"pose":{"rotation":{"radians":-2.9843102282068092},"translation":{"x":5.461668579398224,"y":1.9687839485467}},"time":2.109706871232964,"velocity":2.719367793727782,"position":3.058987407950213,"holonomicRotation":188.45461013410466,"angularVelocity":-0.06126877516291856,"angularAcceleration":2.154254740989446,"curveRadius":-47.40256792514006},{"acceleration":-2.996479377166159,"curvature":-0.0196542916188859,"pose":{"rotation":{"radians":-2.9844175165229276},"translation":{"x":5.4566448184361755,"y":1.9679877711438822}},"time":2.1115811990436786,"velocity":2.713751409096927,"position":3.064073867687649,"holonomicRotation":188.5074864737327,"angularVelocity":-0.05724095620044899,"angularAcceleration":2.148940510536488,"curveRadius":-50.87947301235193},{"acceleration":-2.996346182803759,"curvature":-0.018209009117199894,"pose":{"rotation":{"radians":-2.9845175053895585},"translation":{"x":5.451619158268244,"y":1.967191807873742}},"time":2.1134601036372915,"velocity":2.708121560490002,"position":3.069162169727716,"holonomicRotation":188.5603628133608,"angularVelocity":-0.05321657468440406,"angularAcceleration":2.1418764580837184,"curveRadius":-54.917870245636735},{"acceleration":-2.996212763103555,"curvature":-0.016761096676159545,"pose":{"rotation":{"radians":-2.984610178797225},"translation":{"x":5.446591203510439,"y":1.9663959588256734}},"time":2.1153437641430743,"velocity":2.7024777128412216,"position":3.074252720263153,"holonomicRotation":188.61323915298885,"angularVelocity":-0.04919857234464122,"angularAcceleration":2.1330820110246087,"curveRadius":-59.66196719230004},{"acceleration":-2.996079141837591,"curvature":-0.015311604498496056,"pose":{"rotation":{"radians":-2.9846955242629583},"translation":{"x":5.441560558778772,"y":1.96560012408907}},"time":2.1172323612631643,"velocity":2.6968193264023856,"position":3.0793459254763995,"holonomicRotation":188.6661154926169,"angularVelocity":-0.04518987391507845,"angularAcceleration":2.122579975856306,"curveRadius":-65.30994188742417},{"acceleration":-2.9959453405066525,"curvature":-0.013861567007009747,"pose":{"rotation":{"radians":-2.9847735328326084},"translation":{"x":5.43652682868925,"y":1.9648042037533255}},"time":2.1191260772991662,"velocity":2.691145856668083,"position":3.084442191540392,"holonomicRotation":188.718991832245,"angularVelocity":-0.04119338283411043,"angularAcceleration":2.1103961760842727,"curveRadius":-72.14191580896326},{"acceleration":-2.9958113809447275,"curvature":-0.012412015461179452,"pose":{"rotation":{"radians":-2.9848441990783443},"translation":{"x":5.4314896178578875,"y":1.9640080979078343}},"time":2.121025096179595,"velocity":2.6854567542934658,"position":3.08954192461937,"holonomicRotation":188.77186817187305,"angularVelocity":-0.037211976386447375,"angularAcceleration":2.096559696533593,"curveRadius":-80.56709267948132},{"acceleration":-2.9956772848903674,"curvature":-0.010963996215455591,"pose":{"rotation":{"radians":-2.9849075210924867},"translation":{"x":5.426448530900691,"y":1.9632117066419892}},"time":2.122929603488187,"velocity":2.6797514650102086,"position":3.0946455308696925,"holonomicRotation":188.8247445115011,"angularVelocity":-0.03324850151884957,"angularAcceleration":2.0811024718659046,"curveRadius":-91.20761995433128},{"acceleration":-2.995543074070936,"curvature":-0.009518529537889094,"pose":{"rotation":{"radians":-2.984963500477047},"translation":{"x":5.4214031724336715,"y":1.9624149300451843}},"time":2.1248397864931032,"velocity":2.674029429539624,"position":3.099753416440645,"holonomicRotation":188.8776208511292,"angularVelocity":-0.029305770398010883,"angularAcceleration":2.0640593653547223,"curveRadius":-105.0582441352352},{"acceleration":-2.9954087682385335,"curvature":-0.008076628785420141,"pose":{"rotation":{"radians":-2.985012142328798},"translation":{"x":5.416353147072839,"y":1.9616176682068134}},"time":2.1267558341770547,"velocity":2.6682900835067525,"position":3.1048659874752587,"holonomicRotation":188.93049719075725,"angularVelocity":-0.025386555960127996,"angularAcceleration":2.045468111628754,"curveRadius":-123.81403510895427},{"acceleration":-2.995274389527784,"curvature":-0.0066392982633189926,"pose":{"rotation":{"radians":-2.9850534552207755},"translation":{"x":5.411298059434204,"y":1.9608198212162704}},"time":2.1286779372683866,"velocity":2.662532857343254,"position":3.109983650111131,"holonomicRotation":188.9833735303853,"angularVelocity":-0.02149358802029253,"angularAcceleration":2.02536896038073,"curveRadius":-150.61832747066538},{"acceleration":-2.9951399562367262,"curvature":-0.005207548655406601,"pose":{"rotation":{"radians":-2.985087451179213},"translation":{"x":5.4062375141337755,"y":1.960021289162949}},"time":2.1306062882731402,"velocity":2.656757176199267,"position":3.115106810481241,"holonomicRotation":189.0362498700134,"angularVelocity":-0.01762954895341511,"angularAcceleration":2.0038048349870223,"curveRadius":-192.02893072574102},{"acceleration":-2.9950054895045297,"curvature":-0.0037823399998785207,"pose":{"rotation":{"radians":-2.985114145657133},"translation":{"x":5.401171115787564,"y":1.9592219721362425}},"time":2.132541081508138,"velocity":2.650962459839393,"position":3.120235874714771,"holonomicRotation":189.08912620964145,"angularVelocity":-0.013797070114177423,"angularAcceleration":1.9808208804505694,"curveRadius":-264.3865966655873},{"acceleration":-2.994871007385208,"curvature":-0.0023646704359831343,"pose":{"rotation":{"radians":-2.9851335575035534},"translation":{"x":5.396098469011581,"y":1.9584217702255449}},"time":2.1344825131351137,"velocity":2.645148122546942,"position":3.1253712489379195,"holonomicRotation":189.14200254926953,"angularVelocity":-0.009998727820639777,"angularAcceleration":1.9564646216535435,"curveRadius":-422.89191118687137},{"acceleration":-2.9947365300412603,"curvature":-0.0009554905040638311,"pose":{"rotation":{"radians":-2.9851457089292346},"translation":{"x":5.391019178421835,"y":1.95762058352025}},"time":2.1364307811959367,"velocity":2.639313573014883,"position":3.130513339274721,"holonomicRotation":189.1948788888976,"angularVelocity":-0.006237039925653569,"angularAcceleration":1.9307855888153813,"curveRadius":-1046.5828762785857},{"acceleration":-2.994602074205346,"curvature":0.0004443814669934172,"pose":{"rotation":{"radians":-2.9851506254682216},"translation":{"x":5.385932848634336,"y":1.956818312109752}},"time":2.1383860856489485,"velocity":2.633458214244191,"position":3.135662551847853,"holonomicRotation":189.24775522852565,"angularVelocity":-0.002514462123517378,"angularAcceleration":1.9038353829768766,"curveRadius":2250.3188685292616},{"acceleration":-2.9944676584843575,"curvature":0.0018337959820961796,"pose":{"rotation":{"radians":-2.9851483359361626},"translation":{"x":5.3808390842650935,"y":1.9560148560834438}},"time":2.140348628406468,"velocity":2.6275814434284057,"position":3.1408192927794465,"holonomicRotation":189.30063156815373,"angularVelocity":0.0011666151222844137,"angularAcceleration":1.875667285055318,"curveRadius":545.3169326158725},{"acceleration":-2.9943332997739898,"curvature":0.0032120099700976993,"pose":{"rotation":{"radians":-2.9851388723854306},"translation":{"x":5.375737489930119,"y":1.9552101155307198}},"time":2.1423186133734933,"velocity":2.621682651841588,"position":3.145983968191885,"holonomicRotation":189.3535079077818,"angularVelocity":0.004803869516952767,"angularAcceleration":1.8463361170521535,"curveRadius":311.3315367354178},{"acceleration":-2.994199014668705,"curvature":0.004578124516223097,"pose":{"rotation":{"radians":-2.9851222700557734},"translation":{"x":5.370627670245422,"y":1.9544039905409734}},"time":2.144296246487644,"velocity":2.6157612247198223,"position":3.151156984208602,"holonomicRotation":189.40638424740985,"angularVelocity":0.008395050395588298,"angularAcceleration":1.8158984358319838,"curveRadius":218.430057211504},{"acceleration":-2.994064819070599,"curvature":0.005931287758735295,"pose":{"rotation":{"radians":-2.985098567322811},"translation":{"x":5.365509229827012,"y":1.9535963812035984}},"time":2.1462817357603905,"velocity":2.6098165411396494,"position":3.1563387469548716,"holonomicRotation":189.45926058703793,"angularVelocity":0.011937980873278712,"angularAcceleration":1.7844117952796754,"curveRadius":168.5974514602249},{"acceleration":-2.993930728618706,"curvature":0.007270662649525199,"pose":{"rotation":{"radians":-2.985067805642582},"translation":{"x":5.360381773290899,"y":1.9527871876079885}},"time":2.1482752913196106,"velocity":2.6038479738916918,"position":3.1615296625585874,"holonomicRotation":189.512136926666,"angularVelocity":0.015430560782234712,"angularAcceleration":1.7519350753998264,"curveRadius":137.53904536683513},{"acceleration":-2.993796757832807,"curvature":0.008595437251698979,"pose":{"rotation":{"radians":-2.9850300294933385},"translation":{"x":5.355244905253094,"y":1.9519763098435376}},"time":2.1502771254535205,"velocity":2.5978548893518734,"position":3.1667301371510366,"holonomicRotation":189.56501326629405,"angularVelocity":0.018870768863153847,"angularAcceleration":1.7185280351873733,"curveRadius":116.34079462360563},{"acceleration":-2.9936629206104155,"curvature":0.009904831868652153,"pose":{"rotation":{"radians":-2.984985286314407},"translation":{"x":5.350098230329607,"y":1.9511636479996395}},"time":2.1522874526560303,"velocity":2.5918366473474252,"position":3.171940576867661,"holonomicRotation":189.61788960592213,"angularVelocity":0.02225666492290448,"angularAcceleration":1.6842512281202113,"curveRadius":100.96082530839362},{"acceleration":-2.9935292307148234,"curvature":0.011198079575605108,"pose":{"rotation":{"radians":-2.984933626442364},"translation":{"x":5.344941353136447,"y":1.9503491021656878}},"time":2.1543064896735777,"velocity":2.5857926010175016,"position":3.1771613878488156,"holonomicRotation":189.6707659455502,"angularVelocity":0.025586391727260186,"angularAcceleration":1.6491658030125382,"curveRadius":89.30102641693036},{"acceleration":-2.9933957007789713,"curvature":0.012474458291215618,"pose":{"rotation":{"radians":-2.984875103044089},"translation":{"x":5.339773878289624,"y":1.9495325724310764}},"time":2.1563344555534836,"velocity":2.579722096671265,"position":3.182392976240504,"holonomicRotation":189.72364228517824,"angularVelocity":0.028858176981643308,"angularAcceleration":1.6133334819888787,"curveRadius":80.16380163811918},{"acceleration":-2.993262342667498,"curvature":0.013733265839591734,"pose":{"rotation":{"radians":-2.9848097720479396},"translation":{"x":5.334595410405149,"y":1.9487139588851985}},"time":2.1583715716938943,"velocity":2.5736244736405336,"position":3.187635748195113,"holonomicRotation":189.77651862480633,"angularVelocity":0.032070334554508445,"angularAcceleration":1.576816122137031,"curveRadius":72.81589184104283},{"acceleration":-2.9931291672823175,"curvature":0.01497382753578129,"pose":{"rotation":{"radians":-2.9847376920723803},"translation":{"x":5.329405554099032,"y":1.9478931616174484}},"time":2.160418061895362,"velocity":2.5674990641279627,"position":3.192890109872129,"holonomicRotation":189.82939496443439,"angularVelocity":0.0352212659057241,"angularAcceleration":1.5396757575265383,"curveRadius":66.78319204695067},{"acceleration":-2.9929961858186482,"curvature":0.01619549432101742,"pose":{"rotation":{"radians":-2.9846589243519195},"translation":{"x":5.324203913987281,"y":1.9470700807172197}},"time":2.1624741524141293,"velocity":2.5613451930475946,"position":3.198156467438844,"holonomicRotation":189.88227130406247,"angularVelocity":0.038309461447256415,"angularAcceleration":1.5019745061535221,"curveRadius":61.745568253651115},{"acceleration":-2.9928634075225604,"curvature":0.017397649931491444,"pose":{"rotation":{"radians":-2.9845735326616105},"translation":{"x":5.31899009468591,"y":1.9462446162739062}},"time":2.1645400720171697,"velocity":2.5551621778647715,"position":3.2034352270710422,"holonomicRotation":189.93514764369053,"angularVelocity":0.04133350116011188,"angularAcceleration":1.4637741509422975,"curveRadius":57.47902756624057},{"acceleration":-2.9927308413284366,"curvature":0.018579705051664133,"pose":{"rotation":{"radians":-2.984481583239517},"translation":{"x":5.313763700810925,"y":1.9454166683769014}},"time":2.1666160520390676,"velocity":2.548949328427256,"position":3.2087267949536873,"holonomicRotation":189.98802398331858,"angularVelocity":0.044292055378072126,"angularAcceleration":1.4251361702678988,"curveRadius":53.82216764040787},{"acceleration":-2.992598495214993,"curvature":0.019741107886320393,"pose":{"rotation":{"radians":-2.9843831447070284},"translation":{"x":5.308524336978339,"y":1.9445861371155995}},"time":2.168702326440783,"velocity":2.542705946792077,"position":3.214031577281569,"holonomicRotation":190.04090032294667,"angularVelocity":0.04718388549825365,"angularAcceleration":1.3861216519762665,"curveRadius":50.6557182990196},{"acceleration":-2.992466376931318,"curvature":0.02088132662359242,"pose":{"rotation":{"radians":-2.984278287988129},"translation":{"x":5.303271607804159,"y":1.9437529225793935}},"time":2.1707991318703996,"velocity":2.536431327044982,"position":3.2193499802599668,"holonomicRotation":190.09377666257473,"angularVelocity":0.05000784403654955,"angularAcceleration":1.3467909317709978,"curveRadius":47.88967760650641},{"acceleration":-2.9923344925068416,"curvature":0.02199986911546244,"pose":{"rotation":{"radians":-2.984167086226915},"translation":{"x":5.298005117904397,"y":1.942916924857678}},"time":2.172906707725903,"velocity":2.5301247551169848,"position":3.2246824101052627,"holonomicRotation":190.14665300220278,"angularVelocity":0.05276287490367532,"angularAcceleration":1.3072036576675312,"curveRadius":45.454815878752555},{"acceleration":-2.9922028471237967,"curvature":0.02309627059205742,"pose":{"rotation":{"radians":-2.9840496147035958},"translation":{"x":5.292724471895063,"y":1.9420780440398464}},"time":2.175025296220092,"velocity":2.523785508592788,"position":3.230029273045569,"holonomicRotation":190.19952934183087,"angularVelocity":0.05544801344934118,"angularAcceleration":1.2674186388864779,"curveRadius":43.29703343291666},{"acceleration":-2.992071446319749,"curvature":0.024170092629606267,"pose":{"rotation":{"radians":-2.983925950750115},"translation":{"x":5.287429274392167,"y":1.9412361802152922}},"time":2.177155142447692,"velocity":2.5174128565101355,"position":3.2353909753213177,"holonomicRotation":190.25240568145892,"angularVelocity":0.05806238585605782,"angularAcceleration":1.2274935029760918,"curveRadius":41.37344508043328},{"acceleration":-2.9919402933747077,"curvature":0.025220936497285636,"pose":{"rotation":{"radians":-2.983796173664032},"translation":{"x":5.282119130011719,"y":1.9403912334734092}},"time":2.179296494454755,"velocity":2.511006059157905,"position":3.240767923185843,"holonomicRotation":190.305282021087,"angularVelocity":0.060605209071094304,"angularAcceleration":1.1874849191768906,"curveRadius":39.64959826561648},{"acceleration":-2.9918093909502854,"curvature":0.026248430841977297,"pose":{"rotation":{"radians":-2.9836603646220925},"translation":{"x":5.276793643369729,"y":1.9395431039035917}},"time":2.1814496033104476,"velocity":2.504564367863705,"position":3.2461605229059427,"holonomicRotation":190.35815836071507,"angularVelocity":0.06307578995848896,"angularAcceleration":1.1474482030309419,"curveRadius":38.09751546750632},{"acceleration":-2.991678741139243,"curvature":0.027252232290233575,"pose":{"rotation":{"radians":-2.9835186065923684},"translation":{"x":5.271452419082206,"y":1.9386916915952328}},"time":2.1836147231813086,"velocity":2.498087024774032,"position":3.251569180762421,"holonomicRotation":190.41103470034312,"angularVelocity":0.06547352487586587,"angularAcceleration":1.1074374909429006,"curveRadius":36.694241754220315},{"acceleration":-2.9915483450001403,"curvature":0.028232031971419824,"pose":{"rotation":{"radians":-2.9833709842473843},"translation":{"x":5.266095061765162,"y":1.9378368966377266}},"time":2.1857921114080843,"velocity":2.4915732626277984,"position":3.256994303050616,"holonomicRotation":190.4639110399712,"angularVelocity":0.06779789803617646,"angularAcceleration":1.0675051567411722,"curveRadius":35.42075898087433},{"acceleration":-2.9914182027770404,"curvature":0.029187550071874135,"pose":{"rotation":{"radians":-2.98321758387494},"translation":{"x":5.260721176034606,"y":1.9369786191204665}},"time":2.1879820285852407,"velocity":2.4850223045214785,"position":3.2624362960809044,"holonomicRotation":190.51678737959926,"angularVelocity":0.07004848130528103,"angularAcceleration":1.0277024595180828,"curveRadius":34.26118319411897},{"acceleration":-2.9912883125658443,"curvature":0.030118540089545058,"pose":{"rotation":{"radians":-2.9830584932905273},"translation":{"x":5.255330366506547,"y":1.9361167591328468}},"time":2.190184738643262,"velocity":2.478433363668948,"position":3.2678955661791935,"holonomicRotation":190.56966371922732,"angularVelocity":0.07222493211648147,"angularAcceleration":0.9880786639506887,"curveRadius":33.202140509696434},{"acceleration":-2.991158673313947,"curvature":0.03102477984318885,"pose":{"rotation":{"radians":-2.982893801747996},"translation":{"x":5.249922237796995,"y":1.9352512167642606}},"time":2.1924005089338503,"velocity":2.4718056431461837,"position":3.2733725196873853,"holonomicRotation":190.6225400588554,"angularVelocity":0.07432699284355379,"angularAcceleration":0.9486817004456857,"curveRadius":32.2322996344981},{"acceleration":-2.991029281848594,"curvature":0.03190608398091235,"pose":{"rotation":{"radians":-2.9827235998518264},"translation":{"x":5.2444963945219625,"y":1.934381892104102}},"time":2.1946296103181466,"velocity":2.465138335633544,"position":3.278867562963828,"holonomicRotation":190.67541639848346,"angularVelocity":0.07635448857032154,"angularAcceleration":0.9095574302053459,"curveRadius":31.341984826412563},{"acceleration":-2.990900133568867,"curvature":0.03276229108867417,"pose":{"rotation":{"radians":-2.982547979468475},"translation":{"x":5.239052441297458,"y":1.933508685241765}},"time":2.196872317258098,"velocity":2.458430623147288,"position":3.2843811023837493,"holonomicRotation":190.72829273811152,"angularVelocity":0.07830732594745769,"angularAcceleration":0.8707501378573077,"curveRadius":30.522895889466565},{"acceleration":-2.9907712241127458,"curvature":0.03359327160982157,"pose":{"rotation":{"radians":-2.9823670336384165},"translation":{"x":5.233589982739492,"y":1.9326314962666424}},"time":2.199128907911103,"velocity":2.451681676757678,"position":3.2899135443396648,"holonomicRotation":190.7811690777396,"angularVelocity":0.0801854912487523,"angularAcceleration":0.8323021717711009,"curveRadius":29.767865768323468},{"acceleration":-2.9906425467613444,"curvature":0.03439892236500867,"pose":{"rotation":{"radians":-2.9821808564890127},"translation":{"x":5.228108623464073,"y":1.9317502252681291}},"time":2.2013996642280755,"velocity":2.4448906563028134,"position":3.295465295241771,"holonomicRotation":190.83404541736766,"angularVelocity":0.08198904832380434,"angularAcceleration":0.7942539063182024,"curveRadius":29.070678127324758},{"acceleration":-2.9905140947470383,"curvature":0.035179170003703325,"pose":{"rotation":{"radians":-2.9819895431468613},"translation":{"x":5.222607968087213,"y":1.9308647723356183}},"time":2.203684872055069,"velocity":2.438056710086763,"position":3.3010367615183154,"holonomicRotation":190.88692175699572,"angularVelocity":0.08371813709525444,"angularAcceleration":0.7566439914241688,"curveRadius":28.425912262703456},{"acceleration":-2.9903858592408645,"curvature":0.035933968229925686,"pose":{"rotation":{"radians":-2.9817931896524024},"translation":{"x":5.217087621224921,"y":1.9299750375585036}},"time":2.205984821238622,"velocity":2.431178974571294,"position":3.3066283496159516,"holonomicRotation":190.9397980966238,"angularVelocity":0.08537297078693605,"angularAcceleration":0.7195088063316482,"curveRadius":27.828821843483556},{"acceleration":-2.9902578315461747,"curvature":0.03666329545745223,"pose":{"rotation":{"radians":-2.9815918928739147},"translation":{"x":5.211547187493206,"y":1.9290809210261792}},"time":2.2082998057349785,"velocity":2.4242565740511557,"position":3.3122404660000706,"holonomicRotation":190.99267443625186,"angularVelocity":0.08695383437966406,"angularAcceleration":0.6828830150767887,"curveRadius":27.275235014280167},{"acceleration":-2.9901300001747533,"curvature":0.0373671590025006,"pose":{"rotation":{"radians":-2.9813857504230135},"translation":{"x":5.20598627150808,"y":1.9281823228280381}},"time":2.2106301237233565,"velocity":2.4172886203241597,"position":3.3178735171551135,"holonomicRotation":191.04555077587995,"angularVelocity":0.08846108210524002,"angularAcceleration":0.6467991635017422,"curveRadius":26.761467199930298},{"acceleration":-2.990002354052162,"curvature":0.038045590443846845,"pose":{"rotation":{"radians":-2.9811748605717012},"translation":{"x":5.200404477885552,"y":1.9272791430534748}},"time":2.212976077723446,"velocity":2.4102742123413936,"position":3.3235279095848687,"holonomicRotation":191.098427115508,"angularVelocity":0.08989513490212389,"angularAcceleration":0.611287688006277,"curveRadius":26.284254977615443},{"acceleration":-2.9898748797710133,"curvature":0.038698644611729255,"pose":{"rotation":{"radians":-2.9809593221691624},"translation":{"x":5.194801411241633,"y":1.926371281791883}},"time":2.2153379747173196,"velocity":2.4032124358508047,"position":3.329204049812744,"holonomicRotation":191.15130345513606,"angularVelocity":0.09125647862626413,"angularAcceleration":0.5763772627135876,"curveRadius":25.840698299208853},{"acceleration":-2.989747563800768,"curvature":0.03952805999838324,"pose":{"rotation":{"radians":-2.980739234561077},"translation":{"x":5.189176676192331,"y":1.925458639132656}},"time":2.217716126275959,"velocity":2.396102363022014,"position":3.334902344382024,"holonomicRotation":191.20417979476414,"angularVelocity":0.09254566105588209,"angularAcceleration":0.5420943105727273,"curveRadius":25.298484166460522},{"acceleration":-2.2421925440006505,"curvature":0.22895556123043856,"pose":{"rotation":{"radians":-2.9804000250455847},"translation":{"x":5.177860619341625,"y":1.923618609978872}},"time":2.2225224630775706,"velocity":2.3853256304814843,"position":3.346367022743635,"holonomicRotation":-168.6900675259797,"angularVelocity":0.07057547764414356,"angularAcceleration":-4.57108694596077,"curveRadius":4.3676597966254365},{"acceleration":-3.9686229309325616,"curvature":0.5343933833466344,"pose":{"rotation":{"radians":-2.978293968978982},"translation":{"x":5.171020454838984,"y":1.922491584329928}},"time":2.2254429193011895,"velocity":2.3737354409436455,"position":3.3532994131853635,"holonomicRotation":-168.57515056491204,"angularVelocity":0.7211394060867359,"angularAcceleration":222.76106150169872,"curveRadius":1.8712806542205065},{"acceleration":0.0018400211018079014,"curvature":0.5241697386659564,"pose":{"rotation":{"radians":-2.9745870640843135},"translation":{"x":5.1641761037713785,"y":1.9213377926971185}},"time":2.2283669623922058,"velocity":2.3737408212446356,"position":3.360240333633587,"holonomicRotation":-168.46023360384436,"angularVelocity":1.2677326493776047,"angularAcceleration":186.93063893969594,"curveRadius":1.9077789621069317},{"acceleration":3.0036849846335394,"curvature":0.5140091792910961,"pose":{"rotation":{"radians":-2.970946601786019},"translation":{"x":5.157327576311893,"y":1.9201576408548313}},"time":2.2312838397179036,"velocity":2.382502201869852,"position":3.3671898002846463,"holonomicRotation":-168.34531664277668,"angularVelocity":1.2480683593451216,"angularAcceleration":-6.741555381585641,"curveRadius":1.9454905482022047},{"acceleration":3.0036509981279376,"curvature":0.5039124464469509,"pose":{"rotation":{"radians":-2.967372310862988},"translation":{"x":5.1504748826336115,"y":1.9189515345774524}},"time":2.2341936346064353,"velocity":2.391242210191138,"position":3.3741478246451018,"holonomicRotation":-168.230399681709,"angularVelocity":1.228365249082748,"angularAcceleration":-6.771305544603495,"curveRadius":1.9844717213296188},{"acceleration":3.0036184569907376,"curvature":0.49388017691518743,"pose":{"rotation":{"radians":-2.9638639160764404},"translation":{"x":5.143618032909617,"y":1.9177198796393693}},"time":2.2370964270750378,"velocity":2.399961091226646,"position":3.3811144136256535,"holonomicRotation":-168.11548272064132,"angularVelocity":1.208627493868552,"angularAcceleration":-6.799575039444181,"curveRadius":2.024782622874388},{"acceleration":3.003587323735554,"curvature":0.4839129068493576,"pose":{"rotation":{"radians":-2.960421138635056},"translation":{"x":5.136757037312995,"y":1.9164630818149684}},"time":2.2399922939356345,"velocity":2.4086590802203602,"position":3.388089569634539,"holonomicRotation":-168.00056575957365,"angularVelocity":1.1888590211895649,"angularAcceleration":-6.826443904576997,"curveRadius":2.066487555603266},{"acceleration":3.003557561412449,"curvature":0.47401107560646794,"pose":{"rotation":{"radians":-2.957043696646348},"translation":{"x":5.129891906016829,"y":1.915181546878637}},"time":2.242881308897441,"velocity":2.417336402953928,"position":3.3950732906703927,"holonomicRotation":-167.88564879850597,"angularVelocity":1.1690635158899387,"angularAcceleration":-6.8519912708404,"curveRadius":2.1096553465983083},{"acceleration":3.003529133926048,"curvature":0.46417502986158726,"pose":{"rotation":{"radians":-2.9537313055510697},"translation":{"x":5.123022649194205,"y":1.9138756806047625}},"time":2.245763542666667,"velocity":2.4259932760505833,"position":3.4020655704145404,"holonomicRotation":-167.77073183743832,"angularVelocity":1.1492444265434731,"angularAcceleration":-6.876294892551057,"curveRadius":2.1543597472233498},{"acceleration":3.003502005759835,"curvature":0.4544050273764155,"pose":{"rotation":{"radians":-2.95048367854269},"translation":{"x":5.116149277018205,"y":1.912545888767731}},"time":2.2486390630434,"velocity":2.434629907269705,"position":3.4090663983226985,"holonomicRotation":-167.65581487637064,"angularVelocity":1.1294049712384233,"angularAcceleration":-6.899431304878718,"curveRadius":2.200679877539361},{"acceleration":3.0034761420337635,"curvature":0.4447012406525202,"pose":{"rotation":{"radians":-2.9473005269723314},"translation":{"x":5.109271799661912,"y":1.9111925771419296}},"time":2.2515079350157685,"velocity":2.4432464957932627,"position":3.416075759716067,"holonomicRotation":-167.54089791530296,"angularVelocity":1.109548143318004,"angularAcceleration":-6.921475796644338,"curveRadius":2.2487007199095674},{"acceleration":3.0034515089353904,"curvature":0.4350637607343848,"pose":{"rotation":{"radians":-2.9441815607375506},"translation":{"x":5.102390227298413,"y":1.9098161515017453}},"time":2.2543702208514538,"velocity":2.451843232505456,"position":3.4230936358717883,"holonomicRotation":-167.42598095423529,"angularVelocity":1.0896767177810847,"angularAcceleration":-6.942502139085634,"curveRadius":2.2985136668519726},{"acceleration":3.003428072701192,"curvature":0.4254926004357452,"pose":{"rotation":{"radians":-2.9411264886578596},"translation":{"x":5.095504570100791,"y":1.9084170176215651}},"time":2.25722598018665,"velocity":2.460420300261663,"position":3.430120004112767,"holonomicRotation":-167.3110639931676,"angularVelocity":1.0697932567489556,"angularAcceleration":-6.96258287141765,"curveRadius":2.3502171341543994},{"acceleration":3.003405800876168,"curvature":0.4159876983520908,"pose":{"rotation":{"radians":-2.93813501883516},"translation":{"x":5.088614838242129,"y":1.9069955812757764}},"time":2.260075270112537,"velocity":2.4689778741534494,"position":3.4371548378968297,"holonomicRotation":-167.19614703209993,"angularVelocity":1.0499001156467496,"angularAcceleration":-6.981789013982175,"curveRadius":2.4039172407295633},{"acceleration":3.0033846608793016,"curvature":0.4065489219184171,"pose":{"rotation":{"radians":-2.9352068589998956},"translation":{"x":5.081721041895512,"y":1.9055522482387652}},"time":2.262918145259346,"velocity":2.4775161217621706,"position":3.444198106905206,"holonomicRotation":-167.08123007103225,"angularVelocity":1.0299994491671907,"angularAcceleration":-7.000190107503063,"curveRadius":2.4597285740697936},{"acceleration":3.003364621861202,"curvature":0.39717607077784595,"pose":{"rotation":{"radians":-2.932341716844639},"translation":{"x":5.074823191234024,"y":1.9040874242849188}},"time":2.2657546578780945,"velocity":2.486035203410783,"position":3.451249777130334,"holonomicRotation":-166.96631310996457,"angularVelocity":1.0100932166911367,"angularAcceleration":-7.017854369650553,"curveRadius":2.5177750463202853},{"acceleration":3.00334565215831,"curvature":0.38786887980130375,"pose":{"rotation":{"radians":-2.9295393003428236},"translation":{"x":5.0679212964307485,"y":1.9026015151886242}},"time":2.268584857920059,"velocity":2.494535272401556,"position":3.4583098109629673,"holonomicRotation":-166.8513961488969,"angularVelocity":0.9901831885600065,"angularAcceleration":-7.034848362629911,"curveRadius":2.5781908579834423},{"acceleration":3.003327722264887,"curvature":0.3786270227500798,"pose":{"rotation":{"radians":-2.926799318055364},"translation":{"x":5.06101536765877,"y":1.9010949267242685}},"time":2.2714087931140527,"velocity":2.5030164752555564,"position":3.4653781672785873,"holonomicRotation":-166.73647918782922,"angularVelocity":0.9702709514323332,"angularAcceleration":-7.051237284065823,"curveRadius":2.641121578530515},{"acceleration":3.00331080207854,"curvature":0.36945011472649714,"pose":{"rotation":{"radians":-2.924121479423853},"translation":{"x":5.054105415091174,"y":1.8995680646662385}},"time":2.2742265090415774,"velocity":2.51147895193788,"position":3.4724548015231056,"holonomicRotation":-166.62156222676154,"angularVelocity":0.9503579141363684,"angularAcceleration":-7.067084762323156,"curveRadius":2.70672537411525},{"acceleration":3.0032948627886276,"curvature":0.3603377153437474,"pose":{"rotation":{"radians":-2.921505495051732},"translation":{"x":5.047191448901043,"y":1.8980213347889208}},"time":2.2770380492099136,"velocity":2.519922836081968,"position":3.4795396657978577,"holonomicRotation":-166.50664526569386,"angularVelocity":0.9304453130645745,"angularAcceleration":-7.082452990020009,"curveRadius":2.775174391739818},{"acceleration":3.003279875536681,"curvature":0.3512893316851424,"pose":{"rotation":{"radians":-2.918951076973272},"translation":{"x":5.040273479261461,"y":1.8964551428667027}},"time":2.279843455123212,"velocity":2.528348255204089,"position":3.486632708943885,"holonomicRotation":-166.39172830462618,"angularVelocity":0.9105342176513851,"angularAcceleration":-7.097402667758248,"curveRadius":2.846656330845513},{"acceleration":3.0032658131814545,"curvature":0.3423044209129894,"pose":{"rotation":{"radians":-2.9164579389098018},"translation":{"x":5.033351516345514,"y":1.8948698946739708}},"time":2.282642766351639,"velocity":2.5367553309168787,"position":3.493733876625493,"holonomicRotation":-166.2768113435585,"angularVelocity":0.8906255360791808,"angularAcceleration":-7.111992896692393,"curveRadius":2.921376233858781},{"acceleration":3.0032526477420545,"curvature":0.33338239300008404,"pose":{"rotation":{"radians":-2.9140257965162575},"translation":{"x":5.026425570326282,"y":1.8932659959851126}},"time":2.285436020598652,"velocity":2.5451441791300367,"position":3.5008431114131078,"holonomicRotation":-166.16189438249083,"angularVelocity":0.8707200198998264,"angularAcceleration":-7.126281540837861,"curveRadius":2.999558527974655},{"acceleration":3.0032403527077545,"curvature":0.3245226131971051,"pose":{"rotation":{"radians":-2.911654367614092},"translation":{"x":5.019495651376854,"y":1.8916438525745147}},"time":2.2882232537664375,"velocity":2.553514910251936,"position":3.507960352865397,"holonomicRotation":-166.04697742142318,"angularVelocity":0.8508182700945318,"angularAcceleration":-7.14032469020379,"curveRadius":3.081449363877242},{"acceleration":3.003228902182086,"curvature":0.315724404685072,"pose":{"rotation":{"radians":-2.909343372415842},"translation":{"x":5.01256176967031,"y":1.8900038702165638}},"time":2.2910045000195938,"velocity":2.5618676293835003,"position":3.515085537610702,"holonomicRotation":-165.9320604603555,"angularVelocity":0.8309207412423426,"angularAcceleration":-7.154177315154656,"curveRadius":3.167319298606256},{"acceleration":3.003218270128522,"curvature":0.30698705070820725,"pose":{"rotation":{"radians":-2.907092533737085},"translation":{"x":5.005623935379738,"y":1.888346454685647}},"time":2.293779791847085,"velocity":2.5702024365047604,"position":3.522218599427732,"holonomicRotation":-165.81714349928782,"angularVelocity":0.8110277472302478,"angularAcceleration":-7.167892693316213,"curveRadius":3.2574663904977057},{"acceleration":3.0032084313453598,"curvature":0.29830979731355006,"pose":{"rotation":{"radians":-2.9049015771993725},"translation":{"x":4.9986821586782195,"y":1.886672011756151}},"time":2.2965491601225425,"velocity":2.5785194266591147,"position":3.5293594693255725,"holonomicRotation":-165.70222653822015,"angularVelocity":0.7911394656786105,"angularAcceleration":-7.181522850496263,"curveRadius":3.3522197695334537},{"acceleration":3.003199361506566,"curvature":0.28969185498706507,"pose":{"rotation":{"radians":-2.902770231422705},"translation":{"x":4.991736449738837,"y":1.8849809472024632}},"time":2.299312634162945,"velocity":2.586818690132791,"position":3.536508075622982,"holonomicRotation":-165.58730957715247,"angularVelocity":0.7712559428846025,"angularAcceleration":-7.195118355847881,"curveRadius":3.4519437905654984},{"acceleration":3.003191036366564,"curvature":0.28113240153901975,"pose":{"rotation":{"radians":-2.900698228208142},"translation":{"x":4.984786818734678,"y":1.8832736667989707}},"time":2.3020702417857333,"velocity":2.5951003126273653,"position":3.543664344026984,"holonomicRotation":-165.4723926160848,"angularVelocity":0.7513770985546346,"angularAcceleration":-7.208728379517199,"curveRadius":3.5570428542766352},{"acceleration":3.0031834325190854,"curvature":0.2726305833140634,"pose":{"rotation":{"radians":-2.8986853027119026},"translation":{"x":4.977833275838827,"y":1.8815505763200595}},"time":2.3048220093644156,"velocity":2.6033643754298073,"position":3.5508281977107883,"holonomicRotation":-165.3574756550171,"angularVelocity":0.7315027300391401,"angularAcceleration":-7.2224008558932065,"curveRadius":3.6679670631376884},{"acceleration":3.0031765263823975,"curvature":0.2641855180251496,"pose":{"rotation":{"radians":-2.896731193610037},"translation":{"x":4.970875831224364,"y":1.8798120815401174}},"time":2.307567961882695,"velocity":2.6116109555752645,"position":3.557999557391016,"holonomicRotation":-165.24255869394943,"angularVelocity":0.7116325168980848,"angularAcceleration":-7.236182347940295,"curveRadius":3.785218839682208},{"acceleration":3.003170295658585,"curvature":0.25579629596823805,"pose":{"rotation":{"radians":-2.894835643253304},"translation":{"x":4.963914495064377,"y":1.8780585882335308}},"time":2.310308122987168,"velocity":2.619840126009537,"position":3.5651783414042453,"holonomicRotation":-165.12764173288176,"angularVelocity":0.6917660255955471,"angularAcceleration":-7.2501179839782015,"curveRadius":3.9093607521360236},{"acceleration":3.0031647178101304,"curvature":0.2474619821497179,"pose":{"rotation":{"radians":-2.8929983978156413},"translation":{"x":4.956949277531948,"y":1.8762905021746867}},"time":2.3130425150386467,"velocity":2.628051955743198,"position":3.5723644657829023,"holonomicRotation":-165.01272477181408,"angularVelocity":0.6719027129519455,"angularAcceleration":-7.264251895722307,"curveRadius":4.041024772019268},{"acceleration":3.0031597715768306,"curvature":0.23918161813661018,"pose":{"rotation":{"radians":-2.8912192074326994},"translation":{"x":4.949980188800162,"y":1.8745082291379722}},"time":2.315771159162133,"velocity":2.636246510005802,"position":3.579557844330491,"holonomicRotation":-164.8978078107464,"angularVelocity":0.6520419308724504,"angularAcceleration":-7.278626739392791,"curveRadius":4.180923299167762},{"acceleration":3.003155435091523,"curvature":0.23095422357539216,"pose":{"rotation":{"radians":-2.889497826333254},"translation":{"x":4.943007239042103,"y":1.8727121748977744}},"time":2.318494075295497,"velocity":2.6444238503910116,"position":3.5867583886961727,"holonomicRotation":-164.78289084967872,"angularVelocity":0.6321829300409442,"angularAcceleration":-7.293284059753114,"curveRadius":4.3298623619825785},{"acceleration":3.00315168776108,"curvature":0.2227787978102588,"pose":{"rotation":{"radians":-2.887834012962727},"translation":{"x":4.936030438430854,"y":1.8709027452284794}},"time":2.3212112822368915,"velocity":2.6525840350030574,"position":3.593966008448716,"holonomicRotation":-164.66797388861104,"angularVelocity":0.612324863881228,"angularAcceleration":-7.308264180100638,"curveRadius":4.488757502191489},{"acceleration":3.0031485091822874,"curvature":0.21465432163423404,"pose":{"rotation":{"radians":-2.886227530099733},"translation":{"x":4.929049797139501,"y":1.8690803459044754}},"time":2.3239227976909462,"velocity":2.6607271185965264,"position":3.601180611149813,"holonomicRotation":-164.55305692754337,"angularVelocity":0.5924667921740916,"angularAcceleration":-7.3236063166969965,"curveRadius":4.6586530025888635},{"acceleration":3.0031458788108325,"curvature":0.20657975841552614,"pose":{"rotation":{"radians":-2.884678144964671},"translation":{"x":4.922065325341126,"y":1.8672453827001483}},"time":2.3266286383137786,"velocity":2.6688531527117045,"position":3.6084021024267945,"holonomicRotation":-164.4381399664757,"angularVelocity":0.5726076850158323,"angularAcceleration":-7.3393484415468935,"curveRadius":4.840745326018553},{"acceleration":3.0031437774988827,"curvature":0.19855405601578405,"pose":{"rotation":{"radians":-2.88318562932235},"translation":{"x":4.9150770332088145,"y":1.8653982613898854}},"time":2.3293288197568534,"velocity":2.6769621858105923,"position":3.615630386044733,"holonomicRotation":-164.323223005408,"angularVelocity":0.5527464260407541,"angularAcceleration":-7.355527542794328,"curveRadius":5.036411847061462},{"acceleration":3.0031421855316176,"curvature":0.19057614742156148,"pose":{"rotation":{"radians":-2.8817497595772408},"translation":{"x":4.90808493091565,"y":1.8635393877480735}},"time":2.3320233567097324,"velocity":2.685054263404257,"position":3.622865363977961,"holonomicRotation":-164.20830604434036,"angularVelocity":0.5328818161409664,"angularAcceleration":-7.372179430889968,"curveRadius":5.247246381720389},{"acceleration":3.003141084370865,"curvature":0.18264495293109015,"pose":{"rotation":{"radians":-2.8803703168627965},"translation":{"x":4.9010890286347175,"y":1.8616691675490995}},"time":2.3347122629417454,"velocity":2.6931294281816363,"position":3.6301069364810163,"holonomicRotation":-164.09338908327268,"angularVelocity":0.513012576645908,"angularAcceleration":-7.389338928410139,"curveRadius":5.475103384747174},{"acceleration":3.003140455074427,"curvature":0.17475938082606896,"pose":{"rotation":{"radians":-2.879047087124362},"translation":{"x":4.8940893365391,"y":1.8597880065673509}},"time":2.337395551342618,"velocity":2.701187720130929,"position":3.6373550021590235,"holonomicRotation":-163.978472122205,"angularVelocity":0.49313735266187114,"angularAcceleration":-7.407039801451294,"curveRadius":5.722153484826432},{"acceleration":3.0031402795789703,"curvature":0.16691832857062727,"pose":{"rotation":{"radians":-2.877779861195605},"translation":{"x":4.887085864801883,"y":1.857896310577214}},"time":2.340073233962085,"velocity":2.709229176661379,"position":3.6446094580375226,"holonomicRotation":-163.86355516113733,"angularVelocity":0.4732547164268451,"angularAcceleration":-7.425314744353016,"curveRadius":5.990953830914233},{"acceleration":3.003140540198544,"curvature":0.15912068437738353,"pose":{"rotation":{"radians":-2.8765684348706353},"translation":{"x":4.880078623596148,"y":1.8559944853530757}},"time":2.3427453220485277,"velocity":2.7172538327207563,"position":3.651870199631776,"holonomicRotation":-163.74863820006965,"angularVelocity":0.4533631698431094,"angularAcceleration":-7.44419567777711,"curveRadius":6.284538078206847},{"acceleration":3.003141218651023,"curvature":0.1513653277238839,"pose":{"rotation":{"radians":-2.8754126089683703},"translation":{"x":4.8730676230949825,"y":1.854082936669323}},"time":2.3454118260866563,"velocity":2.7252617209073597,"position":3.659137121015533,"holonomicRotation":-163.63372123900197,"angularVelocity":0.4334611482817059,"angularAcceleration":-7.463713265317584,"curveRadius":6.6065327842065},{"acceleration":3.0031422986213463,"curvature":0.14365113083744493,"pose":{"rotation":{"radians":-2.8743121893938337},"translation":{"x":4.866052873471468,"y":1.8521620703003432}},"time":2.34807275583428,"velocity":2.733252871586109,"position":3.666410114889315,"holonomicRotation":-163.5188042779343,"angularVelocity":0.4135470226221431,"angularAcceleration":-7.483897565257179,"curveRadius":6.961309626804095},{"acceleration":3.0031437624605153,"curvature":0.13597695954138575,"pose":{"rotation":{"radians":-2.8732669871921592},"translation":{"x":4.859034384898689,"y":1.8502322920205228}},"time":2.350728120358183,"velocity":2.741227312993127,"position":3.6736890726481906,"holonomicRotation":-163.40388731686662,"angularVelocity":0.3936191028635933,"angularAcceleration":-7.504777434195471,"curveRadius":7.35418708708251},{"acceleration":3.00314559412464,"curvature":0.1283416744748909,"pose":{"rotation":{"radians":-2.872276818599086},"translation":{"x":4.852012167549731,"y":1.848294007604249}},"time":2.3533779280691367,"velocity":2.7491850713455546,"position":3.6809738844490805,"holonomicRotation":-163.28897035579894,"angularVelocity":0.3736756403040186,"angularAcceleration":-7.526381056683429,"curveRadius":7.791701363500931},{"acceleration":3.003147776623455,"curvature":0.1207441312262941,"pose":{"rotation":{"radians":-2.8713415050858826},"translation":{"x":4.844986231597676,"y":1.8463476228259086}},"time":2.3560221867560847,"velocity":2.7571261709420796,"position":3.6882644392776056,"holonomicRotation":-163.17405339473126,"angularVelocity":0.35371483048168884,"angularAcceleration":-7.5487356516426445,"curveRadius":8.281976025201901},{"acceleration":3.0031502946949007,"curvature":0.11318318221136854,"pose":{"rotation":{"radians":-2.8704608733994545},"translation":{"x":4.83795658721561,"y":1.8443935434598886}},"time":2.3586609036195134,"velocity":2.765050634268102,"position":3.6955606250144832,"holonomicRotation":-163.05913643366358,"angularVelocity":0.3337348158239873,"angularAcceleration":-7.5718675749619635,"curveRadius":8.835234886155694},{"acceleration":3.0031531315170628,"curvature":0.10565767676614722,"pose":{"rotation":{"radians":-2.8696347555985926},"translation":{"x":4.830923244576615,"y":1.842432175280576}},"time":2.361294085304049,"velocity":2.772958482089869,"position":3.7028623285015003,"holonomicRotation":-162.9442194725959,"angularVelocity":0.31373368792347484,"angularAcceleration":-7.595802453729596,"curveRadius":9.464527619827436},{"acceleration":3.003156272480032,"curvature":0.09816646288504975,"pose":{"rotation":{"radians":-2.868862989084862},"translation":{"x":4.823886213853777,"y":1.840463924062357}},"time":2.3639217379302915,"velocity":2.780849733556267,"position":3.7101694356070647,"holonomicRotation":-162.82930251152823,"angularVelocity":0.2937094903728704,"angularAcceleration":-7.620564967615255,"curveRadius":10.186778362086578},{"acceleration":3.003159701541026,"curvature":0.09070838664883615,"pose":{"rotation":{"radians":-2.8681454166302567},"translation":{"x":4.81684550522018,"y":1.8384891955796197}},"time":2.3665438671259222,"velocity":2.7887244062888197,"position":3.7174818312913627,"holonomicRotation":-162.71438555046055,"angularVelocity":0.27366022078585583,"angularAcceleration":-7.646179151058826,"curveRadius":11.024338949730737},{"acceleration":3.0031634043727067,"curvature":0.08328229389735382,"pose":{"rotation":{"radians":-2.867481886399666},"translation":{"x":4.809801128848908,"y":1.8365083956067503}},"time":2.369160478056105,"velocity":2.7965825164778257,"position":3.724799399671136,"holonomicRotation":-162.59946858939287,"angularVelocity":0.2535838335524108,"angularAcceleration":-7.672668107384179,"curveRadius":12.007354183021292},{"acceleration":3.003167365291082,"curvature":0.07588703100030898,"pose":{"rotation":{"radians":-2.8668722519702334},"translation":{"x":4.802753094913045,"y":1.8345219299181357}},"time":2.3717715754532014,"velocity":2.8044240789683825,"position":3.7321220240840853,"holonomicRotation":-162.48455162832522,"angularVelocity":0.2334782417960745,"angularAcceleration":-7.700054306167674,"curveRadius":13.177482197134955},{"acceleration":3.0031715704865722,"curvature":0.06852144536013902,"pose":{"rotation":{"radians":-2.8663163723465375},"translation":{"x":4.795701413585673,"y":1.8325302042881633}},"time":2.3743771636458284,"velocity":2.8122491073528755,"position":3.73944958715293,"holonomicRotation":-162.36963466725754,"angularVelocity":0.21334131973307482,"angularAcceleration":-7.728359423787965,"curveRadius":14.593971197544676},{"acceleration":3.0031760051930885,"curvature":0.061184385151177974,"pose":{"rotation":{"radians":-2.86581411197125},"translation":{"x":4.788646095039878,"y":1.8305336244912196}},"time":2.376977246587273,"velocity":2.8200576140541336,"position":3.746781970849123,"holonomicRotation":-162.25471770618987,"angularVelocity":0.1931709051590919,"angularAcceleration":-7.757604287337376,"curveRadius":16.344039374247878},{"acceleration":3.0031806551590043,"curvature":0.053874702481078354,"pose":{"rotation":{"radians":-2.865365340733686},"translation":{"x":4.781587149448745,"y":1.8285325963016916}},"time":2.3795718278832956,"velocity":2.827849610410586,"position":3.754119056556259,"holonomicRotation":-162.1398007451222,"angularVelocity":0.1729648010073851,"angularAcceleration":-7.7878092248185755,"curveRadius":18.561587423173535},{"acceleration":3.003185506299946,"curvature":0.04659125014429061,"pose":{"rotation":{"radians":-2.8649699339732355},"translation":{"x":4.774524586985358,"y":1.8265275254939664}},"time":2.382160910819335,"velocity":2.835625106758708,"position":3.7614607251331726,"holonomicRotation":-162.0248837840545,"angularVelocity":0.1527207780586721,"angularAcceleration":-7.8189936162035485,"curveRadius":21.46325751944954},{"acceleration":3.0031905448537795,"curvature":0.03933288648045275,"pose":{"rotation":{"radians":-2.864627772480263},"translation":{"x":4.767458417822797,"y":1.8245188178424305}},"time":2.3847444983871378,"velocity":2.8433841125141353,"position":3.7688068569767523,"holonomicRotation":-161.90996682298683,"angularVelocity":0.13243657665669778,"angularAcceleration":-7.8511762692930365,"curveRadius":25.42401764734377},{"acceleration":3.0031957576539403,"curvature":0.03209847327447396,"pose":{"rotation":{"radians":-2.8643387424928597},"translation":{"x":4.760388652134151,"y":1.8225068791214714}},"time":2.3873225933108295,"velocity":2.8511266362517955,"position":3.7761573320844755,"holonomicRotation":-161.79504986191915,"angularVelocity":0.11210990904451552,"angularAcceleration":-7.8843751738493,"curveRadius":31.154129713553743},{"acceleration":3.003201130184692,"curvature":0.02488687583253858,"pose":{"rotation":{"radians":-2.8641027356912323},"translation":{"x":4.753315300092503,"y":1.8204921151054758}},"time":2.3898951980724568,"velocity":2.858852685779433,"position":3.7835120301167025,"holonomicRotation":-161.68013290085148,"angularVelocity":0.09173846101338394,"angularAcceleration":-7.918607760892937,"curveRadius":40.18182140373524},{"acceleration":3.0032066502642194,"curvature":0.017696966485611483,"pose":{"rotation":{"radians":-2.8639196491879084},"translation":{"x":4.746238371870935,"y":1.8184749315688307}},"time":2.3924623149370046,"velocity":2.8665622682190484,"position":3.790870830458724,"holonomicRotation":-161.5652159397838,"angularVelocity":0.07131989425659911,"angularAcceleration":-7.953890622888163,"curveRadius":56.50685956901427},{"acceleration":3.0032123036124148,"curvature":0.010527621429396644,"pose":{"rotation":{"radians":-2.863789385515113},"translation":{"x":4.739157877642533,"y":1.8164557342859227}},"time":2.3950239459769187,"velocity":2.874255390075434,"position":3.7982336122825817,"holonomicRotation":-161.45029897871612,"angularVelocity":0.050851848203684775,"angularAcceleration":-7.990239708213564,"curveRadius":94.98821806107742},{"acceleration":3.003218078116674,"curvature":0.0033777255295114224,"pose":{"rotation":{"radians":-2.8637118526093444},"translation":{"x":4.732073827580382,"y":1.814434929031139}},"time":2.397580093096145,"velocity":2.8819320573142204,"position":3.8056002546086916,"holonomicRotation":-161.33538201764844,"angularVelocity":0.030331941845339886,"angularAcceleration":-8.027670318348273,"curveRadius":296.0572110619796},{"acceleration":3.003223960260739,"curvature":-0.003753833115150464,"pose":{"rotation":{"radians":-2.863686963792106},"translation":{"x":4.724986231857564,"y":1.8124129215788662}},"time":2.400130758053706,"velocity":2.8895922754293646,"position":3.8129706363672677,"holonomicRotation":-161.22046505658076,"angularVelocity":0.00975777597308526,"angularAcceleration":-8.066196938671764,"curveRadius":-266.394367923284},{"acceleration":3.0032299374093627,"curvature":-0.010868151033659077,"pose":{"rotation":{"radians":-2.863714637748445},"translation":{"x":4.717895100647163,"y":1.8103901177034918}},"time":2.4026759424868285,"velocity":2.8972360495151466,"position":3.8203446364595752,"holonomicRotation":-161.1055480955131,"angularVelocity":-0.010873065220270258,"angularAcceleration":-8.105833481012011,"curveRadius":-92.01197120862251},{"acceleration":2.901042758908946,"curvature":-0.017966330289644263,"pose":{"rotation":{"radians":-2.863794798501614},"translation":{"x":4.710800444122264,"y":1.8083669231794022}},"time":2.4052158742946514,"velocity":2.904604500294354,"position":3.8277221338190186,"holonomicRotation":-160.9906311344454,"angularVelocity":-0.03156019894793394,"angularAcceleration":-8.144759502576985,"curveRadius":-55.65966916329023},{"acceleration":-0.10282444693213337,"curvature":-0.025049454451097006,"pose":{"rotation":{"radians":-2.863927375385769},"translation":{"x":4.703702272455952,"y":1.8063437437809848}},"time":2.407757197123864,"velocity":2.904343190179964,"position":3.835103007472091,"holonomicRotation":-160.87571417337773,"angularVelocity":-0.05216845440922937,"angularAcceleration":-8.109263106757934,"curveRadius":-39.9210290967517},{"acceleration":-2.9953968317013113,"curvature":-0.03211860039048777,"pose":{"rotation":{"radians":-2.8641123030147426},"translation":{"x":4.696600595821309,"y":1.804320985282626}},"time":2.410306342717214,"velocity":2.8967074875460983,"position":3.842487136599193,"holonomicRotation":-160.76079721231008,"angularVelocity":-0.072544945826564,"angularAcceleration":-7.993459247871715,"curveRadius":-31.13460698294187},{"acceleration":-2.9953989821480187,"curvature":-0.039174836577506034,"pose":{"rotation":{"radians":-2.8643495212486547},"translation":{"x":4.689495424391421,"y":1.802299053458713}},"time":2.4128633314778027,"velocity":2.889048286015267,"position":3.8498744005953323,"holonomicRotation":-160.6458802512424,"angularVelocity":-0.09277249770056731,"angularAcceleration":-7.910692524649956,"curveRadius":-25.52659021363204},{"acceleration":-2.9954008615563557,"curvature":-0.04621922309674945,"pose":{"rotation":{"radians":-2.8646389751573285},"translation":{"x":4.68238676833937,"y":1.8002783540836331}},"time":2.415428184314008,"velocity":2.8813655236199325,"position":3.857264679130733,"holonomicRotation":-160.53096329017472,"angularVelocity":-0.11285400261092494,"angularAcceleration":-7.829495956605772,"curveRadius":-21.63601923612448},{"acceleration":-2.995402455733429,"curvature":-0.053252806629790164,"pose":{"rotation":{"radians":-2.8649806149805057},"translation":{"x":4.675274637838242,"y":1.7982592929317727}},"time":2.418000922669041,"velocity":2.8736591368333073,"position":3.8646578522113546,"holonomicRotation":-160.41604632910705,"angularVelocity":-0.13279229211510044,"angularAcceleration":-7.749831795048758,"curveRadius":-18.778352978687696},{"acceleration":-2.9954037513072493,"curvature":-0.0602766259186978,"pose":{"rotation":{"radians":-2.865374396085923},"translation":{"x":4.668159043061121,"y":1.7962422757775185}},"time":2.420581568551029,"velocity":2.865929060477605,"position":3.8720538002393456,"holonomicRotation":-160.30112936803937,"angularVelocity":-0.15259013573523095,"angularAcceleration":-7.671662260333008,"curveRadius":-16.59017877591254},{"acceleration":-2.9954047337273075,"curvature":-0.06729170752811776,"pose":{"rotation":{"radians":-2.865820278924179},"translation":{"x":4.661039994181091,"y":1.7942277083952582}},"time":2.42317014456364,"velocity":2.8581752276358166,"position":3.8794524040734433,"holonomicRotation":-160.1862124069717,"angularVelocity":-0.17225023954638544,"angularAcceleration":-7.594949391237913,"curveRadius":-14.86067209072011},{"acceleration":-2.9954053894359505,"curvature":-0.0742990659639087,"pose":{"rotation":{"radians":-2.866318228980033},"translation":{"x":4.653917501371235,"y":1.7922159965593782}},"time":2.4257666739372743,"velocity":2.8503975695562036,"position":3.886853545089332,"holonomicRotation":-160.071295445904,"angularVelocity":-0.1917752446438785,"angularAcceleration":-7.519655004004187,"curveRadius":-13.459119398429008},{"acceleration":-2.9954057036568207,"curvature":-0.0812997046570327,"pose":{"rotation":{"radians":-2.866868216722153},"translation":{"x":4.646791574804637,"y":1.7902075460442655}},"time":2.428371180560838,"velocity":2.8425960155607686,"position":3.894257105239976,"holonomicRotation":-159.95637848483634,"angularVelocity":-0.21116772641086348,"angularAcceleration":-7.4457410058146545,"curveRadius":-12.30016768472352},{"acceleration":-2.9954056628829404,"curvature":-0.08829461307121575,"pose":{"rotation":{"radians":-2.8674702175488873},"translation":{"x":4.639662224654383,"y":1.7882027626243073}},"time":2.430983689014131,"velocity":2.8347704929454456,"position":3.901662967115941,"holonomicRotation":-159.84146152376866,"angularVelocity":-0.2304301928576252,"angularAcceleration":-7.373169040843828,"curveRadius":-11.325719262096209},{"acceleration":-2.995405252323587,"curvature":-0.09528476856863001,"pose":{"rotation":{"radians":-2.8681242117315153},"translation":{"x":4.632529461093555,"y":1.7862020520738902}},"time":2.433604224600864,"velocity":2.8269209268850446,"position":3.9090710140057237,"holonomicRotation":-159.72654456270098,"angularVelocity":-0.24956508354207715,"angularAcceleration":-7.301900718817195,"curveRadius":-10.494856785843352},{"acceleration":-2.995404457143451,"curvature":-0.10227113473244498,"pose":{"rotation":{"radians":-2.868830184354787},"translation":{"x":4.625393294295239,"y":1.784205820167401}},"time":2.4362328133823317,"velocity":2.819047240333039,"position":3.9164811299560904,"holonomicRotation":-159.6116276016333,"angularVelocity":-0.2685747684266842,"angularAcceleration":-7.231897594112502,"curveRadius":-9.777930034864033},{"acceleration":-2.995403263435694,"curvature":-0.10925466039613287,"pose":{"rotation":{"radians":-2.8695881252540003},"translation":{"x":4.618253734432518,"y":1.7822144726792268}},"time":2.438869482211767,"velocity":2.8111493539167496,"position":3.9238931998324498,"holonomicRotation":-159.49671064056562,"angularVelocity":-0.28746154646037625,"angularAcceleration":-7.163121065051391,"curveRadius":-9.152927631409264},{"acceleration":-2.9954016560286316,"curvature":-0.11623628054213683,"pose":{"rotation":{"radians":-2.87039802894947},"translation":{"x":4.611110791678475,"y":1.7802284153837549}},"time":2.4415142587694003,"velocity":2.803227185836189,"position":3.93130710937927,"holonomicRotation":-159.38179367949795,"angularVelocity":-0.3062276444988486,"angularAcceleration":-7.095532507012478,"curveRadius":-8.603165856098517},{"acceleration":-2.995399620228665,"curvature":-0.12321691417669771,"pose":{"rotation":{"radians":-2.871259894577635},"translation":{"x":4.603964476206196,"y":1.7782480540553718}},"time":2.4441671715982487,"velocity":2.7952806517561566,"position":3.9387227452805456,"holonomicRotation":-159.26687671843027,"angularVelocity":-0.3248752159485146,"angularAcceleration":-7.0290931714333045,"curveRadius":-8.11576889976292},{"acceleration":-2.995397140623792,"curvature":-0.13019746502555996,"pose":{"rotation":{"radians":-2.8721737258196733},"translation":{"x":4.596814798188764,"y":1.7762737944684646}},"time":2.446828250140664,"velocity":2.78730966469923,"position":3.946139995220344,"holonomicRotation":-159.1519597573626,"angularVelocity":-0.34340633975011636,"angularAcceleration":-6.963764318200432,"curveRadius":-7.680641092387499},{"acceleration":-2.9953942022438222,"curvature":-0.13717882068927162,"pose":{"rotation":{"radians":-2.8731395308262497},"translation":{"x":4.589661767799265,"y":1.77430604239742}},"time":2.449497524775666,"velocity":2.779314134933349,"position":3.9535587479434238,"holonomicRotation":-159.0370427962949,"angularVelocity":-0.3618230188501045,"angularAcceleration":-6.899507026550351,"curveRadius":-7.289755043638506},{"acceleration":-2.9953907899086323,"curvature":-0.14416185113618113,"pose":{"rotation":{"radians":-2.8741573221398045},"translation":{"x":4.58250539521078,"y":1.7723452036166252}},"time":2.4521750268570885,"velocity":2.7712939698586947,"position":3.960978893315954,"holonomicRotation":-158.92212583522723,"angularVelocity":-0.3801271792154893,"angularAcceleration":-6.836282403806883,"curveRadius":-6.936647886515827},{"acceleration":-2.995386887789018,"curvature":-0.15114740944202276,"pose":{"rotation":{"radians":-2.8752271166128347},"translation":{"x":4.575345690596396,"y":1.770391683900467}},"time":2.454860788752567,"velocity":2.7632490738932556,"position":3.9684003223863322,"holonomicRotation":-158.80720887415958,"angularVelocity":-0.39832066827343143,"angularAcceleration":-6.774051373866131,"curveRadius":-6.616057818599801},{"acceleration":-2.9953824801114073,"curvature":-0.1581363306394543,"pose":{"rotation":{"radians":-2.8763489353238767},"translation":{"x":4.5681826641291945,"y":1.768445889023332}},"time":2.457554843883399,"velocity":2.755179348353906,"position":3.9758229274461283,"holonomicRotation":-158.6922919130919,"angularVelocity":-0.41640525399917044,"angularAcceleration":-6.712774923856828,"curveRadius":-6.3236575425540105},{"acceleration":-2.995377551170748,"curvature":-0.16512943088285661,"pose":{"rotation":{"radians":-2.8775228034892844},"translation":{"x":4.561016325982262,"y":1.766508224759608}},"time":2.4602572267653087,"velocity":2.7470846913347664,"position":3.983246602091147,"holonomicRotation":-158.57737495202423,"angularVelocity":-0.43438262330103417,"angularAcceleration":-6.652413846390628,"curveRadius":-6.0558556682085545},{"acceleration":-2.9953720846942242,"curvature":-0.17212750683553882,"pose":{"rotation":{"radians":-2.878748750372046},"translation":{"x":4.553846686328681,"y":1.7645790968836812}},"time":2.4629679730501435,"velocity":2.7389649975844836,"position":3.9906712412826417,"holonomicRotation":-158.46245799095655,"angularVelocity":-0.4522543808767018,"angularAcceleration":-6.592928919851571,"curveRadius":-5.8096466879954365},{"acceleration":-2.9953660641706734,"curvature":-0.17913133549943241,"pose":{"rotation":{"radians":-2.880026809187111},"translation":{"x":4.546673755341535,"y":1.7626589111699387}},"time":2.4656871195685404,"velocity":2.7308201583797698,"position":3.998096741408668,"holonomicRotation":-158.34754102988887,"angularVelocity":-0.47002204788082896,"angularAcceleration":-6.534280842873586,"curveRadius":-5.5824962015267765},{"acceleration":-2.995359473332765,"curvature":-0.1861416732746498,"pose":{"rotation":{"radians":-2.8813570170029488},"translation":{"x":4.539497543193911,"y":1.7607480733927674}},"time":2.468414704373592,"velocity":2.72265006139464,"position":4.005523000345601,"holonomicRotation":-158.2326240688212,"angularVelocity":-0.4876870604991209,"angularAcceleration":-6.476430205057364,"curveRadius":-5.372252126070189},{"acceleration":-2.9953522952211165,"curvature":-0.19315925488214486,"pose":{"rotation":{"radians":-2.8827394146400334},"translation":{"x":4.53231806005889,"y":1.7588469893265544}},"time":2.471150766785552,"velocity":2.714454590569107,"position":4.01294991751983,"holonomicRotation":-158.11770710775352,"angularVelocity":-0.5052507687842679,"angularAcceleration":-6.41933758834263,"curveRadius":-5.177075261602893},{"acceleration":-2.995344512808471,"curvature":-0.20018479319563406,"pose":{"rotation":{"radians":-2.884174046564749},"translation":{"x":4.525135316109558,"y":1.7569560647456863}},"time":2.473895347437609,"velocity":2.7062336259730078,"position":4.020377393969621,"holonomicRotation":-158.00279014668584,"angularVelocity":-0.5227144349504251,"angularAcceleration":-6.362963374047281,"curveRadius":-4.995384434734424},{"acceleration":-2.9953361088365895,"curvature":-0.20721897845582105,"pose":{"rotation":{"radians":-2.885660960780483},"translation":{"x":4.517949321518998,"y":1.7550757054245503}},"time":2.476648488322771,"velocity":2.6979870436669677,"position":4.027805332407178,"holonomicRotation":-157.88787318561816,"angularVelocity":-0.5400792323223856,"angularAcceleration":-6.307267988190445,"curveRadius":-4.825812806587112},{"acceleration":-2.995327065560125,"curvature":-0.21426247732317902,"pose":{"rotation":{"radians":-2.887200208714255},"translation":{"x":4.510760086460295,"y":1.7532063171375332}},"time":2.4794102328418997,"velocity":2.6897147155606596,"position":4.035233637280897,"holonomicRotation":-157.77295622455048,"angularVelocity":-0.5573462436916645,"angularAcceleration":-6.252211690720459,"curveRadius":-4.667172770954513},{"acceleration":-2.9953173654352745,"curvature":-0.22131593187933024,"pose":{"rotation":{"radians":-2.8887918450996914},"translation":{"x":4.503567621106533,"y":1.751348305659022}},"time":2.4821806258529304,"velocity":2.6814165092656386,"position":4.042662214837829,"holonomicRotation":-157.6580392634828,"angularVelocity":-0.5745164599747715,"angularAcceleration":-6.197754692110829,"curveRadius":-4.5184275325702155},{"acceleration":-2.995306990501875,"curvature":-0.22837995954902002,"pose":{"rotation":{"radians":-2.8904359278556964},"translation":{"x":4.496371935630795,"y":1.7495020767634037}},"time":2.4849597137213224,"velocity":2.673092287946225,"position":4.050090973186353,"holonomicRotation":-157.54312230241513,"angularVelocity":-0.5915907786522074,"angularAcceleration":-6.143857080458325,"curveRadius":-4.378667909280182},{"acceleration":-2.995295921931253,"curvature":-0.23545515151824778,"pose":{"rotation":{"radians":-2.8921325179613833},"translation":{"x":4.489173040206166,"y":1.7476680362250652}},"time":2.487747544371778,"velocity":2.6647419101678804,"position":4.0575198223590725,"holonomicRotation":-157.42820534134745,"angularVelocity":-0.6085700024173354,"angularAcceleration":-6.090478904216429,"curveRadius":-4.2470933150192725},{"acceleration":-2.995284141226093,"curvature":-0.2425420723958142,"pose":{"rotation":{"radians":-2.8938816793265207},"translation":{"x":4.481970945005729,"y":1.745846589818393}},"time":2.4905441673412785,"velocity":2.656365229738347,"position":4.064948674375941,"holonomicRotation":-157.31328838027977,"angularVelocity":-0.6254548375714444,"angularAcceleration":-6.037580087931931,"curveRadius":-4.1229960234200504},{"acceleration":-2.9952716299163993,"curvature":-0.2496412591738115,"pose":{"rotation":{"radians":-2.895683478657899},"translation":{"x":4.4747656602025705,"y":1.7440381433177745}},"time":2.493349633833481,"velocity":2.6479620955455716,"position":4.072377443307617,"holonomicRotation":-157.1983714192121,"angularVelocity":-0.6422458925765879,"angularAcceleration":-5.985120496648948,"curveRadius":-4.005748101533789},{"acceleration":-2.995258367995377,"curvature":-0.25675322027972297,"pose":{"rotation":{"radians":-2.897537985321063},"translation":{"x":4.467557195969772,"y":1.7422431024975966}},"time":2.4961639967745226,"velocity":2.639532351395841,"position":4.079806045339065,"holonomicRotation":-157.08345445814444,"angularVelocity":-0.658943676424974,"angularAcceleration":-5.933059878270905,"curveRadius":-3.8947904875761155},{"acceleration":-2.995244336363725,"curvature":-0.263878434892763,"pose":{"rotation":{"radians":-2.8994452711975898},"translation":{"x":4.46034556248042,"y":1.7404618731322463}},"time":2.498987310870278,"velocity":2.6310758358407536,"position":4.087234398833396,"holonomicRotation":-156.96853749707677,"angularVelocity":-0.6755485970880715,"angularAcceleration":-5.881357900653475,"curveRadius":-3.789623810700514},{"acceleration":-2.9952295150529267,"curvature":-0.27101735166191687,"pose":{"rotation":{"radians":-2.9014054105380658},"translation":{"x":4.453130769907596,"y":1.73869486099611}},"time":2.5018196326651303,"velocity":2.6225923820046844,"position":4.0946624243959615,"holonomicRotation":-156.8536205360091,"angularVelocity":-0.6920609600358807,"angularAcceleration":-5.829974185073313,"curveRadius":-3.6898006488066466},{"acceleration":-2.9952138835554925,"curvature":-0.2781703880261188,"pose":{"rotation":{"radians":-2.903418479810213},"translation":{"x":4.445912828424387,"y":1.7369424718635753}},"time":2.504661020602293,"velocity":2.614081817406728,"position":4.102090044938697,"holonomicRotation":-156.7387035749414,"angularVelocity":-0.7084809665792127,"angularAcceleration":-5.778868252579966,"curveRadius":-3.594918952717947},{"acceleration":-2.9951974216285393,"curvature":-0.2853379291393127,"pose":{"rotation":{"radians":-2.905484557541842},"translation":{"x":4.4386917482038735,"y":1.7352051115090286}},"time":2.507511535085752,"velocity":2.6055439637755557,"position":4.109517185744729,"holonomicRotation":-156.62378661387373,"angularVelocity":-0.7248087121176112,"angularAcceleration":-5.727999500842056,"curveRadius":-3.504616449051757},{"acceleration":-2.9951801077802,"curvature":-0.29252032687085305,"pose":{"rotation":{"radians":-2.907603724159637},"translation":{"x":4.431467539419143,"y":1.7334831857068569}},"time":2.5103712385438737,"velocity":2.59697863686364,"position":4.116943774533236,"holonomicRotation":-156.50886965280606,"angularVelocity":-0.7410441847656356,"angularAcceleration":-5.677327347322011,"curveRadius":-3.418565850439164},{"acceleration":-2.9951619216060625,"curvature":-0.2997178986972402,"pose":{"rotation":{"radians":-2.9097760618225834},"translation":{"x":4.424240212243277,"y":1.7317771002314475}},"time":2.513240195494742,"velocity":2.5883856462496726,"position":4.124369741524571,"holonomicRotation":-156.39395269173838,"angularVelocity":-0.7571872635763832,"angularAcceleration":-5.626811097971491,"curveRadius":-3.336470742476909},{"acceleration":-2.9951428403505793,"curvature":-0.3069309267775284,"pose":{"rotation":{"radians":-2.9120016542499956},"translation":{"x":4.417009776849362,"y":1.7300872608571871}},"time":2.516118472613283,"velocity":2.57976479514553,"position":4.131795019505656,"holonomicRotation":-156.2790357306707,"angularVelocity":-0.7732377167839768,"angularAcceleration":-5.57640996560119,"curveRadius":-3.258062035321798},{"acceleration":-2.995122842497666,"curvature":-0.31415965669528123,"pose":{"rotation":{"radians":-2.9142805865450687},"translation":{"x":4.40977624341048,"y":1.7284140733584625}},"time":2.519006138800243,"velocity":2.5711158801874574,"position":4.13921954389563,"holonomicRotation":-156.16411876960302,"angularVelocity":-0.7891952003885181,"angularAcceleration":-5.5260832005446945,"curveRadius":-3.1830948967771144},{"acceleration":-2.995101905563093,"curvature":-0.32140429655094,"pose":{"rotation":{"radians":-2.916612945012617},"translation":{"x":4.402539622099717,"y":1.7267579435096607}},"time":2.5219032652530817,"velocity":2.5624386912279027,"position":4.146643252811764,"holonomicRotation":-156.04920180853534,"angularVelocity":-0.8050592563064317,"angularAcceleration":-5.475789951235639,"curveRadius":-3.111346085697109},{"acceleration":-2.9950800066453906,"curvature":-0.328665015730328,"pose":{"rotation":{"radians":-2.918998816971715},"translation":{"x":4.395299923090154,"y":1.7251192770851689}},"time":2.524809925538852,"velocity":2.5537330111198817,"position":4.1540660871356465,"holonomicRotation":-155.93428484746767,"angularVelocity":-0.8208293107998297,"angularAcceleration":-5.42548937369831,"curveRadius":-3.042611632326901},{"acceleration":-2.995057122211066,"curvature":-0.33594194364845964,"pose":{"rotation":{"radians":-2.921438290562412},"translation":{"x":4.388057156554879,"y":1.7234984798593735}},"time":2.527726195669131,"velocity":2.5449986154958983,"position":4.1614879905796185,"holonomicRotation":-155.8193678864,"angularVelocity":-0.8365046726531598,"angularAcceleration":-5.375140557308613,"curveRadius":-2.9767048113719072},{"acceleration":-2.995033228755806,"curvature":-0.343235168867354,"pose":{"rotation":{"radians":-2.9239314545479314},"translation":{"x":4.3808113326669735,"y":1.721895957606662}},"time":2.5306521541770866,"velocity":2.536235272538611,"position":4.16890890975348,"holonomicRotation":-155.7044509253323,"angularVelocity":-0.852084531868948,"angularAcceleration":-5.324702716537993,"curveRadius":-2.913454362208606},{"acceleration":-2.9950083021803313,"curvature":-0.3505447374183562,"pose":{"rotation":{"radians":-2.926478398109742},"translation":{"x":4.373562461599523,"y":1.7203121161014208}},"time":2.5335878821967426,"velocity":2.5274427427467976,"position":4.176328794231438,"holonomicRotation":-155.58953396426463,"angularVelocity":-0.8675679575075361,"angularAcceleration":-5.2741349113131895,"curveRadius":-2.8527029313424097},{"acceleration":-2.9949823174053796,"curvature":-0.3578706522441153,"pose":{"rotation":{"radians":-2.9290792106382892},"translation":{"x":4.366310553525611,"y":1.7187473611180368}},"time":2.536533463544534,"velocity":2.518620778695684,"position":4.183747596619323,"holonomicRotation":-155.47461700319695,"angularVelocity":-0.8829538965194509,"angularAcceleration":-5.223396401342683,"curveRadius":-2.794305690419865},{"acceleration":-2.994955249872532,"curvature":-0.36521287127796764,"pose":{"rotation":{"radians":-2.9317339815171684},"translation":{"x":4.359055618618321,"y":1.7172020984308978}},"time":2.539488984803227,"velocity":2.509769124785851,"position":4.191165272622039,"holonomicRotation":-155.3597000421293,"angularVelocity":-0.898241171864548,"angularAcceleration":-5.172446417068499,"curveRadius":-2.7381291259006275},{"acceleration":-2.99492707359936,"curvature":-0.3725713067179992,"pose":{"rotation":{"radians":-2.934442799901192},"translation":{"x":4.351797667050737,"y":1.71567673381439}},"time":2.542454535408296,"velocity":2.5008875169906,"position":4.198581781111261,"holonomicRotation":-155.24478308106163,"angularVelocity":-0.9134284808336983,"angularAcceleration":-5.121244244893246,"curveRadius":-2.6840499576015504},{"acceleration":-2.994897763071024,"curvature":-0.3799458235005474,"pose":{"rotation":{"radians":-2.9372057544893906},"translation":{"x":4.3445367089959435,"y":1.7141716730429002}},"time":2.5454302077368434,"velocity":2.4919756825902017,"position":4.205997084193357,"holonomicRotation":-155.12986611999395,"angularVelocity":-0.928514393769739,"angularAcceleration":-5.069749377750154,"curveRadius":-2.6319541843800773},{"acceleration":-2.994867291400854,"curvature":-0.3873362379560548,"pose":{"rotation":{"radians":-2.940022933291113},"translation":{"x":4.337272754627026,"y":1.7126873218908156}},"time":2.5484160971991576,"velocity":2.4830333399037783,"position":4.213411147277551,"holonomicRotation":-155.01494915892627,"angularVelocity":-0.9434973522225129,"angularAcceleration":-5.017921340316825,"curveRadius":-2.5817362332967537},{"acceleration":-2.9948356315612488,"curvature":-0.394742316710727,"pose":{"rotation":{"radians":-2.9428944233865493},"translation":{"x":4.330005814117068,"y":1.7112240861325232}},"time":2.551412302333012,"velocity":2.4740601980094445,"position":4.220823939144291,"holonomicRotation":-154.9000321978586,"angularVelocity":-0.958375667603963,"angularAcceleration":-4.965719874563636,"curveRadius":-2.533298199019323},{"acceleration":-2.994802755981559,"curvature":-0.4021637752944925,"pose":{"rotation":{"radians":-2.945820310680741},"translation":{"x":4.322735897639151,"y":1.7097823715424099}},"time":2.554418924900798,"velocity":2.465055956457243,"position":4.228235432013831,"holonomicRotation":-154.78511523679092,"angularVelocity":-0.973147519592542,"angularAcceleration":-4.913104872839904,"curveRadius":-2.4865491658658962},{"acceleration":-2.9947686370146656,"curvature":-0.4096002766992078,"pose":{"rotation":{"radians":-2.94880067965149},"translation":{"x":4.315463015366363,"y":1.7083625838948622}},"time":2.5574360699896066,"velocity":2.456020304971956,"position":4.2356456016149915,"holonomicRotation":-154.67019827572324,"angularVelocity":-0.9878109547346082,"angularAcceleration":-4.860036461771735,"curveRadius":-2.441404600745315},{"acceleration":-2.9947332452711914,"curvature":-0.4170514301811192,"pose":{"rotation":{"radians":-2.951835613091643},"translation":{"x":4.308187177471785,"y":1.7069651289642678}},"time":2.5604638461143714,"velocity":2.4469529231518843,"position":4.243054427254134,"holonomicRotation":-154.55528131465556,"angularVelocity":-1.0023638852720387,"angularAcceleration":-4.806475095169388,"curveRadius":-2.3977858068145577},{"acceleration":-2.9946965524463764,"curvature":-0.4245167898766945,"pose":{"rotation":{"radians":-2.954925191843703},"translation":{"x":4.300908394128503,"y":1.705590412525013}},"time":2.563502365324183,"velocity":2.437853480149719,"position":4.250461891884275,"holonomicRotation":-154.44036435358788,"angularVelocity":-1.0168040873604378,"angularAcceleration":-4.752381371087029,"curveRadius":-2.35561943331019},{"acceleration":-2.9946585279941016,"curvature":-0.43199585357087394,"pose":{"rotation":{"radians":-2.9580694945298425},"translation":{"x":4.293626675509599,"y":1.704238840351485}},"time":2.566551743311905,"velocity":2.4287216343537104,"position":4.2578679821743775,"holonomicRotation":-154.3254473925202,"angularVelocity":-1.0311292003811472,"angularAcceleration":-4.697716412458068,"curveRadius":-2.3148370331196673},{"acceleration":-2.9946191423045687,"curvature":-0.43948806109556987,"pose":{"rotation":{"radians":-2.9612685972740644},"translation":{"x":4.28634203178816,"y":1.7029108182180706}},"time":2.5696120995272134,"velocity":2.419557033049077,"position":4.265272688578762,"holonomicRotation":-154.21053043145253,"angularVelocity":-1.0453367252542412,"angularAcceleration":-4.642441556974804,"curveRadius":-2.2753746654850375},{"acceleration":-2.9945783640567494,"curvature":-0.4469927932825813,"pose":{"rotation":{"radians":-2.9645225734193588},"translation":{"x":4.2790544731372675,"y":1.7016067518991569}},"time":2.5726835572932027,"velocity":2.410359312076931,"position":4.272676005406666,"holonomicRotation":-154.09561347038485,"angularVelocity":-1.059424023773333,"angularAcceleration":-4.586518712737054,"curveRadius":-2.237172533937962},{"acceleration":-2.9945361616217414,"curvature":-0.454509370393446,"pose":{"rotation":{"radians":-2.967831493237219},"translation":{"x":4.271764009730008,"y":1.7003270471691303}},"time":2.5757662439266866,"velocity":2.4011280954780156,"position":4.280077930891879,"holonomicRotation":-153.98069650931717,"angularVelocity":-1.073388317164316,"angularAcceleration":-4.529910124274058,"curveRadius":-2.200174661161221},{"acceleration":-2.9944925033989933,"curvature":-0.46203705090127434,"pose":{"rotation":{"radians":-2.9711954236324987},"translation":{"x":4.2644706517394635,"y":1.6990721098023787}},"time":2.578860290862358,"velocity":2.3918629951239834,"position":4.2874784672624875,"holonomicRotation":-153.8657795482495,"angularVelocity":-1.0872266857030983,"angularAcceleration":-4.472578737975753,"curveRadius":-2.1643285923701274},{"acceleration":-2.994447355877382,"curvature":-0.46957503022420555,"pose":{"rotation":{"radians":-2.974614427839933},"translation":{"x":4.2571744093387185,"y":1.697842345573288}},"time":2.5819658337809446,"velocity":2.382563610342858,"position":4.29487762081067,"holonomicRotation":-153.7508625871818,"angularVelocity":-1.1009360672402009,"angularAcceleration":-4.41448786782238,"curveRadius":-2.129585126199183},{"acceleration":-2.994400686301837,"curvature":-0.4771224393453234,"pose":{"rotation":{"radians":-2.9780885651166775},"translation":{"x":4.249875292700858,"y":1.696638160256246}},"time":2.585083012741541,"velocity":2.3732295275239217,"position":4.302275401962534,"holonomicRotation":-153.63594562611416,"angularVelocity":-1.114513257230337,"angularAcceleration":-4.355601703258469,"curveRadius":-2.0958980704662213},{"acceleration":-2.9943524599566405,"curvature":-0.4846783434764576,"pose":{"rotation":{"radians":-2.9816178904268704},"translation":{"x":4.242573311998965,"y":1.695459959625639}},"time":2.5882119723182764,"velocity":2.3638603197182197,"position":4.309671825347981,"holonomicRotation":-153.5210286650465,"angularVelocity":-1.1279549075783983,"angularAcceleration":-4.295884947828772,"curveRadius":-2.0632240195163027},{"acceleration":-2.9943026426197537,"curvature":-0.49224174097295637,"pose":{"rotation":{"radians":-2.9852024541211093},"translation":{"x":4.235268477406124,"y":1.6943081494558538}},"time":2.5913528617415023,"velocity":2.354455546218078,"position":4.317066909870553,"holonomicRotation":-153.4061117039788,"angularVelocity":-1.1412575265248641,"angularAcceleration":-4.235303174985131,"curveRadius":-2.031522150119609},{"acceleration":-2.9942511982587403,"curvature":-0.49981156185888714,"pose":{"rotation":{"radians":-2.9888423016098846},"translation":{"x":4.2279607990954196,"y":1.6931831355212783}},"time":2.5945058350436905,"velocity":2.345014752129923,"position":4.324460678777256,"holonomicRotation":-153.29119474291113,"angularVelocity":-1.154417478336783,"angularAcceleration":-4.173822785871903,"curveRadius":-2.000754036743016},{"acceleration":-2.9941980908431054,"curvature":-0.5073866670553586,"pose":{"rotation":{"radians":-2.9925374730301733},"translation":{"x":4.220650287239936,"y":1.6920853235962983}},"time":2.5976710512102383,"velocity":2.33553746792694,"position":4.3318531597283165,"holonomicRotation":-153.17627778184345,"angularVelocity":-1.1674309828635725,"angularAcceleration":-4.111410988078762,"curveRadius":-1.9708834798587536},{"acceleration":-2.994143283515564,"curvature":-0.5149658465104724,"pose":{"rotation":{"radians":-2.996288002908031},"translation":{"x":4.213336952012756,"y":1.6910151194553014}},"time":2.600848674335395,"velocity":2.326023208989208,"position":4.339244384866852,"holonomicRotation":-153.06136082077577,"angularVelocity":-1.180294116116326,"angularAcceleration":-4.048036140887182,"curveRadius":-1.9418763531139613},{"acceleration":-2.994086738158401,"curvature":-0.5225478188438334,"pose":{"rotation":{"radians":-3.000093919813521},"translation":{"x":4.206020803586965,"y":1.6899729288726744}},"time":2.604038873783523,"velocity":2.316471475129488,"position":4.346634390888414,"holonomicRotation":-152.9464438597081,"angularVelocity":-1.1930028098160308,"angularAcceleration":-3.983667449746092,"curveRadius":-1.913700457524742},{"acceleration":-2.9940284166720823,"curvature":-0.5301312297674184,"pose":{"rotation":{"radians":-3.003955246011834},"translation":{"x":4.198701852135646,"y":1.688959157622804}},"time":2.6072418243559383,"velocity":2.3068817500984804,"position":4.3540232191103865,"holonomicRotation":-152.83152689864042,"angularVelocity":-1.2055528522880257,"angularAcceleration":-3.9182754114531235,"curveRadius":-1.8863253923726104},{"acceleration":-2.9939682792059368,"curvature":-0.5377146511977441,"pose":{"rotation":{"radians":-3.007871997108287},"translation":{"x":4.191380107831884,"y":1.6879742114800775}},"time":2.610457706463567,"velocity":2.297253501078574,"position":4.361410915541192,"holonomicRotation":-152.71660993757274,"angularVelocity":-1.2179398887669295,"angularAcceleration":-3.8518316481563195,"curveRadius":-1.8597224341433294},{"acceleration":-2.9939062859695365,"curvature":-0.5452965803982982,"pose":{"rotation":{"radians":-3.0118441816882253},"translation":{"x":4.1840555808487645,"y":1.6870184962188814}},"time":2.613686706305682,"velocity":2.2875861781538718,"position":4.3687975309492755,"holonomicRotation":-152.60169297650506,"angularVelocity":-1.2301594221624,"angularAcceleration":-3.784309071835398,"curveRadius":-1.8338644252446534},{"acceleration":-2.993842395542526,"curvature":-0.5528754388760581,"pose":{"rotation":{"radians":-3.0158718009527714},"translation":{"x":4.176728281359368,"y":1.6860924176136032}},"time":2.616929016054997,"velocity":2.277879213766891,"position":4.3761831209318345,"holonomicRotation":-152.48677601543739,"angularVelocity":-1.242206814261549,"angularAcceleration":-3.7156820386125315,"curveRadius":-1.8087256725183933},{"acceleration":-2.993776566292216,"curvature":-0.5604495717974083,"pose":{"rotation":{"radians":-3.0199548483487013},"translation":{"x":4.16939821953678,"y":1.685196381438629}},"time":2.620184834049401,"velocity":2.2681320221511316,"position":4.383567745983238,"holonomicRotation":-152.3718590543697,"angularVelocity":-1.2540772865521739,"angularAcceleration":-3.6459262498786758,"curveRadius":-1.7842818521440156},{"acceleration":-2.993708754988932,"curvature":-0.568017246880799,"pose":{"rotation":{"radians":-3.024093309195604},"translation":{"x":4.162065405554086,"y":1.6843307934683465}},"time":2.6234543649906494,"velocity":2.2583439987476095,"position":4.390951471563126,"holonomicRotation":-152.25694209330203,"angularVelocity":-1.2657659221669886,"angularAcceleration":-3.575019115846668,"curveRadius":-1.760509923759154},{"acceleration":-2.993638917941673,"curvature":-0.5755766540799224,"pose":{"rotation":{"radians":-3.0282871603074737},"translation":{"x":4.154729849584369,"y":1.6834960594771422}},"time":2.626737820150333,"velocity":2.248514519596265,"position":4.398334368164117,"holonomicRotation":-152.14202513223435,"angularVelocity":-1.2772676671101897,"angularAcceleration":-3.5029395511251797,"curveRadius":-1.73738804885777},{"acceleration":-2.9935670104057066,"curvature":-0.5831259047493476,"pose":{"rotation":{"radians":-3.0325363696114604},"translation":{"x":4.147391561800713,"y":1.6826925852394032}},"time":2.630035417583467,"velocity":2.2386429407068364,"position":4.4057165113790955,"holonomicRotation":-152.02710817116667,"angularVelocity":-1.2885773324818512,"angularAcceleration":-3.4296682966886958,"curveRadius":-1.7148955171693887},{"acceleration":-2.9934929861578596,"curvature":-0.5906630312520004,"pose":{"rotation":{"radians":-3.036840895763052},"translation":{"x":4.140050552376203,"y":1.6819207765295163}},"time":2.633347382350073,"velocity":2.2287285974075988,"position":4.413097981968037,"holonomicRotation":-151.91219121009902,"angularVelocity":-1.299689596638538,"angularAcceleration":-3.3551879140530576,"curveRadius":-1.693012677431915},{"acceleration":-2.9934167988140117,"curvature":-0.5981859865740038,"pose":{"rotation":{"radians":-3.041200687758121},"translation":{"x":4.132706831483922,"y":1.6811810391218687}},"time":2.6366739467451348,"velocity":2.2187708036650844,"position":4.420478865924312,"holonomicRotation":-151.79727424903135,"angularVelocity":-1.3105990076552152,"angularAcceleration":-3.279482890177068,"curveRadius":-1.671720873515124},{"acceleration":-2.993338399955953,"curvature":-0.605692643953051,"pose":{"rotation":{"radians":-3.045615684542314},"translation":{"x":4.125360409296955,"y":1.680473778790847}},"time":2.640015350537342,"velocity":2.2087688513841126,"position":4.427859254540436,"holonomicRotation":-151.68235728796367,"angularVelocity":-1.3212999860986385,"angularAcceleration":-3.2025397434397425,"curveRadius":-1.6510023854235762},{"acceleration":-2.9932577405370084,"curvature":-0.6131807966972003,"pose":{"rotation":{"radians":-3.0500858146184546},"translation":{"x":4.118011295988385,"y":1.6797994013108382}},"time":2.6433718412170593,"velocity":2.198722009676008,"position":4.435239244473203,"holonomicRotation":-151.567440326896,"angularVelocity":-1.3317868281751972,"angularAcceleration":-3.1243471462407038,"curveRadius":-1.6308403743012487},{"acceleration":-2.9931747700715103,"curvature":-0.6206481583245014,"pose":{"rotation":{"radians":-3.0546109956520833},"translation":{"x":4.1106595017312975,"y":1.6791583124562295}},"time":2.646743674253987,"velocity":2.188629524100982,"position":4.442618937808162,"holonomicRotation":-151.4525233658283,"angularVelocity":-1.342053709086252,"angularAcceleration":-3.0448959953275487,"curveRadius":-1.6112188308100275},{"acceleration":-2.99308943704249,"curvature":-0.6280923624017783,"pose":{"rotation":{"radians":-3.0591911340754496},"translation":{"x":4.103305036698775,"y":1.6785509180014073}},"time":2.650131113365007,"velocity":2.1784906158791633,"position":4.449998442123381,"holonomicRotation":-151.33760640476063,"angularVelocity":-1.3520946866517083,"angularAcceleration":-2.9641794985453394,"curveRadius":-1.5921225282473976},{"acceleration":-2.993001688593397,"curvature":-0.6355109629033542,"pose":{"rotation":{"radians":-3.063826124691384},"translation":{"x":4.095947911063903,"y":1.6779776237207589}},"time":2.6535344307927367,"velocity":2.1683044810711496,"position":4.457377870552435,"holonomicRotation":-151.22268944369296,"angularVelocity":-1.3619037055343528,"angularAcceleration":-2.882193357199888,"curveRadius":-1.573536977916895},{"acceleration":-2.9929114704282096,"curvature":-0.6429014344656797,"pose":{"rotation":{"radians":-3.0685158502761984},"translation":{"x":4.088588134999765,"y":1.6774388353886711}},"time":2.656953907595357,"velocity":2.1580702897257233,"position":4.4647573418465765,"holonomicRotation":-151.10777248262528,"angularVelocity":-1.3714746013835708,"angularAcceleration":-2.798935744170928,"curveRadius":-1.55544838818272},{"acceleration":-2.9928187269340984,"curvature":-0.6502611729541397,"pose":{"rotation":{"radians":-3.073260181183405},"translation":{"x":4.081225718679445,"y":1.6769349587795312}},"time":2.660389833948312,"velocity":2.1477871849922336,"position":4.47213698043603,"holonomicRotation":-150.9928555215576,"angularVelocity":-1.3808011056833407,"angularAcceleration":-2.714407511019315,"curveRadius":-1.5378436259034123},{"acceleration":-2.9927234008086447,"curvature":-0.657587496221528,"pose":{"rotation":{"radians":-3.078058974948018},"translation":{"x":4.073860672276027,"y":1.6764663996677256}},"time":2.663842509458511,"velocity":2.137454282197462,"position":4.4795169164903434,"holonomicRotation":-150.87793856048992,"angularVelocity":-1.3898768507023793,"angularAcceleration":-2.6286122145649347,"curveRadius":-1.5207101803881016},{"acceleration":-2.992625433444742,"curvature":-0.6648776446894431,"pose":{"rotation":{"radians":-3.0829120758929482},"translation":{"x":4.066493005962595,"y":1.6760335638276416}},"time":2.6673122434917236,"velocity":2.1270706678823816,"position":4.486897285977743,"holonomicRotation":-150.76302159942225,"angularVelocity":-1.3986953750565343,"angularAcceleration":-2.5415562892555585,"curveRadius":-1.5040361305381065},{"acceleration":-2.992524764498091,"curvature":-0.6721287825970302,"pose":{"rotation":{"radians":-3.0878193147367123},"translation":{"x":4.059122729912235,"y":1.675636857033666}},"time":2.670799355513886,"velocity":2.1166353987994815,"position":4.494278230723431,"holonomicRotation":-150.64810463835457,"angularVelocity":-1.407250129211789,"angularAcceleration":-2.4532490212200306,"curveRadius":-1.4878101130204722},{"acceleration":-2.992421332132522,"curvature":-0.6793379989883446,"pose":{"rotation":{"radians":-3.0927805082048216},"translation":{"x":4.051749854298028,"y":1.6752766850601855}},"time":2.674304175447107,"velocity":2.106147500866028,"position":4.5016598984667695,"holonomicRotation":-150.5331876772869,"angularVelocity":-1.41553448183859,"angularAcceleration":-2.3637027820678864,"curveRadius":-1.4720212935080599},{"acceleration":-2.9923150719637306,"curvature":-0.6865023092196602,"pose":{"rotation":{"radians":-3.097795458644268},"translation":{"x":4.04437438929306,"y":1.674953453681587}},"time":2.6778270440411873,"velocity":2.0956059680754135,"position":4.50904244291727,"holonomicRotation":-150.4182707162192,"angularVelocity":-1.4235417261583465,"angularAcceleration":-2.27293301067523,"curveRadius":-1.4566593390438691},{"acceleration":-2.9922059189210652,"curvature":-0.6936186563379355,"pose":{"rotation":{"radians":-3.102863953642476},"translation":{"x":4.036996345070414,"y":1.6746675686722579}},"time":2.68136831326157,"velocity":2.0850097613536915,"position":4.516426023809349,"holonomicRotation":-150.30335375515153,"angularVelocity":-1.4312650868323777,"angularAcceleration":-2.1809583495029066,"curveRadius":-1.4417143928619958},{"acceleration":-2.9685696898891902,"curvature":-0.7006839130130569,"pose":{"rotation":{"radians":-3.1079857656512027},"translation":{"x":4.029615731803176,"y":1.674419435806585}},"time":2.6849282022377396,"velocity":2.0744419828396636,"position":4.523810806955764,"holonomicRotation":-150.18843679408388,"angularVelocity":-1.4387561081294693,"angularAcceleration":-2.1042850906973216,"curveRadius":-1.4271770500621805},{"acceleration":-2.904408320415767,"curvature":-0.7076948833846683,"pose":{"rotation":{"radians":-3.113160651616271},"translation":{"x":4.022232559664428,"y":1.6742094608589548}},"time":2.688506682555909,"velocity":2.0640486148291286,"position":4.531196964299674,"holonomicRotation":-150.07351983301618,"angularVelocity":-1.4461127364019095,"angularAcceleration":-2.055796767998914,"curveRadius":-1.4130383354155873},{"acceleration":-2.8240605202720186,"curvature":-0.7146483051292897,"pose":{"rotation":{"radians":-3.118388352614185},"translation":{"x":4.014846838827256,"y":1.6740380496037546}},"time":2.6921036168174144,"velocity":2.0538906547871973,"position":4.538584673965264,"holonomicRotation":-149.95860287194853,"angularVelocity":-1.4533768531332796,"angularAcceleration":-2.019530022861695,"curveRadius":-1.3992896825230507},{"acceleration":-2.7453663343270316,"curvature":-0.7215408520266006,"pose":{"rotation":{"radians":-3.1236685934958817},"translation":{"x":4.007458579464742,"y":1.6739056078153713}},"time":2.695718866905538,"velocity":2.0439654689050903,"position":4.545974120306845,"holonomicRotation":-149.84368591088085,"angularVelocity":-1.460546505217714,"angularAcceleration":-1.9831690504586674,"curveRadius":-1.385922913707918},{"acceleration":-2.6682516174637265,"curvature":-0.7283691363384587,"pose":{"rotation":{"radians":-3.1290010825388475},"translation":{"x":4.000067791749972,"y":1.673812541268192}},"time":2.6993522939203425,"velocity":2.0342705713959015,"position":4.553365493956377,"holonomicRotation":-149.72876894981317,"angularVelocity":-1.467619693814747,"angularAcceleration":-1.9466989616725037,"curveRadius":-1.3729302219298318},{"acceleration":-2.5926458996944763,"curvature":-0.7351297117711585,"pose":{"rotation":{"radians":-3.134385511108698},"translation":{"x":3.992674485856028,"y":1.673759255736603}},"time":2.70300375811582,"velocity":2.024803617721615,"position":4.560758991869361,"holonomicRotation":-149.6138519887455,"angularVelocity":-1.4745943768308438,"angularAcceleration":-1.9101058213127031,"curveRadius":-1.3603041531142657},{"acceleration":-2.518482167043078,"curvature":-0.741819076272081,"pose":{"rotation":{"radians":-3.139821553330623},"translation":{"x":3.985278671955996,"y":1.6737461569949919}},"time":2.7066731188393205,"velocity":2.0155623981750312,"position":4.568154817368988,"holonomicRotation":-149.49893502767782,"angularVelocity":-1.4814684713634374,"angularAcceleration":-1.8733766044228406,"curveRadius":-1.3480375902779085},{"acceleration":-2.4456966913817517,"curvature":-0.7484336756184488,"pose":{"rotation":{"radians":3.1378764414079137},"translation":{"x":3.9778803602229598,"y":1.673773650817745}},"time":2.710360234473505,"velocity":2.006544831667764,"position":4.575553180188523,"holonomicRotation":-149.38401806661014,"angularVelocity":1702.6040454320398,"angularAcceleration":462173.05964157206,"curveRadius":-1.3361237375825934},{"acceleration":-2.3742288059385,"curvature":-0.7549699064627566,"pose":{"rotation":{"radians":3.1323382200440713},"translation":{"x":3.970479560830003,"y":1.67384214297925}},"time":2.7140649623805957,"velocity":1.9977489599525853,"position":4.58295429651182,"holonomicRotation":-149.26910110554246,"angularVelocity":-1.494906374431096,"angularAcceleration":-459979.51659148064,"curveRadius":-1.3245561067265281},{"acceleration":-2.304020733917945,"curvature":-0.7614241204039237,"pose":{"rotation":{"radians":3.1267494692105133},"translation":{"x":3.963076283950209,"y":1.6739520392538931}},"time":2.71778715884896,"velocity":1.9891729421137574,"position":4.590358389011922,"holonomicRotation":-149.15418414447478,"angularVelocity":-1.5014658363838636,"angularAcceleration":-1.7622557026523102,"curveRadius":-1.3133285027397286},{"acceleration":-2.2350174574988553,"curvature":-0.7677926276674911,"pose":{"rotation":{"radians":3.1211105867952513},"translation":{"x":3.9556705397566634,"y":1.6741037454160619}},"time":2.721526679042292,"velocity":1.980815049198991,"position":4.597765686887658,"holonomicRotation":-149.0392671834071,"angularVelocity":-1.5079160223059993,"angularAcceleration":-1.7248699267989929,"curveRadius":-1.3024350117009345},{"acceleration":-2.167166518120036,"curvature":-0.7740717013749269,"pose":{"rotation":{"radians":3.115421989386274},"translation":{"x":3.94826233842245,"y":1.6742976672401426}},"time":2.7252833769510874,"velocity":1.9726736592723584,"position":4.605176425898182,"holonomicRotation":-148.92435022233943,"angularVelocity":-1.5142546851210004,"angularAcceleration":-1.6872963887143537,"curveRadius":-1.2918699885601983},{"acceleration":-2.100417907234572,"curvature":-0.7802575818685763,"pose":{"rotation":{"radians":3.1096841125193406},"translation":{"x":3.9408516901206516,"y":1.6745342105005228}},"time":2.729057105346681,"velocity":1.9647472525732144,"position":4.6125908483953815,"holonomicRotation":-148.80943326127175,"angularVelocity":-1.5204795537573073,"angularAcceleration":-1.6495274656161425,"curveRadius":-1.2816280459655134},{"acceleration":-2.03472391809198,"curvature":-0.7863464813527521,"pose":{"rotation":{"radians":3.103897410910446},"translation":{"x":3.933438605024354,"y":1.6748137809715886}},"time":2.7328477157377744,"velocity":1.9570344069462882,"position":4.62000920335408,"holonomicRotation":-148.69451630020407,"angularVelocity":-1.5265883358761871,"angularAcceleration":-1.6115563164267694,"curveRadius":-1.271704043591191},{"acceleration":-1.9700390240969,"curvature":-0.7923345886867804,"pose":{"rotation":{"radians":3.0980623586694302},"translation":{"x":3.9260230933066405,"y":1.6751367844277278}},"time":2.736655058329521,"velocity":1.949533793462441,"position":4.627431746399979,"holonomicRotation":-148.5795993391364,"angularVelocity":-1.5325787213540198,"angularAcceleration":-1.5733770559072744,"curveRadius":-1.2620930781999626},{"acceleration":-1.9063197460635484,"curvature":-0.7982180743678279,"pose":{"rotation":{"radians":3.092179449496257},"translation":{"x":3.9186051651405944,"y":1.675503626643327}},"time":2.740478981985076,"velocity":1.9422441722904173,"position":4.634858739835264,"holonomicRotation":-148.46468237806874,"angularVelocity":-1.5384483852410396,"angularAcceleration":-1.5349845906293427,"curveRadius":-1.2527904743224203},{"acceleration":-1.843524570023614,"curvature":-0.8039930959253175,"pose":{"rotation":{"radians":3.0862491968565546},"translation":{"x":3.911184830699301,"y":1.675914713392773}},"time":2.744319334189859,"velocity":1.9351643886433556,"position":4.642290452661808,"holonomicRotation":-148.34976541700104,"angularVelocity":-1.5441949913647082,"angularAcceleration":-1.4963747638853326,"curveRadius":-1.243791775163315},{"acceleration":-1.78161382835342,"curvature":-0.8096558032259825,"pose":{"rotation":{"radians":3.080272134137575},"translation":{"x":3.9037621001558445,"y":1.6763704504504526}},"time":2.7481759610184526,"velocity":1.9282933689547341,"position":4.649727160601918,"holonomicRotation":-148.2348484559334,"angularVelocity":-1.5498161955064884,"angularAcceleration":-1.4575442197579367,"curveRadius":-1.2350927344874358},{"acceleration":-1.7205495869137553,"curvature":-0.8152023441728872,"pose":{"rotation":{"radians":3.07424881478224},"translation":{"x":3.896336983683308,"y":1.6768712435907531}},"time":2.7520487071040445,"velocity":1.9216301172769472,"position":4.657169146116558,"holonomicRotation":-148.1199314948657,"angularVelocity":-1.5553096490741003,"angularAcceleration":-1.418490509370007,"curveRadius":-1.2266893086704878},{"acceleration":-1.660295585582601,"curvature":-0.820628870590564,"pose":{"rotation":{"radians":3.068179812401218},"translation":{"x":3.8889094914547755,"y":1.6774174985880614}},"time":2.755937415610682,"velocity":1.9151737117097591,"position":4.664616698420972,"holonomicRotation":-148.00501453379803,"angularVelocity":-1.5606730025310145,"angularAcceleration":-1.3792120051578565,"curveRadius":-1.218577649212307},{"acceleration":-1.6008171277470369,"curvature":-0.8259315441432826,"pose":{"rotation":{"radians":3.062065720861632},"translation":{"x":3.8814796336433326,"y":1.6780096212167641}},"time":2.7598419282081954,"velocity":1.9089233010681559,"position":4.672070113497679,"holonomicRotation":-147.89009757273035,"angularVelocity":-1.565903909102484,"angularAcceleration":-1.33970795094913,"curveRadius":-1.2107540958945624},{"acceleration":-1.5420810130402987,"curvature":-0.8311065426475147,"pose":{"rotation":{"radians":3.055907154351644},"translation":{"x":3.874047420422062,"y":1.6786480172512483}},"time":2.763762085049912,"velocity":1.902878101634405,"position":4.679529694106754,"holonomicRotation":-147.77518061166268,"angularVelocity":-1.5710000284814765,"angularAcceleration":-1.299978440852673,"curveRadius":-1.2032151700003109},{"acceleration":-1.4840554491148226,"curvature":-0.8361500662347543,"pose":{"rotation":{"radians":3.0497047474204813},"translation":{"x":3.8666128619640485,"y":1.6793330924659011}},"time":2.7676977247530967,"velocity":1.8970373940871408,"position":4.68699574979335,"holonomicRotation":-147.660263650595,"angularVelocity":-1.5759590305340525,"angularAcceleration":-1.2600243992261297,"curveRadius":-1.195957568362189},{"acceleration":-1.4267099888017183,"curvature":-0.8410583440228526,"pose":{"rotation":{"radians":3.0434591549925614},"translation":{"x":3.859175968442376,"y":1.6800652526351094}},"time":2.771648684382218,"velocity":1.8914005205189213,"position":4.694468596892419,"holonomicRotation":-147.54534668952732,"angularVelocity":-1.580778599175187,"angularAcceleration":-1.2198476050251523,"curveRadius":-1.1889781572309432},{"acceleration":-1.3700154728407166,"curvature":-0.8458276406177117,"pose":{"rotation":{"radians":3.0371710523553457},"translation":{"x":3.8517367500301285,"y":1.6808449035332598}},"time":2.775614799435139,"velocity":1.8859668815293529,"position":4.701948558530563,"holonomicRotation":-147.43042972845964,"angularVelocity":-1.585456436162739,"angularAcceleration":-1.179450652624582,"curveRadius":-1.1822739669156421},{"acceleration":-1.3139439466125598,"curvature":-0.8504542628968966,"pose":{"rotation":{"radians":3.030841135119829},"translation":{"x":3.84429521690039,"y":1.6816724509347392}},"time":2.779595903832106,"velocity":1.8807359335061253,"position":4.709435964624978,"holonomicRotation":-147.31551276739197,"angularVelocity":-1.5899902650979878,"angularAcceleration":-1.1388369867172492,"curveRadius":-1.1758421864965516},{"acceleration":-1.2584686018155227,"curvature":-0.8549345667267655,"pose":{"rotation":{"radians":3.0244701191535763},"translation":{"x":3.8368513792262444,"y":1.682548300613935}},"time":2.783591829907558,"velocity":1.875707186004993,"position":4.716931151879448,"holonomicRotation":-147.2005958063243,"angularVelocity":-1.594377835313712,"angularAcceleration":-1.0980108572773666,"curveRadius":-1.1696801590660177},{"acceleration":-1.2035637399846077,"curvature":-0.8592649640688914,"pose":{"rotation":{"radians":3.0180587404853934},"translation":{"x":3.8294052471807767,"y":1.6834728583452339}},"time":2.7876024084049438,"velocity":1.8708801991491777,"position":4.7244344637773406,"holonomicRotation":-147.0856788452566,"angularVelocity":-1.5986169258031901,"angularAcceleration":-1.0569773144302193,"curveRadius":-1.1637853768233302},{"acceleration":-1.1492047085283987,"curvature":-0.863441929765352,"pose":{"rotation":{"radians":3.011607755180577},"translation":{"x":3.82195683093707,"y":1.6844465299030227}},"time":2.791627468474476,"velocity":1.8662545811651614,"position":4.73194625057157,"holonomicRotation":-146.97076188418893,"angularVelocity":-1.6027053493305723,"angularAcceleration":-1.0157422390610686,"curveRadius":-1.1581554769661915},{"acceleration":-1.0953678338556443,"curvature":-0.8674620086320933,"pose":{"rotation":{"radians":3.0051179391871905},"translation":{"x":3.8145061406682093,"y":1.6854697210616885}},"time":2.79566683767369,"velocity":1.8618299860752752,"position":4.739466869271496,"holonomicRotation":-146.85584492312125,"angularVelocity":-1.6066409563773505,"angularAcceleration":-0.974312288053297,"curveRadius":-1.1527882374663379},{"acceleration":-1.0420304053617773,"curvature":-0.8713218225363558,"pose":{"rotation":{"radians":2.9985900881523917},"translation":{"x":3.807053186547278,"y":1.686542837595618}},"time":2.7997203419710854,"velocity":1.8576061113491247,"position":4.746996683626717,"holonomicRotation":-146.74092796205358,"angularVelocity":-1.6104216391218662,"angularAcceleration":-0.9326948899363777,"curveRadius":-1.147681573140302},{"acceleration":-0.9891706007863375,"curvature":-0.8750180773016123,"pose":{"rotation":{"radians":2.9920250172082037},"translation":{"x":3.79959797874736,"y":1.6876662852791984}},"time":2.8037878057525973,"velocity":1.8535826957566899,"position":4.754536064107745,"holonomicRotation":-146.6260110009859,"angularVelocity":-1.6140453355795414,"angularAcceleration":-0.890898272812226,"curveRadius":-1.1428335321754814},{"acceleration":-0.93676747087228,"curvature":-0.8785475699691305,"pose":{"rotation":{"radians":2.985423560727227},"translation":{"x":3.79214052744154,"y":1.6888404698868165}},"time":2.8078690518311373,"velocity":1.8497595171896886,"position":4.762085387883517,"holonomicRotation":-146.51109403991825,"angularVelocity":-1.6175100334401926,"angularAcceleration":-0.8489313787936614,"curveRadius":-1.1382422923725541},{"acceleration":-0.884800881536334,"curvature":-0.8819071955132246,"pose":{"rotation":{"radians":2.978786572047139},"translation":{"x":3.784680842802902,"y":1.6900657971928592}},"time":2.8119639014590456,"velocity":1.8461363906291566,"position":4.769645038795753,"holonomicRotation":-146.39617707885057,"angularVelocity":-1.620813774174695,"angularAcceleration":-0.8068039207071094,"curveRadius":-1.1339061582529117},{"acceleration":-0.8332514717875387,"curvature":-0.8850939539647512,"pose":{"rotation":{"radians":2.972114923164557},"translation":{"x":3.7772189350045298,"y":1.6913426729717134}},"time":2.816072174343406,"velocity":1.8427131662017584,"position":4.777215407330114,"holonomicRotation":-146.2812601177829,"angularVelocity":-1.6239546569507817,"angularAcceleration":-0.7645263263897218,"curveRadius":-1.129823557737041},{"acceleration":-0.7821006343191763,"curvature":-0.8881049571016619,"pose":{"rotation":{"radians":2.9654095043976723},"translation":{"x":3.769754814219508,"y":1.6926715029977664}},"time":2.820193688664361,"velocity":1.8394897272369841,"position":4.78479689058417,"holonomicRotation":-146.16634315671521,"angularVelocity":-1.6269308425771978,"angularAcceleration":-0.7221097379874365,"curveRadius":-1.1259930394528013},{"acceleration":-0.7313304713847938,"curvature":-0.8909374353021716,"pose":{"rotation":{"radians":2.95867122401844},"translation":{"x":3.7622884906209206,"y":1.6940526930454045}},"time":2.82432826109632,"velocity":1.8364659884313448,"position":4.792389892232169,"holonomicRotation":-146.05142619564754,"angularVelocity":-1.6297405572452672,"angularAcceleration":-0.6795659561678093,"curveRadius":-1.1224132698620286},{"acceleration":-0.6809237734874838,"curvature":-0.8935887440786088,"pose":{"rotation":{"radians":2.9519010078530115},"translation":{"x":3.754819974381851,"y":1.6954866488890148}},"time":2.828475706832144,"velocity":1.833641894030573,"position":4.799994822486594,"holonomicRotation":-145.93650923457986,"angularVelocity":-1.632382096515518,"angularAcceleration":-0.6369074940352476,"curveRadius":-1.1190830307862856},{"acceleration":-0.6308639741069543,"curvature":-0.8960563705203602,"pose":{"rotation":{"radians":2.9450997988522505},"translation":{"x":3.7473492756753837,"y":1.6969737763029846}},"time":2.8326358396101337,"velocity":1.8310174161334378,"position":4.807612098056521,"holonomicRotation":-145.82159227351218,"angularVelocity":-1.6348538288837011,"angularAcceleration":-0.5941474707875888,"curveRadius":-1.1160012169985214},{"acceleration":-0.5811351275860486,"curvature":-0.8983379395478012,"pose":{"rotation":{"radians":2.9382685566317273},"translation":{"x":3.739876404674603,"y":1.6985144810617006}},"time":2.836808471743865,"velocity":1.8285925530260323,"position":4.815242142102779,"holonomicRotation":-145.7066753124445,"angularVelocity":-1.6371541994560332,"angularAcceleration":-0.5512996350040357,"curveRadius":-1.1131668339682645},{"acceleration":-0.5317218777885544,"curvature":-0.9004312199359614,"pose":{"rotation":{"radians":2.931408256981167},"translation":{"x":3.7324013715525934,"y":1.7001091689395496}},"time":2.8409934141547915,"velocity":1.8263673275888574,"position":4.822885384189936,"holonomicRotation":-145.59175835137682,"angularVelocity":-1.6392817336383614,"angularAcceleration":-0.5083783654401777,"curveRadius":-1.110578995773958},{"acceleration":-0.48260944069629913,"curvature":-0.9023341302058069,"pose":{"rotation":{"radians":2.924519891344905},"translation":{"x":3.724924186482438,"y":1.7017582457109186}},"time":2.8451904764076557,"velocity":1.824341785722435,"position":4.830542260235115,"holonomicRotation":-145.47684139030915,"angularVelocity":-1.6412350404287872,"angularAcceleration":-0.4653985747037295,"curveRadius":-1.1082369230253069},{"acceleration":-0.4337835834414204,"curvature":-0.9040447442021047,"pose":{"rotation":{"radians":2.91760446627285},"translation":{"x":3.717444859637221,"y":1.7034621171501945}},"time":2.8493994667486944,"velocity":1.822515994809629,"position":4.838213212453657,"holonomicRotation":-145.36192442924147,"angularVelocity":-1.6430128158356578,"angularAcceleration":-0.4223757392686008,"curveRadius":-1.106139940985536},{"acceleration":-0.3852305715325722,"curvature":-0.9055612962212471,"pose":{"rotation":{"radians":2.9106630028431395},"translation":{"x":3.709963401190027,"y":1.7052211890317646}},"time":2.8536201921463147,"velocity":1.8208900423524217,"position":4.845898689301688,"holonomicRotation":-145.2470074681738,"angularVelocity":-1.6446138461469557,"angularAcceleration":-0.3793258647436668,"curveRadius":-1.1042874780236627},{"acceleration":-0.33693718662361805,"curvature":-0.9068821863466924,"pose":{"rotation":{"radians":2.903696536057539},"translation":{"x":3.7024798213139403,"y":1.7070358671300152}},"time":2.857852458334558,"velocity":1.8194640344899127,"position":4.8535991454155845,"holonomicRotation":-145.1320905071061,"angularVelocity":-1.646037010845949,"angularAcceleration":-0.3362654038506845,"curveRadius":-1.1026790635599821},{"acceleration":-0.28889068291856573,"curvature":-0.9080059847850613,"pose":{"rotation":{"radians":2.896706114208942},"translation":{"x":3.6949941301820446,"y":1.7089065572193338}},"time":2.8620960698590796,"velocity":1.8182380946585526,"position":4.861315041548401,"holonomicRotation":-145.01717354603844,"angularVelocity":-1.6472812858112127,"angularAcceleration":-0.29321132673754924,"curveRadius":-1.1013143269498549},{"acceleration":-0.24107875985125002,"curvature":-0.9089314364864887,"pose":{"rotation":{"radians":2.8896927982241207},"translation":{"x":3.6875063379674238,"y":1.710833665074107}},"time":2.866350830125501,"velocity":1.8172123623300593,"position":4.869046844503293,"holonomicRotation":-144.90225658497076,"angularVelocity":-1.648345745862664,"angularAcceleration":-0.25018097020696345,"curveRadius":-1.1001929957066294},{"acceleration":-0.19348956669367973,"curvature":-0.9096574649872575,"pose":{"rotation":{"radians":2.8826576609803736},"translation":{"x":3.680016454843162,"y":1.7128175964687218}},"time":2.870616541450296,"velocity":1.8163869916941844,"position":4.876795027063974,"holonomicRotation":-144.7873396239031,"angularVelocity":-1.6492295676114077,"angularAcceleration":-0.20719211438577767,"curveRadius":-1.0993148943311404},{"acceleration":-0.1461116631434471,"curvature":-0.9101831761281491,"pose":{"rotation":{"radians":2.8756017865991437},"translation":{"x":3.672524490982344,"y":1.7148587571775649}},"time":2.874893005113926,"velocity":1.815762150475919,"position":4.884560067922278,"holonomicRotation":-144.67242266283543,"angularVelocity":-1.649932031748215,"angularAcceleration":-0.16426285643006544,"curveRadius":-1.0986799429252525},{"acceleration":-0.09893401301076264,"curvature":-0.9105078612188294,"pose":{"rotation":{"radians":2.86852626971619},"translation":{"x":3.6650304565580525,"y":1.7169575529750236}},"time":2.8791800214162397,"velocity":1.8153380187492885,"position":4.892342451602866,"holonomicRotation":-144.55750570176775,"angularVelocity":-1.65045252548603,"angularAcceleration":-0.12141165349294844,"curveRadius":-1.0982881560861804},{"acceleration":-0.051945964736420464,"curvature":-0.9106309999451906,"pose":{"rotation":{"radians":2.861432214730737},"translation":{"x":3.6575343617433735,"y":1.7191143896354848}},"time":2.8834773897340353,"velocity":1.8151147878061928,"position":4.900142668385147,"holonomicRotation":-144.44258874070007,"angularVelocity":-1.6507905445470474,"angularAcceleration":-0.07865722368213791,"curveRadius":-1.0981396416992046},{"acceleration":-0.005137237171374751,"curvature":-0.910552262714285,"pose":{"rotation":{"radians":2.8543207350342183},"translation":{"x":3.65003621671139,"y":1.7213296729333352}},"time":2.8877849085806906,"velocity":1.8150926590602574,"position":4.907961214222475,"holonomicRotation":-144.3276717796324,"angularVelocity":-1.6509456951164792,"angularAcceleration":-0.03601854686072694,"curveRadius":-1.0982345999768077},{"acceleration":0.041502095788146336,"curvature":-0.9102715127159986,"pose":{"rotation":{"radians":2.847192952219901},"translation":{"x":3.642536031635186,"y":1.7236038086429617}},"time":2.892102375667771,"velocity":1.8152718429928676,"position":4.9157985906587,"holonomicRotation":-144.21275481856472,"angularVelocity":-1.6509176956198575,"angularAcceleration":0.006485167357841426,"curveRadius":-1.0985733223884777},{"acceleration":0.0879816288826504,"curvature":-0.9097888073071908,"pose":{"rotation":{"radians":2.840049995275676},"translation":{"x":3.6350338166878453,"y":1.7259372025387516}},"time":2.896429587968412,"velocity":1.815652558179599,"position":4.923655304742145,"holonomicRotation":-144.09783785749704,"angularVelocity":-1.650706378137853,"angularAcceleration":0.048834553824206935,"curveRadius":-1.0991561909404204},{"acceleration":0.13431062083556142,"curvature":-0.9091043993433002,"pose":{"rotation":{"radians":2.832892999760645},"translation":{"x":3.627529582042453,"y":1.7283302603950914}},"time":2.900766341782555,"velocity":1.8162350302767876,"position":4.931531868937078,"holonomicRotation":-143.98292089642936,"angularVelocity":-1.6503116897460621,"angularAcceleration":0.09101009849896331,"curveRadius":-1.0999836770368276},{"acceleration":0.18049801055841397,"curvature":-0.9082187376264049,"pose":{"rotation":{"radians":2.825723106967323},"translation":{"x":3.6200233378720923,"y":1.7307833879863683}},"time":2.9051124328038997,"velocity":1.817019491059846,"position":4.939428801032782,"holonomicRotation":-143.86800393536168,"angularVelocity":-1.6497336935902083,"angularAcceleration":0.13299218838611154,"curveRadius":-1.1010563409134917},{"acceleration":0.2265524550611819,"curvature":-0.9071324670969412,"pose":{"rotation":{"radians":2.8185414630714565},"translation":{"x":3.612515094349848,"y":1.733296991086969}},"time":2.9094676561881916,"velocity":1.8180061776098972,"position":4.9473466240502955,"holonomicRotation":-143.753086974294,"angularVelocity":-1.6489725697581512,"angularAcceleration":0.17476114653550048,"curveRadius":-1.1023748308780734},{"acceleration":0.27248231239805343,"curvature":-0.9058464286008773,"pose":{"rotation":{"radians":2.811349218270621},"translation":{"x":3.605004861648804,"y":1.7358714754712805}},"time":2.9138318066230253,"velocity":1.8191953314120337,"position":4.955285866146925,"holonomicRotation":-143.63817001322633,"angularVelocity":-1.6480286159314022,"angularAcceleration":0.216297270418227,"curveRadius":-1.1039398825522195},{"acceleration":0.31829565340094057,"curvature":-0.9043616581504869,"pose":{"rotation":{"radians":2.8041475259134394},"translation":{"x":3.5974926499420437,"y":1.73850724691369}},"time":2.918204678399043,"velocity":1.8205871974912198,"position":4.963247060518613,"holonomicRotation":-143.52325305215865,"angularVelocity":-1.6469022477810127,"angularAcceleration":0.2575808777579221,"curveRadius":-1.1057523182098448},{"acceleration":0.36400030088065366,"curvature":-0.9026793855104184,"pose":{"rotation":{"radians":2.7969375416215834},"translation":{"x":3.589978469402652,"y":1.7412047111885842}},"time":2.922586065482104,"velocity":1.8221820237077286,"position":4.971230745300272,"holonomicRotation":-143.40833609109097,"angularVelocity":-1.6455939991539548,"angularAcceleration":0.29859234125095563,"curveRadius":-1.1078130464168647},{"acceleration":0.409603803067047,"curvature":-0.9008010328489529,"pose":{"rotation":{"radians":2.7897204224057277},"translation":{"x":3.5824623302037133,"y":1.7439642740703498}},"time":2.926975761586693,"velocity":1.8239800599264768,"position":4.979237463464179,"holonomicRotation":-143.2934191300233,"angularVelocity":-1.644104522021726,"angularAcceleration":0.33931212930016763,"curveRadius":-1.11012306106856},{"acceleration":0.45511346756792875,"curvature":-0.8987282121965973,"pose":{"rotation":{"radians":2.782497325777314},"translation":{"x":3.5749442425183107,"y":1.7467863413333742}},"time":2.9313735602501794,"velocity":1.8259815573258817,"position":4.987267762716538,"holonomicRotation":-143.17850216895562,"angularVelocity":-1.6424345862817797,"angularAcceleration":0.379720825742046,"curveRadius":-1.11268344136642},{"acceleration":0.5005363651405259,"curvature":-0.8964627232332989,"pose":{"rotation":{"radians":2.775269408858767},"translation":{"x":3.5674242165195285,"y":1.7496713187520436}},"time":2.935779254907864,"velocity":1.8281867677157582,"position":4.995322195392313,"holonomicRotation":-143.06358520788797,"angularVelocity":-1.640585079117932,"angularAcceleration":0.41979921613992444,"curveRadius":-1.1154953508755725},{"acceleration":0.5458793314424697,"curvature":-0.8940065499190409,"pose":{"rotation":{"radians":2.7680378274924164},"translation":{"x":3.5599022623804513,"y":1.752619612100746}},"time":2.9401926389687567,"velocity":1.8305959428563172,"position":5.00340131834845,"holonomicRotation":-142.94866824682026,"angularVelocity":-1.6385570044605615,"angularAcceleration":0.45952825074555814,"curveRadius":-1.1185600374969933},{"acceleration":0.5911490049724744,"curvature":-0.8913618571506527,"pose":{"rotation":{"radians":2.760803735352121},"translation":{"x":3.5523783902741632,"y":1.7556316271538674}},"time":2.944613505891646,"velocity":1.8332093339388988,"position":5.011505692855592,"holonomicRotation":-142.8337512857526,"angularVelocity":-1.6363514818418776,"angularAcceleration":0.49888916747635226,"curveRadius":-1.1218788329092546},{"acceleration":0.6363517712864577,"curvature":-0.8885309870935919,"pose":{"rotation":{"radians":2.753568283056675},"translation":{"x":3.544852610373747,"y":1.7587077696857953}},"time":2.949041649262005,"velocity":1.8360271908161372,"position":5.0196358844884035,"holonomicRotation":-142.71883432468493,"angularVelocity":-1.6339697453968085,"angularAcceleration":0.5378634443075889,"curveRadius":-1.1254531519165427},{"acceleration":0.6814938393978008,"curvature":-0.8855164544241135,"pose":{"rotation":{"radians":2.7463326172893883},"translation":{"x":3.5373249328522887,"y":1.7618484454709162}},"time":2.9534768628688792,"velocity":1.8390497615656354,"position":5.0277924630146185,"holonomicRotation":-142.60391736361726,"angularVelocity":-1.6314131423279787,"angularAcceleration":0.5764329061552185,"curveRadius":-1.129284492686632},{"acceleration":0.7265812348464807,"curvature":-0.8823209419859044,"pose":{"rotation":{"radians":2.739097879924054},"translation":{"x":3.5297953678828717,"y":1.7650540602836173}},"time":2.957918940781776,"velocity":1.842277292020872,"position":5.035976002282935,"holonomicRotation":-142.48900040254958,"angularVelocity":-1.6286831314528623,"angularAcceleration":0.6145796919028533,"curveRadius":-1.1333744360065021},{"acceleration":0.7716197495502249,"curvature":-0.8789472957660689,"pose":{"rotation":{"radians":2.7318652071597045},"translation":{"x":3.522263925638579,"y":1.7683250198982854}},"time":2.962367677428035,"velocity":1.8457100250776735,"position":5.044187080109866,"holonomicRotation":-142.3740834414819,"angularVelocity":-1.6257812811714891,"angularAcceleration":0.6522863707415142,"curveRadius":-1.1377246449440686},{"acceleration":0.8166150291354937,"curvature":-0.875398519134727,"pose":{"rotation":{"radians":2.724635728664994},"translation":{"x":3.5147306162924963,"y":1.7716617300893076}},"time":2.9668228676696966,"velocity":1.8493482003866721,"position":5.0524262781656635,"holonomicRotation":-142.25916648041422,"angularVelocity":-1.6227092677448327,"angularAcceleration":0.6895358581838386,"curveRadius":-1.1423368650296932},{"acceleration":0.8615725391300996,"curvature":-0.8716777674775313,"pose":{"rotation":{"radians":2.7174105667359902},"translation":{"x":3.5071954500177065,"y":1.7750645966310705}},"time":2.9712843068801713,"velocity":1.8531920538954154,"position":5.060694181859453,"holonomicRotation":-142.14424951934654,"angularVelocity":-1.6194688727440505,"angularAcceleration":0.7263115886851748,"curveRadius":-1.1472129235254085},{"acceleration":0.9064975590787242,"curvature":-0.8677883418985398,"pose":{"rotation":{"radians":2.7101908354657107},"translation":{"x":3.4996584369872945,"y":1.7785340252979613}},"time":2.9757517910207114,"velocity":1.857241817364038,"position":5.068991380223674,"holonomicRotation":-142.02933255827887,"angularVelocity":-1.6160619810072099,"angularAcceleration":0.762597388074607,"curveRadius":-1.1523547295095122},{"acceleration":0.9513952127623064,"curvature":-0.8637336830333976,"pose":{"rotation":{"radians":2.702977639930619},"translation":{"x":3.4921195873743445,"y":1.7820704218643668}},"time":2.980225116716306,"velocity":1.861497718015953,"position":5.0773184657979655,"holonomicRotation":-141.9144155972112,"angularVelocity":-1.6124905776916105,"angularAcceleration":0.7983776632040567,"curveRadius":-1.157764273459894},{"acceleration":0.9962704644973743,"curvature":-0.8595173642879647,"pose":{"rotation":{"radians":2.6957720753927203},"translation":{"x":3.484578911351939,"y":1.7856741921046742}},"time":2.984704081330978,"velocity":1.86595997817308,"position":5.0856760345125975,"holonomicRotation":-141.7994986361435,"angularVelocity":-1.6087567457653775,"angularAcceleration":0.833637290636677,"curveRadius":-1.163443627259832},{"acceleration":1.0411281416481644,"curvature":-0.855143084996461,"pose":{"rotation":{"radians":2.688575226520196},"translation":{"x":3.477036419093164,"y":1.78934574179327}},"time":2.9891884830421867,"velocity":1.8706288149930743,"position":5.094064685571588,"holonomicRotation":-141.68458167507583,"angularVelocity":-1.6048626630696858,"angularAcceleration":0.868361700504819,"curveRadius":-1.169394944010029},{"acceleration":1.0859729058133765,"curvature":-0.8506146634837632,"pose":{"rotation":{"radians":2.681388166627969},"translation":{"x":3.469492120771103,"y":1.7930854767045414}},"time":2.993678120914579,"velocity":1.8755044400794059,"position":5.1024850213356086,"holonomicRotation":-141.56966471400816,"angularVelocity":-1.600810599095772,"angularAcceleration":0.9025369281631695,"curveRadius":-1.1756204576869351},{"acceleration":1.1308092758883406,"curvature":-0.8459360296664254,"pose":{"rotation":{"radians":2.6742119569386045},"translation":{"x":3.46194602655884,"y":1.7968938026128751}},"time":2.998172794972794,"velocity":1.8805870591965304,"position":5.1109376472047945,"holonomicRotation":-141.45474775294048,"angularVelocity":-1.5966029118947809,"angularAcceleration":0.936149573137651,"curveRadius":-1.1821224831791666},{"acceleration":1.175641645842636,"curvature":-0.8411112176498715,"pose":{"rotation":{"radians":2.6670476458659396},"translation":{"x":3.4543981466294587,"y":1.8007711252926584}},"time":3.002672306273071,"velocity":1.8858768720670753,"position":5.119423171501591,"holonomicRotation":-141.33983079187283,"angularVelocity":-1.5922420446469714,"angularAcceleration":0.9691868642581696,"curveRadius":-1.1889034161190666},{"acceleration":1.220474274865794,"curvature":-0.8361443581448638,"pose":{"rotation":{"radians":2.6598962683217566},"translation":{"x":3.4468484911560435,"y":1.8047178505182777}},"time":3.0071764569737054,"velocity":1.8913740721273185,"position":5.127942205353725,"holonomicRotation":-141.22491383080512,"angularVelocity":-1.58773052224375,"angularAcceleration":1.0016366465237856,"curveRadius":-1.1959657327816926},{"acceleration":1.2653112930265527,"curvature":-0.8310396708011855,"pose":{"rotation":{"radians":2.652758845047113},"translation":{"x":3.4392970703116785,"y":1.8087343840641206}},"time":3.011685050404257,"velocity":1.897078846310661,"position":5.13649536257744,"holonomicRotation":-141.10999686973747,"angularVelocity":-1.583070947643647,"angularAcceleration":1.0334874217151977,"curveRadius":-1.2033119899510019},{"acceleration":1.310156702755271,"curvature":-0.8258014564462787,"pose":{"rotation":{"radians":2.645636381969143},"translation":{"x":3.4317438942694487,"y":1.8128211317045735}},"time":3.0161978911334293,"velocity":1.9029913748404528,"position":5.145083259561083,"holonomicRotation":-140.9950799086698,"angularVelocity":-1.5782659981613494,"angularAcceleration":1.0647283541910335,"curveRadius":-1.2109448248049361},{"acceleration":1.3550143786777487,"curvature":-0.820434089297008,"pose":{"rotation":{"radians":2.638529869584335},"translation":{"x":3.424188973202436,"y":1.8169784992140232}},"time":3.020714785035582,"velocity":1.9091118310248318,"position":5.1537065151491674,"holonomicRotation":-140.88016294760212,"angularVelocity":-1.5733184216306144,"angularAcceleration":1.0953492904442044,"curveRadius":-1.2188669547566626},{"acceleration":1.3998881057961126,"curvature":-0.8149420088440987,"pose":{"rotation":{"radians":2.631440282368389},"translation":{"x":3.4166323172837267,"y":1.8212068923668572}},"time":3.0252355393554256,"velocity":1.915440381226407,"position":5.162365750526999,"holonomicRotation":-140.76524598653444,"angularVelocity":-1.5682310327784983,"angularAcceleration":1.1253407047106307,"curveRadius":-1.227081177737278},{"acceleration":1.4447815475100343,"curvature":-0.8093297122901212,"pose":{"rotation":{"radians":2.6243685782157264},"translation":{"x":3.409073936686404,"y":1.8255067169374621}},"time":3.029759962771199,"velocity":1.9219771846906388,"position":5.171061589105996,"holonomicRotation":-140.65032902546676,"angularVelocity":-1.5630067088788695,"angularAcceleration":1.154693851467393,"curveRadius":-1.2355903716550185},{"acceleration":1.4896982450213427,"curvature":-0.8036017464753092,"pose":{"rotation":{"radians":2.6173156979056746},"translation":{"x":3.4015138415835517,"y":1.8298783787002249}},"time":3.034287865456298,"velocity":1.9287223933742583,"position":5.179794656409766,"holonomicRotation":-140.53541206439908,"angularVelocity":-1.5576483861418278,"angularAcceleration":1.1834005961911487,"curveRadius":-1.2443974946372582},{"acceleration":1.5346416599329418,"curvature":-0.7977627000662758,"pose":{"rotation":{"radians":2.61028256459935},"translation":{"x":3.3939520421482543,"y":1.8343222834295323}},"time":3.038819059138869,"velocity":1.9356761519687566,"position":5.18856557996107,"holonomicRotation":-140.4204951033314,"angularVelocity":-1.552159055433268,"angularAcceleration":1.2114535579607268,"curveRadius":-1.253505584952672},{"acceleration":1.5796151320938001,"curvature":-0.7918171959340876,"pose":{"rotation":{"radians":2.603270083365551},"translation":{"x":3.386388548553596,"y":1.8388388368997715}},"time":3.043353357159788,"velocity":1.9428385977360234,"position":5.19737498916975,"holonomicRotation":-140.30557814226373,"angularVelocity":-1.546541758271468,"angularAcceleration":1.2388460431768058,"curveRadius":-1.262917760734312},{"acceleration":1.9083301428936725,"curvature":-0.783712442097243,"pose":{"rotation":{"radians":2.5962791407371864},"translation":{"x":3.3788233709726603,"y":1.8434284448853293}},"time":3.047887594902233,"velocity":1.9514914202949771,"position":5.2062235152217085,"holonomicRotation":-140.19066118119605,"angularVelocity":-1.5418121028199998,"angularAcceleration":1.043098249391296,"curveRadius":-1.2759782112479465},{"acceleration":2.055015939771913,"curvature":-0.31528785509335455,"pose":{"rotation":{"radians":2.5858300921316104},"translation":{"x":3.3636880045442963,"y":1.852828447499948}},"time":3.056931319301659,"velocity":1.9700764180907016,"position":5.224040343392729,"holonomicRotation":-139.96082725906072,"angularVelocity":-1.1553921972942072,"angularAcceleration":42.72796123136197,"curveRadius":-3.1717047892755237},{"acceleration":3.291855970472616,"curvature":0.23327627317277674,"pose":{"rotation":{"radians":2.580640394421766},"translation":{"x":3.3508991221231756,"y":1.860863406742232}},"time":3.064502009593041,"velocity":1.994998040126987,"position":5.239143855686445,"holonomicRotation":-139.95094395002448,"angularVelocity":-0.685498615067079,"angularAcceleration":62.067468637835766,"curveRadius":4.286762585834639},{"acceleration":3.0286185604693867,"curvature":0.2382374392927917,"pose":{"rotation":{"radians":2.5841502017966413},"translation":{"x":3.338180232196385,"y":1.868792266037}},"time":3.0719309625906095,"velocity":2.0174975050602773,"position":5.254131749824249,"holonomicRotation":-139.94106064098824,"angularVelocity":0.47244980228357464,"angularAcceleration":155.86966531214634,"curveRadius":4.197493068127755},{"acceleration":3.028129547818155,"curvature":0.2433043388182697,"pose":{"rotation":{"radians":2.587707198007621},"translation":{"x":3.325530915452248,"y":1.8766154130233925}},"time":3.079223164689791,"velocity":2.0395792377054702,"position":5.269004773822892,"holonomicRotation":-139.931177331952,"angularVelocity":0.4877808051121988,"angularAcceleration":2.1023831512219093,"curveRadius":4.110078779757914},{"acceleration":3.0276649661958954,"curvature":0.24847884072709947,"pose":{"rotation":{"radians":2.5913119884159266},"translation":{"x":3.3129507525790864,"y":1.884333235340551}},"time":3.086383310003651,"velocity":2.0612577588251155,"position":5.283763678905401,"holonomicRotation":-139.92129402291576,"angularVelocity":0.5034521298510304,"angularAcceleration":2.1886880854913127,"curveRadius":4.024487546198289},{"acceleration":3.027222965405598,"curvature":0.2537628150932349,"pose":{"rotation":{"radians":2.594965181740773},"translation":{"x":3.300439324265224,"y":1.8919461206276171}},"time":3.0934158247143726,"velocity":2.082546748861965,"position":5.298409219552538,"holonomicRotation":-139.91141071387952,"angularVelocity":0.519471835483915,"angularAcceleration":2.2779483999458945,"curveRadius":3.9406876836253195},{"acceleration":3.0268018676853172,"curvature":0.259158130651141,"pose":{"rotation":{"radians":2.598667389788604},"translation":{"x":3.2879962111989824,"y":1.8994544565237326}},"time":3.100324888876079,"velocity":2.103459117170576,"position":5.312942153554596,"holonomicRotation":-139.90152740484325,"angularVelocity":0.5358479761051548,"angularAcceleration":2.3702400553760574,"curveRadius":3.858647990273259},{"acceleration":3.0264001475986033,"curvature":0.2646666518965949,"pose":{"rotation":{"radians":2.602419227163438},"translation":{"x":3.2756209940686856,"y":1.9068586306680382}},"time":3.107114455988523,"velocity":2.124007064081807,"position":5.327363242063485,"holonomicRotation":-139.891644095807,"angularVelocity":0.5525885984627442,"angularAcceleration":2.4656391313824564,"curveRadius":3.778337742341258},{"acceleration":3.0260164147296886,"curvature":0.27029023622743287,"pose":{"rotation":{"radians":2.606221310957504},"translation":{"x":3.263313253562656,"y":1.9141590306996756}},"time":3.113788270614834,"velocity":2.1442021366898874,"position":5.341673249645093,"holonomicRotation":-139.88176078677077,"angularVelocity":0.5697017383546054,"angularAcceleration":2.5642216408579728,"curveRadius":3.6997266862372364},{"acceleration":3.0256493987202946,"curvature":0.2760307307305317,"pose":{"rotation":{"radians":2.6100742604215554},"translation":{"x":3.251072570369216,"y":1.9213560442577862}},"time":3.1203498842777395,"velocity":2.164055279123692,"position":5.355872944331874,"holonomicRotation":-139.87187747773453,"angularVelocity":0.5871954159436934,"angularAcceleration":2.666063332558658,"curveRadius":3.6227850332223546},{"acceleration":3.0252979360987853,"curvature":0.28188996869491967,"pose":{"rotation":{"radians":2.613978696613669},"translation":{"x":3.2388985251766895,"y":1.9284500589815117}},"time":3.126802669836145,"velocity":2.1835768779556237,"position":5.369963097675614,"holonomicRotation":-139.8619941686983,"angularVelocity":0.6050776299279875,"angularAcceleration":2.7712394627775785,"curveRadius":3.5474834547314718},{"acceleration":3.024960958971837,"curvature":0.28786976616449794,"pose":{"rotation":{"radians":2.6179352420263653},"translation":{"x":3.2267906986733985,"y":1.935441462509993}},"time":3.1331498345165185,"velocity":2.202776803313919,"position":5.383944484800354,"holonomicRotation":-139.85211085966205,"angularVelocity":0.623356350738876,"angularAcceleration":2.8798245722864015,"curveRadius":3.4737930742909913},{"acceleration":3.024637484847954,"curvature":0.29397191799095085,"pose":{"rotation":{"radians":2.6219445201901306},"translation":{"x":3.214748671547665,"y":1.9423306424823716}},"time":3.139394431750305,"velocity":2.2216644461850077,"position":5.397817884455403,"holonomicRotation":-139.8422275506258,"angularVelocity":0.6420395125041812,"angularAcceleration":2.9918922015049283,"curveRadius":3.4016854631359124},{"acceleration":3.024326608252264,"curvature":0.3001981936979582,"pose":{"rotation":{"radians":2.6260071552536832},"translation":{"x":3.2027720244878135,"y":1.949117986537789}},"time":3.145539371948868,"velocity":2.2402487523336405,"position":5.4115840790683984,"holonomicRotation":-139.83234424158957,"angularVelocity":0.6611350041295342,"angularAcceleration":3.1075146394131985,"curveRadius":3.33113263501559},{"acceleration":3.024027492428513,"curvature":0.30655033331212495,"pose":{"rotation":{"radians":2.630123771539397},"translation":{"x":3.190860338182166,"y":1.9558038823153872}},"time":3.1515874323306616,"velocity":2.258538253204052,"position":5.425243854798367,"holonomicRotation":-139.82246093255333,"angularVelocity":0.6806506591941425,"angularAcceleration":3.2267626036532233,"curveRadius":3.262107038656569},{"acceleration":3.0237393631682736,"curvature":0.31303004252642974,"pose":{"rotation":{"radians":2.63429499307329},"translation":{"x":3.179013193319045,"y":1.9623887174543067}},"time":3.157541265900937,"velocity":2.2765410941322464,"position":5.438798001588723,"holonomicRotation":-139.8125776235171,"angularVelocity":0.7005942448102436,"angularAcceleration":3.3497049221647575,"curveRadius":3.1945815549495316},{"acceleration":3.023461502187869,"curvature":0.3196389879581915,"pose":{"rotation":{"radians":2.6385214430881687},"translation":{"x":3.167230170586774,"y":1.9688728795936892}},"time":3.163403409671968,"velocity":2.2942650601442494,"position":5.452247313220142,"holonomicRotation":-139.80269431448085,"angularVelocity":0.7209734492976025,"angularAcceleration":3.4764081679583914,"curveRadius":3.1285294900595764},{"acceleration":3.023193242222705,"curvature":0.326378792011569,"pose":{"rotation":{"radians":2.6428037435002576},"translation":{"x":3.155510850673676,"y":1.9752567563726762}},"time":3.1691762922011546,"velocity":2.3117175995946315,"position":5.465592587363255,"holonomicRotation":-139.7928110054446,"angularVelocity":0.7417958689508143,"angularAcceleration":3.606936317851242,"curveRadius":3.063924570088345},{"acceleration":3.0229339620074542,"curvature":0.333251027317081,"pose":{"rotation":{"radians":2.6471425143572174},"translation":{"x":3.1438548142680722,"y":1.981540735430409}},"time":3.1748622405152,"velocity":2.328905845859378,"position":5.478834625631089,"holonomicRotation":-139.78292769640834,"angularVelocity":0.76306899347683,"angularAcceleration":3.7413503167919377,"curveRadius":3.0007409370970133},{"acceleration":3.0226830822604147,"curvature":0.340257211138221,"pose":{"rotation":{"radians":2.6515383732571127},"translation":{"x":3.1322616420582867,"y":1.9877252044060294}},"time":3.180463486480621,"velocity":2.3458366372786363,"position":5.491974233631184,"holonomicRotation":-139.7730443873721,"angularVelocity":0.7848001903563424,"angularAcceleration":3.879707660343349,"curveRadius":2.938953142697026},{"acceleration":3.0224400616024294,"curvature":0.34739879928654294,"pose":{"rotation":{"radians":2.6559919347380814},"translation":{"x":3.120730914732642,"y":1.9938105509386783}},"time":3.1859821726739748,"velocity":2.3625165355168405,"position":5.50501222101731,"holonomicRotation":-139.76316107833586,"angularVelocity":0.8069966881487602,"angularAcceleration":4.022061957273462,"curveRadius":2.8785361436300643},{"acceleration":3.0222043934484577,"curvature":0.3546771797357736,"pose":{"rotation":{"radians":2.6605038096367553},"translation":{"x":3.109262212979462,"y":1.9997971626674975}},"time":3.1914203577991658,"velocity":2.378951842494579,"position":5.51794940154071,"holonomicRotation":-139.75327776929961,"angularVelocity":0.8296655584183356,"angularAcceleration":4.168462409373955,"curveRadius":2.8194652972739243},{"acceleration":3.0219756029253992,"curvature":0.3620936660012242,"pose":{"rotation":{"radians":2.665074604415828},"translation":{"x":3.097855117487067,"y":2.005685427231628}},"time":3.196780021693998,"velocity":2.3951486160246422,"position":5.530786593100775,"holonomicRotation":-139.74339446026337,"angularVelocity":0.8528136966722891,"angularAcceleration":4.318953335165751,"curveRadius":2.7617163565534977},{"acceleration":3.021753243962484,"curvature":0.3696494902237861,"pose":{"rotation":{"radians":2.66970492045865},"translation":{"x":3.0865092089437822,"y":2.011475732270211}},"time":3.2020630699635335,"velocity":2.4111126842711212,"position":5.543524617795068,"holonomicRotation":-139.73351115122713,"angularVelocity":0.8764478018348708,"angularAcceleration":4.473573580401922,"curveRadius":2.7052654648450862},{"acceleration":3.021536897154872,"curvature":0.37734579582355127,"pose":{"rotation":{"radians":2.674395353331549},"translation":{"x":3.075224068037929,"y":2.0171684654223894}},"time":3.207271338273823,"velocity":2.426849659140944,"position":5.556164301968609,"holonomicRotation":-139.7236278421909,"angularVelocity":0.9005743547490349,"angularAcceleration":4.632355991817628,"curveRadius":2.650089151828274},{"acceleration":3.0213261672094203,"curvature":0.3851836298625658,"pose":{"rotation":{"radians":2.6791464920122747},"translation":{"x":3.063999275457831,"y":2.022764014327303}},"time":3.212406596336045,"velocity":2.442364948699708,"position":5.5687064762623075,"holonomicRotation":-139.71374453315465,"angularVelocity":0.9251995952604604,"angularAcceleration":4.7953267806702184,"curveRadius":2.596164329093637},{"acceleration":3.021120681296542,"curvature":0.3931639351485223,"pose":{"rotation":{"radians":2.683958918083457},"translation":{"x":3.052834411891811,"y":2.0282627666240933}},"time":3.2174705516079767,"velocity":2.4576637687009013,"position":5.581151975660456,"holonomicRotation":-139.7038612241184,"angularVelocity":0.9503294979433138,"angularAcceleration":4.962504866925466,"curveRadius":2.5434682853660986},{"acceleration":3.020920087030836,"curvature":0.4012875420013713,"pose":{"rotation":{"radians":2.6888332048917927},"translation":{"x":3.0417290580281917,"y":2.0336651099519027}},"time":3.2224648527369917,"velocity":2.4727511533022235,"position":5.593501639537166,"holonomicRotation":-139.69397791508217,"angularVelocity":0.9759697468016157,"angularAcceleration":5.133901259846311,"curveRadius":2.491978681951165},{"acceleration":0.42414292113827873,"curvature":0.40955515960320804,"pose":{"rotation":{"radians":2.6937699166713958},"translation":{"x":3.030682794555295,"y":2.038971431949872}},"time":3.227416532783914,"velocity":2.4748513733418673,"position":5.605756311701642,"holonomicRotation":-139.68409460604593,"angularVelocity":0.9969771335834399,"angularAcceleration":4.24247661051534,"curveRadius":2.441673548854412},{"acceleration":-2.591522377487766,"curvature":0.4179673670565437,"pose":{"rotation":{"radians":2.698769607630566},"translation":{"x":3.0196952021614445,"y":2.0441821202571426}},"time":3.2323557184248584,"velocity":2.462051363226794,"position":5.617916840442159,"holonomicRotation":-139.6742112970097,"angularVelocity":1.012250059549151,"angularAcceleration":3.092195166568293,"curveRadius":2.392531280712921},{"acceleration":-3.002506579830562,"curvature":0.4265246042607368,"pose":{"rotation":{"radians":2.703832821002757},"translation":{"x":3.0087658615349633,"y":2.0492975625128556}},"time":3.2372866641930345,"velocity":2.447246166113058,"position":5.629984078568639,"holonomicRotation":-139.66432798797342,"angularVelocity":1.0268239827070973,"angularAcceleration":2.9556040246893622,"curveRadius":2.344530632021159},{"acceleration":-3.002448892796786,"curvature":0.4352271622689941,"pose":{"rotation":{"radians":2.708960088059788},"translation":{"x":2.997894353364174,"y":2.0543181463561533}},"time":3.2422095728442484,"velocity":2.432465384483881,"position":5.641958883453693,"holonomicRotation":-139.65444467893718,"angularVelocity":1.0415117200614166,"angularAcceleration":2.9835486284510857,"curveRadius":2.297650713679367},{"acceleration":-3.0023887408648253,"curvature":0.4440751734406439,"pose":{"rotation":{"radians":2.7141519270886625},"translation":{"x":2.9870802583373988,"y":2.0592442594261766}},"time":3.2471246542582453,"velocity":2.4177083993860626,"position":5.65384211707198,"holonomicRotation":-139.64456136990094,"angularVelocity":1.056307839395968,"angularAcceleration":3.0103508138066366,"curveRadius":2.2518709889861976},{"acceleration":-3.002326050962132,"curvature":0.45306860137133337,"pose":{"rotation":{"radians":2.719408842329979},"translation":{"x":2.9763231571429616,"y":2.0640762893620668}},"time":3.252032125653138,"velocity":2.402974570172825,"position":5.665634646037757,"holonomicRotation":-139.6346780608647,"angularVelocity":1.0712064968504282,"angularAcceleration":3.035913254627565,"curveRadius":2.2071712693689927},{"acceleration":-3.0022607484714774,"curvature":0.46220723037661193,"pose":{"rotation":{"radians":2.7247313228797427},"translation":{"x":2.965622630469184,"y":2.068814623802965}},"time":3.256932211806479,"velocity":2.3882632338505205,"position":5.677337341640482,"holonomicRotation":-139.62479475182846,"angularVelocity":1.0862014224249001,"angularAcceleration":3.0601350884918417,"curveRadius":2.1635317110578045},{"acceleration":-3.0021927571485114,"curvature":0.47149065483167074,"pose":{"rotation":{"radians":2.7301198415528685},"translation":{"x":2.95497825900439,"y":2.0734596503880134}},"time":3.2618251452832245,"velocity":2.3735737044054255,"position":5.68895107987829,"holonomicRotation":-139.61491144279222,"angularVelocity":1.101285905221377,"angularAcceleration":3.08291189082546,"curveRadius":2.1209328111858654},{"acceleration":-3.002121999226453,"curvature":0.4809182682781622,"pose":{"rotation":{"radians":2.7355748537101676},"translation":{"x":2.9443896234369014,"y":2.078011756756353}},"time":3.266711166670862,"velocity":2.3589052721089083,"position":5.700476741489225,"holonomicRotation":-139.60502813375598,"angularVelocity":1.1164527791674084,"angularAcceleration":3.104135807593182,"curveRadius":2.079355403944859},{"acceleration":-3.0020483954394304,"curvature":0.49048925216998723,"pose":{"rotation":{"radians":2.741096796047423},"translation":{"x":2.9338563044550416,"y":2.082471330547125}},"time":3.27159052482198,"velocity":2.3442572028005704,"position":5.711915211980027,"holonomicRotation":-139.59514482471974,"angularVelocity":1.1316944086160279,"angularAcceleration":3.123695571543025,"curveRadius":2.0387806574269915},{"acceleration":-3.0019718647208857,"curvature":0.500202564588361,"pose":{"rotation":{"radians":2.746686085348255},"translation":{"x":2.923377882747133,"y":2.0868387593994715}},"time":3.276463477104585,"velocity":2.329628737150063,"position":5.723267381652344,"holonomicRotation":-139.5852615156835,"angularVelocity":1.147002674494552,"angularAcceleration":3.141476663576254,"curveRadius":1.9991900697729221},{"acceleration":-3.0018923247548006,"curvature":0.510056928669308,"pose":{"rotation":{"radians":2.7523431172009745},"translation":{"x":2.912953939001499,"y":2.0911144309525334}},"time":3.2813302896604783,"velocity":2.315019089892506,"position":5.734534145626166,"holonomicRotation":-139.57537820664726,"angularVelocity":1.1623689607418632,"angularAcceleration":3.1573614292383794,"curveRadius":1.9605654659155576},{"acceleration":-3.001809691562041,"curvature":0.520050820867776,"pose":{"rotation":{"radians":2.758068264679891},"translation":{"x":2.902584053906462,"y":2.095298732845452}},"time":3.286191237672039,"velocity":2.3004274490412238,"position":5.745716403860323,"holonomicRotation":-139.56549489761102,"angularVelocity":1.1777841411388554,"angularAcceleration":3.171229225313796,"curveRadius":1.9228889944474334},{"acceleration":-3.001723879396676,"curvature":0.5301824592260471,"pose":{"rotation":{"radians":2.7638618769922},"translation":{"x":2.8922678081503443,"y":2.0993920527173686}},"time":3.291046605637762,"velocity":2.285852975075256,"position":5.756815061169855,"holonomicRotation":-139.55561158857478,"angularVelocity":1.1932385667182903,"angularAcceleration":3.1829566139039542,"curveRadius":1.8861431241233177},{"acceleration":-3.0016348012066896,"curvature":0.5404497915471914,"pose":{"rotation":{"radians":2.7697242780916387},"translation":{"x":2.88200478242147,"y":2.103394778207425}},"time":3.2958966876569464,"velocity":2.2712948000977646,"position":5.767831027240077,"holonomicRotation":-139.5457282795385,"angularVelocity":1.208722053822959,"angularAcceleration":3.192417580449889,"curveRadius":1.8503106405818295},{"acceleration":-3.0015423681730384,"curvature":0.5508504833742549,"pose":{"rotation":{"radians":2.775655765260371},"translation":{"x":2.871794557408161,"y":2.1073072969547626}},"time":3.3007417877239407,"velocity":2.2567520269686434,"position":5.778765216637132,"holonomicRotation":-139.53584497050227,"angularVelocity":1.224223872926551,"angularAcceleration":3.199483785524568,"curveRadius":1.8153746437226728},{"acceleration":-3.001446490234219,"curvature":0.5613819062995955,"pose":{"rotation":{"radians":2.781656607660002},"translation":{"x":2.8616367137987395,"y":2.1111299965985224}},"time":3.3055822200323774,"velocity":2.2422237284052695,"position":5.789618548814849,"holonomicRotation":-139.52596166146603,"angularVelocity":1.2397327381629466,"angularAcceleration":3.204024815999149,"curveRadius":1.781318544075635},{"acceleration":-3.001347075276831,"curvature":0.572041126084545,"pose":{"rotation":{"radians":2.787727044853841},"translation":{"x":2.8515308322815303,"y":2.1148632647778465}},"time":3.3104183092898722,"velocity":2.22770894605651,"position":5.8003919481176975,"holonomicRotation":-139.5160783524298,"angularVelocity":1.2552367978799013,"angularAcceleration":3.2059085123226505,"curveRadius":1.7481260601745698},{"acceleration":-3.001244030190714,"curvature":0.5828248909246841,"pose":{"rotation":{"radians":2.7938672853031843},"translation":{"x":2.841476493544854,"y":2.118507489131876}},"time":3.3152503910436892,"velocity":2.213206689539473,"position":5.811086343779647,"holonomicRotation":-139.50619504339355,"angularVelocity":1.2707236264148494,"angularAcceleration":3.205001348065896,"curveRadius":1.715781215887064},{"acceleration":-3.0011372598103927,"curvature":0.5937296202045713,"pose":{"rotation":{"radians":2.8000775048378372},"translation":{"x":2.831473278277035,"y":2.122063057299752}},"time":3.320078812017903,"velocity":2.198715935447711,"position":5.8217026699187,"holonomicRotation":-139.4963117343573,"angularVelocity":1.286180216642041,"angularAcceleration":3.201168727776327,"curveRadius":1.6842683369164688},{"acceleration":-3.0010266679410766,"curvature":0.6047513929285596,"pose":{"rotation":{"radians":2.8063578451055395},"translation":{"x":2.8215207671663953,"y":2.1255303569206156}},"time":3.3249039304626455,"velocity":2.1842356263190634,"position":5.832241865526917,"holonomicRotation":-139.48642842532107,"angularVelocity":1.3015929742709398,"angularAcceleration":3.1942754992246427,"curveRadius":1.6535720490984167},{"acceleration":-3.0009121561859295,"curvature":0.6158859371807144,"pose":{"rotation":{"radians":2.812708412001504},"translation":{"x":2.811618540901258,"y":2.1289097756336095}},"time":3.3297261165160497,"velocity":2.1697646695720127,"position":5.842704874455696,"holonomicRotation":-139.47654511628483,"angularVelocity":1.316947713264029,"angularAcceleration":3.184186346822911,"curveRadius":1.623677274687599},{"acceleration":-3.000793625286607,"curvature":0.6271286194105915,"pose":{"rotation":{"radians":2.819129274082155},"translation":{"x":2.801766180169946,"y":2.132201701077874}},"time":3.3345457525795617,"velocity":2.1553019363964245,"position":5.853092645396109,"holonomicRotation":-139.46666180724858,"angularVelocity":1.332229653035753,"angularAcceleration":3.170766333877122,"curveRadius":1.5945692303755052},{"acceleration":-3.0006709737749797,"curvature":0.638474434392736,"pose":{"rotation":{"radians":2.8256204609649664},"translation":{"x":2.791963265660782,"y":2.1354065208925506}},"time":3.3393632337073393,"velocity":2.1408462606095933,"position":5.863406131854069,"holonomicRotation":-139.45677849821234,"angularVelocity":1.347423417059833,"angularAcceleration":3.153881379310959,"curveRadius":1.5662334247589995},{"acceleration":-3.0005440991611105,"curvature":0.6499179958281679,"pose":{"rotation":{"radians":2.832181961719319},"translation":{"x":2.782209378062088,"y":2.1385246227167816}},"time":3.344178968010515,"velocity":2.1263964374630713,"position":5.873646292120111,"holonomicRotation":-139.4468951891761,"angularVelocity":1.3625130335835958,"angularAcceleration":3.1333988907593353,"curveRadius":1.5386556556658118},{"acceleration":-3.0004128969574198,"curvature":0.6614535274342445,"pose":{"rotation":{"radians":2.8388137232520525},"translation":{"x":2.7725040980621887,"y":2.141556394189707}},"time":3.348993377077153,"velocity":2.111951222408302,"position":5.883814089233571,"holonomicRotation":-139.43701188013986,"angularVelocity":1.3774819382692123,"angularAcceleration":3.109188371496157,"curveRadius":1.5118220079329923},{"acceleration":-3.0002772612504676,"curvature":0.6730748547923452,"pose":{"rotation":{"radians":2.845515648690395},"translation":{"x":2.7628470063494044,"y":2.1445022229504693}},"time":3.353806896408814,"velocity":2.0975093298109306,"position":5.8939104909409545,"holonomicRotation":-139.4271285711036,"angularVelocity":1.3923129786268453,"angularAcceleration":3.0811220098530487,"curveRadius":1.4857188511499462},{"acceleration":-3.000137084537126,"curvature":0.684775398148323,"pose":{"rotation":{"radians":2.8522875957685843},"translation":{"x":2.7532376836120602,"y":2.14736249663821}},"time":3.3586199758746904,"velocity":2.0830694316145304,"position":5.9039364696482535,"holonomicRotation":-139.41724526206735,"angularVelocity":1.4069884210723416,"angularAcceleration":3.049075451494486,"curveRadius":1.4603328371668503},{"acceleration":-2.9999922574077473,"curvature":0.6965481658165167,"pose":{"rotation":{"radians":2.8591293752222153},"translation":{"x":2.743675710538478,"y":2.1501376028920696}},"time":3.3634330801843877,"velocity":2.0686301559513427,"position":5.913893002367033,"holonomicRotation":-139.4073619530311,"angularVelocity":1.421489960200215,"angularAcceleration":3.0129284957851667,"curveRadius":1.4356508983521148},{"acceleration":-2.99984266906705,"curvature":0.7083857489139613,"pose":{"rotation":{"radians":2.866040749194214},"translation":{"x":2.7341606678169805,"y":2.15282792935119}},"time":3.368246689380479,"velocity":2.0541900856926945,"position":5.923781070654043,"holonomicRotation":-139.39747864399487,"angularVelocity":1.4357987303188033,"angularAcceleration":2.9725658099139607,"curveRadius":1.4116602451886102},{"acceleration":-2.999688206679918,"curvature":0.7202803170406797,"pose":{"rotation":{"radians":2.8730214296598002},"translation":{"x":2.7246921361358902,"y":2.1554338636547126}},"time":3.3730612993520843,"velocity":2.0397477569411064,"position":5.933601660544171,"holonomicRotation":-139.38759533495863,"angularVelocity":1.4498953200270424,"angularAcceleration":2.92787781178022,"curveRadius":1.3883483642987322},{"acceleration":-2.9995287556699957,"curvature":0.7322236150890529,"pose":{"rotation":{"radians":2.8800710768740494},"translation":{"x":2.7152696961835305,"y":2.157955793441779}},"time":3.3778774223708186,"velocity":2.025301657455569,"position":5.943355762476523,"holonomicRotation":-139.3777120259224,"angularVelocity":1.4637597891139276,"angularAcceleration":2.878761408907912,"curveRadius":1.3657030166643562},{"acceleration":-2.9993641995809286,"curvature":0.7442069615554616,"pose":{"rotation":{"radians":2.887189297849353},"translation":{"x":2.7058929286482245,"y":2.16039410635153}},"time":3.382695587650571,"velocity":2.010850225007816,"position":5.953044371213438,"holonomicRotation":-139.36782871688615,"angularVelocity":1.4773716886004142,"angularAcceleration":2.8251209114159734,"curveRadius":1.343712235518339},{"acceleration":-2.999194419917702,"curvature":0.7562212480108208,"pose":{"rotation":{"radians":2.8943756448677376},"translation":{"x":2.6965614142182943,"y":2.1627491900231077}},"time":3.3875163419327063,"velocity":1.996391845665041,"position":5.962668485752248,"holonomicRotation":-139.3579454078499,"angularVelocity":1.4907100834853693,"angularAcceleration":2.7668688558518437,"curveRadius":1.3223643247666204},{"acceleration":-2.9990192961314026,"curvature":0.7682569402500481,"pose":{"rotation":{"radians":2.901629614035226},"translation":{"x":2.6872747335820626,"y":2.1650214320956533}},"time":3.392340250098413,"velocity":1.9819248519933208,"position":5.972229109229596,"holonomicRotation":-139.34806209881367,"angularVelocity":1.503753578697284,"angularAcceleration":2.7039269330708686,"curveRadius":1.3016478571277539},{"acceleration":-2.9988387054092214,"curvature":0.7803040809425305,"pose":{"rotation":{"radians":2.908950643884241},"translation":{"x":2.678032467427853,"y":2.1672112202083076}},"time":3.3971678958100844,"velocity":1.9674475211771578,"position":5.981727248818145,"holonomicRotation":-139.33817878977743,"angularVelocity":1.5164803480328994,"angularAcceleration":2.636226868273918,"curveRadius":1.2815516725122065},{"acceleration":-2.998652522459847,"curvature":0.7923522940614867,"pose":{"rotation":{"radians":2.916338114030867},"translation":{"x":2.6688341964439872,"y":2.1693189420002135}},"time":3.401999882183782,"velocity":1.9529580730491778,"position":5.991163915615521,"holonomicRotation":-139.3282954807412,"angularVelocity":1.5288681662760786,"angularAcceleration":2.5637113363172546,"curveRadius":1.2620648763116975},{"acceleration":-2.9984606196654995,"curvature":0.8043907908464538,"pose":{"rotation":{"radians":2.923791343894994},"translation":{"x":2.6596795013187893,"y":2.1713449851105104}},"time":3.4068368324950127,"velocity":1.9384546680216739,"position":6.000540124525315,"holonomicRotation":-139.31841217170495,"angularVelocity":1.5408944447540667,"angularAcceleration":2.486334922660858,"curveRadius":1.2431768381481696},{"acceleration":-2.9714863639318856,"curvature":0.8164083779760947,"pose":{"rotation":{"radians":2.9313095914875706},"translation":{"x":2.6505679627405816,"y":2.173289737178341}},"time":3.4116790621111917,"velocity":1.924066048746171,"position":6.0098568941300385,"holonomicRotation":-139.30852886266868,"angularVelocity":1.5526416937058605,"angularAcceleration":2.4259999799562606,"curveRadius":1.2248771901129132},{"acceleration":-2.907130519715598,"curvature":0.8283934673692637,"pose":{"rotation":{"radians":2.9388920522762705},"translation":{"x":2.6414991613976864,"y":2.175153585842847}},"time":3.4165264327531526,"velocity":1.9099741096125529,"position":6.01911524655588,"holonomicRotation":-139.29864555363244,"angularVelocity":1.5642420084535658,"angularAcceleration":2.393114866704832,"curveRadius":1.2071558255712815},{"acceleration":-2.8323220924673405,"curvature":0.8403340880767609,"pose":{"rotation":{"radians":2.946537858133208},"translation":{"x":2.6324726779784267,"y":2.176936918743169}},"time":3.421378668955511,"velocity":1.896231013818744,"position":6.028316207329166,"holonomicRotation":-139.2887622445962,"angularVelocity":1.5757282906428647,"angularAcceleration":2.367214148337744,"curveRadius":1.1900028978815558},{"acceleration":-2.757844929256849,"curvature":0.8522179003733373,"pose":{"rotation":{"radians":2.9542460763737832},"translation":{"x":2.6234880931711255,"y":2.178640123518449}},"time":3.4262354885066215,"velocity":1.8828366586473977,"position":6.037460805224432,"holonomicRotation":-139.27887893555996,"angularVelocity":1.587091749952418,"angularAcceleration":2.339691477101417,"curveRadius":1.1734088189909209},{"acceleration":-2.683687001860535,"curvature":0.8640322117259394,"pose":{"rotation":{"radians":2.962015708894226},"translation":{"x":2.614544987664106,"y":2.1802635878078274}},"time":3.431096602460601,"velocity":1.8697909503145398,"position":6.046550072104031,"holonomicRotation":-139.26899562652372,"angularVelocity":1.598323469475994,"angularAcceleration":2.3105238078982095,"curveRadius":1.157364258448721},{"acceleration":-2.6098361013001954,"curvature":0.875763995164313,"pose":{"rotation":{"radians":2.9698456914138713},"translation":{"x":2.605642942145691,"y":2.1818076992504465}},"time":3.4359617151586583,"velocity":1.857093803558256,"position":6.055585042749206,"holonomicRotation":-139.25911231748748,"angularVelocity":1.609414417629423,"angularAcceleration":2.2796898739586946,"curveRadius":1.141860142140666},{"acceleration":-2.5362798347329716,"curvature":0.8873999096351514,"pose":{"rotation":{"radians":2.977734892831024},"translation":{"x":2.5967815373042016,"y":2.183272845485448}},"time":3.44083052426011,"velocity":1.8447451412150797,"position":6.0645667546826125,"holonomicRotation":-139.24922900845124,"angularVelocity":1.6203554612154507,"angularAcceleration":2.2471703774061558,"curveRadius":1.1268876513759658},{"acceleration":-2.463005591363294,"curvature":0.8989263225323838,"pose":{"rotation":{"radians":2.985682114698083},"translation":{"x":2.587960353827963,"y":2.184659414151972}},"time":3.445702720783035,"velocity":1.832744893936895,"position":6.07349624798226,"holonomicRotation":-139.239345699415,"angularVelocity":1.6311373791401027,"angularAcceleration":2.2129480766879133,"curveRadius":1.1124382220590443},{"acceleration":-2.390000566748458,"curvature":0.9103293347530406,"pose":{"rotation":{"radians":2.993686090823308},"translation":{"x":2.579178972405297,"y":2.1859677928891617}},"time":3.450577989155257,"velocity":1.8210929997642338,"position":6.0823745650868855,"holonomicRotation":-139.22946239037876,"angularVelocity":1.6417508769013103,"angularAcceleration":2.177007900053374,"curveRadius":1.0985035435239334},{"acceleration":-2.317251737804906,"curvature":0.92159480748447,"pose":{"rotation":{"radians":3.001745487007023},"translation":{"x":2.570436973724526,"y":2.1871983693361567}},"time":3.4554560072756915,"velocity":1.8097894037976128,"position":6.091202750592781,"holonomicRotation":-139.21957908134252,"angularVelocity":1.6521866021680272,"angularAcceleration":2.1393371260759118,"curveRadius":1.085075558020493},{"acceleration":-2.2447458430736082,"curvature":0.9327083915105103,"pose":{"rotation":{"radians":3.0098589009162287},"translation":{"x":2.561733938473973,"y":2.1883515311320996}},"time":3.4603364465861417,"velocity":1.7988340579431066,"position":6.099981851042143,"holonomicRotation":-139.20969577230628,"angularVelocity":1.6624351606694499,"angularAcceleration":2.0999254061981643,"curveRadius":1.0721464598174266},{"acceleration":-2.1724693868283373,"curvature":0.9436555584009004,"pose":{"rotation":{"radians":3.018024862106679},"translation":{"x":2.553069447341961,"y":2.1894276659161314}},"time":3.465218972153901,"velocity":1.7882269206167427,"position":6.10871291470301,"holonomicRotation":-139.19981246327004,"angularVelocity":1.672487133374655,"angularAcceleration":2.0587649907213943,"curveRadius":1.0597086946582286},{"acceleration":-2.100408615616347,"curvature":0.9544216338548474,"pose":{"rotation":{"radians":3.0262418321954385},"translation":{"x":2.544443081016813,"y":2.1904271613273933}},"time":3.4701032427651515,"velocity":1.7779679565438706,"position":6.117396991340902,"holonomicRotation":-139.18992915423377,"angularVelocity":1.6823330938774383,"angularAcceleration":2.015850735236551,"curveRadius":1.047754959158946},{"acceleration":-2.028549509319929,"curvature":0.9649918329119926,"pose":{"rotation":{"radians":3.0345082051907557},"translation":{"x":2.5358544201868516,"y":2.191350405005027}},"time":3.474988911029288,"velocity":1.7680571365839561,"position":6.126035131982291,"holonomicRotation":-139.18004584519753,"angularVelocity":1.691963626756353,"angularAcceleration":1.9711802681339547,"curveRadius":1.0362782003888733},{"acceleration":-1.9568777726100328,"curvature":0.9753512971552921,"pose":{"rotation":{"radians":3.0428223079835175},"translation":{"x":2.5273030455403993,"y":2.192197784588174}},"time":3.479875623494297,"velocity":1.7584944375800442,"position":6.134628388670062,"holonomicRotation":-139.17016253616129,"angularVelocity":1.701369346425617,"angularAcceleration":1.9247540624936885,"curveRadius":1.0252716153826813},{"acceleration":-1.8853788206735456,"curvature":0.9854851335056009,"pose":{"rotation":{"radians":3.051182401004029},"translation":{"x":2.5187885377657797,"y":2.192969687715976}},"time":3.4847630207731912,"velocity":1.7492798422621993,"position":6.143177814211159,"holonomicRotation":-139.16027922712505,"angularVelocity":1.7105409164533405,"angularAcceleration":1.8765755072397992,"curveRadius":1.0147286508957942},{"acceleration":-1.8140377538574386,"curvature":0.9953784546209381,"pose":{"rotation":{"radians":3.059586679048466},"translation":{"x":2.5103104775513145,"y":2.193666502027573}},"time":3.4896507376813375,"velocity":1.7404133392606547,"position":6.151684461916626,"holonomicRotation":-139.1503959180888,"angularVelocity":1.7194690695833124,"angularAcceleration":1.8266510310962312,"curveRadius":1.0046430032291807},{"acceleration":-1.7428393572201795,"curvature":1.005016420883343,"pose":{"rotation":{"radians":3.0680332722765713},"translation":{"x":2.5018684455853277,"y":2.194288615162108}},"time":3.4945384033847935,"velocity":1.7318949231077363,"position":6.1601493853342895,"holonomicRotation":-139.14051260905256,"angularVelocity":1.7281446278400365,"angularAcceleration":1.774990104292485,"curveRadius":0.9950086179896107},{"acceleration":-1.6717680791487253,"curvature":1.0143842834215726,"pose":{"rotation":{"radians":3.076520247384632},"translation":{"x":2.4934620225561415,"y":2.1948364147587216}},"time":3.499425641559481,"velocity":1.7237245943320965,"position":6.168573637974357,"holonomicRotation":-139.13062930001632,"angularVelocity":1.7365585233838108,"angularAcceleration":1.7216053818191617,"curveRadius":0.9858196901739708},{"acceleration":-1.6008080185731837,"curvature":1.0234674284715921,"pose":{"rotation":{"radians":3.0850456089525666},"translation":{"x":2.4850907891520784,"y":2.195310288456556}},"time":3.5043120705610806,"velocity":1.7159023596041474,"position":6.17695827302824,"holonomicRotation":-139.12074599098008,"angularVelocity":1.744701819087953,"angularAcceleration":1.6665126417423988,"curveRadius":0.9770706640790342},{"acceleration":-1.5299429012716257,"curvature":1.032251422242915,"pose":{"rotation":{"radians":3.0936073009687344},"translation":{"x":2.4767543260614615,"y":2.1957106238947515}},"time":3.5091973036053603,"velocity":1.7084282319869941,"position":6.185304343080923,"holonomicRotation":-139.11086268194384,"angularVelocity":1.7525657299385093,"angularAcceleration":1.6097309543429954,"curveRadius":0.9687562336578448},{"acceleration":-1.4591560592559913,"curvature":1.0407220567342343,"pose":{"rotation":{"radians":3.102203208528496},"translation":{"x":2.468452213972614,"y":2.19603780871245}},"time":3.5140809489586498,"velocity":1.7013022312784845,"position":6.193612899817247,"holonomicRotation":-139.1009793729076,"angularVelocity":1.7601416437767754,"angularAcceleration":1.5512825543655004,"curveRadius":0.9608713426695122},{"acceleration":-1.388430436565163,"curvature":1.048865395922443,"pose":{"rotation":{"radians":3.1108311597093943},"translation":{"x":2.4601840335738583,"y":2.196292230548793}},"time":3.518962610138513,"velocity":1.6945243843153635,"position":6.201884993722492,"holonomicRotation":-139.09109606387136,"angularVelocity":1.7674211427224797,"angularAcceleration":1.4911929930188195,"curveRadius":0.9534111849695762},{"acceleration":-1.3177485349030753,"curvature":1.0566678217007708,"pose":{"rotation":{"radians":3.1194889276177444},"translation":{"x":2.4519493655535167,"y":2.1964742770429218}},"time":3.5238418861237895,"velocity":1.688094725534378,"position":6.210121673777663,"holonomicRotation":-139.08121275483512,"angularVelocity":1.7743960240158358,"angularAcceleration":1.4294910380973636,"curveRadius":0.9463712052766399},{"acceleration":-1.2470924104792294,"curvature":1.0641160803172787,"pose":{"rotation":{"radians":3.128174232604821},"translation":{"x":2.4437477905999136,"y":2.1965843358339776}},"time":3.52871837157386,"velocity":1.6820132975397823,"position":6.218323987149941,"holonomicRotation":-139.07132944579885,"angularVelocity":1.781058320793484,"angularAcceleration":1.3662086857147506,"curveRadius":0.939747099491099},{"acceleration":-1.176443669889392,"curvature":1.071197328021577,"pose":{"rotation":{"radians":3.136884744649322},"translation":{"x":2.4355788894013704,"y":2.1966227945611028}},"time":3.533591657056963,"velocity":1.6762801516816221,"position":6.226492978878745,"holonomicRotation":-139.0614461367626,"angularVelocity":1.7874003225755568,"angularAcceleration":1.3013811327209182,"curveRadius":0.9335348155198695},{"acceleration":-1.1057834114556424,"curvature":1.0778991760386356,"pose":{"rotation":{"radians":-3.1375672212789403},"translation":{"x":2.42744224264621,"y":2.1965900408634376}},"time":3.538461329286555,"velocity":1.6708953489109128,"position":6.234629691557891,"holonomicRotation":-139.05156282772637,"angularVelocity":-1288.4752135471076,"angularAcceleration":-264958.8212588441,"curveRadius":0.9277305542389213},{"acceleration":-1.0350922201795958,"curvature":1.084209734852349,"pose":{"rotation":{"radians":-3.128813473803015},"translation":{"x":2.4193374310227553,"y":2.1964864623801232}},"time":3.5433269713654827,"velocity":1.6658589606488365,"position":6.242735165014382,"holonomicRotation":-139.04167951869013,"angularVelocity":1.799094001146655,"angularAcceleration":265180.68666338606,"curveRadius":0.9223307703801268},{"acceleration":-0.9643501474940613,"curvature":1.090117657108148,"pose":{"rotation":{"radians":-3.1200417853692892},"translation":{"x":2.4112640352193297,"y":2.1963124467503023}},"time":3.5481881630374543,"velocity":1.6611710697429738,"position":6.250810435984337,"holonomicRotation":-139.0317962096539,"angularVelocity":1.8044317166716886,"angularAcceleration":1.0980261395183148,"curveRadius":0.9173321737148896},{"acceleration":-0.8935366789600924,"curvature":1.0956121791263687,"pose":{"rotation":{"radians":-3.111254660540917},"translation":{"x":2.4032216359242558,"y":2.1960683816131157}},"time":3.5530444809451334,"velocity":1.6568317715677718,"position":6.258856537786613,"holonomicRotation":-139.02191290061765,"angularVelocity":1.809421251948474,"angularAcceleration":1.0274317644847306,"curveRadius":0.9127317303075173},{"acceleration":-0.8226307090058784,"curvature":1.100683160608915,"pose":{"rotation":{"radians":-3.1024546400577298},"translation":{"x":2.3952098138258555,"y":2.195754654607705}},"time":3.557895498894247,"velocity":1.6528411752328922,"position":6.266874499994702,"holonomicRotation":-139.0120295915814,"angularVelocity":1.8140564672193973,"angularAcceleration":0.9555139394547357,"curveRadius":0.9085266639736586},{"acceleration":-0.7516104969275627,"curvature":1.1053211221843227,"pose":{"rotation":{"radians":-3.0936442975918763},"translation":{"x":2.3872281496124534,"y":2.195371653373211}},"time":3.562740788122819,"velocity":1.6491994049880476,"position":6.274865348107458,"holonomicRotation":-139.00214628254517,"angularVelocity":1.8183315897636259,"angularAcceleration":0.8823255625317449,"curveRadius":0.9047144580244804},{"acceleration":-0.6804536549874586,"curvature":1.1095172810799745,"pose":{"rotation":{"radians":-3.0848262363911534},"translation":{"x":2.3792762239723704,"y":2.1949197655487755}},"time":3.5675799175750993,"velocity":1.645906601665286,"position":6.282830103219279,"holonomicRotation":-138.99226297350893,"angularVelocity":1.8222412290639025,"angularAcceleration":0.8079220320163579,"curveRadius":0.901292856859901},{"acceleration":-0.6091371179336131,"curvature":1.11326358390566,"pose":{"rotation":{"radians":-3.0760030858184555},"translation":{"x":2.3713536175939307,"y":2.1943993787735403}},"time":3.5724124541794704,"velocity":1.6429629242457906,"position":6.290769781690321,"holonomicRotation":-138.9823796644727,"angularVelocity":1.8257803913408972,"angularAcceleration":0.732361193869377,"curveRadius":0.8982598680644007},{"acceleration":-0.5376370831813755,"curvature":1.1165527367571702,"pose":{"rotation":{"radians":-3.067177497800981},"translation":{"x":2.363459911165456,"y":2.1938108806866463}},"time":3.577237963129215,"velocity":1.6403685516891844,"position":6.298685394817377,"holonomicRotation":-138.97249635543645,"angularVelocity":1.828944492568395,"angularAcceleration":0.655703110376671,"curveRadius":0.8956137646523737},{"acceleration":-0.465928993818698,"curvature":1.1193782325678918,"pose":{"rotation":{"radians":-3.058352143199393},"translation":{"x":2.3555946853752707,"y":2.193154658927235}},"time":3.582056008165627,"velocity":1.6381236848131957,"position":6.30657794850602,"holonomicRotation":-138.96261304640018,"angularVelocity":1.8317293705000182,"angularAcceleration":0.5780099419113964,"curveRadius":0.8933530873706254},{"acceleration":-0.3939875078153305,"curvature":1.121734375238465,"pose":{"rotation":{"radians":-3.0495297081104216},"translation":{"x":2.347757520911695,"y":2.1924311011344475}},"time":3.58686615186278,"velocity":1.6362285482857208,"position":6.314448442944658,"holonomicRotation":-138.95272973736394,"angularVelocity":1.8341312951198312,"angularAcceleration":0.4993457100324797,"curveRadius":0.8914766473011171},{"acceleration":-0.32178643913019306,"curvature":1.1236163003214465,"pose":{"rotation":{"radians":-3.0407128901150444},"translation":{"x":2.339947998463055,"y":2.1916405949474256}},"time":3.5916679559128575,"velocity":1.6346833928590454,"position":6.322297872281084,"holonomicRotation":-138.9428464283277,"angularVelocity":1.8361469779747688,"angularAcceleration":0.41977615785987216,"curveRadius":0.889983528820219},{"acceleration":-0.24929871747297294,"curvature":1.1250199924559543,"pose":{"rotation":{"radians":-3.031904394486698},"translation":{"x":2.3321656987176707,"y":2.1907835280053107}},"time":3.5964609814112833,"velocity":1.6334884977494726,"position":6.330127224302182,"holonomicRotation":-138.93296311929146,"angularVelocity":1.8377735798066215,"angularAcceleration":0.3393684912352158,"curveRadius":0.8888730926611965},{"acceleration":-0.1764963520712738,"curvature":1.1259422991737331,"pose":{"rotation":{"radians":-3.0231069303715206},"translation":{"x":2.3244102023638664,"y":2.189860287947244}},"time":3.601244789140916,"velocity":1.632644173136182,"position":6.337937480117371,"holonomicRotation":-138.92307981025522,"angularVelocity":1.8390087169855345,"angularAcceleration":0.2581912252162823,"curveRadius":0.8881449793065282},{"acceleration":-0.10335038384282981,"curvature":1.1263809411493282,"pose":{"rotation":{"radians":-3.0143232069560173},"translation":{"x":2.3166810900899644,"y":2.1888712624123676}},"time":3.606018939854506,"velocity":1.632150762827409,"position":6.34572961384641,"holonomicRotation":-138.91319650121898,"angularVelocity":1.8398504660734536,"angularAcceleration":0.17631389087131946,"curveRadius":0.8877991125982897},{"acceleration":-0.029830823335117957,"curvature":1.126334518502156,"pose":{"rotation":{"radians":-3.0055559296343874},"translation":{"x":2.3089779425842876,"y":2.187816839039822}},"time":3.6107829945544037,"velocity":1.6320086471532975,"position":6.353504592312154,"holonomicRotation":-138.90331319218274,"angularVelocity":1.8402973672443539,"angularAcceleration":0.09380689329824209,"curveRadius":0.8878357038456384},{"acceleration":0.04409338912663097,"curvature":1.1258025137934013,"pose":{"rotation":{"radians":-2.996807796191059},"translation":{"x":2.301300340535159,"y":2.1866974054687494}},"time":3.6155365147689063,"velocity":1.632218245969837,"position":6.361263374738852,"holonomicRotation":-138.8934298831465,"angularVelocity":1.840348425707492,"angularAcceleration":0.010741189862274396,"curveRadius":0.8882552559156146},{"acceleration":0.11845445797339557,"curvature":1.1247852906131648,"pose":{"rotation":{"radians":-2.988081493009691},"translation":{"x":2.293647864630901,"y":2.1855133493382897}},"time":3.6202790628241814,"velocity":1.6327800219291373,"position":6.369006912456544,"holonomicRotation":-138.88354657411026,"angularVelocity":1.8400031121796312,"angularAcceleration":-0.0728118142053887,"curveRadius":0.8890585681955891},{"acceleration":0.19328577507285105,"curvature":1.1232840893531093,"pose":{"rotation":{"radians":-2.979379691326129},"translation":{"x":2.286020095559837,"y":2.184265058287586}},"time":3.6250102021112234,"velocity":1.6336944838532108,"position":6.3767361486121255,"holonomicRotation":-138.87366326507401,"angularVelocity":1.8392613608724873,"angularAcceleration":-0.15678069533389297,"curveRadius":0.8902467412103133},{"acceleration":0.26862198134130916,"curvature":1.1213010184300354,"pose":{"rotation":{"radians":-2.9707050435330045},"translation":{"x":2.2784166140102893,"y":2.18295291995578}},"time":3.629729497347096,"velocity":1.6349621902900056,"position":6.384452017887593,"holonomicRotation":-138.86377995603777,"angularVelocity":1.8381235670923801,"angularAcceleration":-0.24109400307453366,"curveRadius":0.891821182326337},{"acceleration":0.3444990679159851,"curvature":1.1188390423770342,"pose":{"rotation":{"radians":-2.962060179554769},"translation":{"x":2.2708370006705807,"y":2.181577321982011}},"time":3.6344365148292637,"velocity":1.6365837534252765,"position":6.392155446225997,"holonomicRotation":-138.85389664700153,"angularVelocity":1.8365905822501152,"angularAcceleration":-0.3256807199192776,"curveRadius":0.8937836115152415},{"acceleration":0.42095440491784963,"curvature":1.1159019665522818,"pose":{"rotation":{"radians":-2.9534477033016384},"translation":{"x":2.2632808362290344,"y":2.1801386520054225}},"time":3.639130822682874,"velocity":1.6385598429942942,"position":6.399847350565576,"holonomicRotation":-138.84401333796527,"angularVelocity":1.834663707985568,"angularAcceleration":-0.4104703663746997,"curveRadius":0.8961360674805732},{"acceleration":0.49802683961163136,"curvature":1.1124944181155036,"pose":{"rotation":{"radians":-2.9448701892151603},"translation":{"x":2.255747701373973,"y":2.1786372976651545}},"time":3.6438119911000153,"velocity":1.640891190506773,"position":6.407528638582542,"holonomicRotation":-138.83413002892902,"angularVelocity":1.8323446887895292,"angularAcceleration":-0.49539324147092567,"curveRadius":0.8988809145612953},{"acceleration":0.5757567840444726,"curvature":1.1086218241008476,"pose":{"rotation":{"radians":-2.936330178918244},"translation":{"x":2.2482371767937193,"y":2.177073646600349}},"time":3.6484795925702,"velocity":1.6435785937184477,"position":6.415200208442946,"holonomicRotation":-138.82424671989278,"angularVelocity":1.8296357029337775,"angularAcceleration":-0.5803807101047148,"curveRadius":0.9020208499061925},{"acceleration":0.6541862829976322,"curvature":1.1042903864043705,"pose":{"rotation":{"radians":-2.927830177978178},"translation":{"x":2.240748843176596,"y":2.1754480864501473}},"time":3.6531332021017078,"velocity":1.6466229212403871,"position":6.422862948564029,"holonomicRotation":-138.81436341085654,"angularVelocity":1.8265393524136198,"angularAcceleration":-0.6653653468761451,"curveRadius":0.9055589112353449},{"acceleration":0.7333591221523916,"curvature":1.0995070537938059,"pose":{"rotation":{"radians":-2.9193726527939976},"translation":{"x":2.233282281210926,"y":2.1737610048536906}},"time":3.6577723974329923,"velocity":1.6500251174560314,"position":6.430517737385434,"holonomicRotation":-138.8044801018203,"angularVelocity":1.8230586513887383,"angularAcceleration":-0.7502811967000405,"curveRadius":0.909498485298061},{"acceleration":0.8133209173461158,"curvature":1.0942794915514795,"pose":{"rotation":{"radians":-2.9109600276172087},"translation":{"x":2.2258370715850324,"y":2.172012789450121}},"time":3.662396759233726,"velocity":1.6537862076379444,"position":6.438165443150615,"holonomicRotation":-138.79459679278406,"angularVelocity":1.819197013402884,"angularAcceleration":-0.8350639833677577,"curveRadius":0.9138433167400322},{"acceleration":0.8941192164433867,"curvature":1.0886160484973206,"pose":{"rotation":{"radians":-2.9025946817130373},"translation":{"x":2.218412794987237,"y":2.1702038278785794}},"time":3.667005871295019,"velocity":1.6579073033026874,"position":6.445806923698773,"holonomicRotation":-138.78471348374782,"angularVelocity":1.8149582377098352,"angularAcceleration":-0.919651255313537,"curveRadius":0.918597517812049},{"acceleration":0.9758036265883469,"curvature":1.0825257218847686,"pose":{"rotation":{"radians":-2.894278946671229},"translation":{"x":2.211009032105864,"y":2.168334507778207}},"time":3.6715993207081525,"velocity":1.6623896078985734,"position":6.453443026267574,"holonomicRotation":-138.77483017471158,"angularVelocity":1.8103464942994463,"angularAcceleration":-1.0039826273481915,"curveRadius":0.9237655787604895},{"acceleration":1.058425907320178,"curvature":1.0760181206595436,"pose":{"rotation":{"radians":-2.8860151038722974},"translation":{"x":2.203625363629236,"y":2.1664052167881453}},"time":3.6761766980317474,"velocity":1.667234422645446,"position":6.461074587306908,"holonomicRotation":-138.76494686567534,"angularVelocity":1.8053663079803504,"angularAcceleration":-1.087999954346062,"curveRadius":0.9293523787378707},{"acceleration":1.1420401113912082,"curvature":1.0691034266178348,"pose":{"rotation":{"radians":-2.877805382113999},"translation":{"x":2.1962613702456744,"y":2.1644163425475362}},"time":3.6807375974468197,"velocity":1.6724431527214794,"position":6.468702432303897,"holonomicRotation":-138.7550635566391,"angularVelocity":1.8000225418626556,"angularAcceleration":-1.171647438668626,"curveRadius":0.9353631978933534},{"acceleration":1.2267027272491373,"curvature":1.0617923545251111,"pose":{"rotation":{"radians":-2.8696519554044277},"translation":{"x":2.1889166326435032,"y":2.162368272695521}},"time":3.6852816168993168,"velocity":1.6780173137765306,"position":6.4763273756193245,"holonomicRotation":-138.74518024760286,"angularVelocity":1.7943203797445897,"angularAcceleration":-1.2548718546819773,"curveRadius":0.9418037300214429},{"acceleration":1.3124728105727628,"curvature":1.0540961108907771,"pose":{"rotation":{"radians":-2.8615569409242196},"translation":{"x":2.1815907315110454,"y":2.160261394871241}},"time":3.6898083582300294,"velocity":1.683958538693587,"position":6.483950220335635,"holonomicRotation":-138.73529693856662,"angularVelocity":1.7882653080452788,"angularAcceleration":-1.3376226421927297,"curveRadius":0.948680096310134},{"acceleration":1.3994121379019524,"curvature":1.0460263520846556,"pose":{"rotation":{"radians":-2.853522397161729},"translation":{"x":2.174283247536623,"y":2.158096096713837}},"time":3.694317427291661,"velocity":1.6902685846690724,"position":6.491571758116614,"holonomicRotation":-138.72541362953035,"angularVelocity":1.7818630969433722,"angularAcceleration":-1.4198520835229747,"curveRadius":0.9559988598825179},{"acceleration":1.4875853702176403,"curvature":1.0375951416219997,"pose":{"rotation":{"radians":-2.8455503222219063},"translation":{"x":2.166993761408559,"y":2.1558727658624512}},"time":3.698808434052885,"velocity":1.6969493406246174,"position":6.499192769078814,"holonomicRotation":-138.7155303204941,"angularVelocity":1.7751197813049928,"angularAcceleration":-1.5015153610104528,"curveRadius":0.9637670415811412},{"acceleration":1.5770602455702274,"curvature":1.0288149071225368,"pose":{"rotation":{"radians":-2.83764265231117},"translation":{"x":2.159721853815177,"y":2.153591789956225}},"time":3.7032809926890673,"velocity":1.7040028350457226,"position":6.506814021674777,"holonomicRotation":-138.70564701145787,"angularVelocity":1.7680416410338404,"angularAcceleration":-1.58257070435949,"curveRadius":0.9719921368527519},{"acceleration":1.6679077505997852,"curvature":1.019698397302995,"pose":{"rotation":{"radians":-2.829801260398177},"translation":{"x":2.152467105444799,"y":2.1512535566342987}},"time":3.70773472165978,"velocity":1.7114312441150448,"position":6.514436272588075,"holonomicRotation":-138.69576370242163,"angularVelocity":1.7606351811162642,"angularAcceleration":-1.6629794866909908,"curveRadius":0.9806821337023817},{"acceleration":1.7602023179557127,"curvature":1.0102586389839427,"pose":{"rotation":{"radians":-2.8220279550494562},"translation":{"x":2.145229096985748,"y":2.1488584535358153}},"time":3.712169243773097,"velocity":1.7192369002179317,"position":6.522060266640122,"holonomicRotation":-138.6858803933854,"angularVelocity":1.7529071115412411,"angularAcceleration":-1.7427062888726832,"curveRadius":0.9898455320369641},{"acceleration":1.8540220657922188,"curvature":1.00050889429755,"pose":{"rotation":{"radians":-2.8143244794382984},"translation":{"x":2.1380074091263466,"y":2.1464068682999153}},"time":3.7165841862364197,"velocity":1.727422300964135,"position":6.529686736708739,"holonomicRotation":-138.67599708434915,"angularVelocity":1.7448643272601696,"angularAcceleration":-1.821718934705803,"curveRadius":0.9994913645441331},{"acceleration":1.949449012642217,"curvature":0.9904626187864551,"pose":{"rotation":{"radians":-2.806692510526085},"translation":{"x":2.130801622554918,"y":2.14389918856574}},"time":3.7209791806940538,"velocity":1.7359901185701376,"position":6.537316403658362,"holonomicRotation":-138.6661137753129,"angularVelocity":1.7365138877381112,"angularAcceleration":-1.8999886353790092,"curveRadius":1.00962921874349},{"acceleration":2.046569329223132,"curvature":0.9801334199083612,"pose":{"rotation":{"radians":-2.799133658411492},"translation":{"x":2.1236113179597846,"y":2.141335801972431}},"time":3.725353863251597,"velocity":1.744943209717493,"position":6.544949976281817,"holonomicRotation":-138.65623046627667,"angularVelocity":1.7278629969526258,"angularAcceleration":-1.977489948514942,"curveRadius":1.0202692609884645},{"acceleration":2.1454736098387626,"curvature":0.969535016794209,"pose":{"rotation":{"radians":-2.7916494658451203},"translation":{"x":2.1164360760292698,"y":2.13871709615913}},"time":3.7297078744871883,"velocity":1.7542846259203957,"position":6.5525881512535,"holonomicRotation":-138.64634715724043,"angularVelocity":1.7189189833027931,"angularAcceleration":-2.0542008657949595,"curveRadius":1.0314222618864497},{"acceleration":2.2462571688281256,"curvature":0.9586812007452662,"pose":{"rotation":{"radians":-2.7842414079040374},"translation":{"x":2.109275477451696,"y":2.136043458764978}},"time":3.7340408594496775,"velocity":1.7640176244548114,"position":6.560231613093828,"holonomicRotation":-138.6364638482042,"angularVelocity":1.709689280072476,"angularAcceleration":-2.130102760618662,"curveRadius":1.043099623965311},{"acceleration":2.3490203335953277,"curvature":0.9475857975373879,"pose":{"rotation":{"radians":-2.776910891824363},"translation":{"x":2.102129102915386,"y":2.1333152774291166}},"time":3.738352467644059,"velocity":1.7741456797739097,"position":6.567881034144768,"holonomicRotation":-138.62658053916795,"angularVelocity":1.7001814054503182,"angularAcceleration":-2.2051805714971033,"curveRadius":1.055313410773808},{"acceleration":2.4538687880733185,"curvature":0.9362626305062637,"pose":{"rotation":{"radians":-2.769659256982143},"translation":{"x":2.0949965331086626,"y":2.1305329397906876}},"time":3.7426423530042565,"velocity":1.7846724955637112,"position":6.575537074556234,"holonomicRotation":-138.6166972301317,"angularVelocity":1.690402943981188,"angularAcceleration":-2.2794225598326245,"curveRadius":1.068076378803319},{"acceleration":2.5609139505785232,"curvature":0.9247254856283244,"pose":{"rotation":{"radians":-2.762487775021394},"translation":{"x":2.087877348719849,"y":2.127696833488832}},"time":3.7469101738532884,"velocity":1.7956020175145668,"position":6.583200382283146,"holonomicRotation":-138.60681392109544,"angularVelocity":1.6803615274469454,"angularAcceleration":-2.3528205352200846,"curveRadius":1.0814020112363711},{"acceleration":2.67027333890024,"curvature":0.9129880779939724,"pose":{"rotation":{"radians":-2.7553976501202815},"translation":{"x":2.0807711304372676,"y":2.1248073461626906}},"time":3.7511555928512936,"velocity":1.8069384466774008,"position":6.5908715930928965,"holonomicRotation":-138.5969306120592,"angularVelocity":1.670064816792823,"angularAcceleration":-2.4253697123795233,"curveRadius":1.0953045544660465},{"acceleration":2.782071000311007,"curvature":0.9010640201473852,"pose":{"rotation":{"radians":-2.7483900193900306},"translation":{"x":2.073677458949241,"y":2.1218648654514056}},"time":3.755378276931553,"velocity":1.8186862536005657,"position":6.598551330582962,"holonomicRotation":-138.58704730302296,"angularVelocity":1.659520484378803,"angularAcceleration":-2.4970687395993854,"curveRadius":1.1097990571595924},{"acceleration":2.8964379678513206,"curvature":0.8889667920574151,"pose":{"rotation":{"radians":-2.741465953399449},"translation":{"x":2.0665959149440924,"y":2.1188697789941187}},"time":3.7595778972247427,"velocity":1.8308501932683188,"position":6.606240206208402,"holonomicRotation":-138.57716399398672,"angularVelocity":1.6487361968914767,"angularAcceleration":-2.5679196533112765,"curveRadius":1.1249014124426524},{"acceleration":2.9812796063370643,"curvature":0.8767097129765424,"pose":{"rotation":{"radians":-2.7346264568187557},"translation":{"x":2.059526079110145,"y":2.11582247442997}},"time":3.7637544319083864,"velocity":1.8433016109458253,"position":6.613938819318934,"holonomicRotation":-138.56728068495048,"angularVelocity":1.6376008099437698,"angularAcceleration":-2.6661784927383776,"curveRadius":1.1406284032201162},{"acceleration":3.008145912934995,"curvature":0.8643059153672465,"pose":{"rotation":{"radians":-2.727872469175538},"translation":{"x":2.0524675321357204,"y":2.1127233393981024}},"time":3.7679084079736747,"velocity":1.855797377069052,"position":6.621647757205303,"holonomicRotation":-138.55739737591423,"angularVelocity":1.6259091379114718,"angularAcceleration":-2.8145737598241802,"curveRadius":1.1569977507039235},{"acceleration":3.0079141510794707,"curvature":0.8517683204465378,"pose":{"rotation":{"radians":-2.721204865713735},"translation":{"x":2.0454198547091424,"y":2.1095727615376565}},"time":3.7720405822712277,"velocity":1.8682266026133887,"position":6.629367595154627,"holonomicRotation":-138.547514066878,"angularVelocity":1.6135823374515579,"angularAcceleration":-2.9831269380900594,"curveRadius":1.1740281670440056},{"acceleration":3.0076889831719273,"curvature":0.8391096157846688,"pose":{"rotation":{"radians":-2.71462445835204},"translation":{"x":2.0383826275187342,"y":2.106371128487774}},"time":3.77615168311199,"velocity":1.8805915153208586,"position":6.637098896514393,"holonomicRotation":-138.53763075784175,"angularVelocity":1.6006436272370224,"angularAcceleration":-3.147261698435036,"curveRadius":1.1917394118584606},{"acceleration":3.0074702353662097,"curvature":0.8263422349919016,"pose":{"rotation":{"radians":-2.708131996730415},"translation":{"x":2.0313554312528175,"y":2.1031188278875956}},"time":3.78024241148364,"velocity":1.8928942591395634,"position":6.644842212764789,"holonomicRotation":-138.5277474488055,"angularVelocity":1.5871162863367165,"angularAcceleration":-3.3068294130832716,"curveRadius":1.2101523529289293},{"acceleration":3.0072577392338604,"curvature":0.8134783390130665,"pose":{"rotation":{"radians":-2.70172816934016},"translation":{"x":2.0243378465997153,"y":2.099816247376264}},"time":3.7843134422023716,"velocity":1.9051368977751282,"position":6.65259808359902,"holonomicRotation":-138.51786413976927,"angularVelocity":1.5730235983702365,"angularAcceleration":-3.461700227816119,"curveRadius":1.2292890321003833},{"acceleration":3.0070513316732357,"curvature":0.8005297994831937,"pose":{"rotation":{"radians":-2.6954136047283286},"translation":{"x":2.0173294542477507,"y":2.0964637745929195}},"time":3.7883654250045837,"velocity":1.917321418056437,"position":6.660367037011298,"holonomicRotation":-138.50798083073303,"angularVelocity":1.5583887987836307,"angularAcceleration":-3.611762512569483,"curveRadius":1.2491727361624518},{"acceleration":3.006850854459512,"curvature":0.7875081839446331,"pose":{"rotation":{"radians":-2.689188872771585},"translation":{"x":2.0103298348852467,"y":2.093061797176704}},"time":3.7923989855826137,"velocity":1.9294497331270006,"position":6.668149589392129,"holonomicRotation":-138.4980975216968,"angularVelocity":1.5432350243228328,"angularAcceleration":-3.7569224925832745,"curveRadius":1.2698280733934653},{"acceleration":3.006656153455493,"curvature":0.7744247428375491,"pose":{"rotation":{"radians":-2.6830544860096883},"translation":{"x":2.003338569200526,"y":2.0896107027667585}},"time":3.796414726568314,"velocity":1.9415236854723397,"position":6.6759462456305885,"holonomicRotation":-138.48821421266052,"angularVelocity":1.5275852660170828,"angularAcceleration":-3.897103513766865,"curveRadius":1.2912810563566532},{"acceleration":3.0064670793533357,"curvature":0.7612903981871875,"pose":{"rotation":{"radians":-2.677010901033679},"translation":{"x":1.996355237881911,"y":2.086110879002225}},"time":3.800413228467938,"velocity":1.9535450498002918,"position":6.6837574992232165,"holonomicRotation":-138.47833090362428,"angularVelocity":1.5114623245714502,"angularAcceleration":-4.032245538547235,"curveRadius":1.313559191579503},{"acceleration":3.006283486231419,"curvature":0.7481157341147134,"pose":{"rotation":{"radians":-2.6710585199213295},"translation":{"x":1.9893794216177252,"y":2.0825627135222446}},"time":3.804395050551526,"velocity":1.9655155357752936,"position":6.691583832389202,"holonomicRotation":-138.46844759458804,"angularVelocity":1.4948887688587855,"angularAcceleration":-4.162304433685511,"curveRadius":1.33669157644887},{"acceleration":3.006105231907428,"curvature":0.7349109889425495,"pose":{"rotation":{"radians":-2.6651976917134865},"translation":{"x":1.9824107010962904,"y":2.0789665939659585}},"time":3.808360731699717,"velocity":1.9774367906229464,"position":6.699425716191514,"holonomicRotation":-138.4585642855518,"angularVelocity":1.477886897315695,"angularAcceleration":-4.287251271032568,"curveRadius":1.3607090042821137},{"acceleration":3.005932177883389,"curvature":0.7216860488206237,"pose":{"rotation":{"radians":-2.6594287139246324},"translation":{"x":1.9754486570059306,"y":2.0753229079725086}},"time":3.812310791210668,"velocity":1.9893104016114695,"position":6.707283610663634,"holonomicRotation":-138.44868097651556,"angularVelocity":1.4604787023739307,"angularAcceleration":-4.40707156271964,"curveRadius":1.3856440783831083},{"acceleration":3.0057641889477114,"curvature":0.7084504428764308,"pose":{"rotation":{"radians":-2.653751834082038},"translation":{"x":1.9684928700349678,"y":2.0716320431810358}},"time":3.8162457295695695,"velocity":2.001137898416372,"position":6.715157964941564,"holonomicRotation":-138.43879766747932,"angularVelocity":1.4426858376962166,"angularAcceleration":-4.521764524586341,"curveRadius":1.4115313358261559},{"acceleration":3.005601132666811,"curvature":0.6952133397532523,"pose":{"rotation":{"radians":-2.6481672512874885},"translation":{"x":1.961542920871725,"y":2.0678943872306816}},"time":3.82016602918302,"velocity":2.0129207553749517,"position":6.723049217400766,"holonomicRotation":-138.42891435844308,"angularVelocity":1.4245295883479931,"angularAcceleration":-4.6313422795364865,"curveRadius":1.4384073820489747},{"acceleration":3.005442879932071,"curvature":0.6819835458203077,"pose":{"rotation":{"radians":-2.6426751177960632},"translation":{"x":1.954598390204525,"y":2.064110327760588}},"time":3.8240721550803802,"velocity":2.0246603936412915,"position":6.730957795797728,"holonomicRotation":-138.41903104940684,"angularVelocity":1.4060308437925229,"angularAcceleration":-4.735829064795776,"curveRadius":1.4663110365766578},{"acceleration":3.0052893042474738,"curvature":0.6687695038994174,"pose":{"rotation":{"radians":-2.637275540606523},"translation":{"x":1.947658858721691,"y":2.0602802524098958}},"time":3.8279645555840367,"velocity":2.0363581832427777,"position":6.738884117415807,"holonomicRotation":-138.4091477403706,"angularVelocity":1.38721007369823,"angularAcceleration":-4.83526042004487,"curveRadius":1.4952834932951722},{"acceleration":3.0051402820269417,"curvature":0.6555792938861128,"pose":{"rotation":{"radians":-2.6319685830589328},"translation":{"x":1.9407239071115456,"y":2.0564045488177465}},"time":3.831843662950376,"velocity":2.0480154450476715,"position":6.746828589215069,"holonomicRotation":-138.39926443133436,"angularVelocity":1.3680873062810435,"angularAcceleration":-4.929682427231303,"curveRadius":1.5253684936756406},{"acceleration":3.0049956922056613,"curvature":0.6424206343646988,"pose":{"rotation":{"radians":-2.626754266434057},"translation":{"x":1.9337931160624109,"y":2.0524836046232817}},"time":3.8357098939831316,"velocity":2.0596334526461737,"position":6.754791607985791,"holonomicRotation":-138.38938112229812,"angularVelocity":1.348682109449467,"angularAcceleration":-5.0191508648013015,"curveRadius":1.5566125160175122},{"acceleration":3.004855416380521,"curvature":0.6293008848730379,"pose":{"rotation":{"radians":-2.621632571550209},"translation":{"x":1.9268660662626105,"y":2.0485178074656423}},"time":3.8395636506206388,"velocity":2.0712134341517996,"position":6.762773560505347,"holonomicRotation":-138.37949781326188,"angularVelocity":1.3290135744433351,"angularAcceleration":-5.103730426230142,"curveRadius":1.5890649831229},{"acceleration":3.0047193382088215,"curvature":0.6162270493610869,"pose":{"rotation":{"radians":-2.6166034403547704},"translation":{"x":1.919942338400467,"y":2.0445075449839702}},"time":3.8434053204984355,"velocity":2.08275657392463,"position":6.770774823698177,"holonomicRotation":-138.3696145042256,"angularVelocity":1.3091003015393685,"angularAcceleration":-5.183494037074062,"curveRadius":1.6227784889300372},{"acceleration":3.0045873443914366,"curvature":0.6032057805207885,"pose":{"rotation":{"radians":-2.6116667775040563},"translation":{"x":1.9130215131643031,"y":2.040453204817407}},"time":3.847235277488524,"velocity":2.0942640142266136,"position":6.778795764798555,"holonomicRotation":-138.35973119518937,"angularVelocity":1.2889603887170433,"angularAcceleration":-5.258521929735649,"curveRadius":1.6578090467512299},{"acceleration":3.004459323270189,"curvature":0.5902433848140888,"pose":{"rotation":{"radians":-2.6068224519305314},"translation":{"x":1.906103171242442,"y":2.0363551746050934}},"time":3.8510538822165366,"velocity":2.105736856803574,"position":6.786836741515895,"holonomicRotation":-138.34984788615313,"angularVelocity":1.2686114218599236,"angularAcceleration":-5.3289010794556075,"curveRadius":1.6942163618063655},{"acceleration":3.004335166115172,"curvature":0.5773458284241159,"pose":{"rotation":{"radians":-2.602070298392775},"translation":{"x":1.8991868933232061,"y":2.0322138419861715}},"time":3.8548614825579475,"velocity":2.117176164407787,"position":6.794898102202321,"holonomicRotation":-138.3399645771169,"angularVelocity":1.2480704673946081,"angularAcceleration":-5.394724399489869,"curveRadius":1.7320641299678778},{"acceleration":3.0042147658355645,"curvature":0.5645187432738009,"pose":{"rotation":{"radians":-2.597410119004926},"translation":{"x":1.8922722600949184,"y":2.028029594599782}},"time":3.858658414114405,"velocity":2.1285829622545642,"position":6.802980186022244,"holonomicRotation":-138.33008126808065,"angularVelocity":1.227354066976285,"angularAcceleration":-5.456090032249737,"curveRadius":1.771420368083303},{"acceleration":2.700768393754044,"curvature":0.5517674347018671,"pose":{"rotation":{"radians":-2.592841684744579},"translation":{"x":1.8853588522459017,"y":2.0238028200850673}},"time":3.8624470244625444,"velocity":2.1388151213390683,"position":6.811083323123706,"holonomicRotation":-138.3201979590444,"angularVelocity":1.2058337597558524,"angularAcceleration":-5.680264065952863,"curveRadius":1.8123577745038968},{"acceleration":-0.3063266949084546,"curvature":0.5390968879027673,"pose":{"rotation":{"radians":-2.5883647369340306},"translation":{"x":1.8784462504644783,"y":2.019533906081168}},"time":3.8662476973353748,"velocity":2.137650873779506,"position":6.8192078348112615,"holonomicRotation":-138.31031465000817,"angularVelocity":1.1779355814999792,"angularAcceleration":-7.340326092073618,"curveRadius":1.85495413243855},{"acceleration":-2.9879948833898298,"curvature":0.5265117767761313,"pose":{"rotation":{"radians":-2.5839789886958084},"translation":{"x":1.8715340354389722,"y":2.015223240227226}},"time":3.8700790339702693,"velocity":2.126202859517897,"position":6.82735403372015,"holonomicRotation":-138.30043134097193,"angularVelocity":1.1447044872742818,"angularAcceleration":-8.673498935864753,"curveRadius":1.8992927492013008},{"acceleration":-2.987841483276364,"curvature":0.5140164716554693,"pose":{"rotation":{"radians":-2.5796841263777583},"translation":{"x":1.864621787857705,"y":2.0108712101623816}},"time":3.873941679969218,"velocity":2.1146618855670263,"position":6.835522223991565,"holonomicRotation":-138.29054803193569,"angularVelocity":1.1118964355571053,"angularAcceleration":-8.493672919057285,"curveRadius":1.9454629474797684},{"acceleration":-2.9876870698136,"curvature":0.5016150481506918,"pose":{"rotation":{"radians":-2.5754798109478365},"translation":{"x":1.857709088409,"y":2.006478203525778}},"time":3.8778362953866057,"velocity":2.1030259934426008,"position":6.843712701448793,"holonomicRotation":-138.28066472289944,"angularVelocity":1.0795200499519453,"angularAcceleration":-8.313114938285102,"curveRadius":1.9935606072559184},{"acceleration":-2.9875314936288797,"curvature":0.48931129576629495,"pose":{"rotation":{"radians":-2.571365679355541},"translation":{"x":1.85079551778118,"y":2.002044607956555}},"time":3.881763555516039,"velocity":2.0912931801222463,"position":6.851925753774043,"holonomicRotation":-138.2707814138632,"angularVelocity":1.0475831640135163,"angularAcceleration":-8.132103524051248,"curveRadius":2.0436887696081727},{"acceleration":-2.9873745994741965,"curvature":0.47710872706360835,"pose":{"rotation":{"radians":-2.567341345861042},"translation":{"x":1.8438806566625676,"y":1.997570811093855}},"time":3.8857241517209293,"velocity":2.0794613956209824,"position":6.860161660685756,"holonomicRotation":-138.26089810482696,"angularVelocity":1.0160928522654489,"angularAcceleration":-7.95090186401311,"curveRadius":2.09595830735387},{"acceleration":-2.9872162268987843,"curvature":0.4650105868745343,"pose":{"rotation":{"radians":-2.5634064033276527},"translation":{"x":1.836964085741486,"y":1.993057200576819}},"time":3.8897187923118532,"velocity":2.067528540427146,"position":6.86842069411624,"holonomicRotation":-138.2510147957907,"angularVelocity":0.9850554621433693,"angularAcceleration":-7.769757858215983,"curveRadius":2.1504886732176973},{"acceleration":-2.9870562087925316,"curvature":0.4530198616018155,"pose":{"rotation":{"radians":-2.559560424479937},"translation":{"x":1.8300453857062577,"y":1.9885041640445884}},"time":3.893748203473949,"velocity":2.0554924627976305,"position":6.87670311838944,"holonomicRotation":-138.24113148675445,"angularVelocity":0.9544766450976235,"angularAcceleration":-7.588904635346981,"curveRadius":2.2074087358204086},{"acceleration":-2.986894372106507,"curvature":0.441139288431148,"pose":{"rotation":{"radians":-2.555802963124564},"translation":{"x":1.8231241372452058,"y":1.9839120891363051}},"time":3.897813130247931,"velocity":2.0433509558933984,"position":6.8850091903986925,"holonomicRotation":-138.23124817771821,"angularVelocity":0.9243613881122718,"angularAcceleration":-7.408560758857257,"curveRadius":2.2668577164286687},{"acceleration":-2.9867305366723054,"curvature":0.4293713650396096,"pose":{"rotation":{"radians":-2.5521335553340783},"translation":{"x":1.8161999210466528,"y":1.9792813634911095}},"time":3.9019143375686047,"velocity":2.0311017547515178,"position":6.893339159784313,"holonomicRotation":-138.22136486868197,"angularVelocity":0.8947140448103031,"angularAcceleration":-7.228930649889027,"curveRadius":2.3289862376075074},{"acceleration":-2.9865645154155915,"curvature":0.4177183586615587,"pose":{"rotation":{"radians":-2.5485517205938857},"translation":{"x":1.8092723177989218,"y":1.974612374748144}},"time":3.9060526113651246,"velocity":2.0187425330757574,"position":6.901693269110861,"holonomicRotation":-138.21148155964573,"angularVelocity":0.8655383660705971,"angularAcceleration":-7.050205030957992,"curveRadius":2.393957505732263},{"acceleration":-2.986396113299045,"curvature":0.406182315746864,"pose":{"rotation":{"radians":-2.5450569629102615},"translation":{"x":1.8023409081903354,"y":1.9699055105465495}},"time":3.9102287597276333,"velocity":2.0062708998374013,"position":6.910071754043965,"holonomicRotation":-138.2015982506095,"angularVelocity":0.8368375307252768,"angularAcceleration":-6.872561234409606,"curveRadius":2.4619486403814976},{"acceleration":-2.9862251274157496,"curvature":0.39476507104985814,"pose":{"rotation":{"radians":-2.541648771881834},"translation":{"x":1.7954052729092163,"y":1.9651611585254676}},"time":3.9144436141453474,"velocity":1.9936843956668242,"position":6.918474843526569,"holonomicRotation":-138.19171494157325,"angularVelocity":0.8086141751667023,"angularAcceleration":-6.69616379630056,"curveRadius":2.5331521791949565},{"acceleration":-2.986051345584622,"curvature":0.38346825708997234,"pose":{"rotation":{"radians":-2.5383266237319497},"translation":{"x":1.7884649926438876,"y":1.9603797063240396}},"time":3.918698030821634,"velocity":1.9809804890259204,"position":6.92690275995448,"holonomicRotation":-138.181831632537,"angularVelocity":0.7808704230596716,"angularAcceleration":-6.521164760769318,"curveRadius":2.607777779544793},{"acceleration":-2.9858745468499484,"curvature":0.3722933128732914,"pose":{"rotation":{"radians":-2.535089982304222},"translation":{"x":1.7815196480826718,"y":1.955561541581407}},"time":3.922992892072161,"velocity":1.9681565721357206,"position":6.935355719351115,"holonomicRotation":-138.17194832350077,"angularVelocity":0.7536079139531446,"angularAcceleration":-6.347704271746531,"curveRadius":2.68605415520946},{"acceleration":-2.985694499841891,"curvature":0.36124149315070647,"pose":{"rotation":{"radians":-2.531938300019713},"translation":{"x":1.7745688199138923,"y":1.9507070519367111}},"time":3.9273291078127706,"velocity":1.9552099566488543,"position":6.943833931541333,"holonomicRotation":-138.16206501446453,"angularVelocity":0.7268278316950345,"angularAcceleration":-6.175910946336948,"curveRadius":2.768231277304597},{"acceleration":-2.9855109623383136,"curvature":0.35031387740550296,"pose":{"rotation":{"radians":-2.528871018797381},"translation":{"x":1.767612088825871,"y":1.9458166250290931}},"time":3.931707617144413,"velocity":1.9421378690405346,"position":6.952337600324263,"holonomicRotation":-138.1521817054283,"angularVelocity":0.7005309318779234,"angularAcceleration":-6.005902425985158,"curveRadius":2.854582888369159},{"acceleration":-2.9853236807414074,"curvature":0.33951137781851315,"pose":{"rotation":{"radians":-2.5258875709372655},"translation":{"x":1.7606490355069313,"y":1.9408906484976947}},"time":3.936129390043171,"velocity":1.9289374456950128,"position":6.960866923645036,"holonomicRotation":-138.14229839639205,"angularVelocity":0.6747175688181182,"angularAcceleration":-5.837785804661666,"curveRadius":2.94540938929756},{"acceleration":-2.98513238875493,"curvature":0.32883474834117304,"pose":{"rotation":{"radians":-2.5229873799673905},"translation":{"x":1.753679240645396,"y":1.9359295099816578}},"time":3.940595429164239,"velocity":1.915605727665266,"position":6.969422093765331,"holonomicRotation":-138.13241508735578,"angularVelocity":0.6493877217048128,"angularAcceleration":-5.671658135239951,"curveRadius":3.0410411461822724},{"acceleration":-2.984936806534484,"curvature":0.31828459274164983,"pose":{"rotation":{"radians":-2.5201698614544434},"translation":{"x":1.746702284929588,"y":1.9309335971201227}},"time":3.9451067717696278,"velocity":1.9021396550755536,"position":6.978003297432673,"holonomicRotation":-138.12253177831954,"angularVelocity":0.6245410201347856,"angularAcceleration":-5.507606879678654,"curveRadius":3.141842309695762},{"acceleration":-2.9847366396683017,"curvature":0.30786137259463114,"pose":{"rotation":{"radians":-2.517434423779898},"translation":{"x":1.7397177490478295,"y":1.9259032975522314}},"time":3.949664491790364,"velocity":1.888536061136313,"position":6.986610716048396,"holonomicRotation":-138.1126484692833,"angularVelocity":0.600176768669449,"angularAcceleration":-5.345710432954986,"curveRadius":3.2482152326291525},{"acceleration":-2.98453157786839,"curvature":0.29756541522628316,"pose":{"rotation":{"radians":-2.5147804688802644},"translation":{"x":1.7327252136884441,"y":1.9208389989171257}},"time":3.954269702035111,"velocity":1.874791665738142,"position":6.99524452583422,"holonomicRotation":-138.10276516024706,"angularVelocity":0.5762939710865094,"angularAcceleration":-5.186038489812968,"curveRadius":3.3606055973929347},{"acceleration":-2.984321293799038,"curvature":0.28739692103850795,"pose":{"rotation":{"radians":-2.5122073929542923},"translation":{"x":1.7257242595397542,"y":1.9157410888539463}},"time":3.9589235565584064,"velocity":1.8609030685860284,"position":7.003904897997374,"holonomicRotation":-138.09288185121082,"angularVelocity":0.552891353413014,"angularAcceleration":-5.028652605351227,"curveRadius":3.479508396911501},{"acceleration":-2.984105441363875,"curvature":0.27735597118618754,"pose":{"rotation":{"radians":-2.5097145871365703},"translation":{"x":1.7187144672900825,"y":1.910609955001835}},"time":3.963627253203142,"velocity":1.8468667418339486,"position":7.012591998894211,"holonomicRotation":-138.08299854217458,"angularVelocity":0.5299673865048532,"angularAcceleration":-4.873606577885628,"curveRadius":3.6054749271242676},{"acceleration":-2.9838836543022085,"curvature":0.2674425346097501,"pose":{"rotation":{"radians":-2.5073014381384477},"translation":{"x":1.7116954176277521,"y":1.9054459849999332}},"time":3.968382036333547,"velocity":1.832679022171381,"position":7.021305990192279,"holonomicRotation":-138.07311523313834,"angularVelocity":0.507520307854062,"angularAcceleration":-4.720946893928825,"curveRadius":3.739121009525249},{"acceleration":-2.9836555444353934,"curvature":0.25765647512829337,"pose":{"rotation":{"radians":-2.5049673288574263},"translation":{"x":1.7046666912410855,"y":1.900249566487382}},"time":3.973189199776759,"velocity":1.8183361023110334,"position":7.030047029030782,"holonomicRotation":-138.0632319241021,"angularVelocity":0.48554814259896967,"angularAcceleration":-4.5707131689306175,"curveRadius":3.8811366937395064},{"acceleration":-2.9834206995018047,"curvature":0.2479975573143356,"pose":{"rotation":{"radians":-2.5027116389557547},"translation":{"x":1.6976278688184057,"y":1.8950210871033235}},"time":3.97805008999313,"velocity":1.8038340218215072,"position":7.038815268179411,"holonomicRotation":-138.05334861506586,"angularVelocity":0.46404872384792434,"angularAcceleration":-4.422938555295634,"curveRadius":4.032297780790257},{"acceleration":-2.9831786809850285,"curvature":0.2384654540748462,"pose":{"rotation":{"radians":-2.500533745408359},"translation":{"x":1.6905785310480357,"y":1.889760934486898}},"time":3.9829661094977764,"velocity":1.7891686572399392,"position":7.047610856195504,"holonomicRotation":-138.04346530602962,"angularVelocity":0.443019712459896,"angularAcceleration":-4.277650112688178,"curveRadius":4.193479528846698},{"acceleration":-2.9829290219312687,"curvature":0.22905975204330764,"pose":{"rotation":{"radians":-2.4984330230227823},"translation":{"x":1.6835182586182977,"y":1.884469496277248}},"time":3.987938720558553,"velocity":1.7743357113919722,"position":7.056433937579503,"holonomicRotation":-138.03358199699338,"angularVelocity":0.422458615785766,"angularAcceleration":-4.134869271460536,"curveRadius":4.3656731096562655},{"acceleration":-2.982671224180919,"curvature":0.2197799574957818,"pose":{"rotation":{"radians":-2.4964088449289665},"translation":{"x":1.676446632217515,"y":1.8791471601135141}},"time":3.992969449198661,"velocity":1.7593307018404596,"position":7.065284652928673,"holonomicRotation":-138.0236986879571,"angularVelocity":0.40236280638907757,"angularAcceleration":-3.9946120799426432,"curveRadius":4.550005429950057},{"acceleration":-2.982404754901032,"curvature":0.21062550266827182,"pose":{"rotation":{"radians":-2.494460583043444},"translation":{"x":1.6693632325340106,"y":1.8737943136348385}},"time":3.998059889535582,"velocity":1.7441489483750858,"position":7.07416313908908,"holonomicRotation":-138.01381537892087,"angularVelocity":0.3827295394058217,"angularAcceleration":-3.8568897155821475,"curveRadius":4.747763149911465},{"acceleration":-2.9821290441680626,"curvature":0.2015957507687806,"pose":{"rotation":{"radians":-2.4925876085054357},"translation":{"x":1.6622676402561067,"y":1.8684113444803616}},"time":4.003211708492018,"velocity":1.728785559434802,"position":7.0830695293057895,"holonomicRotation":-138.00393206988463,"angularVelocity":0.3635559700071123,"angularAcceleration":-3.7217086937335035,"curveRadius":4.960422013790091},{"acceleration":-2.9818434800864115,"curvature":0.19269000110055665,"pose":{"rotation":{"radians":-2.4907892920882038},"translation":{"x":1.6551594360721267,"y":1.8629986402892258}},"time":4.00842665091905,"velocity":1.7132354173597306,"position":7.092003953371273,"holonomicRotation":-137.9940487608484,"angularVelocity":0.3448391698267344,"angularAcceleration":-3.5890712970018734,"curveRadius":5.189682880733095},{"acceleration":-2.981547405707496,"curvature":0.18390749426047606,"pose":{"rotation":{"radians":-2.4890650045847624},"translation":{"x":1.648038200670393,"y":1.857556588700572}},"time":4.013706545177022,"velocity":1.6974931623324658,"position":7.100966537772018,"holonomicRotation":-137.98416545181215,"angularVelocity":0.32657614323204265,"angularAcceleration":-3.4589758245856124,"curveRadius":5.437516312324158},{"acceleration":-2.981240113690778,"curvature":0.17524741714866157,"pose":{"rotation":{"radians":-2.4874141171701947},"translation":{"x":1.6409035147392288,"y":1.8520855773535416}},"time":4.019053309225671,"velocity":1.6815531748721921,"position":7.109957405833317,"holonomicRotation":-137.9742821427759,"angularVelocity":0.3087638428676751,"angularAcceleration":-3.331416947203142,"curveRadius":5.706218192943207},{"acceleration":-2.9809208407366503,"curvature":0.16670890721242085,"pose":{"rotation":{"radians":-2.4858360017405556},"translation":{"x":1.6337549589669562,"y":1.8465859938872762}},"time":4.024468957282066,"velocity":1.6654095567147909,"position":7.11897667786224,"holonomicRotation":-137.96439883373966,"angularVelocity":0.2913991849554712,"angularAcceleration":-3.2063859636707206,"curveRadius":5.998479725656157},{"acceleration":-2.9805887626944094,"curvature":0.15829105703223534,"pose":{"rotation":{"radians":-2.4843300312292853},"translation":{"x":1.6265921140418986,"y":1.8410582259409172}},"time":4.029955607113023,"velocity":1.6490561098838001,"position":7.128024471288773,"holonomicRotation":-137.95451552470342,"angularVelocity":0.2744790642138628,"angularAcceleration":-3.083871080333911,"curveRadius":6.317476291767727},{"acceleration":-2.9802429867096305,"curvature":0.149992918292813,"pose":{"rotation":{"radians":-2.4828955799026273},"translation":{"x":1.6194145606523787,"y":1.8355026611536058}},"time":4.035515488038157,"velocity":1.63248631374973,"position":7.137100900805132,"holonomicRotation":-137.94463221566718,"angularVelocity":0.25800036834844864,"angularAcceleration":-2.9638576953908786,"curveRadius":6.666981424068442},{"acceleration":-2.979882544299663,"curvature":0.14181350588262742,"pose":{"rotation":{"radians":-2.4815320236339744},"translation":{"x":1.6122218794867198,"y":1.8299196871644834}},"time":4.041150949730732,"velocity":1.6156932998229547,"position":7.146206078503235,"holonomicRotation":-137.93474890663094,"angularVelocity":0.24195999246154729,"angularAcceleration":-2.8463286172335707,"curveRadius":7.051514549168924},{"acceleration":-2.9795063822297543,"curvature":0.1337518015348258,"pose":{"rotation":{"radians":-2.4802387401589456},"translation":{"x":1.6050136512332434,"y":1.8243096916126917}},"time":4.046864471916467,"velocity":1.5986698240055468,"position":7.155340114010356,"holonomicRotation":-137.9248655975947,"angularVelocity":0.2263548530988092,"angularAcceleration":-2.7312643331814304,"curveRadius":7.476534809436743},{"acceleration":-2.979113353189327,"curvature":0.12580675759990992,"pose":{"rotation":{"radians":-2.479015109310362},"translation":{"x":1.5977894565802735,"y":1.8186730621373721}},"time":4.0526586750856035,"velocity":1.5814082359732804,"position":7.1645031146229305,"holonomicRotation":-137.91498228855846,"angularVelocity":0.2111819024747673,"angularAcceleration":-2.61864318201033,"curveRadius":7.9486986158581034},{"acceleration":-2.978702204051514,"curvature":0.11797729969313889,"pose":{"rotation":{"radians":-2.477860513236526},"translation":{"x":1.5905488762161324,"y":1.8130101863776653}},"time":4.05853633235153,"velocity":1.5639004453206045,"position":7.1736951854385556,"holonomicRotation":-137.9050989795222,"angularVelocity":0.19643814220495948,"angularAcceleration":-2.508441646517593,"curveRadius":8.476206885570514},{"acceleration":-2.978271563132856,"curvature":0.11026233115027022,"pose":{"rotation":{"radians":-2.476774336600851},"translation":{"x":1.5832914908291431,"y":1.8073214519727137}},"time":4.064500382610452,"velocity":1.546137884033362,"position":7.182916429486154,"holonomicRotation":-137.89521567048595,"angularVelocity":0.18212063757343708,"angularAcceleration":-2.4006344698561106,"curveRadius":9.06928041125085},{"acceleration":-2.9778199254956976,"curvature":0.10266073504876454,"pose":{"rotation":{"radians":-2.475755966765028},"translation":{"x":1.576016881107628,"y":1.8016072465616582}},"time":4.070553945181863,"velocity":1.528111464787981,"position":7.1921669478543375,"holonomicRotation":-137.8853323614497,"angularVelocity":0.16822653170094662,"angularAcceleration":-2.2951948887270266,"curveRadius":9.740822521142025},{"acceleration":-2.9773456357463615,"curvature":0.09517137740729813,"pose":{"rotation":{"radians":-2.4748047939564737},"translation":{"x":1.5687246277399107,"y":1.79586795778364}},"time":4.0767003361396785,"velocity":1.5098115344941376,"position":7.201446839817958,"holonomicRotation":-137.87544905241347,"angularVelocity":0.15475305997982144,"angularAcceleration":-2.1920948103687583,"curveRadius":10.507360797357924},{"acceleration":-2.9768468681877396,"curvature":0.08779310988091892,"pose":{"rotation":{"radians":-2.473920211420502},"translation":{"x":1.5614143114143135,"y":1.790103973277801}},"time":4.082943086580016,"velocity":1.4912278223969406,"position":7.2107562029628705,"holonomicRotation":-137.86556574337723,"angularVelocity":0.1416975649476246,"angularAcceleration":-2.09130497157765,"curveRadius":11.390415504774612},{"acceleration":-2.9763216040750113,"curvature":0.08052477235944391,"pose":{"rotation":{"radians":-2.47310161555746},"translation":{"x":1.5540855128191589,"y":1.7843156806832825}},"time":4.0892859631150476,"velocity":1.4723493819337465,"position":7.220095133308906,"holonomicRotation":-137.855682434341,"angularVelocity":0.12905751176476077,"angularAcceleration":-1.9927950848567884,"curveRadius":12.418538676970508},{"acceleration":-2.9757676045841737,"curvature":0.0733651947816595,"pose":{"rotation":{"radians":-2.472348406046309},"translation":{"x":1.5467378126427702,"y":1.7785034676392257}},"time":4.095732990934959,"velocity":1.4531645254014014,"position":7.229463725431077,"holonomicRotation":-137.84579912530475,"angularVelocity":0.11683050425575095,"angularAcceleration":-1.8965340076937867,"curveRadius":13.63044155987151},{"acceleration":-2.97518237983543,"curvature":0.0663132004609624,"pose":{"rotation":{"radians":-2.4716599859551383},"translation":{"x":1.5393707915734702,"y":1.7726677217847722}},"time":4.102288479843981,"velocity":1.4336607503080718,"position":7.238862072579022,"holonomicRotation":-137.8359158162685,"angularVelocity":0.10501430186588734,"angularAcceleration":-1.8024898758658727,"curveRadius":15.079953810835676},{"acceleration":-2.974563151800501,"curvature":0.059367607667790596,"pose":{"rotation":{"radians":-2.4710357618385608},"translation":{"x":1.5319840302995813,"y":1.766808830759063}},"time":4.108957053754574,"velocity":1.4138246560785632,"position":7.248290266794701,"holonomicRotation":-137.82603250723227,"angularVelocity":0.09360683782568317,"angularAcceleration":-1.7106302176666548,"curveRadius":16.844202407410492},{"acceleration":-2.9739068109110134,"curvature":0.05252723057517122,"pose":{"rotation":{"radians":-2.4704751438234265},"translation":{"x":1.5245771095094267,"y":1.76092718220124}},"time":4.1157436842198925,"velocity":1.3936418495146174,"position":7.257748399028359,"holonomicRotation":-137.81614919819603,"angularVelocity":0.08260623854492063,"angularAcceleration":-1.6209220963155637,"curveRadius":19.03774459551812},{"acceleration":-2.973209864603237,"curvature":0.04579088326848073,"pose":{"rotation":{"radians":-2.469977545683089},"translation":{"x":1.5171496098913293,"y":1.7550231637504443}},"time":4.122653728703363,"velocity":1.3730968370915153,"position":7.267236559252774,"holonomicRotation":-137.8062658891598,"angularVelocity":0.07201084472433482,"angularAcceleration":-1.5333322160126164,"curveRadius":21.838408185682034},{"acceleration":-2.9724683758769297,"curvature":0.039157379244428546,"pose":{"rotation":{"radians":-2.4695423849008797},"translation":{"x":1.5097011121336115,"y":1.7490971630458176}},"time":4.129692974431878,"velocity":1.3521729017734787,"position":7.276754836575797,"holonomicRotation":-137.79638258012355,"angularVelocity":0.061819234473735246,"angularAcceleration":-1.4478270319951,"curveRadius":25.537970602112846},{"acceleration":-2.971677889435868,"curvature":0.03262553466111265,"pose":{"rotation":{"radians":-2.4691690827230244},"translation":{"x":1.5022311969245963,"y":1.7431495677265012}},"time":4.136867688863985,"velocity":1.3308519615325691,"position":7.286303319351203,"holonomicRotation":-137.78649927108728,"angularVelocity":0.05203024892319231,"angularAcceleration":-1.3643728462190294,"curveRadius":30.65083868776961},{"acceleration":-2.9708333431459972,"curvature":0.02619416955416304,"pose":{"rotation":{"radians":-2.4688570642022922},"translation":{"x":1.4947394449526064,"y":1.737180765431636}},"time":4.1441846780376315,"velocity":1.309114406124062,"position":7.295882095287877,"holonomicRotation":-137.77661596205104,"angularVelocity":0.04264302069161795,"angularAcceleration":-1.282935919241798,"curveRadius":38.176434566182685},{"acceleration":-2.9699289602947343,"curvature":0.019862107532452766,"pose":{"rotation":{"radians":-2.468605758232144},"translation":{"x":1.4872254369059652,"y":1.7311911438003644}},"time":4.15165135435816,"velocity":1.2869389078825777,"position":7.3054912515573305,"holonomicRotation":-137.7667326530148,"angularVelocity":0.03365700605735434,"angularAcceleration":-1.20348254678698,"curveRadius":50.347124461293774},{"acceleration":-2.9689581179125177,"curvature":0.013628178465111164,"pose":{"rotation":{"radians":-2.4684145975721044},"translation":{"x":1.4796887534729946,"y":1.725181090471827}},"time":4.159275815766541,"velocity":1.2643022012894551,"position":7.315130874899593,"holonomicRotation":-137.75684934397856,"angularVelocity":0.025072021458384688,"angularAcceleration":-1.1259791530367207,"curveRadius":73.37737780291411},{"acceleration":-2.9679131858816303,"curvature":0.007491224876582606,"pose":{"rotation":{"radians":-2.4682830188651548},"translation":{"x":1.4721289753420177,"y":1.7191509930851656}},"time":4.167066938717589,"velocity":1.2411788247502131,"position":7.3248010517274595,"holonomicRotation":-137.74696603494232,"angularVelocity":0.01688828526725627,"angularAcceleration":-1.0503923815022098,"curveRadius":133.4895182663621},{"acceleration":-2.966785326243994,"curvature":0.0014500852411324077,"pose":{"rotation":{"radians":-2.468210462647139},"translation":{"x":1.464545683201358,"y":1.7131012392795213}},"time":4.17503448803623,"velocity":1.2175408163455435,"position":7.334501868229151,"holonomicRotation":-137.73708272590608,"angularVelocity":0.009106466130832188,"angularAcceleration":-0.9766891706860908,"curveRadius":689.6146320467858},{"acceleration":-2.9655642441899723,"curvature":-0.00449637671964737,"pose":{"rotation":{"radians":-2.4681963733492607},"translation":{"x":1.4569384577393376,"y":1.707032216694036}},"time":4.183189247559925,"velocity":1.1933573530821064,"position":7.344233410469369,"holonomicRotation":-137.72719941686984,"angularVelocity":0.0017277392223796443,"angularAcceleration":-0.904836848592849,"curveRadius":-222.40129383074142},{"acceleration":-2.964237873888748,"curvature":-0.010349296496957787,"pose":{"rotation":{"radians":-2.4682401992930196},"translation":{"x":1.4493068796442792,"y":1.7009443129678503}},"time":4.191543176592664,"velocity":1.168594320247482,"position":7.353995764488778,"holonomicRotation":-137.7173161078336,"angularVelocity":-0.00524614748188575,"angularAcceleration":-0.8348032018149272,"curveRadius":-96.62492521051587},{"acceleration":-2.9627919793859343,"curvature":-0.016109798436791566,"pose":{"rotation":{"radians":-2.468341392679454},"translation":{"x":1.441650529604506,"y":1.6948379157401063}},"time":4.200109598698926,"velocity":1.1432137935390145,"position":7.363789016401935,"holonomicRotation":-137.70743279879736,"angularVelocity":-0.011812794790996404,"angularAcceleration":-0.7665565889299879,"curveRadius":-62.074023081269566},{"acceleration":-2.961209642841901,"curvature":-0.0217789919325024,"pose":{"rotation":{"radians":-2.4684994095718182},"translation":{"x":1.4339689883083406,"y":1.6887134126499452}},"time":4.208903431413067,"velocity":1.1171734113083616,"position":7.373613252493667,"holonomicRotation":-137.69754948976112,"angularVelocity":-0.017969058259452185,"angularAcceleration":-0.7000660199683046,"curveRadius":-45.915807448719704},{"acceleration":-2.9594706004116262,"curvature":-0.02735797257650336,"pose":{"rotation":{"radians":-2.468713709872896},"translation":{"x":1.4262618364441062,"y":1.6825711913365087}},"time":4.217941468265258,"velocity":1.0904256069588656,"position":7.3834685593139335,"holonomicRotation":-137.68766618072488,"angularVelocity":-0.0237109346401914,"angularAcceleration":-0.635301279983971,"curveRadius":-36.552416199834155},{"acceleration":-2.957550370661082,"curvature":-0.03284782706499379,"pose":{"rotation":{"radians":-2.4689837572967877},"translation":{"x":1.418528654700125,"y":1.6764116394389377}},"time":4.227242728483206,"velocity":1.06291666135366,"position":7.393355023771176,"holonomicRotation":-137.67778287168863,"angularVelocity":-0.02903342316672294,"angularAcceleration":-0.5722330524912567,"curveRadius":-30.443414050535736},{"acceleration":-2.955419095214336,"curvature":-0.03824962314562559,"pose":{"rotation":{"radians":-2.469309019335934},"translation":{"x":1.4107690237647204,"y":1.6702351445963735}},"time":4.236828895363071,"velocity":1.0345855207069954,"position":7.403272733224165,"holonomicRotation":-137.66789956265237,"angularVelocity":-0.033930354355680516,"angularAcceleration":-0.5108330837890098,"curveRadius":-26.144048431346828},{"acceleration":-2.9530399746876466,"curvature":-0.04356441786975587,"pose":{"rotation":{"radians":-2.469688967223699},"translation":{"x":1.4029825243262146,"y":1.6640420944479584}},"time":4.246724872466438,"velocity":1.005362304732158,"position":7.413221775572383,"holonomicRotation":-137.65801625361613,"angularVelocity":-0.0383941761178457,"angularAcceleration":-0.45107438260404575,"curveRadius":-22.954513084271905},{"acceleration":-2.9503671243963,"curvature":-0.04879325092938421,"pose":{"rotation":{"radians":-2.4701230758919923},"translation":{"x":1.3951687370729309,"y":1.657832876632833}},"time":4.256959498862346,"velocity":0.9751663994831922,"position":7.423202239344937,"holonomicRotation":-137.64813294457988,"angularVelocity":-0.04241568294733832,"angularAcceleration":-0.3929314734048772,"curveRadius":-20.494637699940203},{"acceleration":-2.94734258219578,"curvature":-0.05393714868698834,"pose":{"rotation":{"radians":-2.470610823926072},"translation":{"x":1.3873272426931922,"y":1.6516078787901392}},"time":4.267566482849885,"velocity":0.9439039839080506,"position":7.433214213788023,"holonomicRotation":-137.63824963554364,"angularVelocity":-0.04598366836913405,"angularAcceleration":-0.3363807681794821,"curveRadius":-18.54009758289721},{"acceleration":-2.9438920491907328,"curvature":-0.058997120567566806,"pose":{"rotation":{"radians":-2.4711516935146847},"translation":{"x":1.3794576218753205,"y":1.6453674885590177}},"time":4.278585641789249,"velocity":0.911464769517688,"position":7.4432577889509695,"holonomicRotation":-137.6283663265074,"angularVelocity":-0.049084471109722964,"angularAcceleration":-0.2814010359276918,"curveRadius":-16.949979768160787},{"acceleration":-2.9399186887139805,"curvature":-0.06397416044895532,"pose":{"rotation":{"radians":-2.471745170397386},"translation":{"x":1.3715594553076396,"y":1.6391120935786105}},"time":4.290064580522809,"velocity":0.8777176230082931,"position":7.453333055770847,"holonomicRotation":-137.61848301747116,"angularVelocity":-0.051701372093405425,"angularAcceleration":-0.22797412238395595,"curveRadius":-15.631311032176738},{"acceleration":-2.935293864752174,"curvature":-0.06886924620864196,"pose":{"rotation":{"radians":-2.472390743808769},"translation":{"x":1.3636323236784715,"y":1.632842081488059}},"time":4.302061014509741,"velocity":0.8425045639275457,"position":7.463440106155693,"holonomicRotation":-137.60859970843492,"angularVelocity":-0.053813776000975144,"angularAcceleration":-0.17608598604141212,"curveRadius":-14.520269279127326},{"acceleration":-2.929842895824001,"curvature":-0.07368333892678841,"pose":{"rotation":{"radians":-2.4730879064195594},"translation":{"x":1.35567580767614,"y":1.6265578399265046}},"time":4.314646069156627,"velocity":0.8056323309768106,"position":7.4735790330663345,"holonomicRotation":-137.59871639939868,"angularVelocity":-0.055396073386368115,"angularAcceleration":-0.12572828881474266,"curveRadius":-13.57158910773028},{"acceleration":-2.9233223791611196,"curvature":-0.07841738376444056,"pose":{"rotation":{"radians":-2.473836154275796},"translation":{"x":1.3476894879889665,"y":1.6202597565330885}},"time":4.327909109383291,"velocity":0.7668601886664895,"position":7.483749930596845,"holonomicRotation":-137.58883309036244,"angularVelocity":-0.056416013481761056,"angularAcceleration":-0.07690092753714584,"curveRadius":-12.752274457458547},{"acceleration":-2.9153826122439885,"curvature":-0.08307230879269356,"pose":{"rotation":{"radians":-2.4746349867348467},"translation":{"x":1.339672945305275,"y":1.613948218946952}},"time":4.34196506864683,"velocity":0.7258816894311588,"position":7.493952894053638,"holonomicRotation":-137.5789497813262,"angularVelocity":-0.05683229753822881,"angularAcceleration":-0.02961619685022853,"curveRadius":-12.037705639017377},{"acceleration":-2.9055022368128585,"curvature":-0.08764902603354113,"pose":{"rotation":{"radians":-2.4754839064003438},"translation":{"x":1.331625760313388,"y":1.607623614807237}},"time":4.35696606853359,"velocity":0.6822962507057464,"position":7.5041880200332125,"holonomicRotation":-137.56906647228996,"angularVelocity":-0.056590872068886404,"angularAcceleration":0.016093958480426537,"curveRadius":-11.409139898683238},{"acceleration":-2.8928676637864386,"curvature":-0.09214842995107504,"pose":{"rotation":{"radians":-2.476382419054518},"translation":{"x":1.323547513701628,"y":1.6012863317530845}},"time":4.373120869463472,"velocity":0.6355625494807844,"position":7.514455406498563,"holonomicRotation":-137.55918316325372,"angularVelocity":-0.05561892455833828,"angularAcceleration":0.06016462318333499,"curveRadius":-10.852056844928736},{"acceleration":-2.876133539063687,"curvature":-0.09657139882302855,"pose":{"rotation":{"radians":-2.477330033589099},"translation":{"x":1.3154377861583177,"y":1.594936757423636}},"time":4.390729772020505,"velocity":0.5849169942503982,"position":7.52475515285427,"holonomicRotation":-137.54929985421745,"angularVelocity":-0.053814514079559624,"angularAcceleration":0.10247148980093596,"curveRadius":-10.35503277562071},{"acceleration":-2.852898894976914,"curvature":-0.10091879373381253,"pose":{"rotation":{"radians":-2.47832626193521},"translation":{"x":1.307296158371781,"y":1.5885752794580328}},"time":4.4102532958651866,"velocity":0.52921835464785,"position":7.535087360020281,"holonomicRotation":-137.5394165451812,"angularVelocity":-0.05102707656858264,"angularAcceleration":0.14277327869457757,"curveRadius":-9.90895712286891},{"acceleration":-2.818400977789712,"curvature":-0.10519145967138069,"pose":{"rotation":{"radians":-2.4793706189916955},"translation":{"x":1.299122211030339,"y":1.5822022854954167}},"time":4.432466026483853,"velocity":0.4666139729528207,"position":7.545452130504388,"holonomicRotation":-137.52953323614497,"angularVelocity":-0.04701614918104232,"angularAcceleration":0.1805688573997163,"curveRadius":-9.506475175114133},{"acceleration":-2.761561538560691,"curvature":-0.10939022455414134,"pose":{"rotation":{"radians":-2.4804626225520057},"translation":{"x":1.290915524822316,"y":1.5758181631749284}},"time":4.458877021833343,"velocity":0.39367838400056326,"position":7.5558495684734215,"holonomicRotation":-137.51964992710873,"angularVelocity":-0.04134655077780769,"angularAcceleration":0.21466810804402597,"curveRadius":-9.141584671535822},{"acceleration":-2.648244223350426,"curvature":-0.1135159000632474,"pose":{"rotation":{"radians":-2.4816017932316337},"translation":{"x":1.2826756804360344,"y":1.5694233001357103}},"time":4.493378822250511,"velocity":0.3023091903506094,"position":7.566279779823174,"holonomicRotation":-137.5097666180725,"angularVelocity":-0.03301771692648094,"angularAcceleration":0.2414028760998338,"curveRadius":-8.809338598758696},{"acceleration":-2.1196530852096256,"curvature":-0.1135159000632474,"pose":{"rotation":{"radians":-2.4827876543930567},"translation":{"x":1.2744022585598167,"y":1.563018084016903}},"time":4.576897652158793,"velocity":0.12527824486242084,"position":7.5767428722470465,"holonomicRotation":-137.49988330903625,"angularVelocity":-0.014198728151787167,"angularAcceleration":0.2253262982175419,"curveRadius":-8.809338598758696}] \ No newline at end of file diff --git a/src/main/deploy/pathplanner/generatedJSON/Blue3(23).wpilib.json b/src/main/deploy/pathplanner/generatedJSON/Blue3(23).wpilib.json new file mode 100644 index 0000000..3418ca9 --- /dev/null +++ b/src/main/deploy/pathplanner/generatedJSON/Blue3(23).wpilib.json @@ -0,0 +1 @@ +[{"acceleration":0.0,"curvature":-1.3502928725411096,"pose":{"rotation":{"radians":2.2959404598841444},"translation":{"x":7.64,"y":0.86}},"time":0.0,"velocity":0,"position":0.0,"holonomicRotation":-90.0,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-0.7405800773561848},{"acceleration":1.5000000000000002,"curvature":-1.3502928725411096,"pose":{"rotation":{"radians":2.2959404598841444},"translation":{"x":7.635124399710297,"y":0.8655016279029729}},"time":0.07000546996707849,"velocity":0.10500820495061775,"position":0.007351148737967293,"holonomicRotation":-90.36763660973199,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-0.7405800773561848},{"acceleration":5.117525654440643,"curvature":-1.3316831473698487,"pose":{"rotation":{"radians":2.2860081149750973},"translation":{"x":7.630297757753251,"y":0.8710582312309265}},"time":0.09903310238254358,"velocity":0.25355785852443313,"position":0.01471133305126704,"holonomicRotation":-90.73527321946398,"angularVelocity":-0.34216861943433885,"angularAcceleration":-11.787686110150727,"curveRadius":-0.7509293798416372},{"acceleration":3.452903203107882,"curvature":-1.3129741139790136,"pose":{"rotation":{"radians":2.2762003037232867},"translation":{"x":7.625519673245971,"y":0.8766691530687354}},"time":0.12132885598359512,"velocity":0.3305429375492081,"position":0.02208103694143195,"holonomicRotation":-91.10290982919595,"angularVelocity":-0.4398959293911441,"angularAcceleration":-4.383225241249351,"curveRadius":-0.7616296386601753},{"acceleration":3.2774377244746873,"curvature":-1.29418892370111,"pose":{"rotation":{"radians":2.2665174841891544},"translation":{"x":7.620789745305569,"y":0.8823337365012736}},"time":0.1401444971400027,"velocity":0.39221002968539687,"position":0.029460720117936347,"holonomicRotation":-91.47054643892794,"angularVelocity":-0.514615444333921,"angularAcceleration":-3.9711383907495246,"curveRadius":-0.7726847152579617},{"acceleration":3.200739692269524,"curvature":-1.275349720742765,"pose":{"rotation":{"radians":2.256960004105281},"translation":{"x":7.616107573049155,"y":0.8880513246134154}},"time":0.1567393128327845,"velocity":0.4453257149591807,"position":0.03685081828094023,"holonomicRotation":-91.83818304865993,"angularVelocity":-0.5759316801590498,"angularAcceleration":-3.6949030926447337,"curveRadius":-0.7840986544597344},{"acceleration":3.15730375850817,"curvature":-1.2564776298045657,"pose":{"rotation":{"radians":2.247528105427337},"translation":{"x":7.61147275559384,"y":0.8938212604900353}},"time":0.17175902386124445,"velocity":0.4927475050410439,"position":0.04425174341665132,"holonomicRotation":-92.20581965839192,"angularVelocity":-0.627968052119769,"angularAcceleration":-3.4645388224925635,"curveRadius":-0.7958756895302158},{"acceleration":3.1292569227414337,"curvature":-1.2375927491411056,"pose":{"rotation":{"radians":2.23822192892775},"translation":{"x":7.606884892056736,"y":0.8996428872160075}},"time":0.18558714773060989,"velocity":0.5360192573877818,"position":0.05166388410417484,"holonomicRotation":-92.5734562681239,"angularVelocity":-0.672989090024259,"angularAcceleration":-3.25575893952098,"curveRadius":-0.808020247932128},{"acceleration":3.1096220952183704,"curvature":-1.2187141493987204,"pose":{"rotation":{"radians":2.2290415188124864},"translation":{"x":7.602343581554952,"y":0.9055155478762064}},"time":0.19847351768394617,"velocity":0.5760909981218344,"position":0.05908760583275956,"holonomicRotation":-92.9410928778559,"angularVelocity":-0.7124124286752227,"angularAcceleration":-3.059305203383285,"curveRadius":-0.8205369573278296},{"acceleration":3.0950963291834577,"curvature":-1.1998598765317834,"pose":{"rotation":{"radians":2.2199868273367582},"translation":{"x":7.597848423205599,"y":0.9114385855555058}},"time":0.2105916290333088,"velocity":0.6135977200758831,"position":0.06652325132835415,"holonomicRotation":-93.30872948758787,"angularVelocity":-0.7472031915439007,"angularAcceleration":-2.8709723706663124,"curveRadius":-0.8334306526613074},{"acceleration":3.0839095239444476,"curvature":-1.1810469595782462,"pose":{"rotation":{"radians":2.211057719406718},"translation":{"x":7.593399016125789,"y":0.9174113433387806}},"time":0.22206776876809461,"velocity":0.6489890967021064,"position":0.07397114088845995,"holonomicRotation":-93.67636609731986,"angularVelocity":-0.7780584879926834,"angularAcceleration":-2.688647677864702,"curveRadius":-0.8467063835946892},{"acceleration":3.075026351833419,"curvature":-1.1622914222020841,"pose":{"rotation":{"radians":2.202253977147263},"translation":{"x":7.5889949594326325,"y":0.9234331643109047}},"time":0.2329972427938089,"velocity":0.6825975173428567,"position":0.08143157272427576,"holonomicRotation":-94.04400270705185,"angularVelocity":-0.8055046600359862,"angularAcceleration":-2.511207033268838,"curveRadius":-0.8603694227609407},{"acceleration":3.0678003598993837,"curvature":-1.1436082976729343,"pose":{"rotation":{"radians":2.193575304421171},"translation":{"x":7.58463585224324,"y":0.9295033915567527}},"time":0.24345406590591862,"velocity":0.714676963049591,"position":0.0889048233091851,"holonomicRotation":-94.41163931678383,"angularVelocity":-0.8299530969440816,"angularAcceleration":-2.338036767570682,"curveRadius":-0.874425274838286},{"acceleration":3.0618068556748694,"curvature":-1.125011647095523,"pose":{"rotation":{"radians":2.185021331287419},"translation":{"x":7.580321293674723,"y":0.9356213681611987}},"time":0.2534970712949466,"velocity":0.7454267058012966,"position":0.09639114773267289,"holonomicRotation":-94.77927592651582,"angularVelocity":-0.8517343964683212,"angularAcceleration":-2.168802931046492,"curveRadius":-0.8888796863407864},{"acceleration":3.056755227130256,"curvature":-1.1065145804717464,"pose":{"rotation":{"radians":2.1765916183852023},"translation":{"x":7.576050882844192,"y":0.9417864372091169}},"time":0.2631739349540551,"velocity":0.7750065093735033,"position":0.1038907800588019,"holonomicRotation":-95.14691253624781,"angularVelocity":-0.8711203546080979,"angularAcceleration":-2.003330709483474,"curveRadius":-0.903738656180802},{"acceleration":3.0524398470965597,"curvature":-1.088129279699304,"pose":{"rotation":{"radians":2.168285661232647},"translation":{"x":7.571824218868757,"y":0.9479979417853818}},"time":0.27252392395092806,"velocity":0.8035467883574727,"position":0.11140393368841686,"holonomicRotation":-95.5145491459798,"angularVelocity":-0.8883387087763766,"angularAcceleration":-1.8415373722939399,"curveRadius":-0.919008447485525},{"acceleration":3.048711093165789,"curvature":-1.0698670242225934,"pose":{"rotation":{"radians":2.1601028944326472},"translation":{"x":7.5676409008655305,"y":0.9542552249748676}},"time":0.28157983086423427,"velocity":0.8311556322227461,"position":0.11893080172429622,"holonomicRotation":-95.88218575571177,"angularVelocity":-0.9035833603784464,"angularAcceleration":-1.683393143062271,"curveRadius":-0.9346955998822738},{"acceleration":3.045457476612126,"curvature":-1.0517382178733048,"pose":{"rotation":{"radians":2.1520426957757355},"translation":{"x":7.563500527951622,"y":0.9605576298624485}},"time":0.2903693709036882,"velocity":0.8579238026518827,"position":0.1264715573385055,"holonomicRotation":-96.24982236544376,"angularVelocity":-0.9170216667461166,"angularAcceleration":-1.5288975654413284,"curveRadius":-0.9508069432164181},{"acceleration":3.0425942078650787,"curvature":-1.033752417451832,"pose":{"rotation":{"radians":2.144104390233704},"translation":{"x":7.559402699244142,"y":0.9669044995329991}},"time":0.29891621361317167,"velocity":0.883928376775291,"position":0.13402635414125297,"holonomicRotation":-96.61745897517575,"angularVelocity":-0.9287997699107308,"angularAcceleration":-1.3780648088381575,"curveRadius":-0.9673496120714951},{"acceleration":3.0400556457716257,"curvature":-1.0159183620588084,"pose":{"rotation":{"radians":2.1362872538379802},"translation":{"x":7.555347013860203,"y":0.9732951770713933}},"time":0.3072407596121596,"velocity":0.9092354598379998,"position":0.14159532655058532,"holonomicRotation":-96.98509558490774,"angularVelocity":-0.939046573431655,"angularAcceleration":-1.2309143972740395,"curveRadius":-0.9843310617729666},{"acceleration":3.037790173460401,"curvature":-0.9982440037067017,"pose":{"rotation":{"radians":2.1285905174398785},"translation":{"x":7.551333070916915,"y":0.9797290055625056}},"time":0.3153607354150878,"velocity":0.9339022425408714,"position":0.1491785901623176,"holonomicRotation":-97.35273219463973,"angularVelocity":-0.9478767652640244,"angularAcceleration":-1.087465288897178,"curveRadius":-1.00175908524046},{"acceleration":3.0357566368811155,"curvature":-0.9807365381579373,"pose":{"rotation":{"radians":2.1210133703449117},"translation":{"x":7.547360469531387,"y":0.9862053280912104}},"time":0.3232916558564488,"velocity":0.9579785869073092,"position":0.15677624211960692,"holonomicRotation":-97.72036880437172,"angularVelocity":-0.9553931540468861,"angularAcceleration":-0.9477322132324625,"curveRadius":-1.0196418315139397},{"acceleration":3.033921816724209,"curvature":-0.9634024363515036,"pose":{"rotation":{"radians":2.113554963822601},"translation":{"x":7.543428808820733,"y":0.9927234877423818}},"time":0.33104718846074055,"velocity":0.9815082664757858,"position":0.16438836148164174,"holonomicRotation":-98.08800541410369,"angularVelocity":-0.9616885006947625,"angularAcceleration":-0.8117233166414324,"curveRadius":-1.0379878255104844},{"acceleration":3.0322585999544422,"curvature":-0.9462474758338488,"pose":{"rotation":{"radians":2.1062144144875026},"translation":{"x":7.539537687902062,"y":0.999282827600894}},"time":0.33863944404134605,"velocity":1.004529948753129,"position":0.17201500959094804,"holonomicRotation":-98.45564202383568,"angularVelocity":-0.966846974152179,"angularAcceleration":-0.6794388574844433,"curveRadius":-1.0568059894889374},{"acceleration":3.030744634948945,"curvature":-0.9292767725720591,"pose":{"rotation":{"radians":2.0989908075508112},"translation":{"x":7.535686705892484,"y":1.0058826907516216}},"time":0.34607921100893513,"velocity":1.02707798257542,"position":0.17965623043885068,"holonomicRotation":-98.82327863356767,"angularVelocity":-0.9709453223683701,"angularAcceleration":-0.5508705089884213,"curveRadius":-1.0761056657342167},{"acceleration":3.0293613272989925,"curvature":-0.9124948118757097,"pose":{"rotation":{"radians":2.0918831999411776},"translation":{"x":7.531875461909113,"y":1.0125224202794387}},"time":0.35337614617539376,"velocity":1.0491830357764977,"position":0.18731205102866003,"holonomicRotation":-99.19091524329966,"angularVelocity":-0.9740538249955671,"angularAcceleration":-0.42600113010264185,"curveRadius":-1.0958966418060132},{"acceleration":3.0280930796370136,"curvature":-0.8959054798670978,"pose":{"rotation":{"radians":2.0848906232977207},"translation":{"x":7.528103555069058,"y":1.0192013592692195}},"time":0.3605389315420329,"velocity":1.070872616576143,"position":0.19498248173620622,"holonomicRotation":-99.55855185303164,"angularVelocity":-0.976237076155451,"angularAcceleration":-0.30480477190512595,"curveRadius":-1.1161891767291612},{"acceleration":3.0269267090079084,"curvature":-0.8795120938802422,"pose":{"rotation":{"radians":2.078012086831402},"translation":{"x":7.524370584489429,"y":1.0259188508058388}},"time":0.3675754042074014,"velocity":1.092171503624151,"position":0.20266751666735197,"holonomicRotation":-99.92618846276363,"angularVelocity":-0.9775546347494602,"angularAcceleration":-0.1872470279738211,"curveRadius":-1.1369940299378805},{"acceleration":3.025850995179633,"curvature":-0.8633174325229477,"pose":{"rotation":{"radians":2.0712465800599933},"translation":{"x":7.520676149287337,"y":1.03267423797417}},"time":0.3744926648255053,"velocity":1.1131021035493576,"position":0.21036713401216253,"holonomicRotation":-100.29382507249562,"angularVelocity":-0.978061568723002,"angularAcceleration":-0.07328536562797487,"curveRadius":-1.1583224922003637},{"acceleration":3.0248563268160136,"curvature":-0.8473237651640949,"pose":{"rotation":{"radians":2.0645930754170987},"translation":{"x":7.517019848579894,"y":1.0394668638590883}},"time":0.3812971687939726,"velocity":1.1336847504292205,"position":0.218081296395449,"holonomicRotation":-100.6614616822276,"angularVelocity":-0.9778089150550268,"angularAcceleration":0.03713035794321583,"curveRadius":-1.1801864188316935},{"acceleration":3.023934421624009,"curvature":-0.8315328805387848,"pose":{"rotation":{"radians":2.0580505307361006},"translation":{"x":7.51340128148421,"y":1.0462960715454674}},"time":0.38799480342173254,"velocity":1.1539379583235647,"position":0.22580995122340353,"holonomicRotation":-101.02909829195958,"angularVelocity":-0.9768440717684084,"angularAcceleration":0.14405731877629796,"curveRadius":-1.2025982656898164},{"acceleration":3.023078103040571,"curvature":-0.8159461147633185,"pose":{"rotation":{"radians":2.0516178916132577},"translation":{"x":7.509820047117396,"y":1.053161204118182}},"time":0.3945909536267521,"velocity":1.173878635572726,"position":0.23355303102610467,"holonomicRotation":-101.39673490169157,"angularVelocity":-0.9752111342079073,"angularAcceleration":0.24755918372787325,"curveRadius":-1.2255711276841732},{"acceleration":3.0222811205625226,"curvature":-0.8005643780761946,"pose":{"rotation":{"radians":2.0452940936507282},"translation":{"x":7.5062757445965635,"y":1.060061604662106}},"time":0.40109055818328565,"velocity":1.1935222677150594,"position":0.2413104537956697,"holonomicRotation":-101.76437151142356,"angularVelocity":-0.9729511861106466,"angularAcceleration":0.3477054761722335,"curveRadius":-1.249118780931849},{"acceleration":3.0215380040579602,"curvature":-0.7853881814506352,"pose":{"rotation":{"radians":2.039078064586075},"translation":{"x":7.5027679730388215,"y":1.0669966162621138}},"time":0.4074981581307088,"velocity":1.2128830744709982,"position":0.24908212331988047,"holonomicRotation":-102.13200812115555,"angularVelocity":-0.9701025525404344,"angularAcceleration":0.4445710708512238,"curveRadius":-1.2732557270634892},{"acceleration":3.0208439448363213,"curvature":-0.7704176611810116,"pose":{"rotation":{"radians":2.0329687263049747},"translation":{"x":7.4992963315612835,"y":1.0739655820030798}},"time":0.41381793864057764,"velocity":1.2319741451569302,"position":0.2568679295111056,"holonomicRotation":-102.49964473088754,"angularVelocity":-0.9667010225371184,"angularAcceleration":0.5382354652988701,"curveRadius":-1.2979972427774438},{"acceleration":3.0201946978671543,"curvature":-0.7556526037196887,"pose":{"rotation":{"radians":2.0269649967497783},"translation":{"x":7.495860419281058,"y":1.0809678449698783}},"time":0.42005376539231654,"velocity":1.2508075560493501,"position":0.2646677487303953,"holonomicRotation":-102.86728134061951,"angularVelocity":-0.9627800441252294,"angularAcceleration":0.6287824482608664,"curveRadius":-1.3233594314073887},{"acceleration":3.0195865008851883,"curvature":-0.7410924684722568,"pose":{"rotation":{"radians":2.0210657917170485},"translation":{"x":7.492459835315258,"y":1.0880027482473837}},"time":0.42620921631409453,"velocity":1.2693944725596122,"position":0.27248144410661224,"holonomicRotation":-103.2349179503515,"angularVelocity":-0.958370898849731,"angularAcceleration":0.7162993144659545,"curveRadius":-1.3493592804437406},{"acceleration":3.019016007133631,"curvature":-0.7267364103266566,"pose":{"rotation":{"radians":2.015270026557097},"translation":{"x":7.489094178780992,"y":1.0950696349204698}},"time":0.4322876093917971,"velocity":1.2877452385588466,"position":0.2803088658505128,"holonomicRotation":-103.60255456008349,"angularVelocity":-0.9535028560775455,"angularAcceleration":0.8008765984620236,"curveRadius":-1.3760147225188781},{"acceleration":3.018480229014171,"curvature":-0.7125833008841663,"pose":{"rotation":{"radians":2.0095766177719545},"translation":{"x":7.485763048795372,"y":1.1021678480740116}},"time":0.43829202712627374,"velocity":1.3058694547771064,"position":0.2881498515636878,"holonomicRotation":-103.97019116981548,"angularVelocity":-0.9482033124463872,"angularAcceleration":0.8826074176566572,"curveRadius":-1.403344701958648},{"acceleration":3.0179764908000113,"curvature":-0.6986317484855954,"pose":{"rotation":{"radians":2.003984484520323},"translation":{"x":7.482466044475509,"y":1.109296730792883}},"time":0.4442253381204164,"velocity":1.3237760478700342,"position":0.2960042265422978,"holonomicRotation":-104.33782777954747,"angularVelocity":-0.9424979167874494,"angularAcceleration":0.9615871584297734,"curveRadius":-1.4313692473433568},{"acceleration":3.01750238857315,"curvature":-0.6848801180143739,"pose":{"rotation":{"radians":1.998492550031944},"translation":{"x":7.479202764938513,"y":1.116455626161958}},"time":0.45009021619786604,"velocity":1.3414733314774288,"position":0.3038718040755631,"holonomicRotation":-104.70546438927946,"angularVelocity":-0.9364106833687561,"angularAcceleration":1.0379130372886456,"curveRadius":-1.4601095486597444},{"acceleration":3.017055756273491,"curvature":-0.67132654877663,"pose":{"rotation":{"radians":1.9930997429323096},"translation":{"x":7.4759728093014965,"y":1.1236438772661115}},"time":0.4558891573902287,"velocity":1.358969060382138,"position":0.31175238573895947,"holonomicRotation":-105.07310099901144,"angularVelocity":-0.929964095296695,"angularAcceleration":1.1116836433091253,"curveRadius":-1.4895880429908772},{"acceleration":3.016634636734333,"curvature":-0.6579689719511486,"pose":{"rotation":{"radians":1.9878049984873853},"translation":{"x":7.472775776681568,"y":1.1308608271902174}},"time":0.4616244950766164,"velocity":1.3762704787002629,"position":0.3196457616821119,"holonomicRotation":-105.44073760874342,"angularVelocity":-0.9231791978859233,"angularAcceleration":1.182998766903485,"curveRadius":-1.519828506554935},{"acceleration":3.016237256849359,"curvature":-0.64480512718372,"pose":{"rotation":{"radians":1.9826072597656181},"translation":{"x":7.469611266195841,"y":1.13810581901915}},"time":0.46729841351565193,"velocity":1.3933843628884064,"position":0.3275517109113682,"holonomicRotation":-105.80837421847541,"angularVelocity":-0.9160756851927424,"angularAcceleration":1.2519589009792598,"curveRadius":-1.5508561545837038},{"acceleration":3.015862006250018,"curvature":-0.631832578022946,"pose":{"rotation":{"radians":1.9775054787266957},"translation":{"x":7.466478876961424,"y":1.1453781958377838}},"time":0.4729129599740066,"velocity":1.4103170602344839,"position":0.3354700015670649,"holonomicRotation":-106.1760108282074,"angularVelocity":-0.9086719785408097,"angularAcceleration":1.3186651329450934,"curveRadius":-1.582697750611529},{"acceleration":3.0155074189132383,"curvature":-0.6190487263490481,"pose":{"rotation":{"radians":1.972498617235781},"translation":{"x":7.4633782080954285,"y":1.152677300730993}},"time":0.47847005562555955,"velocity":1.4270745233993523,"position":0.34340039119548943,"holonomicRotation":-106.54364743793938,"angularVelocity":-0.9009852996709712,"angularAcceleration":1.3832187444336124,"curveRadius":-1.6153817259227412},{"acceleration":3.0151721571785157,"curvature":-0.6064508263312979,"pose":{"rotation":{"radians":1.9675856480107305},"translation":{"x":7.460308858714967,"y":1.1600024767836519}},"time":0.48397150537028566,"velocity":1.4436623414937673,"position":0.351342627015571,"holonomicRotation":-106.91128404767137,"angularVelocity":-0.8930317376361063,"angularAcceleration":1.445721110601699,"curveRadius":-1.6489383088971343},{"acceleration":3.014854997927394,"curvature":-0.5940359972702464,"pose":{"rotation":{"radians":1.9627655555041497},"translation":{"x":7.457270427937148,"y":1.1673530670806347}},"time":0.48941900670102717,"velocity":1.4600857681069694,"position":0.35929644618033046,"holonomicRotation":-107.27892065740336,"angularVelocity":-0.884826310987753,"angularAcceleration":1.5062734545925136,"curveRadius":-1.6833996670155789},{"acceleration":3.014554820470821,"curvature":-0.5818012357226415,"pose":{"rotation":{"radians":1.9580373367220567},"translation":{"x":7.454262514879083,"y":1.1747284147068158}},"time":0.4948141577286874,"velocity":1.4763497466445707,"position":0.36726157603312587,"holonomicRotation":-107.64655726713534,"angularVelocity":-0.8763830257673935,"angularAcceleration":1.5649766201301663,"curveRadius":-1.7188000619454231},{"acceleration":3.014270595993242,"curvature":-0.5697434264025305,"pose":{"rotation":{"radians":1.953400001986521},"translation":{"x":7.4512847186578846,"y":1.1821278627470693}},"time":0.5001584644615131,"velocity":1.492458933285296,"position":0.37523773435874835,"holonomicRotation":-108.01419387686732,"angularVelocity":-0.8677149286833366,"angularAcceleration":1.6219310599849883,"curveRadius":-1.7551760207470795},{"acceleration":3.014001378271794,"curvature":-0.5578593534258979,"pose":{"rotation":{"radians":1.9488525756425787},"translation":{"x":7.448336638390661,"y":1.1895507542862698}},"time":0.5054533474215156,"velocity":1.5084177178245313,"position":0.3832246296294233,"holonomicRotation":-108.38183048659931,"angularVelocity":-0.8588341571085663,"angularAcceleration":1.6772366153993625,"curveRadius":-1.7925665203224614},{"acceleration":3.0137462955235335,"curvature":-0.5461457094684024,"pose":{"rotation":{"radians":1.944394096711803},"translation":{"x":7.445417873194524,"y":1.1969964324092912}},"time":0.510700147670346,"velocity":1.5242302426377958,"position":0.3912219612457701,"holonomicRotation":-108.7494670963313,"angularVelocity":-0.8497519858450205,"angularAcceleration":1.7309923825612168,"curveRadius":-1.8310131942139807},{"acceleration":3.013504543179334,"curvature":-0.5345991051048836,"pose":{"rotation":{"radians":1.9400236194997114},"translation":{"x":7.442528022186584,"y":1.2044642402010082}},"time":0.515900132307795,"velocity":1.539900419967211,"position":0.3992294197728008,"holonomicRotation":-109.11710370606329,"angularVelocity":-0.8404788699982948,"angularAcceleration":1.7832967774449004,"curveRadius":-1.8705605573428876},{"acceleration":3.013275377559977,"curvature":-0.5232160774332947,"pose":{"rotation":{"radians":1.9357402141553461},"translation":{"x":7.439666684483953,"y":1.211953520746295}},"time":0.5210544994982242,"velocity":1.5554319477090346,"position":0.40724668717101775,"holonomicRotation":-109.48474031579528,"angularVelocity":-0.8310244858609853,"angularAcceleration":1.8342473068012215,"curveRadius":-1.9112562536411948},{"acceleration":3.013058110172776,"curvature":-0.5119930973161152,"pose":{"rotation":{"radians":1.9315429671886486},"translation":{"x":7.436833459203742,"y":1.2194636171300257}},"time":0.5261643830735104,"velocity":1.5708283238575893,"position":0.415273437022692,"holonomicRotation":-109.85237692552727,"angularVelocity":-0.8213977686296831,"angularAcceleration":1.883940620068452,"curveRadius":-1.9531513320043439},{"acceleration":3.0128521027418884,"curvature":-0.5009265771371441,"pose":{"rotation":{"radians":1.9274309819483166},"translation":{"x":7.434027945463061,"y":1.2269938724370746}},"time":0.5312308567552687,"velocity":1.5860928597431612,"position":0.42330933475340543,"holonomicRotation":-110.22001353525926,"angularVelocity":-0.8116069476758698,"angularAcceleration":1.9324724786521357,"curveRadius":-1.9963005471083626},{"acceleration":3.0126567626750353,"curvature":-0.490012876967189,"pose":{"rotation":{"radians":1.923403379061076},"translation":{"x":7.431249742379022,"y":1.2345436297523162}},"time":0.5362549380340996,"velocity":1.6012286921840602,"position":0.4313540378489343,"holonomicRotation":-110.58765014499123,"angularVelocity":-0.8016595798740312,"angularAcceleration":1.9799376741280135,"curveRadius":-2.040762696256571},{"acceleration":3.012471539099715,"curvature":-0.47924831079980773,"pose":{"rotation":{"radians":1.919459296836874},"translation":{"x":7.428498449068734,"y":1.2421122321606248}},"time":0.5412375917392559,"velocity":1.6162387946600332,"position":0.4394071960675644,"holonomicRotation":-110.95528675472322,"angularVelocity":-0.7915625804218644,"angularAcceleration":2.026430101236612,"curveRadius":-2.086600990478444},{"acceleration":3.012295919292159,"curvature":-0.46862915190010146,"pose":{"rotation":{"radians":1.9155978916414038},"translation":{"x":7.4257736646493075,"y":1.2496990227468745}},"time":0.5461797333283421,"velocity":1.6311259876014017,"position":0.44746845164792864,"holonomicRotation":-111.3229233644552,"angularVelocity":-0.7813222518750469,"angularAcceleration":2.0720427292960086,"curveRadius":-2.133883468293436},{"acceleration":3.0121294254225996,"curvature":-0.45815163793817376,"pose":{"rotation":{"radians":1.9118183382385638},"translation":{"x":7.423074988237855,"y":1.2573033445959396}},"time":0.5510822319233651,"velocity":1.6458929478775635,"position":0.4555374395124567,"holonomicRotation":-111.6905599741872,"angularVelocity":-0.7709443112695551,"angularAcceleration":2.1168676348071633,"curveRadius":-2.1826834549807876},{"acceleration":3.0119716117041784,"curvature":-0.44781197504137327,"pose":{"rotation":{"radians":1.908119830105505},"translation":{"x":7.420402018951487,"y":1.2649245407926943}},"time":0.5559459131165739,"velocity":1.6605422175598878,"position":0.4636137874665319,"holonomicRotation":-112.05819658391918,"angularVelocity":-0.7604339154102469,"angularAcceleration":2.160996052534039,"curveRadius":-2.2330800776544892},{"acceleration":3.0118220617973557,"curvature":-0.4376063423922423,"pose":{"rotation":{"radians":1.904501579721838},"translation":{"x":7.417754355907314,"y":1.2725619544220135}},"time":0.5607715615670087,"velocity":1.6750762120253855,"position":0.47169711639345235,"holonomicRotation":-112.42583319365116,"angularVelocity":-0.7497956846277992,"angularAcceleration":2.2045183961730976,"curveRadius":-2.285158835983378},{"acceleration":3.0116803863865242,"curvature":-0.4275308953530561,"pose":{"rotation":{"radians":1.9009628188352365},"translation":{"x":7.415131598222447,"y":1.2802149285687707}},"time":0.5655599234064635,"velocity":1.6894972274601934,"position":0.4797870404452875,"holonomicRotation":-112.79346980338315,"angularVelocity":-0.7390337249459875,"angularAcceleration":2.247524318888342,"curveRadius":-2.339012246528283},{"acceleration":3.011546221202482,"curvature":-0.4175817690006844,"pose":{"rotation":{"radians":1.8975027987060666},"translation":{"x":7.412533345013998,"y":1.2878828063178405}},"time":0.5703117084716263,"velocity":1.7038074478171505,"position":0.48788316722973807,"holonomicRotation":-113.16110641311514,"angularVelocity":-0.7281516486376309,"angularAcceleration":2.290102805393607,"curveRadius":-2.394740561574567},{"acceleration":3.0114192249212692,"curvature":-0.4077550803862603,"pose":{"rotation":{"radians":1.894120790332096},"translation":{"x":7.409959195399074,"y":1.2955649307540975}},"time":0.5750275923774381,"velocity":1.718008951273609,"position":0.4959850979930899,"holonomicRotation":-113.52874302284712,"angularVelocity":-0.7171525935578447,"angularAcceleration":2.332342207625422,"curveRadius":-2.4524525826942853},{"acceleration":3.0112990775802837,"curvature":-0.39804693131869406,"pose":{"rotation":{"radians":1.8908160846550806},"translation":{"x":7.407408748494792,"y":1.3032606449624153}},"time":0.5797082184452002,"velocity":1.7321037162339592,"position":0.5040924277993621,"holonomicRotation":-113.89637963257911,"angularVelocity":-0.7060392411555131,"angularAcceleration":2.37433032279058,"curveRadius":-2.512266572906589},{"acceleration":3.011185478897117,"curvature":-0.3884534104583224,"pose":{"rotation":{"radians":1.8875879927536732},"translation":{"x":7.404881603418257,"y":1.3109692920276692}},"time":0.5843541994976231,"velocity":1.7460936269142464,"position":0.5122047457057622,"holonomicRotation":-114.2640162423111,"angularVelocity":-0.694813832640119,"angularAcceleration":2.416154605180713,"curveRadius":-2.574311289531827},{"acceleration":3.011078146844588,"curvature":-0.3789705945069941,"pose":{"rotation":{"radians":1.8844358460182893},"translation":{"x":7.402377359286582,"y":1.3186902150347324}},"time":0.5889661195318034,"velocity":1.7599804785441615,"position":0.5203216349345263,"holonomicRotation":-114.63165285204309,"angularVelocity":-0.6834781852292291,"angularAcceleration":2.4579019859143294,"curveRadius":-2.638727158503968},{"acceleration":3.0109768163458135,"curvature":-0.369594549920406,"pose":{"rotation":{"radians":1.881358996316639},"translation":{"x":7.399895615216879,"y":1.32642275706848}},"time":0.5935445352800801,"velocity":1.7737659822178151,"position":0.5284426730412698,"holonomicRotation":-114.99928946177506,"angularVelocity":-0.6720337057219781,"angularAcceleration":2.4996593006126138,"curveRadius":-2.7056676030946747},{"acceleration":3.0108812380981576,"curvature":-0.36032133383239384,"pose":{"rotation":{"radians":1.878356816147258},"translation":{"x":7.397435970326258,"y":1.334166261213786}},"time":0.5980899776677597,"velocity":1.7874517694217358,"position":0.5365674320799323,"holonomicRotation":-115.36692607150705,"angularVelocity":-0.660481403860386,"angularAcceleration":2.541513207362273,"curveRadius":-2.7753005612072847},{"acceleration":3.01079117741619,"curvature":-0.351146995042411,"pose":{"rotation":{"radians":1.8754286987826438},"translation":{"x":7.394998023731829,"y":1.3419200705555243}},"time":0.6026029531758736,"velocity":1.8010393962654605,"position":0.5446954787644266,"holonomicRotation":-115.73456268123904,"angularVelocity":-0.6488219046058601,"angularAcceleration":2.5835503059042115,"curveRadius":-2.8478102165710446},{"acceleration":3.0107064132366768,"curvature":-0.3420675739036002,"pose":{"rotation":{"radians":1.8725740584044201},"translation":{"x":7.392581374550704,"y":1.34968352817857}},"time":0.6070839451163726,"velocity":1.8145303474383827,"position":0.5528263746270888,"holonomicRotation":-116.10219929097103,"angularVelocity":-0.6370554591771487,"angularAcceleration":2.625857306808971,"curveRadius":-2.923398989820108},{"acceleration":3.0106267372617985,"curvature":-0.3330791029542684,"pose":{"rotation":{"radians":1.8697923302331423},"translation":{"x":7.390185621899993,"y":1.3574559771677968}},"time":0.6115334148264958,"velocity":1.827926039914316,"position":0.560959676174033,"holonomicRotation":-116.469835900703,"angularVelocity":-0.6251819548179064,"angularAcceleration":2.6685212245019665,"curveRadius":-3.00228981983688},{"acceleration":3.010551953031942,"curvature":-0.3241776070331038,"pose":{"rotation":{"radians":1.8670829706500442},"translation":{"x":7.387810364896807,"y":1.3652367606080793}},"time":0.6159518027884476,"velocity":1.8412278264224229,"position":0.5690949350375085,"holonomicRotation":-116.83747251043499,"angularVelocity":-0.613200924506679,"angularAcceleration":2.711629312409865,"curveRadius":-3.0847287977478466},{"acceleration":3.0104818751901687,"curvature":-0.3153591019917264,"pose":{"rotation":{"radians":1.8644454573171272},"translation":{"x":7.385455202658258,"y":1.3730252215842915}},"time":0.6203395296799769,"velocity":1.854436998702656,"position":0.5772316981253629,"holonomicRotation":-117.20510912016698,"angularVelocity":-0.6011115545976544,"angularAcceleration":2.755269461361376,"curveRadius":-3.170988227973314},{"acceleration":3.0104163287230703,"curvature":-0.3066195954519827,"pose":{"rotation":{"radians":1.861879289292082},"translation":{"x":7.383119734301455,"y":1.3808207031813078}},"time":0.6246969973609646,"velocity":1.8675547905613847,"position":0.585369507767708,"holonomicRotation":-117.57274572989897,"angularVelocity":-0.5889126926269178,"angularAcceleration":2.799530108728498,"curveRadius":-3.261370163005783},{"acceleration":3.0103551483958606,"curvature":-0.297955084868098,"pose":{"rotation":{"radians":1.859383987142355},"translation":{"x":7.3808035589435095,"y":1.3886225484840025}},"time":0.6290245898006899,"velocity":1.8805823807424706,"position":0.5935079018608896,"holonomicRotation":-117.94038233963096,"angularVelocity":-0.576602853545366,"angularAcceleration":2.8445005515198987,"curveRadius":-3.3562105524820653},{"acceleration":3.010298177987752,"curvature":-0.2893615571638352,"pose":{"rotation":{"radians":1.856959093057885},"translation":{"x":7.378506275701533,"y":1.3964301005772501}},"time":0.633322673950048,"velocity":1.8935208956261216,"position":0.6016464140088588,"holonomicRotation":-118.30801894936295,"angularVelocity":-0.5641802254690857,"angularAcceleration":2.890271024157428,"curveRadius":-3.4558840842628054},{"acceleration":3.0102452698592415,"curvature":-0.28083498710209875,"pose":{"rotation":{"radians":1.854604170964969},"translation":{"x":7.376227483692637,"y":1.4042427025459248}},"time":0.6375916005626404,"velocity":1.906371411769054,"position":0.609784573662045,"holonomicRotation":-118.67565555909493,"angularVelocity":-0.5516426742894807,"angularAcceleration":2.9369329382758975,"curveRadius":-3.560809891669394},{"acceleration":3.0101962843787966,"curvature":-0.27237133640457406,"pose":{"rotation":{"radians":1.8523188066402412},"translation":{"x":7.373966782033929,"y":1.4120596974749007}},"time":0.6418317049683294,"velocity":1.9191349582964372,"position":0.6179219062538295,"holonomicRotation":-119.04329216882692,"angularVelocity":-0.5389877479576938,"angularAcceleration":2.984578944520235,"curveRadius":-3.6714582863250453},{"acceleration":3.0101510894780508,"curvature":-0.2639665508899301,"pose":{"rotation":{"radians":1.8501026078266205},"translation":{"x":7.371723769842524,"y":1.419880428449052}},"time":0.6460433078025605,"velocity":1.9318125191563467,"position":0.6260579333347114,"holonomicRotation":-119.41092877855891,"angularVelocity":-0.5262126797920874,"angularAcceleration":3.033303155219955,"curveRadius":-3.7883587773853376},{"acceleration":3.01010956007677,"curvature":-0.2556165604412365,"pose":{"rotation":{"radians":1.8479552043554233},"translation":{"x":7.369498046235529,"y":1.4277042385532532}},"time":0.6502267156944943,"velocity":1.9444050352455573,"position":0.6341921727042735,"holonomicRotation":-119.77856538829089,"angularVelocity":-0.513314390245742,"angularAcceleration":3.08320151406107,"curveRadius":-3.9121095999172923},{"acceleration":3.0100715778800993,"curvature":-0.2473172752075452,"pose":{"rotation":{"radians":1.8458762482677527},"translation":{"x":7.367289210330058,"y":1.435530470872379}},"time":0.6543822219167393,"velocity":1.956913406416841,"position":0.6423241385410334,"holonomicRotation":-120.14620199802287,"angularVelocity":-0.5002894897718257,"angularAcceleration":3.1343715488120445,"curveRadius":-4.043389201829164},{"acceleration":3.0100370307699444,"curvature":-0.2390645842598629,"pose":{"rotation":{"radians":1.8438654139460542},"translation":{"x":7.36509686124322,"y":1.443358468491303}},"time":0.6585101069992692,"velocity":1.9693384933740186,"position":0.6504533415302838,"holonomicRotation":-120.51383860775486,"angularVelocity":-0.48713427857010577,"angularAcceleration":3.186913138012475,"curveRadius":-4.182970066837676},{"acceleration":3.0100058125998306,"curvature":-0.2308543531065024,"pose":{"rotation":{"radians":1.8419223982477457},"translation":{"x":7.362920598092128,"y":1.4511875744948997}},"time":0.6626106393099028,"velocity":1.9816811194637793,"position":0.6585792889900177,"holonomicRotation":-120.88147521748685,"angularVelocity":-0.4738447477342753,"angularAcceleration":3.240928208605374,"curveRadius":-4.3317355143771525},{"acceleration":3.0099778227807596,"curvature":-0.22268242083685136,"pose":{"rotation":{"radians":1.84004692064814},"translation":{"x":7.360760019993889,"y":1.4590171319680436}},"time":0.6666840756035453,"velocity":1.9939420723701533,"position":0.6667014849950309,"holonomicRotation":-121.24911182721884,"angularVelocity":-0.46041657814382503,"angularAcceleration":3.296521320686457,"curveRadius":-4.490700236875239},{"acceleration":3.009952966054654,"curvature":-0.21454459718239027,"pose":{"rotation":{"radians":1.8382387233888988},"translation":{"x":7.358614726065617,"y":1.466846483995609}},"time":0.6707306615422199,"velocity":2.0061221057186622,"position":0.6748194304992965,"holonomicRotation":-121.61674843695081,"angularVelocity":-0.4468451397410346,"angularAcceleration":3.3537996247857382,"curveRadius":-4.66103557550728},{"acceleration":3.0099311520278973,"curvature":-0.20643665987949783,"pose":{"rotation":{"radians":1.8364975716373104},"translation":{"x":7.356484315424423,"y":1.4746749736624698}},"time":0.6747506321877793,"velocity":2.018221940594969,"position":0.6829326234567121,"holonomicRotation":-121.9843850466828,"angularVelocity":-0.4331254889912567,"angularAcceleration":3.412873366359839,"curveRadius":-4.8441008519694355},{"acceleration":3.009912295161201,"curvature":-0.19835435153612627,"pose":{"rotation":{"radians":1.834823253653742},"translation":{"x":7.3543683871874155,"y":1.4825019440535006}},"time":0.6787442124690335,"velocity":2.0302422669852294,"position":0.6910405589403131,"holonomicRotation":-122.35202165641479,"angularVelocity":-0.4192523664611293,"angularAcceleration":3.473855927035615,"curveRadius":-5.041482539987887},{"acceleration":3.0098963142266624,"curvature":-0.19029337560375564,"pose":{"rotation":{"radians":1.8332155809683635},"translation":{"x":7.352266540471705,"y":1.4903267382535754}},"time":0.6827116176249138,"velocity":2.0421837451409575,"position":0.6991427292600404,"holonomicRotation":-122.71965826614678,"angularVelocity":-0.40522019360584166,"angularAcceleration":3.536864097302906,"curveRadius":-5.255043675730896},{"acceleration":3.009883132284052,"curvature":-0.18224939306373006,"pose":{"rotation":{"radians":1.8316743885695181},"translation":{"x":7.350178374394407,"y":1.4981486993475692}},"time":0.6866530536251743,"velocity":2.0540470068751184,"position":0.7072386240791652,"holonomicRotation":-123.08729487587877,"angularVelocity":-0.3910230684307656,"angularAcceleration":3.6020184455964763,"curveRadius":-5.4869867229149785},{"acceleration":3.009872676427659,"curvature":-0.174218019506726,"pose":{"rotation":{"radians":1.8301995351066487},"translation":{"x":7.348103488072627,"y":1.5059671704203557}},"time":0.6905687175700262,"velocity":2.0658326567928014,"position":0.7153277305294665,"holonomicRotation":-123.45493148561076,"angularVelocity":-0.37665475986734925,"angularAcceleration":3.669443743329073,"curveRadius":-5.739934381250346},{"acceleration":3.0098648774314802,"curvature":-0.16619481961480834,"pose":{"rotation":{"radians":1.828790903099085},"translation":{"x":7.346041480623478,"y":1.513781494556809}},"time":0.6944587980700019,"velocity":2.077541273460059,"position":0.723409533325248,"holonomicRotation":-123.82256809534275,"angularVelocity":-0.3621087038102465,"angularAcceleration":3.739268649374698,"curveRadius":-6.017034720562961},{"acceleration":3.0098596697135496,"curvature":-0.15817530428223,"pose":{"rotation":{"radians":1.827448399165441},"translation":{"x":7.343991951164072,"y":1.5215910148418041}},"time":0.6983234756072572,"velocity":2.0891734105158917,"position":0.7314835148762998,"holonomicRotation":-124.19020470507473,"angularVelocity":-0.3473779948526663,"angularAcceleration":3.811626925035011,"curveRadius":-6.32209942340755},{"acceleration":3.009856991104997,"curvature":-0.15015492547281434,"pose":{"rotation":{"radians":1.8261719542622041},"translation":{"x":7.3419544988115195,"y":1.5293950743602145}},"time":0.702162922879437,"velocity":2.1007295977300413,"position":0.739549155399892,"holonomicRotation":-124.55784131480672,"angularVelocity":-0.33245538035798006,"angularAcceleration":3.886656968260374,"curveRadius":-6.659788194434227},{"acceleration":3.009856782625842,"curvature":-0.14212907202036648,"pose":{"rotation":{"radians":1.824961523940077},"translation":{"x":7.339928722682929,"y":1.5371930161969154}},"time":0.705977305127158,"velocity":2.1122103420098717,"position":0.7476059330319069,"holonomicRotation":-124.9254779245387,"angularVelocity":-0.3173332517606045,"angularAcceleration":3.9645026678726367,"curveRadius":-7.035858222283365},{"acceleration":3.0098589884090248,"curvature":-0.13409306445892902,"pose":{"rotation":{"radians":1.8238170886131457},"translation":{"x":7.337914221895414,"y":1.5449841834367801}},"time":0.7097667804460795,"velocity":2.123616128359882,"position":0.7556533239371905,"holonomicRotation":-125.29311453427069,"angularVelocity":-0.3020036365501082,"angularAcceleration":4.0453133799163465,"curveRadius":-7.457507247187174},{"acceleration":3.009863555400952,"curvature":-0.12604215017653925,"pose":{"rotation":{"radians":1.822738653848104},"translation":{"x":7.335910595566085,"y":1.5527679191646835}},"time":0.713531500084493,"velocity":2.1349474207958448,"position":0.7636908024192407,"holonomicRotation":-125.66075114400267,"angularVelocity":-0.2864581877592753,"angularAcceleration":4.129244746996447,"curveRadius":-7.933853862373527},{"acceleration":3.0098704334478206,"curvature":-0.11797149798142774,"pose":{"rotation":{"radians":1.8217262506685576},"translation":{"x":7.33391744281205,"y":1.5605435664654999}},"time":0.7172716087272722,"velocity":2.146204663217629,"position":0.7717178410293142,"holonomicRotation":-126.02838775373465,"angularVelocity":-0.27068817412590085,"angularAcceleration":4.216458702027345,"curveRadius":-8.47662373633189},{"acceleration":3.0098795749036618,"curvature":-0.10987619305629287,"pose":{"rotation":{"radians":1.8207799358766132},"translation":{"x":7.331934362750422,"y":1.5683104684241034}},"time":0.7209872447669957,"velocity":2.1573882802413684,"position":0.779733910675056,"holonomicRotation":-126.39602436346664,"angularVelocity":-0.25468446904579783,"angularAcceleration":4.307123977970154,"curveRadius":-9.101152598977196},{"acceleration":3.0098909346947593,"curvature":-0.10175123074417104,"pose":{"rotation":{"radians":1.819899792396771},"translation":{"x":7.329960954498313,"y":1.5760679681253682}},"time":0.7246785405629897,"velocity":2.1684986779950077,"position":0.7877384807287576,"holonomicRotation":-126.76366097319863,"angularVelocity":-0.2384375375166072,"angularAcceleration":4.40141685389249,"curveRadius":-9.827890952142477},{"acceleration":2.8184607125335486,"curvature":-0.09359150995425031,"pose":{"rotation":{"radians":1.8190859296368023},"translation":{"x":7.327996817172833,"y":1.583815408654169}},"time":0.7283467986756434,"velocity":2.1788375193689546,"position":0.7957310191353371,"holonomicRotation":-127.13129758293061,"angularVelocity":-0.22186627412103962,"angularAcceleration":4.5174747486838,"curveRadius":-10.684729848773923},{"acceleration":-0.18931589324940148,"curvature":-0.0853918279460576,"pose":{"rotation":{"radians":1.8183384838706105},"translation":{"x":7.326041549891091,"y":1.5915521330953797}},"time":0.7320104561925166,"velocity":2.178143930773588,"position":0.8037109925201473,"holonomicRotation":-127.4989341926626,"angularVelocity":-0.20401627683521023,"angularAcceleration":4.872179564716521,"curveRadius":-11.710722490115852},{"acceleration":-2.9948718997208217,"curvature":-0.07714687341908301,"pose":{"rotation":{"radians":1.8176576186415907},"translation":{"x":7.3240947517701995,"y":1.5992774845338746}},"time":0.7356866817449116,"velocity":2.1671341061696845,"position":0.811677866296715,"holonomicRotation":-127.86657080239459,"angularVelocity":-0.18520768633910573,"angularAcceleration":5.116277613556938,"curveRadius":-12.962288109431542},{"acceleration":-2.9949119592016302,"curvature":-0.06885121774731999,"pose":{"rotation":{"radians":1.817043525191091},"translation":{"x":7.322156021927269,"y":1.6069908060545282}},"time":0.7393754195964232,"velocity":2.1560866610638327,"position":0.8196311047745204,"holonomicRotation":-128.23420741212658,"angularVelocity":-0.16647793234968716,"angularAcceleration":5.077550843506929,"curveRadius":-14.524071363123053},{"acceleration":-2.9949520588622796,"curvature":-0.06049931184907217,"pose":{"rotation":{"radians":1.8164964229074914},"translation":{"x":7.320224959479412,"y":1.6146914407422146}},"time":0.7430766130524202,"velocity":2.1450017641025467,"position":0.8275701712669189,"holonomicRotation":-128.60184402185857,"angularVelocity":-0.14781780258289182,"angularAcceleration":5.041652101853858,"curveRadius":-16.52911362851041},{"acceleration":-2.994992192385179,"curvature":-0.0520854740661529,"pose":{"rotation":{"radians":1.8160165598017988},"translation":{"x":7.318301163543737,"y":1.6223787316818084}},"time":0.746790204475986,"velocity":2.1338795867832587,"position":0.8354945281993192,"holonomicRotation":-128.96948063159056,"angularVelocity":-0.12921806708392028,"angularAcceleration":5.008557317571639,"curveRadius":-19.19921087268816},{"acceleration":-2.9950323535372454,"curvature":-0.04360388562144667,"pose":{"rotation":{"radians":1.815604213007216},"translation":{"x":7.316384233237355,"y":1.6300520219581838}},"time":0.7505161353043286,"velocity":2.122720303405331,"position":0.8434036372177259,"holonomicRotation":-129.33711724132255,"angularVelocity":-0.11066947122206998,"angularAcceleration":4.978244824287631,"curveRadius":-22.93373596751542},{"acceleration":-2.995072535806638,"curvature":-0.035048579945921345,"pose":{"rotation":{"radians":1.8152596893065363},"translation":{"x":7.314473767677379,"y":1.6377106546562148}},"time":0.7542543460657419,"velocity":2.111524091020765,"position":0.8512969592977633,"holonomicRotation":-129.70475385105453,"angularVelocity":-0.09216272775095634,"angularAcceleration":4.950695573974706,"curveRadius":-28.531826440413926},{"acceleration":-2.9951127328248224,"curvature":-0.026413435635038823,"pose":{"rotation":{"radians":1.8149833256870513},"translation":{"x":7.312569365980917,"y":1.6453539728607758}},"time":0.7580047763972048,"velocity":2.100291129381428,"position":0.8591739548542977,"holonomicRotation":-130.0723904607865,"angularVelocity":-0.07368850906693576,"angularAcceleration":4.925893044602922,"curveRadius":-37.85952020090287},{"acceleration":-2.9951529378715787,"curvature":-0.017692167177150157,"pose":{"rotation":{"radians":1.8147754899217945},"translation":{"x":7.310670627265081,"y":1.652981319656741}},"time":0.7617673650627029,"velocity":2.089021600885959,"position":0.867034083851772,"holonomicRotation":-130.4400270705185,"angularVelocity":-0.055237439894145306,"angularAcceleration":4.903823089135769,"curveRadius":-56.52218803875667},{"acceleration":-2.9951931441408064,"curvature":-0.008878315540231293,"pose":{"rotation":{"radians":1.8146365811846583},"translation":{"x":7.308777150646981,"y":1.6605920381289851}},"time":0.7655420499723768,"velocity":2.077715690523212,"position":0.8748768059153827,"holonomicRotation":-130.80766368025047,"angularVelocity":-0.03680008807627293,"angularAcceleration":4.8844744022528515,"curveRadius":-112.63397831138006},{"acceleration":-2.9952333446147645,"curvature":0.00003494196989300099,"pose":{"rotation":{"radians":1.8145670306921935},"translation":{"x":7.306888535243731,"y":1.6681854713623825}},"time":0.7693287682025922,"velocity":2.0663735858134102,"position":0.8827015804432179,"holonomicRotation":-131.17530028998246,"angularVelocity":-0.018366957411791583,"angularAcceleration":4.867837938771843,"curveRadius":28618.878759903684},{"acceleration":-2.9952735320174892,"curvature":0.009053905769307076,"pose":{"rotation":{"radians":1.8145673023814408},"translation":{"x":7.305004380172439,"y":1.6757609624418066}},"time":0.7731274560170449,"velocity":2.0549954767463827,"position":0.8905078667194898,"holonomicRotation":-131.54293689971445,"angularVelocity":0.00007152186770608837,"angularAcceleration":4.853907501781438,"curveRadius":110.44957010597794},{"acceleration":-2.9953136987166133,"curvature":0.018186155138407357,"pose":{"rotation":{"radians":1.8146378936172252},"translation":{"x":7.303124284550216,"y":1.6833178544521328}},"time":0.7769380488890154,"velocity":2.0435815557167376,"position":0.8982951240289944,"holonomicRotation":-131.91057350944644,"angularVelocity":0.018525000742953095,"angularAcceleration":4.842679209050354,"curveRadius":54.98688383495086},{"acceleration":-2.9953538367922237,"curvature":0.02743876942126353,"pose":{"rotation":{"radians":1.8147793359375177},"translation":{"x":7.3012478474941735,"y":1.6908554904782345}},"time":0.7807604815248945,"velocity":2.0321320174549773,"position":0.9060628117729291,"holonomicRotation":-132.27821011917842,"angularVelocity":0.03700322118561857,"angularAcceleration":4.834152018591613,"curveRadius":36.44478309676145},{"acceleration":-2.9953939379190393,"curvature":0.03681923510592447,"pose":{"rotation":{"radians":1.8149921958330673},"translation":{"x":7.2993746681214215,"y":1.6983732136049863}},"time":0.7845946878891166,"velocity":2.020647058954856,"position":0.9138103895862204,"holonomicRotation":-132.6458467289104,"angularVelocity":0.05551602478567215,"angularAcceleration":4.828327388113807,"curveRadius":27.159716846999167},{"acceleration":-2.9954339933489496,"curvature":0.04633527932869242,"pose":{"rotation":{"radians":1.815277075564046},"translation":{"x":7.297504345549072,"y":1.7058703669172623}},"time":0.7884406012306353,"velocity":2.0091268793961965,"position":0.9215373174564941,"holonomicRotation":-133.0134833386424,"angularVelocity":0.07407336195104808,"angularAcceleration":4.825209389155843,"curveRadius":21.581827378361464},{"acceleration":-2.995473993747818,"curvature":0.0559948832430883,"pose":{"rotation":{"radians":1.815634614017033},"translation":{"x":7.295636478894236,"y":1.713346293499937}},"time":0.7922981541110968,"velocity":1.997571680063267,"position":0.9292430558448506,"holonomicRotation":-133.3811199483744,"angularVelocity":0.09268530181347791,"angularAcceleration":4.824804854056355,"curveRadius":17.858774625151746},{"acceleration":-2.995513929384795,"curvature":0.06580629421295903,"pose":{"rotation":{"radians":1.8160654876010864},"translation":{"x":7.293770667274023,"y":1.7208003364378852}},"time":0.7961672784348695,"velocity":1.9859816642568846,"position":0.9369270658085933,"holonomicRotation":-133.74875655810638,"angularVelocity":0.11136204163978472,"angularAcceleration":4.827123210167593,"curveRadius":15.196114778380473},{"acceleration":-2.995553789760258,"curvature":0.07577804226563474,"pose":{"rotation":{"radians":1.8165704111848093},"translation":{"x":7.2919065098055444,"y":1.7282318388159803}},"time":0.8000479054810983,"velocity":1.9743570372019077,"position":0.9445888091260712,"holonomicRotation":-134.11639316783837,"angularVelocity":0.1301139165675754,"angularAcceleration":4.832176528278765,"curveRadius":13.196434878781487},{"acceleration":-2.9955935638295674,"curvature":0.0859189525422793,"pose":{"rotation":{"radians":1.8171501390788447},"translation":{"x":7.290043605605912,"y":1.7356401437190974}},"time":0.803939965937976,"velocity":1.9626980059472492,"position":0.9522277484238113,"holonomicRotation":-134.48402977757036,"angularVelocity":0.14895141030271705,"angularAcceleration":4.839979734090092,"curveRadius":11.638875596253534},{"acceleration":-2.995633239726737,"curvature":0.09623816353984167,"pose":{"rotation":{"radians":1.8178054660618208},"translation":{"x":7.288181553792235,"y":1.7430245942321099}},"time":0.8078433899394181,"velocity":1.9510047792597822,"position":0.9598433473061021,"holonomicRotation":-134.85166638730232,"angularVelocity":0.16788516510991403,"angularAcceleration":4.850550388633723,"curveRadius":10.390888221656574},{"acceleration":-2.9956728048352597,"curvature":0.1067451417978551,"pose":{"rotation":{"radians":1.8185372284523433},"translation":{"x":7.286319953481625,"y":1.7503845334398926}},"time":0.8117581071043595,"velocity":1.9392775675101455,"position":0.9674350704872199,"holonomicRotation":-135.21930299703433,"angularVelocity":0.18692599227241508,"angularAcceleration":4.863908773032916,"curveRadius":9.368107842263353},{"acceleration":-2.99571224556055,"curvature":0.11744969946398272,"pose":{"rotation":{"radians":1.8193463052308272},"translation":{"x":7.284458403791193,"y":1.75771930442732}},"time":0.8156840465788939,"velocity":1.927516582550953,"position":0.9750023839264764,"holonomicRotation":-135.5869396067663,"angularVelocity":0.20608488330803776,"angularAcceleration":4.880078044986817,"curveRadius":8.51428317453176},{"acceleration":-2.9957515474728007,"curvature":0.12836201270389522,"pose":{"rotation":{"radians":1.8202336192104664},"translation":{"x":7.282596503838049,"y":1.7650282502792658}},"time":0.819621137081501,"velocity":1.9157220375852275,"position":0.9825447549662882,"holonomicRotation":-135.95457621649828,"angularVelocity":0.2253730207755453,"angularAcceleration":4.899084096424865,"curveRadius":7.790466812847462},{"acceleration":-2.9957906949698603,"curvature":0.13949264079493162,"pose":{"rotation":{"radians":1.8212001382591854},"translation":{"x":7.2807338527393055,"y":1.7723107140806051}},"time":0.8235693069516182,"velocity":1.9038941470261699,"position":0.9900616524734696,"holonomicRotation":-136.32221282623027,"angularVelocity":0.2448017893136427,"angularAcceleration":4.920955576189625,"curveRadius":7.1688369673214645},{"acceleration":-2.9958296713962236,"curvature":0.1508525447398481,"pose":{"rotation":{"radians":1.8222468765774482},"translation":{"x":7.278870049612072,"y":1.7795660389162116}},"time":0.8275284842018368,"velocity":1.8920331263456482,"position":0.9975525469839571,"holonomicRotation":-136.68984943596226,"angularVelocity":0.26438278766253054,"angularAcceleration":4.945724101593828,"curveRadius":6.628989930030974},{"acceleration":-2.99586845876149,"curvature":0.1624531094668006,"pose":{"rotation":{"radians":1.82337489602931},"translation":{"x":7.27700469357346,"y":1.7867935678709594}},"time":0.8314985965740199,"velocity":1.880139191912086,"position":1.0050169108511937,"holonomicRotation":-137.05748604569425,"angularVelocity":0.28412783974711603,"angularAcceleration":4.973423982386623,"curveRadius":6.155622402563879},{"acceleration":-2.9959070378477137,"curvature":0.17430616470881338,"pose":{"rotation":{"radians":1.8245853075322778},"translation":{"x":7.275137383740579,"y":1.7939926440297236}},"time":0.8354795715996647,"velocity":1.8682125608152609,"position":1.0124542183983951,"holonomicRotation":-137.42512265542624,"angularVelocity":0.3040490068816287,"angularAcceleration":5.004092466339009,"curveRadius":5.7370317433726274},{"acceleration":-2.995945387784357,"curvature":0.18642400797786832,"pose":{"rotation":{"radians":1.825879272506121},"translation":{"x":7.2732677192305415,"y":1.8011626104773777}},"time":0.8394713366648479,"velocity":1.8562534506791066,"position":1.0198639460749417,"holonomicRotation":-137.79275926515822,"angularVelocity":0.3241585996955178,"angularAcceleration":5.037769629602762,"curveRadius":5.364115978660414},{"acceleration":-2.9959834863848096,"curvature":0.19881942867837726,"pose":{"rotation":{"radians":1.8272580043839166},"translation":{"x":7.271395299160458,"y":1.8083028102987966}},"time":0.8434738190801327,"velocity":1.8442620794583675,"position":1.0272455726171505,"holonomicRotation":-138.16039587489018,"angularVelocity":0.3444691905529444,"angularAcceleration":5.074498461220824,"curveRadius":5.029689536115017},{"acceleration":-2.9960213094891204,"curvature":0.21150573237742357,"pose":{"rotation":{"radians":1.828722770185623},"translation":{"x":7.269519722647439,"y":1.815412586578854}},"time":0.8474869461558254,"velocity":1.8322386652219045,"position":1.0345985792136836,"holonomicRotation":-138.5280324846222,"angularVelocity":0.36499362568866045,"angularAcceleration":5.1143247518952455,"curveRadius":4.728004242530599},{"acceleration":-2.9960588312628915,"curvature":0.22449676810803434,"pose":{"rotation":{"radians":1.830274892157162},"translation":{"x":7.267640588808595,"y":1.8224912824024246}},"time":0.8515106452830148,"velocity":1.820183425917544,"position":1.0419224496758726,"holonomicRotation":-138.89566909435416,"angularVelocity":0.3857450377069516,"angularAcceleration":5.157297144328599,"curveRadius":4.454407109855457},{"acceleration":-2.996096023768408,"curvature":0.23780695466908963,"pose":{"rotation":{"radians":1.8319157494789884},"translation":{"x":7.2657574967610365,"y":1.8295382408543825}},"time":0.8555448440208511,"velocity":1.8080965791200212,"position":1.0492166706132446,"holonomicRotation":-139.26330570408618,"angularVelocity":0.4067368586571785,"angularAcceleration":5.203467234607716,"curveRadius":4.205091484357589},{"acceleration":-2.9961328569860157,"curvature":0.25145130978734104,"pose":{"rotation":{"radians":1.833646780041589},"translation":{"x":7.263870045621876,"y":1.836552805019602}},"time":0.8595894701905592,"velocity":1.7959783417587332,"position":1.056480731614551,"holonomicRotation":-139.63094231381814,"angularVelocity":0.4279828320266033,"angularAcceleration":5.2528892604574,"curveRadius":3.9769130685607728},{"acceleration":-2.9961692985439883,"curvature":0.26544548003056406,"pose":{"rotation":{"radians":1.8354694822957012},"translation":{"x":7.261977834508223,"y":1.8435343179829577}},"time":0.8636444519767182,"velocity":1.7838289298248884,"position":1.0637141254346145,"holonomicRotation":-139.99857892355013,"angularVelocity":0.44949702618484144,"angularAcceleration":5.3056204177471304,"curveRadius":3.7672519414715873},{"acceleration":-2.9962053134888436,"curvature":0.2798057721006166,"pose":{"rotation":{"radians":1.8373854171743194},"translation":{"x":7.260080462537189,"y":1.8504821228293236}},"time":0.8677097180363773,"velocity":1.771648558056192,"position":1.0709163481873243,"holonomicRotation":-140.36621553328212,"angularVelocity":0.4712938465776249,"angularAcceleration":5.361720505597474,"curveRadius":3.5739076877956815},{"acceleration":-2.9962408642728056,"curvature":0.29454918537511543,"pose":{"rotation":{"radians":1.8393962100916426},"translation":{"x":7.258177528825884,"y":1.8573955626435739}},"time":0.8717851976166274,"velocity":1.7594374395963372,"position":1.0780868995451267,"holonomicRotation":-140.7338521430141,"angularVelocity":0.493388048628082,"angularAcceleration":5.4212520552246595,"curveRadius":3.39501872574007},{"acceleration":-2.996275910331256,"curvature":0.30969344641751206,"pose":{"rotation":{"radians":1.8415035530196546},"translation":{"x":7.2562686324914205,"y":1.8642739805105832}},"time":0.8758708206812901,"velocity":1.7471957856289948,"position":1.085225282945374,"holonomicRotation":-141.1014887527461,"angularVelocity":0.5157947501909536,"angularAcceleration":5.484280171773921,"curveRadius":3.228999552841211},{"acceleration":-2.9963104080024188,"curvature":0.3252570442456091,"pose":{"rotation":{"radians":1.8437092066456906},"translation":{"x":7.2543533726509075,"y":1.8711167195152256}},"time":0.8799665180474391,"velocity":1.7349238049827744,"position":1.092331005803911,"holonomicRotation":-141.46912536247808,"angularVelocity":0.5385294441590656,"angularAcceleration":5.550872521982347,"curveRadius":3.074491445125711},{"acceleration":-2.99634431019691,"curvature":0.3412592677928691,"pose":{"rotation":{"radians":1.8460150026097697},"translation":{"x":7.252431348421456,"y":1.8779231227423756}},"time":0.8840722215325265,"velocity":1.722621703705877,"position":1.0994035797363035,"holonomicRotation":-141.83676197221007,"angularVelocity":0.561608010041181,"angularAcceleration":5.62109903112596,"curveRadius":2.9303233476049084},{"acceleration":-2.9963775661492704,"curvature":0.3577202447249472,"pose":{"rotation":{"radians":1.8484228458269687},"translation":{"x":7.250502158920178,"y":1.884692533276907}},"time":0.8881878641129417,"velocity":1.7102896846076323,"position":1.1064425207871196,"holonomicRotation":-142.20439858194206,"angularVelocity":0.5850467260342358,"angularAcceleration":5.695031950682724,"curveRadius":2.7954805878233278},{"acceleration":-2.996410121211035,"curvature":0.3746609810410045,"pose":{"rotation":{"radians":1.85093471689567},"translation":{"x":7.248565403264184,"y":1.8914242942036945}},"time":0.892313380094905,"velocity":1.6979279467640596,"position":1.1134473496677169,"holonomicRotation":-142.57203519167405,"angularVelocity":0.6088622804233894,"angularAcceleration":5.772745637945611,"curveRadius":2.669079649611433},{"acceleration":-2.996441916418058,"curvature":0.39210340402776417,"pose":{"rotation":{"radians":1.8535526745894517},"translation":{"x":7.246620680570585,"y":1.8981177486076124}},"time":0.8964487052986548,"velocity":1.6855366849855236,"position":1.1204175920029824,"holonomicRotation":-142.939671801406,"angularVelocity":0.6330717814908,"angularAcceleration":5.854316135876806,"curveRadius":2.550347662702749},{"acceleration":-2.9964728882948615,"curvature":0.4100704046550046,"pose":{"rotation":{"radians":1.856278858440462},"translation":{"x":7.2446675899564905,"y":1.904772239573535}},"time":0.9005937772569803,"velocity":1.67311608924237,"position":1.1273527785875241,"holonomicRotation":-143.30730841113802,"angularVelocity":0.6576927682846604,"angularAcceleration":5.939821320691079,"curveRadius":2.4386056361256006},{"acceleration":-2.99650296832765,"curvature":0.4285858835389222,"pose":{"rotation":{"radians":1.8591154914084198},"translation":{"x":7.242705730539012,"y":1.9113871101863364}},"time":0.9047485354292197,"velocity":1.660666344046571,"position":1.1342524456518146,"holonomicRotation":-143.67494502086998,"angularVelocity":0.6827432188258826,"angularAcceleration":6.0293402173441,"curveRadius":2.333254636720168},{"acceleration":-2.996532082845079,"curvature":0.44767479716290465,"pose":{"rotation":{"radians":1.8620648826414625},"translation":{"x":7.240734701435261,"y":1.9179617035308907}},"time":0.9089129214319457,"velocity":1.6481876277840517,"position":1.1411161351388246,"holonomicRotation":-144.042581630602,"angularVelocity":0.708241558566398,"angularAcceleration":6.122952993268285,"curveRadius":2.2337643448713274},{"acceleration":-2.9965601522643173,"curvature":0.4673632062611831,"pose":{"rotation":{"radians":1.8651294303249415},"translation":{"x":7.238754101762348,"y":1.9244953626920729}},"time":0.9130868792876501,"velocity":1.6356801119964173,"position":1.1479433949917115,"holonomicRotation":-144.41021824033396,"angularVelocity":0.7342066665313256,"angularAcceleration":6.2207403290960315,"curveRadius":2.13966351352262},{"acceleration":-2.996587091010228,"curvature":0.48767832548057577,"pose":{"rotation":{"radians":1.8683116246221227},"translation":{"x":7.236763530637383,"y":1.9309874307547565}},"time":0.917270355692849,"velocity":1.6231439606050524,"position":1.1547337794531438,"holonomicRotation":-144.77785485006595,"angularVelocity":0.7606578809017953,"angularAcceleration":6.322783209102896,"curveRadius":2.050531975179672},{"acceleration":-2.9966128067568762,"curvature":0.5086485744933235,"pose":{"rotation":{"radians":1.8716140507005299},"translation":{"x":7.234762587177478,"y":1.937437250803816}},"time":0.9214633003071447,"velocity":1.6105793290758315,"position":1.1614868493768884,"holonomicRotation":-145.14549145979794,"angularVelocity":0.787615001435408,"angularAcceleration":6.429162083778287,"curveRadius":1.9659939104245459},{"acceleration":-2.9966372000888257,"curvature":0.5303036308131002,"pose":{"rotation":{"radians":1.8750393918507213},"translation":{"x":7.232750870499744,"y":1.9438441659241263}},"time":0.9256656660649084,"velocity":1.5979863635177374,"position":1.1682021725523086,"holonomicRotation":-145.51312806952993,"angularVelocity":0.8150982916856502,"angularAcceleration":6.539956737337329,"curveRadius":1.8857121503519167},{"acceleration":-2.996660163838976,"curvature":0.5526744831331435,"pose":{"rotation":{"radians":1.8785904326870415},"translation":{"x":7.230727979721291,"y":1.9502075192005612}},"time":0.9298774095113739,"velocity":1.5853651997114044,"position":1.1748793240424475,"holonomicRotation":-145.88076467926192,"angularVelocity":0.8431284767120019,"angularAcceleration":6.655245121797453,"curveRadius":1.8093833359755318},{"acceleration":-2.9966815825803415,"curvature":0.5757934861923202,"pose":{"rotation":{"radians":1.8822700624345496},"translation":{"x":7.2286935139592305,"y":1.9565266537179948}},"time":0.934098491165098,"velocity":1.5727159620611215,"position":1.1815178865364229,"holonomicRotation":-146.2484012889939,"angularVelocity":0.8717267395814746,"angularAcceleration":6.775102974907222,"curveRadius":1.736733783865681},{"acceleration":-2.9967013319271696,"curvature":0.5996944164566809,"pose":{"rotation":{"radians":1.8860812782955483},"translation":{"x":7.226647072330671,"y":1.9628009125613017}},"time":0.9383288759088884,"velocity":1.5600387624648406,"position":1.1881174507168757,"holonomicRotation":-146.6160378987259,"angularVelocity":0.9009147138668688,"angularAcceleration":6.899602767393299,"curveRadius":1.6675159423836914},{"acceleration":-2.996719277864485,"curvature":0.6244125287035381,"pose":{"rotation":{"radians":1.8900271888893854},"translation":{"x":7.224588253952727,"y":1.9690296388153563}},"time":0.9425685334114787,"velocity":1.5473336990952853,"position":1.194677615643256,"holonomicRotation":-146.98367450845788,"angularVelocity":0.9307144719652936,"angularAcceleration":7.028812605786558,"curveRadius":1.6015053414707912},{"acceleration":-2.9967352760277906,"curvature":0.6499846116299796,"pose":{"rotation":{"radians":1.8941110177677127},"translation":{"x":7.222516657942507,"y":1.9752121755650327}},"time":0.9468174385824345,"velocity":1.5346008550849852,"position":1.2011979891517797,"holonomicRotation":-147.35131111818987,"angularVelocity":0.9611485109724691,"angularAcceleration":7.162795539710656,"curveRadius":1.5384979615013958},{"acceleration":-2.9967491708732186,"curvature":0.6764490452439145,"pose":{"rotation":{"radians":1.8983361069862168},"translation":{"x":7.220431883417123,"y":1.9813478658952048}},"time":0.95107557206296,"velocity":1.521840297107753,"position":1.207678188272907,"holonomicRotation":-147.71894772792186,"angularVelocity":0.9922397308180757,"angularAcceleration":7.30160761465128,"curveRadius":1.478307947998388},{"acceleration":-2.9967607948092634,"curvature":0.703845856312768,"pose":{"rotation":{"radians":1.9027059207359727},"translation":{"x":7.218333529493685,"y":1.9874360528907475}},"time":0.9553429207555236,"velocity":1.5090520738480977,"position":1.2141178396672532,"holonomicRotation":-148.08658433765385,"angularVelocity":1.0240114095599464,"angularAcceleration":7.44529707573153,"curveRadius":1.4207656279155958},{"acceleration":-2.996769967297934,"curvature":0.7322167736747859,"pose":{"rotation":{"radians":1.9072240490170014},"translation":{"x":7.216221195289304,"y":1.993476079636535}},"time":0.9596194783954529,"velocity":1.496236214349339,"position":1.2205165800808677,"holonomicRotation":-148.4542209473858,"angularVelocity":1.0564871706261896,"angularAcceleration":7.593902339354447,"curveRadius":1.3657157770113446},{"acceleration":-2.9967764938260832,"curvature":0.7616052812652144,"pose":{"rotation":{"radians":1.9118942113454411},"translation":{"x":7.214094479921091,"y":1.9994672892174414}},"time":0.9639052461679307,"velocity":1.4833927262307802,"position":1.2268740568208756,"holonomicRotation":-148.82185755711782,"angularVelocity":1.0896909436928537,"angularAcceleration":7.747450358811084,"curveRadius":1.3130161050600293},{"acceleration":-2.9967801649084107,"curvature":0.7920566694703481,"pose":{"rotation":{"radians":1.9167202604782738},"translation":{"x":7.211952982506157,"y":2.005409024718341}},"time":0.9682002333741125,"velocity":1.4705215937627591,"position":1.2331899282525007,"holonomicRotation":-149.18949416684978,"angularVelocity":1.1236469170121166,"angularAcceleration":7.905954474180906,"curveRadius":1.262535925199272},{"acceleration":-2.99678075474154,"curvature":0.8236180829076898,"pose":{"rotation":{"radians":1.9217061861408213},"translation":{"x":7.209796302161611,"y":2.0113006292241087}},"time":0.972504458150415,"velocity":1.4576227757890543,"position":1.2394638643185547,"holonomicRotation":-149.55713077658177,"angularVelocity":1.1583794810155577,"angularAcceleration":8.069412219051959,"curveRadius":1.2141549836662326},{"acceleration":-2.996778020193093,"curvature":0.8563385644704642,"pose":{"rotation":{"radians":1.9268561187353968},"translation":{"x":7.207624038004567,"y":2.0171414458196177}},"time":0.9768179482453686,"velocity":1.4446962034821766,"position":1.2456955470824922,"holonomicRotation":-149.92476738631376,"angularVelocity":1.1939131610851126,"angularAcceleration":8.237802634837603,"curveRadius":1.1677624265565711},{"acceleration":-2.996771699269451,"curvature":0.8902690938236264,"pose":{"rotation":{"radians":1.9321743330114287},"translation":{"x":7.205435789152135,"y":2.0229308175897427}},"time":0.9811407418588343,"velocity":1.43174177791956,"position":1.2518846712962148,"holonomicRotation":-150.29240399604575,"angularVelocity":1.2302725393748923,"angularAcceleration":8.411083558678113,"curveRadius":1.1232558862681497},{"acceleration":-2.9967615097796974,"curvature":0.9254626191531629,"pose":{"rotation":{"radians":1.9376652516698019},"translation":{"x":7.203231154721424,"y":2.0286680876193586}},"time":0.9854728885487866,"velocity":1.4187593674643915,"position":1.2580309449938145,"holonomicRotation":-150.66004060577774,"angularVelocity":1.2674821633137279,"angularAcceleration":8.589188363620542,"curveRadius":1.0805406715562882},{"acceleration":-2.9967471476868157,"curvature":0.9619740823871745,"pose":{"rotation":{"radians":1.9433334488685146},"translation":{"x":7.201009733829546,"y":2.034352598993339}},"time":0.9898144502113406,"velocity":1.4057488049356262,"position":1.2641340901125042,"holonomicRotation":-151.02767721550973,"angularVelocity":1.3055664388233525,"angularAcceleration":8.772022251371272,"curveRadius":1.0395290458537747},{"acceleration":-2.9967282855356085,"curvature":0.9998604328264167,"pose":{"rotation":{"radians":1.9491836536041294},"translation":{"x":7.198771125593612,"y":2.0399836947965584}},"time":0.9941655021402246,"velocity":1.3927098845485053,"position":1.2701938431420448,"holonomicRotation":-151.39531382524171,"angularVelocity":1.3445495092299167,"angularAcceleration":8.959458780020398,"curveRadius":1.0001395866552982},{"acceleration":-2.996704570604492,"curvature":1.0391806305769775,"pose":{"rotation":{"radians":1.9552207529211758},"translation":{"x":7.196514929130732,"y":2.045560718113891}},"time":0.9985261341724402,"velocity":1.3796423586068405,"position":1.2762099558039872,"holonomicRotation":-151.7629504349737,"angularVelocity":1.384455113948022,"angularAcceleration":9.151335041179703,"curveRadius":0.9622966119420224},{"acceleration":-2.996675622916703,"curvature":1.0799956358782292,"pose":{"rotation":{"radians":1.9614497949097802},"translation":{"x":7.1942407435580185,"y":2.0510830120302117}},"time":1.0028964519274848,"velocity":1.3665459339258983,"position":1.2821821957621076,"holonomicRotation":-152.1305870447057,"angularVelocity":1.4253064279855436,"angularAcceleration":9.34744710275761,"curveRadius":0.9259296674720555},{"acceleration":-2.9966410332031765,"curvature":1.122368381981407,"pose":{"rotation":{"radians":1.9678759914434414},"translation":{"x":7.191948167992581,"y":2.0565499196303936}},"time":1.0072765781481923,"velocity":1.353420267962317,"position":1.2881103473654463,"holonomicRotation":-152.49822365443768,"angularVelocity":1.4671258794508406,"angularAcceleration":9.547544832747345,"curveRadius":0.8909730673583479},{"acceleration":-2.9966003607588583,"curvature":1.1663637293833562,"pose":{"rotation":{"radians":1.9745047205951638},"translation":{"x":7.189636801551529,"y":2.061960783999312}},"time":1.0116666541519992,"velocity":1.3402649646255504,"position":1.293994212425392,"holonomicRotation":-152.86586026416967,"angularVelocity":1.5099349409837577,"angularAcceleration":9.751325830303294,"curveRadius":0.857365481116846},{"acceleration":-2.9965531308513884,"curvature":1.212048398111755,"pose":{"rotation":{"radians":1.9813415286742166},"translation":{"x":7.187306243351977,"y":2.067314948221841}},"time":1.0160668414022662,"velocity":1.3270795697444304,"position":1.2998336110282713,"holonomicRotation":-153.23349687390163,"angularVelocity":1.5537538950502503,"angularAcceleration":9.958429397256541,"curveRadius":0.825049562012454},{"acceleration":-2.9964988322697286,"curvature":1.2594908731661298,"pose":{"rotation":{"radians":1.988392131810084},"translation":{"x":7.184956092511033,"y":2.072611755382855}},"time":1.0204773232102256,"velocity":1.3138635661571334,"position":1.305628382384948,"holonomicRotation":-153.60113348363365,"angularVelocity":1.5986015684598107,"angularAcceleration":10.168429519112063,"curveRadius":0.7939716128995701},{"acceleration":-2.996436914578297,"curvature":1.3087612822936086,"pose":{"rotation":{"radians":1.9956624170006472},"translation":{"x":7.182585948145809,"y":2.077850548567228}},"time":1.024898306579116,"velocity":1.3006163683918535,"position":1.311378385718915,"holonomicRotation":-153.9687700933656,"angularVelocity":1.6444950328750034,"angularAcceleration":10.380827201960544,"curveRadius":0.7640812832172852},{"acceleration":-2.99636678503113,"curvature":1.3599312378438648,"pose":{"rotation":{"radians":2.0031584425427025},"translation":{"x":7.1801954093734155,"y":2.083030670859834}},"time":1.0293300242032253,"velocity":1.2873373169023352,"position":1.3170835011944046,"holonomicRotation":-154.33640670309762,"angularVelocity":1.6914492704308624,"angularAcceleration":10.595042721228364,"curveRadius":0.7353312962980935},{"acceleration":-2.9962878054987385,"curvature":1.4130736411455118,"pose":{"rotation":{"radians":2.010886437738225},"translation":{"x":7.177784075310963,"y":2.0881514653455477}},"time":1.0337727366357936,"velocity":1.274025671817293,"position":1.3227436308859986,"holonomicRotation":-154.70404331282958,"angularVelocity":1.7394767977487402,"angularAcceleration":10.810406490818755,"curveRadius":0.7076772015854371},{"acceleration":-2.9961992890068965,"curvature":1.4682624420980936,"pose":{"rotation":{"radians":2.0188528017724643},"translation":{"x":7.1753515450755625,"y":2.0932122751092432}},"time":1.038226734641148,"velocity":1.260680606160412,"position":1.328358699791226,"holonomicRotation":-155.07167992256157,"angularVelocity":1.788587247830495,"angularAcceleration":11.026149994390735,"curveRadius":0.6810771503294986},{"acceleration":-2.996100496118306,"curvature":1.5255723489667705,"pose":{"rotation":{"radians":2.027064101638331},"translation":{"x":7.172897417784326,"y":2.0982124432357954}},"time":1.0426923417479972,"velocity":1.2473011984921119,"position":1.3339286568875939,"holonomicRotation":-155.43931653229356,"angularVelocity":1.838786903861822,"angularAcceleration":11.241395588593726,"curveRadius":0.655491691808175},{"acceleration":-2.9959906309786417,"curvature":1.585078481410167,"pose":{"rotation":{"radians":2.035527068975763},"translation":{"x":7.170421292554363,"y":2.1031513128100783}},"time":1.0471699170225572,"velocity":1.2338864249200283,"position":1.339453476235431,"holonomicRotation":-155.80695314202555,"angularVelocity":1.8900781826082556,"angularAcceleration":11.455146055913739,"curveRadius":0.6308835882437498},{"acceleration":-2.995868837182456,"curvature":1.646855960532347,"pose":{"rotation":{"radians":2.0442485956762324},"translation":{"x":7.167922768502784,"y":2.1080282269169657}},"time":1.0516598580821492,"velocity":1.2204351504188107,"position":1.3449331581278658,"holonomicRotation":-156.17458975175754,"angularVelocity":1.942459062316059,"angularAcceleration":11.666273345816094,"curveRadius":0.607217646209174},{"acceleration":-2.9957341932406347,"curvature":1.7109794280121493,"pose":{"rotation":{"radians":2.0532357280942524},"translation":{"x":7.1654014447467,"y":2.1128425286413317}},"time":1.0561626043721102,"velocity":1.2069461193944873,"position":1.3503677302891521,"holonomicRotation":-156.54222636148953,"angularVelocity":1.9959224524946328,"angularAcceleration":11.873507130031445,"curveRadius":0.5844605631301016},{"acceleration":-2.9955857078412973,"curvature":1.777522486448095,"pose":{"rotation":{"radians":2.0624956596887545},"translation":{"x":7.1628569204032235,"y":2.117593561068052}},"time":1.0606786407313433,"velocity":1.1934179454206768,"position":1.3557572491224332,"holonomicRotation":-156.90986297122151,"angularVelocity":2.050455500777792,"angularAcceleration":12.075422770161067,"curveRadius":0.5625807873734602},{"acceleration":-2.995422314692802,"curvature":1.846557052397576,"pose":{"rotation":{"radians":2.0720357219052934},"translation":{"x":7.160288794589465,"y":2.1222806672819994}},"time":1.0652085012746393,"velocity":1.1798491000668416,"position":1.3611018010078693,"holonomicRotation":-157.27749958095347,"angularVelocity":2.106038833945535,"angularAcceleration":12.270429218843073,"curveRadius":0.5415483906666174},{"acceleration":-2.995242867040772,"curvature":1.9181526135606386,"pose":{"rotation":{"radians":2.0818633730910245},"translation":{"x":7.157696666422533,"y":2.1269031903680484}},"time":1.0697527736230938,"velocity":1.1662379007292425,"position":1.3664015036518729,"holonomicRotation":-157.6451361906855,"angularVelocity":2.162645728985277,"angularAcceleration":12.45675670363221,"curveRadius":0.5213349516249985},{"acceleration":-2.995046131880508,"curvature":1.9923753818264407,"pose":{"rotation":{"radians":2.0919861852241626},"translation":{"x":7.155080135019539,"y":2.1314604734110745}},"time":1.0743121035175558,"velocity":1.152582497364867,"position":1.371656507487942,"holonomicRotation":-158.01277280041745,"angularVelocity":2.220241212515428,"angularAcceleration":12.632444868731742,"curveRadius":0.5019134492031742},{"acceleration":-2.994830783551772,"curvature":2.0692873308074304,"pose":{"rotation":{"radians":2.102411828225033},"translation":{"x":7.152438799497596,"y":2.135951859495951}},"time":1.0788871998541858,"velocity":1.1388808580182126,"position":1.3768669971293193,"holonomicRotation":-158.38040941014947,"angularVelocity":2.2787810865093046,"angularAcceleration":12.795331439293088,"curveRadius":0.48325816580039793},{"acceleration":-2.994595397092012,"curvature":2.14894511198843,"pose":{"rotation":{"radians":2.1131480515933365},"translation":{"x":7.149772258973814,"y":2.140376691707552}},"time":1.0834788401859416,"velocity":1.1251307530156345,"position":1.3820331928733647,"holonomicRotation":-158.74804601988143,"angularVelocity":2.338210877287493,"angularAcceleration":12.94304137176667,"curveRadius":0.46534459834327496},{"acceleration":-2.9943384410122653,"curvature":2.23139883751846,"pose":{"rotation":{"radians":2.124202663115966},"translation":{"x":7.147080112565302,"y":2.1447343131307526}},"time":1.088087876739244,"velocity":1.1113297376880509,"position":1.3871553522571407,"holonomicRotation":-159.11568262961345,"angularVelocity":2.3984647105281076,"angularAcceleration":13.072977951855123,"curveRadius":0.44814937750532335},{"acceleration":-2.994058269502917,"curvature":2.3166907253110995,"pose":{"rotation":{"radians":2.1355835043663998},"translation":{"x":7.1443619593891725,"y":2.1490240668504264}},"time":1.092715243001363,"velocity":1.0974751334649346,"position":1.392233771663251,"holonomicRotation":-159.4833192393454,"angularVelocity":2.4594641110647815,"angularAcceleration":13.182315183484164,"curveRadius":0.4316501935603484},{"acceleration":-2.9937531140847278,"curvature":2.4048535957251493,"pose":{"rotation":{"radians":2.147298422723193},"translation":{"x":7.141617398562537,"y":2.1532452959514483}},"time":1.0973619609413812,"velocity":1.0835640071617316,"position":1.3972687879744874,"holonomicRotation":-159.8509558490774,"angularVelocity":2.5211167340075873,"angularAcceleration":13.267993396337642,"curveRadius":0.41582572917436345},{"acceleration":-2.9934210745421845,"curvature":2.4959092171050927,"pose":{"rotation":{"radians":2.15935523961212},"translation":{"x":7.138846029202504,"y":2.1573973435186913}},"time":1.1020291489360265,"velocity":1.0695931482597099,"position":1.4022607802752,"holonomicRotation":-160.21859245880938,"angularVelocity":2.58331502882671,"angularAcceleration":13.326717263260518,"curveRadius":0.40065559802686285},{"acceleration":-2.993060109078571,"curvature":2.589866497114627,"pose":{"rotation":{"radians":2.171761714690315},"translation":{"x":7.1360474504261875,"y":2.1614795526370316}},"time":1.1067180304816377,"velocity":1.0555590439493463,"position":1.4072101715966772,"holonomicRotation":-160.58622906854137,"angularVelocity":2.645934847683964,"angularAcceleration":13.354958586203994,"curveRadius":0.38612028886975486},{"acceleration":-2.9926680236628274,"curvature":2.6867195163387354,"pose":{"rotation":{"radians":2.1845255056951833},"translation":{"x":7.133221261350695,"y":2.1654912663913426}},"time":1.1114299437851531,"velocity":1.0414578516756443,"position":1.4121174307030382,"holonomicRotation":-160.95386567827336,"angularVelocity":2.708834009179613,"angularAcceleration":13.34896409251042,"curveRadius":0.3722011151215095},{"acceleration":-2.9922424601326902,"curvature":2.7864454120106026,"pose":{"rotation":{"radians":2.1976541236783937},"translation":{"x":7.130367061093139,"y":2.1694318278664975}},"time":1.1161663523407894,"velocity":1.0272853688869337,"position":1.4169830739133142,"holonomicRotation":-161.32150228800535,"angularVelocity":2.77185082937735,"angularAcceleration":13.304768678104756,"curveRadius":0.3588801688666259},{"acceleration":-2.9917808832906942,"curvature":2.8890021152028216,"pose":{"rotation":{"radians":2.2111548833886108},"translation":{"x":7.127484448770631,"y":2.173300580147372}},"time":1.1209288566154116,"velocity":1.0130369996415287,"position":1.4218076669544575,"holonomicRotation":-161.68913889773734,"angularVelocity":2.8348026440958884,"angularAcceleration":13.218216948168942,"curveRadius":0.3461402796272426},{"acceleration":-2.991280566285231,"curvature":2.9943259564636464,"pose":{"rotation":{"radians":2.2250348485752247},"translation":{"x":7.124573023500281,"y":2.177096866318841}},"time":1.1257192069850304,"velocity":0.998707717675191,"position":1.426591826838964,"holonomicRotation":-162.0567755074693,"angularVelocity":2.8974843415720097,"angularAcceleration":13.084992253105339,"curveRadius":0.33396497727355584},{"acceleration":-2.990738574401648,"curvature":3.1023291591642828,"pose":{"rotation":{"radians":2.2393007720389866},"translation":{"x":7.121632384399199,"y":2.1808200294657767}},"time":1.1305393180882293,"velocity":0.9842920254659523,"position":1.4313362237597025,"holonomicRotation":-162.4244121172013,"angularVelocity":2.959666936783712,"angularAcceleration":12.900655997417585,"curveRadius":0.3223384588466376},{"acceleration":-2.9901517464199414,"curvature":3.212897246767242,"pose":{"rotation":{"radians":2.2539590303085766},"translation":{"x":7.118662130584497,"y":2.1844694126730544}},"time":1.1353912847904157,"velocity":0.969783908757838,"position":1.4360415829933117,"holonomicRotation":-162.79204872693327,"angularVelocity":3.0210962212466312,"angularAcceleration":12.660697864071754,"curveRadius":0.3112455591308379},{"acceleration":-2.9895166734103498,"curvature":3.325886398918693,"pose":{"rotation":{"radians":2.2690155528883},"translation":{"x":7.115661861173286,"y":2.188044359025549}},"time":1.1402773999868347,"velocity":0.9551767859099397,"position":1.440708686802213,"holonomicRotation":-163.1596853366653,"angularVelocity":3.0814915274118433,"angularAcceleration":12.36059809017093,"curveRadius":0.300671724784442},{"acceleration":-2.988829674098045,"curvature":3.441120801640725,"pose":{"rotation":{"radians":2.2844757461103513},"translation":{"x":7.112631175282676,"y":2.1915442116081345}},"time":1.1452001745137783,"velocity":0.9404634513249168,"position":1.4453383763239167,"holonomicRotation":-163.52732194639725,"angularVelocity":3.1405446537179014,"angularAcceleration":11.995903119845467,"curveRadius":0.29060299177035587},{"acceleration":-2.9880867658924206,"curvature":3.5583900461614593,"pose":{"rotation":{"radians":2.300344411726139},"translation":{"x":7.109569672029778,"y":2.194968313505684}},"time":1.150162359488234,"velocity":0.9256360120728356,"position":1.4499315534348396,"holonomicRotation":-163.89495855612927,"angularVelocity":3.197919000899062,"angularAcceleration":11.562315285809014,"curveRadius":0.28102596596422297},{"acceleration":-2.9844930140551056,"curvature":3.677446643050121,"pose":{"rotation":{"radians":2.3166256604973965},"translation":{"x":7.106476950531704,"y":2.1983160078030735}},"time":1.1551668934314077,"velocity":0.9107000154808321,"position":1.4544891825743622,"holonomicRotation":-164.26259516586123,"angularVelocity":3.2532996990590175,"angularAcceleration":11.066105013733866,"curveRadius":0.27192780672694883},{"acceleration":-2.9154800422087495,"curvature":3.7980037267464377,"pose":{"rotation":{"radians":2.3333228211873784},"translation":{"x":7.103352609905563,"y":2.2015866375851765}},"time":1.1602151083606265,"velocity":0.8959820456059144,"position":1.459012292513302,"holonomicRotation":-164.63023177559322,"angularVelocity":3.3075375997443457,"angularAcceleration":10.743976127363755,"curveRadius":0.2632962134707147},{"acceleration":-2.7850148387056852,"curvature":3.9197330429183315,"pose":{"rotation":{"radians":2.3504383455067654},"translation":{"x":7.100196249268468,"y":2.204779545936867}},"time":1.165306596751143,"velocity":0.8818021748872285,"position":1.4635019780494725,"holonomicRotation":-164.9978683853252,"angularVelocity":3.3615954720169716,"angularAcceleration":10.617302471575082,"curveRadius":0.25511941477919553},{"acceleration":-2.655729570653438,"curvature":4.042263312866856,"pose":{"rotation":{"radians":2.367973709763863},"translation":{"x":7.0970074677375266,"y":2.20789407594302}},"time":1.170440890244211,"velocity":0.8681668798332741,"position":1.4679594016114976,"holonomicRotation":-165.3655049950572,"angularVelocity":3.4153412306430186,"angularAcceleration":10.46799500235246,"curveRadius":0.24738616032679459},{"acceleration":-2.5275353484106104,"curvature":4.165179088732326,"pose":{"rotation":{"radians":2.385929314142746},"translation":{"x":7.093785864429853,"y":2.210929570688509}},"time":1.1756174561678656,"velocity":0.8550829264778591,"position":1.4723857947506018,"holonomicRotation":-165.73314160478918,"angularVelocity":3.4686324184212034,"angularAcceleration":10.294698949870803,"curveRadius":0.24008571509090873},{"acceleration":-2.4003475324952377,"curvature":4.288020209971673,"pose":{"rotation":{"radians":2.4043043807649243},"translation":{"x":7.090531038462556,"y":2.213885373258209}},"time":1.1808356941801972,"velocity":0.8425573417409862,"position":1.4767824594988437,"holonomicRotation":-166.10077821452117,"angularVelocity":3.5213163099795186,"angularAcceleration":10.096107428180622,"curveRadius":0.23320785608111813},{"acceleration":-2.274085447465522,"curvature":4.4102819841075345,"pose":{"rotation":{"radians":2.42309685188634},"translation":{"x":7.087242588952747,"y":2.2167608267369943}},"time":1.186094933086102,"velocity":0.8305973830803237,"position":1.4811507695710824,"holonomicRotation":-166.46841482425316,"angularVelocity":3.573230168402615,"angularAcceleration":9.870983112178246,"curveRadius":0.2267428712276229},{"acceleration":-2.1486721424712734,"curvature":4.531416209994003,"pose":{"rotation":{"radians":2.4423032898160266},"translation":{"x":7.083920115017537,"y":2.219555274209738}},"time":1.191394427883772,"velocity":0.8192105062393985,"position":1.4854921713870948,"holonomicRotation":-166.83605143398512,"angularVelocity":3.624201676380695,"angularAcceleration":9.61818247288194,"curveRadius":0.22068156039043774},{"acceleration":-2.024034151963125,"curvature":4.650833156999703,"pose":{"rotation":{"radians":2.461918780353325},"translation":{"x":7.080563215774037,"y":2.222268058761316}},"time":1.1967333571004364,"velocity":0.8084043311699561,"position":1.489808184889656,"holonomicRotation":-167.20368804371714,"angularVelocity":3.6740495596144345,"angularAcceleration":9.33668179719446,"curveRadius":0.21501523839765296},{"acceleration":-1.900101283531904,"curvature":4.767904604572136,"pose":{"rotation":{"radians":2.4819368417380527},"translation":{"x":7.077171490339358,"y":2.2248985234766017}},"time":1.2021108204801376,"velocity":0.79818660610004,"position":1.494100404134127,"holonomicRotation":-167.5713246534491,"angularVelocity":3.7225844178301015,"angularAcceleration":9.02560459990776,"curveRadius":0.20973573989736702},{"acceleration":-1.776806418393548,"curvature":4.881968024450813,"pose":{"rotation":{"radians":2.502349341288951},"translation":{"x":7.07374453783061,"y":2.227446011440469}},"time":1.2075258370881559,"velocity":0.7885651698352055,"position":1.4983704976252894,"holonomicRotation":-167.9389612631811,"angularVelocity":3.7696097774977564,"angularAcceleration":8.68425031199765,"curveRadius":0.2048354259986152},{"acceleration":-1.6540853387361514,"curvature":4.992331968219871,"pose":{"rotation":{"radians":2.5231464220362323},"translation":{"x":7.070281957364903,"y":2.229909865737794}},"time":1.2129773438976668,"velocity":0.7795479123475733,"position":1.5026202083777922,"holonomicRotation":-168.30659787291307,"angularVelocity":3.8149233732952355,"angularAcceleration":8.312123121340198,"curveRadius":0.2003071923833969},{"acceleration":-1.5318765591359311,"curvature":5.098282680376779,"pose":{"rotation":{"radians":2.5443164417575725},"translation":{"x":7.06678334805935,"y":2.2322894294534485}},"time":1.2184641949229305,"velocity":0.7711427338785009,"position":1.506851353677798,"holonomicRotation":-168.6742344826451,"angularVelocity":3.8583186647249694,"angularAcceleration":7.908961119943733,"curveRadius":0.1961444789730837},{"acceleration":-1.4101211761760246,"curvature":5.1990919276472445,"pose":{"rotation":{"radians":2.5658459268296503},"translation":{"x":7.063248309031062,"y":2.2345840456723085}},"time":1.2239851609606798,"velocity":0.7633575027557219,"position":1.5110658245251736,"holonomicRotation":-169.04187109237705,"angularVelocity":3.899586580477222,"angularAcceleration":7.4747635595084985,"curveRadius":0.19234128073063944},{"acceleration":-1.2887627393275725,"curvature":5.294025977192384,"pose":{"rotation":{"radians":2.5877195432864784},"translation":{"x":7.0596764393971485,"y":2.2367930574792485}},"time":1.229538929996986,"velocity":0.7562000121588991,"position":1.5152655847379561,"holonomicRotation":-169.40950770210904,"angularVelocity":3.938517484943096,"angularAcceleration":7.009816974989981,"curveRadius":0.18889215963581965},{"acceleration":-1.1677471187807822,"curvature":5.382355611949463,"pose":{"rotation":{"radians":2.609920087318689},"translation":{"x":7.05606733827472,"y":2.238915807959142}},"time":1.2351241083294882,"velocity":0.749677936253243,"position":1.5194526697038726,"holonomicRotation":-169.77714431184103,"angularVelocity":3.974903344270693,"angularAcceleration":6.514717554470108,"curveRadius":0.18579225753495035},{"acceleration":-1.04702240304543,"curvature":5.463367013436874,"pose":{"rotation":{"radians":2.632428497236792},"translation":{"x":7.052420604780888,"y":2.240951640196862}},"time":1.2407392224466192,"velocity":0.7437987859769501,"position":1.5236291847673167,"holonomicRotation":-170.14478092157302,"angularVelocity":4.008540066787405,"angularAcceleration":5.990389832699998,"curveRadius":0.18303730969209112},{"acceleration":-0.9265387979222783,"curvature":5.536373286782398,"pose":{"rotation":{"radians":2.6552238885960913},"translation":{"x":7.048735838032763,"y":2.242899897277286}},"time":1.2463827216940788,"velocity":0.7385698649681336,"position":1.5277973032444607,"holonomicRotation":-170.512417531305,"angularVelocity":4.039229981214245,"angularAcceleration":5.438100207181633,"curveRadius":0.1806236588828668},{"acceleration":-0.8062485303377579,"curvature":5.6007263525432744,"pose":{"rotation":{"radians":2.6782836137586856},"translation":{"x":7.045012637147456,"y":2.244759922285285}},"time":1.2520529817454913,"velocity":0.7339982261350494,"position":1.531959264063922,"holonomicRotation":-170.880054141037,"angularVelocity":4.066784407330693,"angularAcceleration":4.859464269118375,"curveRadius":0.1785482698232351},{"acceleration":-0.6861057710324824,"curvature":5.655828887086481,"pose":{"rotation":{"radians":2.7015833466589028},"translation":{"x":7.041250601242078,"y":2.246531058305736}},"time":1.2577483088799404,"velocity":0.730090629320186,"position":1.5361173690356962,"holonomicRotation":-171.24769075076898,"angularVelocity":4.091026265951434,"angularAcceleration":4.25644709223285,"curveRadius":0.17680874368091706},{"acceleration":-0.5660665631029429,"curvature":5.7011459565630025,"pose":{"rotation":{"radians":2.7250971929576937},"translation":{"x":7.037449329433741,"y":2.248212648423512}},"time":1.2634669450528222,"velocity":0.7268535005961666,"position":1.5402739797565912,"holonomicRotation":-171.61532736050094,"angularVelocity":4.111792670129161,"angularAcceleration":3.631356069862175,"curveRadius":0.17540333252630158},{"acceleration":-0.4460887451687142,"curvature":5.7362159716965255,"pose":{"rotation":{"radians":2.7487978251137637},"translation":{"x":7.0336084208395535,"y":2.2498040357234865}},"time":1.2692070737290126,"velocity":0.7242928937978979,"position":1.5444315141662415,"holonomicRotation":-171.98296397023296,"angularVelocity":4.128937432078507,"angularAcceleration":2.986825368647295,"curveRadius":0.17433095353002254},{"acceleration":-0.32613189653754027,"curvature":5.760660591855958,"pose":{"rotation":{"radians":2.7726566412133393},"translation":{"x":7.029727474576628,"y":2.2513045632905353}},"time":1.274966826430662,"velocity":0.7224144547257217,"position":1.5485924427735585,"holonomicRotation":-172.35060057996492,"angularVelocity":4.142333418714952,"angularAcceleration":2.3257919793343813,"curveRadius":0.1735912026155011},{"acceleration":-0.20615727515147766,"curvature":5.774193214906881,"pose":{"rotation":{"radians":2.796643945714646},"translation":{"x":7.0258060897620735,"y":2.252713574209532}},"time":1.2807442899344796,"velocity":0.7212233885924876,"position":1.5527592845792513,"holonomicRotation":-172.71823718969694,"angularVelocity":4.151874691282123,"angularAcceleration":1.651463927182975,"curveRadius":0.17318436754391267},{"acceleration":-0.08612775917727283,"curvature":5.776625735636765,"pose":{"rotation":{"radians":2.820729149564546},"translation":{"x":7.021843865513004,"y":2.254030411565351}},"time":1.286537514037213,"velocity":0.7207244311821074,"position":1.5569346027254043,"holonomicRotation":-173.0858737994289,"angularVelocity":4.157478361407744,"angularAcceleration":0.9672800544651109,"curveRadius":0.17311144009743756},{"acceleration":0.03399220604102913,"curvature":5.767873299645068,"pose":{"rotation":{"radians":2.844880986546253},"translation":{"x":7.017840400946527,"y":2.2552544184428664}},"time":1.2923445197937817,"velocity":0.7209218241182661,"position":1.561120999908095,"holonomicRotation":-173.4535104091609,"angularVelocity":4.159086109805761,"angularAcceleration":0.27686357916876936,"curveRadius":0.17337412735150337},{"acceleration":0.1542366639940875,"curvature":5.747956858725451,"pose":{"rotation":{"radians":2.869067742153921},"translation":{"x":7.013795295179755,"y":2.2563849379269527}},"time":1.2981633081199955,"velocity":0.7218192946181891,"position":1.5653211135932552,"holonomicRotation":-173.82114701889287,"angularVelocity":4.1566653144445995,"angularAcceleration":-0.41603083416111947,"curveRadius":0.17397486177753593},{"acceleration":0.274638199313329,"curvature":5.717003408923979,"pose":{"rotation":{"radians":2.893257490881541},"translation":{"x":7.0097081473298,"y":2.257421313102484}},"time":1.3039918686425584,"velocity":0.7234200399846945,"position":1.569537611079541,"holonomicRotation":-174.18878362862486,"angularVelocity":4.150209753159302,"angularAcceleration":-1.107573861557595,"curveRadius":0.17491681016650193},{"acceleration":0.39522799583705953,"curvature":5.675243888730545,"pose":{"rotation":{"radians":2.9174183375080376},"translation":{"x":7.005578556513771,"y":2.258362887054335}},"time":1.3098281886724374,"velocity":0.7257267170531673,"position":1.5737731844544967,"holonomicRotation":-174.55642023835685,"angularVelocity":4.139739853675841,"angularAcceleration":-1.7939214144976605,"curveRadius":0.17620388120865108},{"acceleration":0.5160358926768714,"curvature":5.623008803003001,"pose":{"rotation":{"radians":2.941518657829195},"translation":{"x":7.001406121848778,"y":2.2592090028673795}},"time":1.3156702621750207,"velocity":0.7287414366681567,"position":1.5780305454918901,"holonomicRotation":-174.92405684808884,"angularVelocity":4.125302482158205,"angularAcceleration":-2.4712752263817666,"curveRadius":0.17784073172105724},{"acceleration":0.6370904440308076,"curvature":5.5607217304641345,"pose":{"rotation":{"radians":2.9655273343001145},"translation":{"x":6.997190442451934,"y":2.259959003626492}},"time":1.3215160986111305,"velocity":0.7324657631989694,"position":1.5823124205386017,"holonomicRotation":-175.29169345782083,"angularVelocity":4.106970274196798,"angularAcceleration":-3.1359426767688765,"curveRadius":0.17983277144071969},{"acceleration":0.75841897658523,"curvature":5.488890950533647,"pose":{"rotation":{"radians":2.9894139822362105},"translation":{"x":6.992931117440349,"y":2.260612232416547}},"time":1.3273637315274454,"velocity":0.736900718970807,"position":1.5866215454389114,"holonomicRotation":-175.65933006755282,"angularVelocity":4.0848405291399885,"angularAcceleration":-3.7843936809145178,"curveRadius":0.18218616638808918},{"acceleration":0.8800476553894505,"curvature":5.408099491567125,"pose":{"rotation":{"radians":3.013149162542535},"translation":{"x":6.988627745931134,"y":2.2611680323224186}},"time":1.333211226782159,"velocity":0.7420467934596187,"position":1.590960660542442,"holonomicRotation":-176.0269666772848,"angularVelocity":4.059033701171734,"angularAcceleration":-4.413313195500501,"curveRadius":0.184907840833791},{"acceleration":1.00200154609075,"curvature":5.318993953959936,"pose":{"rotation":{"radians":3.03670457739769},"translation":{"x":6.984279927041399,"y":2.2616257464289813}},"time":1.3390566903025065,"velocity":0.747903956944624,"position":1.5953325058394854,"holonomicRotation":-176.39460328701676,"angularVelocity":4.02969153312835,"angularAcceleration":-5.019647790332935,"curveRadius":0.1880054778508463},{"acceleration":1.124304679273713,"curvature":5.222272487946212,"pose":{"rotation":{"radians":3.0600532458875387},"translation":{"x":6.9798872598882555,"y":2.2619847178211083}},"time":1.344898275283765,"velocity":0.754471678273428,"position":1.5997398162640724,"holonomicRotation":-176.76223989674878,"angularVelocity":3.996974890335058,"angularAcceleration":-5.600644841812015,"curveRadius":0.19148751856747231},{"acceleration":1.246980115163683,"curvature":5.118672319340062,"pose":{"rotation":{"radians":3.0831696572152394},"translation":{"x":6.9754493435888145,"y":2.262244289583675}},"time":1.350734188754254,"velocity":0.7617489463249437,"position":1.604185317201061,"holonomicRotation":-177.12987650648074,"angularVelocity":3.9610613564774972,"angularAcceleration":-6.153883884531114,"curveRadius":0.19536316013464358},{"acceleration":1.3700500094842358,"curvature":5.008957203449978,"pose":{"rotation":{"radians":3.1060298998080156},"translation":{"x":6.970965777260187,"y":2.2624038048015565}},"time":1.3565626974469482,"velocity":0.7697342947146483,"position":1.60867172022887,"holonomicRotation":-177.49751311621276,"angularVelocity":3.922142660854369,"angularAcceleration":-6.677299061406852,"curveRadius":0.1996423525661665},{"acceleration":1.4935356802755608,"curvature":4.89390516453264,"pose":{"rotation":{"radians":3.1286117653291052},"translation":{"x":6.966436160019483,"y":2.2624626065596254}},"time":1.3623821329350077,"velocity":0.7784258292551268,"position":1.6132017191244594,"holonomicRotation":-177.86514972594472,"angularVelocity":3.880422004406472,"angularAcceleration":-7.169193048621558,"curveRadius":0.2043357944995034},{"acceleration":1.6174576673300383,"curvature":4.774296835594705,"pose":{"rotation":{"radians":-3.1322904798893125},"translation":{"x":6.961860090983815,"y":2.262420037942756}},"time":1.3681908960055138,"velocity":0.7878212576212206,"position":1.6177779861518893,"holonomicRotation":-178.23278633567674,"angularVelocity":-1077.837427559749,"angularAcceleration":-186221.71991427068,"curveRadius":0.2094549280104483},{"acceleration":1.7418357919806233,"curvature":4.650904663389972,"pose":{"rotation":{"radians":-3.1103248125841803},"translation":{"x":6.957237169270291,"y":2.2622754420358246}},"time":1.3739874602617712,"velocity":0.7979179207132853,"position":1.6224031686505231,"holonomicRotation":-178.6004229454087,"angularVelocity":3.7894287605662735,"angularAcceleration":186597.92396033494,"curveRadius":0.2150119325970263},{"acceleration":1.8666892238510617,"curvature":4.52448318500459,"pose":{"rotation":{"radians":-3.088693266264659},"translation":{"x":6.952566993996025,"y":2.262028161923703}},"time":1.3797703749590962,"velocity":0.8087128252612317,"position":1.6270798859336415,"holonomicRotation":-178.96805955514068,"angularVelocity":3.7405957811426207,"angularAcceleration":-8.444354098157788,"curveRadius":0.2210197185204006},{"acceleration":1.9920365280316745,"curvature":4.3957605279069965,"pose":{"rotation":{"radians":-3.0674106959063403},"translation":{"x":6.947849164278125,"y":2.261677540691267}},"time":1.3855382670934018,"velocity":0.820202677082515,"position":1.6318107265033222,"holonomicRotation":-179.33569616487267,"angularVelocity":3.689835014725141,"angularAcceleration":-8.800574843549944,"curveRadius":0.22749191946453495},{"acceleration":2.117895720152574,"curvature":4.26543121811176,"pose":{"rotation":{"radians":-3.0464900995355353},"translation":{"x":6.943083279233704,"y":2.2612229214233905}},"time":1.391289842773094,"velocity":0.8323839145986688,"position":1.6365982455826948,"holonomicRotation":-179.70333277460466,"angularVelocity":3.6373678337697877,"angularAcceleration":-9.122227347299937,"curveRadius":0.23444288487265405},{"acceleration":2.2442843193158475,"curvature":4.134150336523742,"pose":{"rotation":{"radians":-3.0259426515568855},"translation":{"x":6.938268937979871,"y":2.260663647204948}},"time":1.3970238879146912,"velocity":0.8452527421962047,"position":1.6414449629625067,"holonomicRotation":-180.07096938433665,"angularVelocity":3.5834123156076516,"angularAcceleration":-9.409677955047702,"curveRadius":0.24188767185492918},{"acceleration":2.371219386781769,"curvature":4.002529006810097,"pose":{"rotation":{"radians":-3.0057777527079095},"translation":{"x":6.93340573963374,"y":2.259999061120813}},"time":1.4027392683107287,"velocity":0.8588051629941212,"position":1.6463533611550991,"holonomicRotation":-180.43860599406864,"angularVelocity":3.5281814073051905,"angularAcceleration":-9.663557711880953,"curveRadius":0.24984203694677823},{"acceleration":2.4987175689613115,"curvature":3.871131162970924,"pose":{"rotation":{"radians":-2.986003094251534},"translation":{"x":6.9284932833124175,"y":2.2592285062558615}},"time":1.4084349291240534,"velocity":0.8730370107352202,"position":1.6513258838457259,"holonomicRotation":-180.80624260380063,"angularVelocity":3.4718813329111375,"angularAcceleration":-9.884730892391195,"curveRadius":0.25832242770935815},{"acceleration":2.7850280679292982,"curvature":3.6967190690161726,"pose":{"rotation":{"radians":-2.9666247339739518},"translation":{"x":6.923531168133017,"y":2.258351325694966}},"time":1.4141042607120802,"velocity":0.8888262583342729,"position":1.656364934628368,"holonomicRotation":-181.1738792135326,"angularVelocity":3.418103170840801,"angularAcceleration":-9.485802909096478,"curveRadius":0.27051014192055856},{"acceleration":2.255778020858007,"curvature":1.594938829433553,"pose":{"rotation":{"radians":-2.938296047505536},"translation":{"x":6.9134563576684265,"y":2.2562744598248425}},"time":1.4253562383395977,"velocity":0.9142082221576129,"position":1.666651585090978,"holonomicRotation":178.09084756700352,"angularVelocity":2.5176628861344135,"angularAcceleration":-80.02506888249556,"curveRadius":0.6269832933687826},{"acceleration":2.7745687470572533,"curvature":-0.01719734277298267,"pose":{"rotation":{"radians":-2.9200503113757543},"translation":{"x":6.901171557749045,"y":2.253507438252807}},"time":1.4385983380538998,"velocity":0.9509493381703313,"position":1.6792441510502791,"holonomicRotation":178.14372390663158,"angularVelocity":1.3778582342251633,"angularAcceleration":-86.0743142326745,"curveRadius":-58.14851824498246},{"acceleration":3.070990462724125,"curvature":-0.017452667583007554,"pose":{"rotation":{"radians":-2.9202661985073517},"translation":{"x":6.888962353885816,"y":2.250760213292275}},"time":1.4512420491665725,"velocity":0.9897780544107883,"position":1.6917586188359124,"holonomicRotation":178.19660024625966,"angularVelocity":-0.01707466499934403,"angularAcceleration":-110.32622359003248,"curveRadius":-57.297831133484166},{"acceleration":3.065994746307657,"curvature":-0.01771168515861627,"pose":{"rotation":{"radians":-2.9204839314053577},"translation":{"x":6.876828350694748,"y":2.248032685032641}},"time":1.463352924195832,"velocity":1.0269099336236867,"position":1.704195396708334,"holonomicRotation":178.24947658588772,"angularVelocity":-0.017978296157786813,"angularAcceleration":-0.07461320146229172,"curveRadius":-56.45990153079964},{"acceleration":3.0617265134761804,"curvature":-0.01797443790097832,"pose":{"rotation":{"radians":-2.9207035233100846},"translation":{"x":6.864769152791852,"y":2.245324753563299}},"time":1.4749851225270656,"velocity":1.0625245436644377,"position":1.7165548929320422,"holonomicRotation":178.30235292551578,"angularVelocity":-0.018877936781507114,"angularAcceleration":-0.07734055060810675,"curveRadius":-55.63456312286526},{"acceleration":3.0580377321629633,"curvature":-0.018240964425123476,"pose":{"rotation":{"radians":-2.920924987425226},"translation":{"x":6.852784364793138,"y":2.2426363189736414}},"time":1.4861840152988306,"velocity":1.0967711803189422,"position":1.7288375157755962,"holonomicRotation":178.35522926514386,"angularVelocity":-0.01977553671195037,"angularAcceleration":-0.08015077461106808,"curveRadius":-54.821662752803206},{"acceleration":3.0548179979601473,"curvature":-0.018511306543599372,"pose":{"rotation":{"radians":-2.9211483369124482},"translation":{"x":6.840873591314614,"y":2.239967281353063}},"time":1.49698807029413,"velocity":1.1297756019695342,"position":1.7410436735116226,"holonomicRotation":178.40810560477192,"angularVelocity":-0.020672746234587886,"angularAcceleration":-0.08304377597373085,"curveRadius":-54.02103831216433},{"acceleration":3.0519832858313936,"curvature":-0.01878550430312596,"pose":{"rotation":{"radians":-2.921373584885046},"translation":{"x":6.829036436972293,"y":2.237317540790957}},"time":1.5074302462124578,"velocity":1.1616449483399816,"position":1.7531737744168254,"holonomicRotation":178.4609819444,"angularVelocity":-0.021570980450787387,"angularAcceleration":-0.08601983180755947,"curveRadius":-53.232534185073604},{"acceleration":3.0494685112102156,"curvature":-0.01906359845083211,"pose":{"rotation":{"radians":-2.921600744402765},"translation":{"x":6.817272506382184,"y":2.2346869973767176}},"time":1.517539044012577,"velocity":1.1924714089176365,"position":1.7652282267719972,"holonomicRotation":178.51385828402806,"angularVelocity":-0.022471467152712074,"angularAcceleration":-0.08907950477692408,"curveRadius":-52.455993687611006},{"acceleration":3.0472224751535406,"curvature":-0.019345627484636422,"pose":{"rotation":{"radians":-2.921829828464789},"translation":{"x":6.805581404160296,"y":2.2320755511997374}},"time":1.527339313168237,"velocity":1.222335009351317,"position":1.777207438862026,"holonomicRotation":178.56673462365612,"angularVelocity":-0.023375282697388353,"angularAcceleration":-0.09222354308037678,"curveRadius":-51.691267227913016},{"acceleration":3.0452043469313006,"curvature":-0.019631631820862243,"pose":{"rotation":{"radians":-2.9220608500042844},"translation":{"x":6.793962734922641,"y":2.229483102349412}},"time":1.5368528792947407,"velocity":1.2513057622745647,"position":1.7891118189759003,"holonomicRotation":178.6196109632842,"angularVelocity":-0.0242833797992731,"angularAcceleration":-0.09545286066335162,"curveRadius":-50.93820061036978},{"acceleration":3.043381164702215,"curvature":-0.019921649570402444,"pose":{"rotation":{"radians":-2.922293821880782},"translation":{"x":6.782416103285226,"y":2.226909550915134}},"time":1.5460990392946798,"velocity":1.2794453514642026,"position":1.8009417754067167,"holonomicRotation":178.67248730291226,"angularVelocity":-0.025196608808310133,"angularAcceleration":-0.09876846269619408,"curveRadius":-50.196646440649076},{"acceleration":3.0417260261405175,"curvature":-0.020215720312596133,"pose":{"rotation":{"radians":-2.9225287568743363},"translation":{"x":6.770941113864065,"y":2.2243547969862973}},"time":1.555094956704629,"velocity":1.3068084675790557,"position":1.8126977164516802,"holonomicRotation":178.72536364254032,"angularVelocity":-0.02611573482150854,"angularAcceleration":-0.10217145970925456,"curveRadius":-49.466454053428606},{"acceleration":3.0402167564856573,"curvature":-0.020513881254071983,"pose":{"rotation":{"radians":-2.92276566767796},"translation":{"x":6.759537371275165,"y":2.2218187406522953}},"time":1.563855980799523,"velocity":1.3334438798363266,"position":1.824380050412115,"holonomicRotation":178.7782399821684,"angularVelocity":-0.02704145098309166,"angularAcceleration":-0.1056630082917643,"curveRadius":-48.747479212472335},{"acceleration":3.038834913297076,"curvature":-0.020816169741813897,"pose":{"rotation":{"radians":-2.9230045668906284},"translation":{"x":6.748204480134536,"y":2.219301282002523}},"time":1.5723959067062983,"velocity":1.3593953048388057,"position":1.8359891855934567,"holonomicRotation":178.83111632179646,"angularVelocity":-0.027974389388876423,"angularAcceleration":-0.10924432084880255,"curveRadius":-48.039577520896074},{"acceleration":3.0375650324912136,"curvature":-0.02112262324804816,"pose":{"rotation":{"radians":-2.9232454670093984},"translation":{"x":6.736942045058191,"y":2.2168023211263725}},"time":1.5807271893444188,"velocity":1.3847021176561618,"position":1.8475255303052542,"holonomicRotation":178.88399266142451,"angularVelocity":-0.0289151297865855,"angularAcceleration":-0.11291663463734047,"curveRadius":-47.34260457409831},{"acceleration":3.036394050076004,"curvature":-0.02143327761911806,"pose":{"rotation":{"radians":-2.923488380422552},"translation":{"x":6.725749670662136,"y":2.214321758113239}},"time":1.5888611208423815,"velocity":1.4093999388603016,"position":1.8589894928611768,"holonomicRotation":178.9368690010526,"angularVelocity":-0.029864206898530647,"angularAcceleration":-0.1166812275444981,"curveRadius":-46.656419879898344},{"acceleration":3.035310853654985,"curvature":-0.021748168764309656,"pose":{"rotation":{"radians":-2.923733319400612},"translation":{"x":6.714626961562384,"y":2.211859493052515}},"time":1.5968079787818377,"velocity":1.4335211230163871,"position":1.8703814815789976,"holonomicRotation":178.98974534068066,"angularVelocity":-0.030822116102514313,"angularAcceleration":-0.12053936427221719,"curveRadius":-45.98088284293037},{"acceleration":3.0343059308908784,"curvature":-0.022067331762575245,"pose":{"rotation":{"radians":-2.923980296089142},"translation":{"x":6.703573522374945,"y":2.209415426033595}},"time":1.6045771509327282,"velocity":1.4570951681519466,"position":1.881701904780601,"holonomicRotation":179.0426216803087,"angularVelocity":-0.03178931856999565,"angularAcceleration":-0.12449234599216208,"curveRadius":-45.31585471044283},{"acceleration":3.033371091234776,"curvature":-0.022390799945522864,"pose":{"rotation":{"radians":-2.924229322499565},"translation":{"x":6.6925889577158255,"y":2.2069894571458724}},"time":1.6121772408867892,"velocity":1.4801490613093788,"position":1.892951170791971,"holonomicRotation":179.0954980199368,"angularVelocity":-0.032766245127117524,"angularAcceleration":-0.1285414466179938,"curveRadius":-44.661200244431384},{"acceleration":3.032499243940827,"curvature":-0.022718606163043043,"pose":{"rotation":{"radians":-2.9244804105009656},"translation":{"x":6.681672872201039,"y":2.2045814864787414}},"time":1.6196161580517714,"velocity":1.502707571987926,"position":1.9041296879431808,"holonomicRotation":179.14837435956485,"angularVelocity":-0.033753299819333824,"angularAcceleration":-0.13268795314225762,"curveRadius":-44.016784868903024},{"acceleration":3.0316842192414777,"curvature":-0.02305078319527449,"pose":{"rotation":{"radians":-2.9247335718108696},"translation":{"x":6.670824870446596,"y":2.2021914141215952}},"time":1.6269011947501393,"velocity":1.5247935027829629,"position":1.9152378645683876,"holonomicRotation":179.20125069919294,"angularVelocity":-0.034750862677281356,"angularAcceleration":-0.13693312734732324,"curveRadius":-43.38247388509577},{"acceleration":3.030920623350197,"curvature":-0.023387361948290344,"pose":{"rotation":{"radians":-2.924988817986395},"translation":{"x":6.660044557068504,"y":2.199819140163828}},"time":1.6340390926142496,"velocity":1.5464279046266622,"position":1.926276109005823,"holonomicRotation":179.254127038821,"angularVelocity":-0.03575929221526172,"angularAcceleration":-0.14127822465081685,"curveRadius":-42.758135877445625},{"acceleration":3.0302037200827376,"curvature":-0.023728372285284113,"pose":{"rotation":{"radians":-2.9252461604143494},"translation":{"x":6.649331536682775,"y":2.1974645646948328}},"time":1.641036100042519,"velocity":1.567630262565251,"position":1.937244829597772,"holonomicRotation":179.30700337844905,"angularVelocity":-0.03677892736181284,"angularAcceleration":-0.14572446249400312,"curveRadius":-42.14364086912869},{"acceleration":3.0295293334001876,"curvature":-0.02407384343039963,"pose":{"rotation":{"radians":-2.9255056103019488},"translation":{"x":6.638685413905418,"y":2.1951275878040044}},"time":1.647898022147053,"velocity":1.5884186568644434,"position":1.948144434690564,"holonomicRotation":179.35987971807714,"angularVelocity":-0.03781008930835581,"angularAcceleration":-0.15027304752726015,"curveRadius":-41.538859504969366},{"acceleration":3.028893766906602,"curvature":-0.02442380302884696,"pose":{"rotation":{"radians":-2.9257671786664337},"translation":{"x":6.628105793352443,"y":2.192808109580736}},"time":1.6546302643600703,"velocity":1.6088099033407572,"position":1.9589753326345551,"holonomicRotation":179.4127560577052,"angularVelocity":-0.038853082852413,"angularAcceleration":-0.1549251365377894,"curveRadius":-40.94366462171758},{"acceleration":3.028293736742285,"curvature":-0.02477827663443619,"pose":{"rotation":{"radians":-2.9260308763250653},"translation":{"x":6.61759227963986,"y":2.190506030114421}},"time":1.6612378706577027,"velocity":1.6288196761067362,"position":1.9697379317841055,"holonomicRotation":179.46563239733325,"angularVelocity":-0.03990819772754091,"angularAcceleration":-0.15968186172138935,"curveRadius":-40.35793185916032},{"acceleration":3.0277263154887266,"curvature":-0.025137290827619476,"pose":{"rotation":{"radians":-2.926296713884593},"translation":{"x":6.607144477383679,"y":2.188221249494454}},"time":1.6677255571929197,"velocity":1.6484626153560547,"position":1.9804326404975596,"holonomicRotation":179.51850873696134,"angularVelocity":-0.04097570961307242,"angularAcceleration":-0.16454430708647028,"curveRadius":-39.781534408682376},{"acceleration":3.0271888849483535,"curvature":-0.025500867722737904,"pose":{"rotation":{"radians":-2.9265647017299705},"translation":{"x":6.596761991199911,"y":2.185953667810228}},"time":1.6740977419951524,"velocity":1.6677524223622102,"position":1.9910598671372228,"holonomicRotation":179.5713850765894,"angularVelocity":-0.04205588094112059,"angularAcceleration":-0.16951349679464753,"curveRadius":-39.21435187510689},{"acceleration":3.0266790963144548,"curvature":-0.025869030358618747,"pose":{"rotation":{"radians":-2.926834850013862},"translation":{"x":6.586444425704565,"y":2.1837031851511366}},"time":1.680358571285592,"velocity":1.686701943501177,"position":2.0016200200693364,"holonomicRotation":179.62426141621745,"angularVelocity":-0.043148961800300555,"angularAcceleration":-0.1745904269980853,"curveRadius":-38.65626141131461},{"acceleration":3.0261948362417423,"curvature":-0.02624179761342615,"pose":{"rotation":{"radians":-2.9271071686448464},"translation":{"x":6.576191385513652,"y":2.1814697016065745}},"time":1.686511942868742,"velocity":1.7053232448115825,"position":2.0121135076640453,"holonomicRotation":179.67713775584554,"angularVelocity":-0.04425519039516993,"angularAcceleration":-0.17977601058557624,"curveRadius":-38.10714550623497},{"acceleration":3.025734197945191,"curvature":-0.026619189652631974,"pose":{"rotation":{"radians":-2.927381667275493},"translation":{"x":6.566002475243181,"y":2.1792531172659344}},"time":1.6925615269884473,"velocity":1.7236276783659208,"position":2.022540738295372,"holonomicRotation":179.7300140954736,"angularVelocity":-0.04537479357507181,"angularAcceleration":-0.18507109873140057,"curveRadius":-37.56688362979994},{"acceleration":3.02529545649231,"curvature":-0.02700122280383119,"pose":{"rotation":{"radians":-2.927658355290966},"translation":{"x":6.555877299509161,"y":2.177053332218611}},"time":1.6985107849770578,"velocity":1.7416259415283646,"position":2.032902120341181,"holonomicRotation":179.78289043510168,"angularVelocity":-0.04650798738307969,"angularAcceleration":-0.19047649474561595,"curveRadius":-37.03535974148958},{"acceleration":3.0248770475857727,"curvature":-0.02738791178321364,"pose":{"rotation":{"radians":-2.9279372417957203},"translation":{"x":6.545815462927606,"y":2.174870246553997}},"time":1.704362985977158,"velocity":1.7593281300114265,"position":2.0431980621831385,"holonomicRotation":179.83576677472973,"angularVelocity":-0.04765497711877836,"angularAcceleration":-0.19599288125596107,"curveRadius":-36.51245877799677},{"acceleration":3.0244775490869107,"curvature":-0.027779269631357913,"pose":{"rotation":{"radians":-2.9282183356022093},"translation":{"x":6.535816570114522,"y":2.172703760361488}},"time":1.7101212219743775,"velocity":1.776743785507361,"position":2.053428972206683,"holonomicRotation":179.8886431143578,"angularVelocity":-0.04881595798170321,"angularAcceleration":-0.2016209240964526,"curveRadius":-35.99806666159343},{"acceleration":3.0240956652530877,"curvature":-0.028175307173809113,"pose":{"rotation":{"radians":-2.9285016452162265},"translation":{"x":6.5258802256859205,"y":2.1705537737304748}},"time":1.7157884213456223,"velocity":1.793881938560067,"position":2.063595258800978,"holonomicRotation":179.94151945398588,"angularVelocity":-0.049991114739077844,"angularAcceleration":-0.20736111091086015,"curveRadius":-35.49207090560378},{"acceleration":3.0237302128090935,"curvature":-0.028576032941255564,"pose":{"rotation":{"radians":-2.9287871788253823},"translation":{"x":6.516006034257812,"y":2.1684201867503536}},"time":1.7213673610984705,"velocity":1.8107511472461961,"position":2.0736973303588653,"holonomicRotation":179.99439579361393,"angularVelocity":-0.051180622448927536,"angularAcceleration":-0.21321393715399015,"curveRadius":-34.994360555774975},{"acceleration":3.023380109020381,"curvature":-0.0289814530872548,"pose":{"rotation":{"radians":-2.9290749442839865},"translation":{"x":6.506193600446206,"y":2.166302899510517}},"time":1.726860677953367,"velocity":1.8273595321578366,"position":2.0837355952768237,"holonomicRotation":180.047272133242,"angularVelocity":-0.052384645962612456,"angularAcceleration":-0.21917969516207741,"curveRadius":-34.50482613791959},{"acceleration":3.023044361066023,"curvature":-0.029391571303473585,"pose":{"rotation":{"radians":-2.929364949100348},"translation":{"x":6.496442528867112,"y":2.16420181210036}},"time":1.732270878399888,"velocity":1.8437148081099284,"position":2.093710461954917,"holonomicRotation":180.10014847287007,"angularVelocity":-0.05360334043596283,"angularAcceleration":-0.22525865453544894,"curveRadius":-34.02335961132561},{"acceleration":3.0227220569209132,"curvature":-0.029806389215021812,"pose":{"rotation":{"radians":-2.929657200421309},"translation":{"x":6.486752424136541,"y":2.1621168246092743}},"time":1.7376003478410866,"velocity":1.8598243129415257,"position":2.1036223387967374,"holonomicRotation":180.15302481249813,"angularVelocity":-0.05483685086955975,"angularAcceleration":-0.23145088778658568,"curveRadius":-33.549853784235644},{"acceleration":3.0224123571062926,"curvature":-0.030225905332410426,"pose":{"rotation":{"radians":-2.9299517050192034},"translation":{"x":6.477122890870502,"y":2.1600478371266556}},"time":1.7428513589252457,"velocity":1.8756950337295901,"position":2.1134716342093536,"holonomicRotation":180.2059011521262,"angularVelocity":-0.05608531255681769,"angularAcceleration":-0.23775643723629292,"curveRadius":-33.084203401104645},{"acceleration":3.022114487627593,"curvature":-0.030650115922095406,"pose":{"rotation":{"radians":-2.9302484692752593},"translation":{"x":6.467553533685007,"y":2.1579947497418965}},"time":1.7480260791517843,"velocity":1.891333630695632,"position":2.123258756603247,"holonomicRotation":180.25877749175427,"angularVelocity":-0.05734885038497105,"angularAcceleration":-0.24417509987753247,"curveRadius":-32.626304009477124},{"acceleration":3.0218277336170765,"curvature":-0.031079013453407092,"pose":{"rotation":{"radians":-2.930547499165748},"translation":{"x":6.458043957196064,"y":2.155957462544391}},"time":1.753126577827344,"velocity":1.9067464590487153,"position":2.132984114392253,"holonomicRotation":180.31165383138233,"angularVelocity":-0.05862757928390032,"angularAcceleration":-0.250706642677242,"curveRadius":-32.176053512740225},{"acceleration":3.021551433760004,"curvature":-0.031512587460762125,"pose":{"rotation":{"radians":-2.930848800245575},"translation":{"x":6.448593766019684,"y":2.153935875623533}},"time":1.758154832438806,"velocity":1.9219395889792892,"position":2.14264811599349,"holonomicRotation":180.36453017101041,"angularVelocity":-0.05992160363954142,"angularAcceleration":-0.2573506028694931,"curveRadius":-31.733351037744814},{"acceleration":3.0212849751813904,"curvature":-0.03195082543277132,"pose":{"rotation":{"radians":-2.931152377632918},"translation":{"x":6.439202564771876,"y":2.1519298890687164}},"time":1.7631127345020503,"velocity":1.9369188239913897,"position":2.1522511698272933,"holonomicRotation":180.41740651063847,"angularVelocity":-0.06123101736792771,"angularAcceleration":-0.2641064126888938,"curveRadius":-31.298095947603287},{"acceleration":3.0210277891531483,"curvature":-0.03239371124086689,"pose":{"rotation":{"radians":-2.9314582359924035},"translation":{"x":6.429869958068652,"y":2.1499394029693346}},"time":1.7680020949383453,"velocity":1.9516897177406227,"position":2.161793684317138,"holonomicRotation":180.47028285026653,"angularVelocity":-0.06255590347057409,"angularAcceleration":-0.27097329393255987,"curveRadius":-30.870189357569853},{"acceleration":3.0207793471430087,"curvature":-0.03284122401927583,"pose":{"rotation":{"radians":-2.9317663795192397},"translation":{"x":6.420595550526019,"y":2.1479643174147816}},"time":1.772824649024315,"velocity":1.966257589524,"position":2.1712760678895657,"holonomicRotation":180.5231591898946,"angularVelocity":-0.06389633404686043,"angularAcceleration":-0.2779503458937,"curveRadius":-30.449534993368694},{"acceleration":3.020539157144191,"curvature":-0.0332933405306814,"pose":{"rotation":{"radians":-2.932076811921572},"translation":{"x":6.41137894675999,"y":2.1460045324944503}},"time":1.7775820609562043,"velocity":1.9806275385509369,"position":2.1806987289740967,"holonomicRotation":180.57603552952267,"angularVelocity":-0.06525236972891892,"angularAcceleration":-0.2850364234740421,"curveRadius":-30.03603675871613},{"acceleration":3.0203067604774545,"curvature":-0.0337500335625049,"pose":{"rotation":{"radians":-2.932389536404066},"translation":{"x":6.402219751386575,"y":2.1440599482977354}},"time":1.7822759280646694,"velocity":1.9948044571114167,"position":2.1900620760031515,"holonomicRotation":180.62891186915073,"angularVelocity":-0.06662405970763598,"angularAcceleration":-0.2922302542914575,"curveRadius":-29.62960016463405},{"acceleration":3.020081729262586,"curvature":-0.03421127281422397,"pose":{"rotation":{"radians":-2.9327045556496083},"translation":{"x":6.393117569021781,"y":2.1421304649140307}},"time":1.7869077847123267,"velocity":2.00879304274557,"position":2.1993665174119603,"holonomicRotation":180.6817882087788,"angularVelocity":-0.06801144109272987,"angularAcceleration":-0.29953029435736145,"curveRadius":-29.23013140815479},{"acceleration":3.0198636634547587,"curvature":-0.03467702274725662,"pose":{"rotation":{"radians":-2.933021871801601},"translation":{"x":6.384072004281621,"y":2.14021598243273}},"time":1.791479105902859,"velocity":2.022597809502839,"position":2.208612461638465,"holonomicRotation":180.73466454840687,"angularVelocity":-0.06941453876609763,"angularAcceleration":-0.3069348258166001,"curveRadius":-28.83753911887122},{"acceleration":3.019652188764436,"curvature":-0.0351472439628508,"pose":{"rotation":{"radians":-2.9333414864459346},"translation":{"x":6.375082661782103,"y":2.1383164009432254}},"time":1.7959913106274268,"velocity":2.0362230983755336,"position":2.217800317123229,"holonomicRotation":180.78754088803493,"angularVelocity":-0.07083336502743574,"angularAcceleration":-0.31444190765834834,"curveRadius":-28.451732973912808},{"acceleration":3.01944695446676,"curvature":-0.03562189359247742,"pose":{"rotation":{"radians":-2.9336634005924727},"translation":{"x":6.3661491461392385,"y":2.1364316205349128}},"time":1.8004457649714407,"velocity":2.0496730869783777,"position":2.2269304923093283,"holonomicRotation":180.840417227663,"angularVelocity":-0.07226791918310699,"angularAcceleration":-0.3220493566398443,"curveRadius":-28.07262329847559},{"acceleration":3.019247631658695,"curvature":-0.03610092362376964,"pose":{"rotation":{"radians":-2.9339876146556394},"translation":{"x":6.357271061969037,"y":2.134561541297185}},"time":1.8048437850024177,"velocity":2.0629517985408925,"position":2.236003395642251,"holonomicRotation":180.89329356729107,"angularVelocity":-0.07371818702124379,"angularAcceleration":-0.32975471414909185,"curveRadius":-27.700122313257882},{"acceleration":3.019053911344998,"curvature":-0.036584281784102085,"pose":{"rotation":{"radians":-2.9343141284357297},"translation":{"x":6.3484480138875075,"y":2.1327060633194357}},"time":1.809186639457532,"velocity":2.0760631102700073,"position":2.2450194355697857,"holonomicRotation":180.94616990691915,"angularVelocity":-0.07518414063031405,"angularAcceleration":-0.3375553162606921,"curveRadius":-27.334143277743827},{"acceleration":3.0188655031004146,"curvature":-0.03707191035320334,"pose":{"rotation":{"radians":-2.9346429410991504},"translation":{"x":6.339679606510662,"y":2.130865086691059}},"time":1.8134755522476387,"velocity":2.0890107611378665,"position":2.2539790205419004,"holonomicRotation":180.9990462465472,"angularVelocity":-0.07666573780169698,"angularAcceleration":-0.34544819255839526,"curveRadius":-26.974601267441592},{"acceleration":3.0186821334656693,"curvature":-0.03756374863545514,"pose":{"rotation":{"radians":-2.93497405115866},"translation":{"x":6.3309654444545105,"y":2.129038511501448}},"time":1.8177117047929146,"velocity":2.101798359140926,"position":2.262882559010632,"holonomicRotation":181.05192258617527,"angularVelocity":-0.0781629216537159,"angularAcceleration":-0.353430108103298,"curveRadius":-26.621411236261284},{"acceleration":3.018503544847335,"curvature":-0.038059728078462786,"pose":{"rotation":{"radians":-2.9353074564531596},"translation":{"x":6.322305132335061,"y":2.127226237839997}},"time":1.8218962382037835,"velocity":2.114429388075166,"position":2.2717304594299557,"holonomicRotation":181.10479892580335,"angularVelocity":-0.07967562013811665,"angularAcceleration":-0.3614975281286161,"curveRadius":-26.274491450344318},{"acceleration":3.018329494176784,"curvature":-0.038559777379562676,"pose":{"rotation":{"radians":-2.9356431541271406},"translation":{"x":6.313698274768325,"y":2.1254281657960994}},"time":1.8260302553195198,"velocity":2.1269072138650245,"position":2.2805231302556566,"holonomicRotation":181.1576752654314,"angularVelocity":-0.0812037455537288,"angularAcceleration":-0.3696466107494601,"curveRadius":-25.933759683218934},{"acceleration":3.018159752037121,"curvature":-0.03906381755761448,"pose":{"rotation":{"radians":-2.9359811406101617},"translation":{"x":6.3051444763703115,"y":2.1236441954591494}},"time":1.830114822615752,"velocity":2.1392350904829995,"position":2.2892609799451957,"holonomicRotation":181.21055160505946,"angularVelocity":-0.08274719413555892,"angularAcceleration":-0.3778732164001483,"curveRadius":-25.599136554565334},{"acceleration":3.017994101446929,"curvature":-0.03957176658641348,"pose":{"rotation":{"radians":-2.9363214115955034},"translation":{"x":6.296643341757032,"y":2.1218742269185404}},"time":1.8341509719910607,"velocity":2.15141616549024,"position":2.2979444169575682,"holonomicRotation":181.26342794468755,"angularVelocity":-0.08430584542369714,"angularAcceleration":-0.386172845255262,"curveRadius":-25.27054226442695},{"acceleration":3.0178323372634925,"curvature":-0.040083534947631366,"pose":{"rotation":{"radians":-2.9366639620191504},"translation":{"x":6.288194475544495,"y":2.120118160263666}},"time":1.83813970244194,"velocity":2.163453485229531,"position":2.306573849753164,"holonomicRotation":181.3163042843156,"angularVelocity":-0.08587956189705448,"angularAcceleration":-0.39454069226724875,"curveRadius":-24.94789946312089},{"acceleration":3.0176742650780546,"curvature":-0.0405990270457963,"pose":{"rotation":{"radians":-2.937008786038006},"translation":{"x":6.279797482348711,"y":2.1183758955839203}},"time":1.8420819816345537,"velocity":2.1753499996948342,"position":2.3151496867936134,"holonomicRotation":181.36918062394366,"angularVelocity":-0.08746818832657793,"angularAcceleration":-0.40297156845204674,"curveRadius":-24.63113214195959},{"acceleration":3.017519700601324,"curvature":-0.041118143225917905,"pose":{"rotation":{"radians":-2.937355877007942},"translation":{"x":6.271451966785691,"y":2.116647332968697}},"time":1.8459787473809852,"velocity":2.1871085671033197,"position":2.3236723365416285,"holonomicRotation":181.42205696357175,"angularVelocity":-0.08907155126119087,"angularAcceleration":-0.41145992316351987,"curveRadius":-24.320164325165155},{"acceleration":3.0173684691653313,"curvature":-0.04164077577633269,"pose":{"rotation":{"radians":-2.9377052274619255},"translation":{"x":6.263157533471444,"y":2.1149323725073894}},"time":1.8498309090270049,"velocity":2.1987319581921474,"position":2.332142207460854,"holonomicRotation":181.4749333031998,"angularVelocity":-0.09068945856530178,"angularAcceleration":-0.4199998475616028,"curveRadius":-24.014922425349447},{"acceleration":3.017220404554548,"curvature":-0.042166810358671765,"pose":{"rotation":{"radians":-2.9380568290875275},"translation":{"x":6.254913787021981,"y":2.113230914289392}},"time":1.8536393487577632,"velocity":2.2102228602573075,"position":2.340559708015688,"holonomicRotation":181.52780964282786,"angularVelocity":-0.0923216987687469,"angularAcceleration":-0.4285850161320856,"curveRadius":-23.715334204650038},{"acceleration":3.0170753491038087,"curvature":-0.042696126931998514,"pose":{"rotation":{"radians":-2.938410672704224},"translation":{"x":6.246720332053311,"y":2.111542858404098}},"time":1.8574049228272977,"velocity":2.221583880957725,"position":2.3489252466711186,"holonomicRotation":181.58068598245595,"angularVelocity":-0.09396804050657827,"angularAcceleration":-0.43720869844285243,"curveRadius":-23.421328159172027},{"acceleration":3.0169331526398984,"curvature":-0.043228599022307385,"pose":{"rotation":{"radians":-2.9387667482407034},"translation":{"x":6.238576773181443,"y":2.109868104940901}},"time":1.861128462717228,"velocity":2.2328175518968325,"position":2.357239231892543,"holonomicRotation":181.633562322084,"angularVelocity":-0.09562823200639535,"angularAcceleration":-0.4458637610696272,"curveRadius":-23.13283387888576},{"acceleration":3.0167936722657482,"curvature":-0.043764092400434385,"pose":{"rotation":{"radians":-2.9391250447121187},"translation":{"x":6.23048271502239,"y":2.108206553989196}},"time":1.8648107762295767,"velocity":2.2439263320001848,"position":2.365502072145582,"holonomicRotation":181.6864386617121,"angularVelocity":-0.09730200055310921,"angularAcceleration":-0.45454265127095905,"curveRadius":-22.84978266772132},{"acceleration":3.016656771811653,"curvature":-0.04430246542602401,"pose":{"rotation":{"radians":-2.9394855501960255},"translation":{"x":6.22243776219216,"y":2.1065581056383746}},"time":1.868452648518259,"velocity":2.2549126107019117,"position":2.373714175895898,"holonomicRotation":181.73931500134015,"angularVelocity":-0.09898905160051556,"angularAcceleration":-0.4632372894154156,"curveRadius":-22.57210722662363},{"acceleration":3.0165223211936985,"curvature":-0.044843570556449636,"pose":{"rotation":{"radians":-2.9398482518103535},"translation":{"x":6.214441519306764,"y":2.104922659977832}},"time":1.8720548430634016,"velocity":2.2657787109526164,"position":2.3818759516089916,"holonomicRotation":181.7921913409682,"angularVelocity":-0.10068906878364892,"angularAcceleration":-0.4719393030634,"curveRadius":-22.299740800995938},{"acceleration":3.016390196613977,"curvature":-0.04538725129162528,"pose":{"rotation":{"radians":-2.940213135688611},"translation":{"x":6.20649359098221,"y":2.103300117096962}},"time":1.8756181025923329,"velocity":2.276526892063676,"position":2.3899878077500056,"holonomicRotation":181.8450676805963,"angularVelocity":-0.10240171261590647,"angularAcceleration":-0.4806396554480705,"curveRadius":-22.032618665861285},{"acceleration":3.016260279616373,"curvature":-0.04593334482322118,"pose":{"rotation":{"radians":-2.940580186956898},"translation":{"x":6.198593581834511,"y":2.101690377085158}},"time":1.8791431499507805,"velocity":2.287159352394728,"position":2.3980501527835134,"holonomicRotation":181.89794402022434,"angularVelocity":-0.10412662042895862,"angularAcceleration":-0.4893289756571615,"curveRadius":-21.77067670226487},{"acceleration":3.0161324570093506,"curvature":-0.046481680105437836,"pose":{"rotation":{"radians":-2.9409493897100236},"translation":{"x":6.190741096479674,"y":2.100093340031813}},"time":1.8826306889275422,"velocity":2.297678231897624,"position":2.4060633951733132,"holonomicRotation":181.9508203598524,"angularVelocity":-0.10586340556637534,"angularAcceleration":-0.49799734110194643,"curveRadius":-21.513852290442728},{"acceleration":3.0160066204096063,"curvature":-0.04703207703317058,"pose":{"rotation":{"radians":-2.941320726987579},"translation":{"x":6.182935739533712,"y":2.0985089060263222}},"time":1.8860814050356287,"velocity":2.3080856145247672,"position":2.4140279433821967,"holonomicRotation":182.00369669948049,"angularVelocity":-0.10761165680519273,"angularAcceleration":-0.5066343286602047,"curveRadius":-21.26208458313938},{"acceleration":3.0158826663902967,"curvature":-0.047584350337807536,"pose":{"rotation":{"radians":-2.9416941807500274},"translation":{"x":6.175177115612633,"y":2.0969369751580786}},"time":1.88949596625268,"velocity":2.318383530512601,"position":2.4219442058717355,"holonomicRotation":182.05657303910854,"angularVelocity":-0.10937093778940678,"angularAcceleration":-0.5152290067106482,"curveRadius":-21.015312658486856},{"acceleration":3.015760495404777,"curvature":-0.04813830229528387,"pose":{"rotation":{"radians":-2.942069731854573},"translation":{"x":6.167464829332448,"y":2.095377447516476}},"time":1.8928750237232117,"velocity":2.3285739585439327,"position":2.429812591102039,"holonomicRotation":182.1094493787366,"angularVelocity":-0.1111407863940462,"angularAcceleration":-0.5237699033159516,"curveRadius":-20.77347875431765},{"acceleration":3.015640012478079,"curvature":-0.04869373047678306,"pose":{"rotation":{"radians":-2.942447360031387},"translation":{"x":6.1597984853091665,"y":2.0938302231909076}},"time":1.8962192124250883,"velocity":2.338658827802589,"position":2.4376335075315203,"holonomicRotation":182.16232571836468,"angularVelocity":-0.11292071425337513,"angularAcceleration":-0.5322450429696525,"curveRadius":-20.536524727280757},{"acceleration":3.015521126185906,"curvature":-0.049250422198953335,"pose":{"rotation":{"radians":-2.9428270438595336},"translation":{"x":6.1521776881587975,"y":2.092295202270768}},"time":1.899529151802427,"velocity":2.3486400199213486,"position":2.445407363616652,"holonomicRotation":182.21520205799274,"angularVelocity":-0.11471020609807889,"angularAcceleration":-0.5406418791097334,"curveRadius":-20.304394467125032},{"acceleration":3.015403749024114,"curvature":-0.04980815576060102,"pose":{"rotation":{"radians":-2.9432087607424653},"translation":{"x":6.144602042497354,"y":2.0907722848454506}},"time":1.9028054463669795,"velocity":2.358519370834207,"position":2.4531345678117074,"holonomicRotation":182.26807839762083,"angularVelocity":-0.11650871904547519,"angularAcceleration":-0.5489472670910566,"curveRadius":-20.077033263516547},{"acceleration":3.0152877967370406,"curvature":-0.05036670173491397,"pose":{"rotation":{"radians":-2.9435924868850925},"translation":{"x":6.137071152940843,"y":2.0892613710043495}},"time":1.9060486862699024,"velocity":2.3682986725353814,"position":2.4608155285685136,"holonomicRotation":182.32095473724888,"angularVelocity":-0.11831568250049221,"angularAcceleration":-0.5571476391211437,"curveRadius":-19.854387235104667},{"acceleration":3.0151731885092365,"curvature":-0.05092582123151887,"pose":{"rotation":{"radians":-2.9439781972686982},"translation":{"x":6.129584624105275,"y":2.087762360836858}},"time":1.9092594478456735,"velocity":2.377979674753342,"position":2.468450654336176,"holonomicRotation":182.37383107687694,"angularVelocity":-0.12013049692522589,"angularAcceleration":-0.5652286480654852,"curveRadius":-19.6364040052256},{"acceleration":3.0150598466664404,"curvature":-0.05148526595739196,"pose":{"rotation":{"radians":-2.9443658656281295},"translation":{"x":6.122142060606663,"y":2.086275154432369}},"time":1.9124382941298055,"velocity":2.387564086543353,"position":2.4760403535608115,"holonomicRotation":182.42670741650502,"angularVelocity":-0.12195253396378804,"angularAcceleration":-0.5731755724261651,"curveRadius":-19.42303261728467},{"acceleration":3.0149476961700965,"curvature":-0.05204477859898494,"pose":{"rotation":{"radians":-2.9447554644280296},"translation":{"x":6.114743067061014,"y":2.0847996518802785}},"time":1.9155857753518881,"velocity":2.39705357780261,"position":2.4835850346852713,"holonomicRotation":182.47958375613308,"angularVelocity":-0.12378113558443737,"angularAcceleration":-0.5809730040071154,"curveRadius":-19.21422334611495},{"acceleration":3.0148366652630942,"curvature":-0.05260409291071606,"pose":{"rotation":{"radians":-2.945146964838631},"translation":{"x":6.107387248084338,"y":2.083335753269978}},"time":1.9187024294053763,"velocity":2.406449780716007,"position":2.4910851061488555,"holonomicRotation":182.53246009576114,"angularVelocity":-0.12561561337334315,"angularAcceleration":-0.5886048812034913,"curveRadius":-19.009927643791542},{"acceleration":3.0147266844499363,"curvature":-0.05316293285984907,"pose":{"rotation":{"radians":-2.9455403367137727},"translation":{"x":6.1000742082926465,"y":2.0818833586908627}},"time":1.9217887822954585,"velocity":2.4157542911313667,"position":2.498540976387017,"holonomicRotation":182.58533643538922,"angularVelocity":-0.12745524868712652,"angularAcceleration":-0.5960547543655571,"curveRadius":-18.81009843148144},{"acceleration":3.0146176869732884,"curvature":-0.05372101238030397,"pose":{"rotation":{"radians":-2.9459355485666707},"translation":{"x":6.092803552301949,"y":2.0804423682323256}},"time":1.924845348566248,"velocity":2.424968669872695,"position":2.5059530538310715,"holonomicRotation":182.63821277501728,"angularVelocity":-0.12929929138946802,"angularAcceleration":-0.603305323350694,"curveRadius":-18.61469014993164},{"acceleration":3.0145096083392438,"curvature":-0.05427803737806369,"pose":{"rotation":{"radians":-2.9463325675482963},"translation":{"x":6.0855748847282545,"y":2.0790126819837607}},"time":1.9278726317084465,"velocity":2.4340944439920156,"position":2.5133217469078875,"holonomicRotation":182.69108911464534,"angularVelocity":-0.1311469601542666,"angularAcceleration":-0.6103389336277188,"curveRadius":-18.42365804486783},{"acceleration":3.014402386664566,"curvature":-0.05483370263580636,"pose":{"rotation":{"radians":-2.9467313594242333},"translation":{"x":6.078387810187575,"y":2.0775942000345617}},"time":1.930871124548563,"velocity":2.4431331079656595,"position":2.520647464039574,"holonomicRotation":182.74396545427342,"angularVelocity":-0.13299744144843198,"angularAcceleration":-0.6171371395015389,"curveRadius":-18.236959240957784},{"acceleration":3.0142959616367073,"curvature":-0.055387693493013215,"pose":{"rotation":{"radians":-2.947131888553027},"translation":{"x":6.071241933295919,"y":2.076186822474122}},"time":1.9338413096207072,"velocity":2.4520861248339374,"position":2.527930613643168,"holonomicRotation":182.79684179390148,"angularVelocity":-0.13484988950687876,"angularAcceleration":-0.6236810210312884,"curveRadius":-18.054552138484397},{"acceleration":3.014190275742278,"curvature":-0.05593968595994439,"pose":{"rotation":{"radians":-2.9475341178647545},"translation":{"x":6.064136858669297,"y":2.0747904493918363}},"time":1.9367836595218892,"velocity":2.4609549272939115,"position":2.5351716041303045,"holonomicRotation":182.84971813352956,"angularVelocity":-0.13670342591342807,"angularAcceleration":-0.62995104892341,"curveRadius":-17.876396387281293},{"acceleration":3.0140852730434724,"curvature":-0.056489345515027524,"pose":{"rotation":{"radians":-2.9479380088390603},"translation":{"x":6.057072190923719,"y":2.0734049808770973}},"time":1.939698637251721,"velocity":2.4697409187406474,"position":2.542370843906888,"holonomicRotation":182.90259447315762,"angularVelocity":-0.13855713893536997,"angularAcceleration":-0.6359269928449274,"curveRadius":-17.70245328358382},{"acceleration":3.0139808993191175,"curvature":-0.05703632886521967,"pose":{"rotation":{"radians":-2.948343521485686},"translation":{"x":6.050047534675196,"y":2.0720303170192995}},"time":1.9425866965373477,"velocity":2.4784454742636273,"position":2.5495287413727543,"holonomicRotation":182.95547081278568,"angularVelocity":-0.1404100839078931,"angularAcceleration":-0.6415882740859666,"curveRadius":-17.5326852182766},{"acceleration":3.0138771029058193,"curvature":-0.05758028208539716,"pose":{"rotation":{"radians":-2.948750614323293},"translation":{"x":6.043062494539736,"y":2.0706663579078364}},"time":1.9454482821443804,"velocity":2.487069941602668,"position":2.556645704921328,"holonomicRotation":183.00834715241376,"angularVelocity":-0.14226128220889436,"angularAcceleration":-0.6469134791745306,"curveRadius":-17.367056287027264},{"acceleration":3.0137738330566717,"curvature":-0.05812084173594405,"pose":{"rotation":{"radians":-2.949159244360439},"translation":{"x":6.03611667513335,"y":2.0693130036321015}},"time":1.9482838301745673,"velocity":2.4956156420584206,"position":2.5637221429392705,"holonomicRotation":183.06122349204182,"angularVelocity":-0.14410972157604873,"angularAcceleration":-0.6518808172092624,"curveRadius":-17.205531959485775},{"acceleration":3.0136710412986227,"curvature":-0.05865763398476725,"pose":{"rotation":{"radians":-2.9495693670765495},"translation":{"x":6.029209681072048,"y":2.067970154281489}},"time":1.9510937683508822,"velocity":2.5040838713682203,"position":2.5707584638061225,"holonomicRotation":183.11409983166988,"angularVelocity":-0.1459543557105878,"angularAcceleration":-0.6564678718156695,"curveRadius":-17.04807937291997},{"acceleration":3.013568680445393,"curvature":-0.059190276455789545,"pose":{"rotation":{"radians":-2.9499809364036333},"translation":{"x":6.022341116971841,"y":2.066637709945392}},"time":1.9538785162906778,"velocity":2.512475900542523,"position":2.5777550758939443,"holonomicRotation":183.16697617129796,"angularVelocity":-0.14779410416372438,"angularAcceleration":-0.6606516973567294,"curveRadius":-16.894666824996516},{"acceleration":3.013466704836138,"curvature":-0.059718375301684834,"pose":{"rotation":{"radians":-2.9503939047088075},"translation":{"x":6.015510587448738,"y":2.0653155707132043}},"time":1.9566384857675045,"velocity":2.5207929766673045,"position":2.5847123875669453,"holonomicRotation":183.21985251092602,"angularVelocity":-0.14962785227933928,"angularAcceleration":-0.6644088389423866,"curveRadius":-16.745264668507936},{"acceleration":3.0133650707160715,"curvature":-0.060241529156568024,"pose":{"rotation":{"radians":-2.950808222777623},"translation":{"x":6.008717697118749,"y":2.0640036366743204}},"time":1.9593740809621638,"velocity":2.5290363236745095,"position":2.591630807181108,"holonomicRotation":183.27272885055407,"angularVelocity":-0.15145445116452172,"angularAcceleration":-0.6677153435378628,"curveRadius":-16.599844227077888},{"acceleration":3.0132637353355203,"curvature":-0.060759324801783345,"pose":{"rotation":{"radians":-2.9512238397979167},"translation":{"x":6.001962050597884,"y":2.0627018079181334}},"time":1.9620856987035342,"velocity":2.5372071430786733,"position":2.598510743083812,"holonomicRotation":183.32560519018216,"angularVelocity":-0.15327271759320882,"angularAcceleration":-0.6705467370810811,"curveRadius":-16.458379076171845},{"acceleration":3.0131626573766757,"curvature":-0.06127134189408131,"pose":{"rotation":{"radians":-2.9516407033450545},"translation":{"x":5.995243252502154,"y":2.0614099845340372}},"time":1.964773728699667,"velocity":2.545306614684929,"position":2.60535260361344,"holonomicRotation":183.37848152981022,"angularVelocity":-0.1550814342613414,"angularAcceleration":-0.6728781563951318,"curveRadius":-16.320843792334145},{"acceleration":3.0130617971145606,"curvature":-0.06177714858881348,"pose":{"rotation":{"radians":-2.952058759367848},"translation":{"x":5.988560907447567,"y":2.060128066611426}},"time":1.9674385537596335,"velocity":2.5533358972691076,"position":2.612156797098995,"holonomicRotation":183.43135786943827,"angularVelocity":-0.15687934982064727,"angularAcceleration":-0.6746842733940733,"curveRadius":-16.187215221860832},{"acceleration":3.012961115848345,"curvature":-0.062276306012241295,"pose":{"rotation":{"radians":-2.9524779521750997},"translation":{"x":5.981914620050135,"y":2.0588559542396925}},"time":1.9700805500065637,"velocity":2.5612961292293255,"position":2.6189237318596956,"holonomicRotation":183.48423420906636,"angularVelocity":-0.1586651789301226,"angularAcceleration":-0.6759393059510768,"curveRadius":-16.057471356818045},{"acceleration":3.012860576475363,"curvature":-0.06276836455826859,"pose":{"rotation":{"radians":-2.9528982244242754},"translation":{"x":5.975303994925868,"y":2.057593547508232}},"time":1.972700087082302,"velocity":2.569188429213433,"position":2.625653816204578,"holonomicRotation":183.53711054869441,"angularVelocity":-0.16043760291397716,"angularAcceleration":-0.676617254350192,"curveRadius":-15.931592403872312},{"acceleration":3.012760142556987,"curvature":-0.06325286700702233,"pose":{"rotation":{"radians":-2.9533195171096103},"translation":{"x":5.968728636690774,"y":2.0563407465064367}},"time":1.9752975283440783,"velocity":2.5770138967195457,"position":2.6323474584320885,"holonomicRotation":183.5899868883225,"angularVelocity":-0.1621952694501882,"angularAcceleration":-0.676691543357156,"curveRadius":-15.809560061348366},{"acceleration":3.01265977950613,"curvature":-0.06372934697546147,"pose":{"rotation":{"radians":-2.953741769553263},"translation":{"x":5.962188149960865,"y":2.055097451323701}},"time":1.977873231053565,"velocity":2.584773612676381,"position":2.6390050668296685,"holonomicRotation":183.64286322795056,"angularVelocity":-0.1639367936747394,"angularAcceleration":-0.6761355719109127,"curveRadius":-15.691358023565545},{"acceleration":3.0125594534638407,"curvature":-0.064197329918438,"pose":{"rotation":{"radians":-2.954164919396312},"translation":{"x":5.955682139352151,"y":2.053863562049419}},"time":1.98042754655868,"velocity":2.5924686399984447,"position":2.645627049673341,"holonomicRotation":183.6957395675786,"angularVelocity":-0.16566075811769232,"angularAcceleration":-0.6749222793741143,"curveRadius":-15.576971834661798},{"acceleration":3.0124591316068483,"curvature":-0.06465633418769207,"pose":{"rotation":{"radians":-2.9545889025913254},"translation":{"x":5.949210209480642,"y":2.052638978772983}},"time":1.9829608204684688,"velocity":2.600100024120849,"position":2.6522138152272876,"holonomicRotation":183.7486159072067,"angularVelocity":-0.16736571334634043,"angularAcceleration":-0.6730244297942053,"curveRadius":-15.466388754690014},{"acceleration":3.012358782510867,"curvature":-0.06510586833292595,"pose":{"rotation":{"radians":-2.9550136533971476},"translation":{"x":5.942771964962346,"y":2.0514236015837883}},"time":1.9854733928213817,"velocity":2.6076687935148404,"position":2.6587657717434268,"holonomicRotation":183.80149224683475,"angularVelocity":-0.16905017892508936,"angularAcceleration":-0.6704147551397176,"curveRadius":-15.35959853705339},{"acceleration":3.0122583756974435,"curvature":-0.06554543596826279,"pose":{"rotation":{"radians":-2.9554391043734505},"translation":{"x":5.936367010413274,"y":2.0502173305712286}},"time":1.9879655982472444,"velocity":2.615175960182854,"position":2.66528332746098,"holonomicRotation":183.8543685864628,"angularVelocity":-0.17071264346340606,"angularAcceleration":-0.6670656122744052,"curveRadius":-15.256592396215074},{"acceleration":3.012157881891585,"curvature":-0.06597453157481374,"pose":{"rotation":{"radians":-2.955865186378053},"translation":{"x":5.929994950449439,"y":2.049020065824697}},"time":1.9904377661232093,"velocity":2.622622520135801,"position":2.671766890606042,"holonomicRotation":183.9072449260909,"angularVelocity":-0.17235156590504316,"angularAcceleration":-0.6629494936695586,"curveRadius":-15.157364154469532},{"acceleration":3.0120572722008045,"curvature":-0.0663926439241678,"pose":{"rotation":{"radians":-2.9562918285658517},"translation":{"x":5.923655389686847,"y":2.0478317074335872}},"time":1.9928902207239567,"velocity":2.6300094538507244,"position":2.6782168693911474,"holonomicRotation":183.96012126571895,"angularVelocity":-0.17396537643082638,"angularAcceleration":-0.6580388991875343,"curveRadius":-15.061909586582782},{"acceleration":3.0119565197197615,"curvature":-0.0667992561301775,"pose":{"rotation":{"radians":-2.956718958388013},"translation":{"x":5.917347932741509,"y":2.046652155487293}},"time":1.9953232813663924,"velocity":2.637337726715582,"position":2.68463367201483,"holonomicRotation":184.012997605347,"angularVelocity":-0.1755524768727567,"angularAcceleration":-0.6523061588557637,"curveRadius":-14.970226585326241},{"acceleration":3.011855597661067,"curvature":-0.06719384370577526,"pose":{"rotation":{"radians":-2.9571465015941047},"translation":{"x":5.911072184229437,"y":2.0454813100752087}},"time":1.9977372625490908,"velocity":2.6446082894533407,"position":2.6910177066611785,"holonomicRotation":184.0658739449751,"angularVelocity":-0.17711124227319772,"angularAcceleration":-0.6457239234560098,"curveRadius":-14.882315772539304},{"acceleration":3.0117544806777445,"curvature":-0.06757587896958646,"pose":{"rotation":{"radians":-2.9575743822354346},"translation":{"x":5.904827748766639,"y":2.044319071286728}},"time":2.0001324740867115,"velocity":2.651822078533941,"position":2.6973693814994,"holonomicRotation":184.11875028460315,"angularVelocity":-0.17864002181404665,"angularAcceleration":-0.6382649368696539,"curveRadius":-14.798179694415298},{"acceleration":3.0116531441366865,"curvature":-0.06794482796247048,"pose":{"rotation":{"radians":-2.958002522669729},"translation":{"x":5.898614230969126,"y":2.0431653392112437}},"time":2.0025092212396003,"velocity":2.6589800165697564,"position":2.7036891046833706,"holonomicRotation":184.17162662423124,"angularVelocity":-0.18013713986105076,"angularAcceleration":-0.6299021101947835,"curveRadius":-14.71782371061934},{"acceleration":3.011551564460879,"curvature":-0.06830015253430459,"pose":{"rotation":{"radians":-2.958430843568663},"translation":{"x":5.892431235452907,"y":2.04202001393815}},"time":2.0048678048387867,"velocity":2.666083012697798,"position":2.709977284351189,"holonomicRotation":184.2245029638593,"angularVelocity":-0.1816008977089965,"angularAcceleration":-0.6206088469582691,"curveRadius":-14.641255735084012},{"acceleration":3.0114497189461886,"curvature":-0.06864131088991784,"pose":{"rotation":{"radians":-2.958859263926063},"translation":{"x":5.886278366833993,"y":2.0408829955568413}},"time":2.007208521406569,"velocity":2.6731319629479784,"position":2.7162343286247297,"holonomicRotation":184.27737930348735,"angularVelocity":-0.183029574488907,"angularAcceleration":-0.6103587250053611,"curveRadius":-14.568486339133738},{"acceleration":3.0113475862106758,"curvature":-0.0689677577454651,"pose":{"rotation":{"radians":-2.9592877010687357},"translation":{"x":5.880155229728394,"y":2.0397541841567106}},"time":2.0095316632728744,"velocity":2.6801277505995023,"position":2.7224606456091944,"holonomicRotation":184.33025564311544,"angularVelocity":-0.18442142896505706,"angularAcceleration":-0.599125906315642,"curveRadius":-14.499528949319133},{"acceleration":3.01124514440496,"curvature":-0.06927894533908792,"pose":{"rotation":{"radians":-2.959716070669196},"translation":{"x":5.874061428752119,"y":2.038633479827152}},"time":2.011837518687572,"velocity":2.68707124652071,"position":2.7286566433926622,"holonomicRotation":184.3831319827435,"angularVelocity":-0.18577470110654137,"angularAcceleration":-0.5868850808504976,"curveRadius":-14.434399875827634},{"acceleration":3.0111423746636015,"curvature":-0.06957432492755804,"pose":{"rotation":{"radians":-2.9601442867600625},"translation":{"x":5.867996568521179,"y":2.037520782657559}},"time":2.0141263719289,"velocity":2.69396330950506,"position":2.7348227300456425,"holonomicRotation":184.43600832237155,"angularVelocity":-0.18708761362868923,"angularAcceleration":-0.5736114917468056,"curveRadius":-14.373118259375378},{"acceleration":3.011039256777154,"curvature":-0.06985334447395404,"pose":{"rotation":{"radians":-2.9605722617512016},"translation":{"x":5.861960253651585,"y":2.0364159927373255}},"time":2.0163985034081766,"velocity":2.7008047865857203,"position":2.7409593136206243,"holonomicRotation":184.48888466199963,"angularVelocity":-0.18835837408291517,"angularAcceleration":-0.5592812149368382,"curveRadius":-14.315706821637816},{"acceleration":3.0109357732267035,"curvature":-0.07011545274518598,"pose":{"rotation":{"radians":-2.960999906448079},"translation":{"x":5.855952088759344,"y":2.0353190101558454}},"time":2.0186541897709342,"velocity":2.707596513348527,"position":2.7470668021516347,"holonomicRotation":184.5417610016277,"angularVelocity":-0.18958517635163913,"angularAcceleration":-0.5438709427777719,"curveRadius":-14.262191298032494},{"acceleration":3.0108319065594777,"curvature":-0.0703600979143676,"pose":{"rotation":{"radians":-2.9614271300728245},"translation":{"x":5.84997167846047,"y":2.034229735002512}},"time":2.0208937039946298,"velocity":2.714339314228423,"position":2.753145603653785,"holonomicRotation":184.59463734125575,"angularVelocity":-0.1907662028779562,"angularAcceleration":-0.5273583502266039,"curveRadius":-14.212601028740167},{"acceleration":3.010727639729652,"curvature":-0.07058672963891961,"pose":{"rotation":{"radians":-2.961853840287956},"translation":{"x":5.8440186273709696,"y":2.0331480673667195}},"time":2.0231173154830695,"velocity":2.721034002796689,"position":2.759196126122839,"holonomicRotation":184.64751368088383,"angularVelocity":-0.19189962695823426,"angularAcceleration":-0.5097221732171169,"curveRadius":-14.16696884974576},{"acceleration":3.0106229572493968,"curvature":-0.07079479810114274,"pose":{"rotation":{"radians":-2.962279943220921},"translation":{"x":5.838092540106855,"y":2.0320739073378613}},"time":2.0253252901576677,"velocity":2.7276813820410597,"position":2.7652187775347588,"holonomicRotation":184.7003900205119,"angularVelocity":-0.1929836142900481,"angularAcceleration":-0.4909419226065577,"curveRadius":-14.125331617887028},{"acceleration":3.010517844601551,"curvature":-0.0709837575403735,"pose":{"rotation":{"radians":-2.9627053434926394},"translation":{"x":5.832193021284135,"y":2.031007155005331}},"time":2.027517890545679,"velocity":2.734282244635248,"position":2.7712139658452783,"holonomicRotation":184.75326636013997,"angularVelocity":-0.19401632602290064,"angularAcceleration":-0.47099860900290774,"curveRadius":-14.087729850469369},{"acceleration":3.0104122869417984,"curvature":-0.07115306261841507,"pose":{"rotation":{"radians":-2.9631299442472736},"translation":{"x":5.826319675518819,"y":2.0299477104585235}},"time":2.0296953758655114,"velocity":2.740837373196707,"position":2.7771820989894622,"holonomicRotation":184.80614269976803,"angularVelocity":-0.19499592064616955,"angularAcceleration":-0.44987427210039704,"curveRadius":-14.0542088168836},{"acceleration":3.0103062720858373,"curvature":-0.07130217526568934,"pose":{"rotation":{"radians":-2.963553647183915},"translation":{"x":5.820472107426919,"y":2.0288954737868306}},"time":2.031858002109239,"velocity":2.747347540542378,"position":2.78312358488128,"holonomicRotation":184.8590190393961,"angularVelocity":-0.19592055625435134,"angularAcceleration":-0.4275521999529504,"curveRadius":-14.024817563752515},{"acceleration":3.0101997864827674,"curvature":-0.07143056016995092,"pose":{"rotation":{"radians":-2.9639763525931055},"translation":{"x":5.814649921624444,"y":2.027850345079648}},"time":2.034006022122422,"velocity":2.7538135099274212,"position":2.789038831413177,"holonomicRotation":184.91189537902417,"angularVelocity":-0.19678839424043285,"angularAcceleration":-0.40401764450771355,"curveRadius":-13.999610217542092},{"acceleration":3.01009281967047,"curvature":-0.0715376894910044,"pose":{"rotation":{"radians":-2.9643979593918632},"translation":{"x":5.808852722727404,"y":2.026812224426368}},"time":2.0361396856813325,"velocity":2.7602360352856907,"position":2.794928246455658,"holonomicRotation":184.96477171865223,"angularVelocity":-0.1975976001450497,"angularAcceleration":-0.3792565614374578,"curveRadius":-13.978645482053851},{"acceleration":3.0099853601281548,"curvature":-0.0716230401508607,"pose":{"rotation":{"radians":-2.96481836516508},"translation":{"x":5.803080115351809,"y":2.0257810119163855}},"time":2.0382592395676946,"velocity":2.7666158614536434,"position":2.8007922378568733,"holonomicRotation":185.0176480582803,"angularVelocity":-0.19834634822068994,"angularAcceleration":-0.35325739083961477,"curveRadius":-13.961987621492817},{"acceleration":3.009877398310332,"curvature":-0.07168609873708655,"pose":{"rotation":{"radians":-2.9652374662064442},"translation":{"x":5.797331704113669,"y":2.0247566076390933}},"time":2.0403649276410176,"velocity":2.77295372439343,"position":2.806631213442205,"holonomicRotation":185.07052439790837,"angularVelocity":-0.1990328228922928,"angularAcceleration":-0.3260096689057635,"curveRadius":-13.949705976713357},{"acceleration":3.0097689246336214,"curvature":-0.07172635881388015,"pose":{"rotation":{"radians":-2.9656551575637877},"translation":{"x":5.791607093628994,"y":2.0237389116838855}},"time":2.0424569909086294,"velocity":2.7792503514046554,"position":2.812445581013876,"holonomicRotation":185.12340073753643,"angularVelocity":-0.19965522257857085,"angularAcceleration":-0.2975051930377613,"curveRadius":-13.941875992825175},{"acceleration":3.009659931318643,"curvature":-0.07174332502850876,"pose":{"rotation":{"radians":-2.9660713330852984},"translation":{"x":5.785905888513795,"y":2.022727824140156}},"time":2.0445356675934794,"velocity":2.7855064613332146,"position":2.8182357483505482,"holonomicRotation":185.17627707716449,"angularVelocity":-0.20021176190787537,"angularAcceleration":-0.2677373221919287,"curveRadius":-13.93857894936746},{"acceleration":3.0095504106535023,"curvature":-0.07173651140540463,"pose":{"rotation":{"radians":-2.966485885469671},"translation":{"x":5.780227693384081,"y":2.021723245097298}},"time":2.046601193199805,"velocity":2.791722764769947,"position":2.8240021232069425,"holonomicRotation":185.22915341679257,"angularVelocity":-0.2007006754615184,"angularAcceleration":-0.23670176353454883,"curveRadius":-13.93990285293773},{"acceleration":3.0094403559034895,"curvature":-0.07170544410793854,"pose":{"rotation":{"radians":-2.966898706317642},"translation":{"x":5.774572112855862,"y":2.020725074644706}},"time":2.048653800576735,"velocity":2.7978999642449054,"position":2.829745113313464,"holonomicRotation":185.28202975642063,"angularVelocity":-0.20112022036511576,"angularAcceleration":-0.2043960809615953,"curveRadius":-13.945942493497359},{"acceleration":3.00932976102388,"curvature":-0.07164966177785002,"pose":{"rotation":{"radians":-2.9673096861865025},"translation":{"x":5.768938751545147,"y":2.019733212871773}},"time":2.0506937199799036,"velocity":2.8040387544149508,"position":2.8354651263758317,"holonomicRotation":185.3349060960487,"angularVelocity":-0.20146867970465854,"angularAcceleration":-0.17082015054198496,"curveRadius":-13.956800006963087},{"acceleration":3.0092186213217818,"curvature":-0.0715687174500262,"pose":{"rotation":{"radians":-2.9677187146472126},"translation":{"x":5.763327214067949,"y":2.0187475598678937}},"time":2.052721179131149,"velocity":2.810139822246848,"position":2.8411625700747254,"holonomicRotation":185.38778243567677,"angularVelocity":-0.20174436582796165,"angularAcceleration":-0.13597616658947764,"curveRadius":-13.972585168907953},{"acceleration":3.009106931931988,"curvature":-0.07146217630963082,"pose":{"rotation":{"radians":-2.9681256803431397},"translation":{"x":5.757737105040276,"y":2.017768015722461}},"time":2.054736403276366,"velocity":2.8162038471916175,"position":2.8468378520654394,"holonomicRotation":185.44065877530483,"angularVelocity":-0.20194562321665582,"angularAcceleration":-0.099868488163873,"curveRadius":-13.99341654062153},{"acceleration":3.0089946896633424,"curvature":-0.07132962351929778,"pose":{"rotation":{"radians":-2.968530471052598},"translation":{"x":5.752168029078138,"y":2.0167944805248688}},"time":2.056739615241576,"velocity":2.8222315013572032,"position":2.8524913799775495,"holonomicRotation":185.4935351149329,"angularVelocity":-0.20207083248730193,"angularAcceleration":-0.06250425457747504,"curveRadius":-14.01942069313539},{"acceleration":3.0088818916218343,"curvature":-0.071170655633149,"pose":{"rotation":{"radians":-2.9689329737523558},"translation":{"x":5.746619590797545,"y":2.015826854364511}},"time":2.0587310354872757,"velocity":2.8282234496730987,"position":2.8581235614145917,"holonomicRotation":185.54641145456097,"angularVelocity":-0.2021184130405158,"angularAcceleration":-0.023892773670763312,"curveRadius":-14.050734689793025},{"acceleration":3.0087685367678625,"curvature":-0.07098489184536416,"pose":{"rotation":{"radians":-2.9693330746844793},"translation":{"x":5.741091394814508,"y":2.0148650373307815}},"time":2.06071088216113,"velocity":2.8341803500530167,"position":2.863734803953748,"holonomicRotation":185.59928779418902,"angularVelocity":-0.20208682692814442,"angularAcceleration":0.015953817428647408,"curveRadius":-14.087504735210882},{"acceleration":3.008654622137308,"curvature":-0.07077196695998422,"pose":{"rotation":{"radians":-2.9697306594248003},"translation":{"x":5.735583045745037,"y":2.0139089295130734}},"time":2.0626793711490663,"velocity":2.840102853545197,"position":2.8693255151455577,"holonomicRotation":185.6521641338171,"angularVelocity":-0.2019745819040044,"angularAcceleration":0.057020905287202606,"curveRadius":-14.129888470747444},{"acceleration":3.0085401491943458,"curvature":-0.07053153687784866,"pose":{"rotation":{"radians":-2.9701256129548943},"translation":{"x":5.730094148205141,"y":2.012958431000781}},"time":2.0646367161248156,"velocity":2.8459916044905627,"position":2.874896102513632,"holonomicRotation":185.70504047344517,"angularVelocity":-0.20178023546554877,"angularAcceleration":0.09929084594873089,"curveRadius":-14.178054871140386},{"acceleration":3.0084251177948977,"curvature":-0.07026327754771469,"pose":{"rotation":{"radians":-2.970517819734405},"translation":{"x":5.72462430681083,"y":2.0120134418832984}},"time":2.066583128597968,"velocity":2.8518472406643833,"position":2.880446973554386,"holonomicRotation":185.75791681307322,"angularVelocity":-0.20150239731837338,"angularAcceleration":0.14274371491537657,"curveRadius":-14.232185501465054},{"acceleration":3.008309528466757,"curvature":-0.06996688672301346,"pose":{"rotation":{"radians":-2.970907163776901},"translation":{"x":5.719173126178116,"y":2.011073862250018}},"time":2.068518817960583,"velocity":2.85767039341809,"position":2.8859785357367853,"holonomicRotation":185.8107931527013,"angularVelocity":-0.2011397334797757,"angularAcceleration":0.18735642484894235,"curveRadius":-14.292475295618388},{"acceleration":3.0081933838272295,"curvature":-0.06964208582751631,"pose":{"rotation":{"radians":-2.9712935287286593},"translation":{"x":5.713740210923005,"y":2.0101395921903356}},"time":2.070443991532411,"velocity":2.8634616878195818,"position":2.8914911965021175,"holonomicRotation":185.86366949232936,"angularVelocity":-0.20069097010900083,"angularAcceleration":0.23310281075008088,"curveRadius":-14.35913339064422},{"acceleration":3.0080766867443844,"curvature":-0.0692886195137141,"pose":{"rotation":{"radians":-2.9716767979460625},"translation":{"x":5.708325165661511,"y":2.0092105317936433}},"time":2.07235885460476,"velocity":2.8692217427858235,"position":2.89698536326376,"holonomicRotation":185.91654583195742,"angularVelocity":-0.2001548951137535,"angularAcceleration":0.27995474088370104,"curveRadius":-14.432384524590981},{"acceleration":3.0079594405321113,"curvature":-0.06890625574564346,"pose":{"rotation":{"radians":-2.972056854579587},"translation":{"x":5.702927595009643,"y":2.008286581149335}},"time":2.074263610483072,"velocity":2.8749511712119,"position":2.9024614434069846,"holonomicRotation":185.9694221715855,"angularVelocity":-0.19953036389169382,"angularAcceleration":0.32787992895618295,"curveRadius":-14.512470445228395},{"acceleration":3.0078416495023066,"curvature":-0.0684947908446537,"pose":{"rotation":{"radians":-2.9724335816564826},"translation":{"x":5.6975471035834095,"y":2.007367640346805}},"time":2.076158460528233,"velocity":2.8806505800972966,"position":2.907919844288775,"holonomicRotation":186.02229851121356,"angularVelocity":-0.19881630098265946,"angularAcceleration":0.37684402037929876,"curveRadius":-14.59965039192545},{"acceleration":3.0077233184383076,"curvature":-0.06805404415517174,"pose":{"rotation":{"radians":-2.972806862165555},"translation":{"x":5.692183295998822,"y":2.0064536094754466}},"time":2.07804360419667,"velocity":2.8863205706674617,"position":2.913360973237649,"holonomicRotation":186.07517485084165,"angularVelocity":-0.19801170346957445,"angularAcceleration":0.4268096519943181,"curveRadius":-14.69420388478126},{"acceleration":3.0076044539186566,"curvature":-0.06758386570803815,"pose":{"rotation":{"radians":-2.973176579145247},"translation":{"x":5.686835776871891,"y":2.005544388624654}},"time":2.079919239079272,"velocity":2.8919617384942997,"position":2.9187852375535184,"holonomicRotation":186.1280511904697,"angularVelocity":-0.19711564501258083,"angularAcceleration":0.4777360803562693,"curveRadius":-14.79643091621887},{"acceleration":3.007485061506527,"curvature":-0.0670841307940692,"pose":{"rotation":{"radians":-2.9735426157720832},"translation":{"x":5.681504150818625,"y":2.0046398778838204}},"time":2.081785560939169,"velocity":2.8975746736079033,"position":2.924193044507557,"holonomicRotation":186.18092753009776,"angularVelocity":-0.19612727831227364,"angularAcceleration":0.5295799837878362,"curveRadius":-14.906655093583002},{"acceleration":3.0073651491094786,"curvature":-0.06655474662749288,"pose":{"rotation":{"radians":-2.9739048554505625},"translation":{"x":5.676188022455034,"y":2.00373997734234}},"time":2.083642763748413,"velocity":2.903159960611253,"position":2.9295848013420898,"holonomicRotation":186.23380386972585,"angularVelocity":-0.19504583811536355,"angularAcceleration":0.5822951545879568,"curveRadius":-15.0252243554769},{"acceleration":3.0072447251463568,"curvature":-0.06599564604985941,"pose":{"rotation":{"radians":-2.974263181905277},"translation":{"x":5.6708869963971305,"y":2.0028445870896063}},"time":2.085491039723589,"velocity":2.9087181787882153,"position":2.9349609152705014,"holonomicRotation":186.2866802093539,"angularVelocity":-0.19387064460466943,"angularAcceleration":0.6358322709801372,"curveRadius":-15.152514746874429},{"acceleration":3.0071237970850704,"curvature":-0.06540679642178687,"pose":{"rotation":{"radians":-2.974617479273557},"translation":{"x":5.6656006772609215,"y":2.001953607215013}},"time":2.0873305793603976,"velocity":2.9142499022057433,"position":2.940321793477174,"holonomicRotation":186.33955654898196,"angularVelocity":-0.1926011058368129,"angularAcceleration":0.6901393927336763,"curveRadius":-15.288931039388164},{"acceleration":3.007002375859575,"curvature":-0.06478819322392294,"pose":{"rotation":{"radians":-2.974967632199958},"translation":{"x":5.660328669662419,"y":2.001066937807954}},"time":2.0891615714672316,"velocity":2.9197556998211733,"position":2.9456678431174304,"holonomicRotation":186.39243288861005,"angularVelocity":-0.19123672084332496,"angularAcceleration":0.7451615921201844,"curveRadius":-15.434911057694869},{"acceleration":3.006880470890082,"curvature":-0.06413986580538766,"pose":{"rotation":{"radians":-2.975313525930653},"translation":{"x":5.655070578217631,"y":2.0001844789578236}},"time":2.090984203197791,"velocity":2.9252361355774177,"position":2.9509994713175134,"holonomicRotation":186.4453092282381,"angularVelocity":-0.189777081620784,"angularAcceleration":0.8008415512950573,"curveRadius":-15.590927536926673},{"acceleration":3.006758093027201,"curvature":-0.06346187349959494,"pose":{"rotation":{"radians":-2.9756550464102633},"translation":{"x":5.64982600754257,"y":1.9993061307540143}},"time":2.0927986600827557,"velocity":2.9306917685007337,"position":2.9563170851745784,"holonomicRotation":186.49818556786616,"angularVelocity":-0.18822187644150298,"angularAcceleration":0.8571188393442755,"curveRadius":-15.757492567665572},{"acceleration":3.0066352543232386,"curvature":-0.06275431017243084,"pose":{"rotation":{"radians":-2.975992080378627},"translation":{"x":5.6445945622532445,"y":1.9984317932859208}},"time":2.0946051260605483,"velocity":2.9361231527953002,"position":2.961621091756712,"holonomicRotation":186.55106190749424,"angularVelocity":-0.18657089173390098,"angularAcceleration":0.9139306955669637,"curveRadius":-15.93516042567095},{"acceleration":3.0065119660123147,"curvature":-0.06201730166523397,"pose":{"rotation":{"radians":-2.976324515467583},"translation":{"x":5.639375846965666,"y":1.9975613666429366}},"time":2.09640378350722,"velocity":2.941530837931476,"position":2.966911898102972,"holonomicRotation":186.6039382471223,"angularVelocity":-0.18482401391709938,"angularAcceleration":0.9712120671081956,"curveRadius":-16.124532560251424},{"acceleration":3.0063882428908504,"curvature":-0.06125100752553082,"pose":{"rotation":{"radians":-2.9766522402996323},"translation":{"x":5.634169466295843,"y":1.996694750914455}},"time":2.098194813265478,"velocity":2.9469153687393703,"position":2.972189911223452,"holonomicRotation":186.6568145867504,"angularVelocity":-0.1829812321869068,"angularAcceleration":1.0288950932814032,"curveRadius":-16.32626205508827},{"acceleration":3.006264096401791,"curvature":-0.060455622111557986,"pose":{"rotation":{"radians":-2.976975144586052},"translation":{"x":5.628975024859785,"y":1.9958318461898703}},"time":2.099978394672888,"velocity":2.9522772854874764,"position":2.977455538099366,"holonomicRotation":186.70969092637844,"angularVelocity":-0.1810426398695218,"angularAcceleration":1.0869099158194537,"curveRadius":-16.541058797719636},{"acceleration":3.0061395428284308,"curvature":-0.05963137176372053,"pose":{"rotation":{"radians":-2.977293119224984},"translation":{"x":5.623792127273504,"y":1.9949725525585762}},"time":2.101754705589269,"velocity":2.9576171239735674,"position":2.982709185683156,"holonomicRotation":186.7625672660065,"angularVelocity":-0.17900843596679816,"angularAcceleration":1.1451845980139308,"curveRadius":-16.7696963934074},{"acceleration":3.0060145950616812,"curvature":-0.058778519798064394,"pose":{"rotation":{"radians":-2.977606056400415},"translation":{"x":5.6186203781530075,"y":1.9941167701099665}},"time":2.1035239224233173,"velocity":2.9629354155985457,"position":2.987951260898631,"holonomicRotation":186.81544360563458,"angularVelocity":-0.1768789271098274,"angularAcceleration":1.2036449212943185,"curveRadius":-17.013017739057297},{"acceleration":3.005889270847649,"curvature":-0.05789736370894879,"pose":{"rotation":{"radians":-2.977913849680029},"translation":{"x":5.613459382114309,"y":1.9932643989334344}},"time":2.1052862201584643,"velocity":2.968232687452663,"position":2.993182170641118,"holonomicRotation":186.86831994526264,"angularVelocity":-0.17465452827592415,"angularAcceleration":1.2622151124297203,"curveRadius":-17.271943590161033},{"acceleration":3.0057635845559956,"curvature":-0.0569882319670505,"pose":{"rotation":{"radians":-2.9782163941139483},"translation":{"x":5.608308743773415,"y":1.9924153391183739}},"time":2.1070417723780106,"velocity":2.973509462384962,"position":2.99840232177765,"holonomicRotation":186.9211962848907,"angularVelocity":-0.1723357645251362,"angularAcceleration":1.3208173046468898,"curveRadius":-17.54748244476475},{"acceleration":3.0056375532887025,"curvature":-0.056051491764947434,"pose":{"rotation":{"radians":-2.978513586331728},"translation":{"x":5.603168067746338,"y":1.9915694907541792}},"time":2.1087907512895416,"velocity":2.9787662590813695,"position":3.0036121211471634,"holonomicRotation":186.97407262451878,"angularVelocity":-0.16992327112711,"angularAcceleration":1.3793724910692737,"curveRadius":-17.84073837309293},{"acceleration":3.0055111949679887,"curvature":-0.05508754074520612,"pose":{"rotation":{"radians":-2.978805324639168},"translation":{"x":5.598036958649087,"y":1.9907267539302436}},"time":2.110533327748655,"velocity":2.9840035921373227,"position":3.008811975560732,"holonomicRotation":187.02694896414684,"angularVelocity":-0.16741779444691593,"angularAcceleration":1.437800141905242,"curveRadius":-18.15292508019652},{"acceleration":3.0053845270685122,"curvature":-0.05409681500330614,"pose":{"rotation":{"radians":-2.9790915091153254},"translation":{"x":5.592915021097672,"y":1.989887028735961}},"time":2.1122696712820184,"velocity":2.989221972126168,"position":3.0140022918018206,"holonomicRotation":187.0798253037749,"angularVelocity":-0.16482019292756797,"angularAcceleration":1.4960181953835154,"curveRadius":-18.48537663333571},{"acceleration":3.005257568030985,"curvature":-0.05307978317005739,"pose":{"rotation":{"radians":-2.979372041706799},"translation":{"x":5.587801859708104,"y":1.989050215260725}},"time":2.113999950109772,"velocity":2.9944219056680783,"position":3.0191834766265595,"holonomicRotation":187.13270164340298,"angularVelocity":-0.162131436259823,"angularAcceleration":1.5539441531720204,"curveRadius":-18.83956452490005},{"acceleration":3.0051303364648603,"curvature":-0.05203694539107802,"pose":{"rotation":{"radians":-2.9796468263223272},"translation":{"x":5.582697079096391,"y":1.9882162135939294}},"time":2.1157243311673035,"velocity":2.999603895495692,"position":3.0243559367640502,"holonomicRotation":187.18557798303104,"angularVelocity":-0.15935260615861777,"angularAcceleration":1.6114942164715338,"curveRadius":-19.21711569510102},{"acceleration":3.00500285278196,"curvature":-0.0509688361073707,"pose":{"rotation":{"radians":-2.9799157689253892},"translation":{"x":5.577600283878544,"y":1.9873849238249681}},"time":2.1174429801264036,"velocity":3.0047684405207185,"position":3.029520078916688,"holonomicRotation":187.2384543226591,"angularVelocity":-0.15648489567223828,"angularAcceleration":1.6685841929471217,"curveRadius":-19.619831967388954},{"acceleration":3.0048751362289323,"curvature":-0.04987602422878399,"pose":{"rotation":{"radians":-2.980178777625193},"translation":{"x":5.5725110786705745,"y":1.9865562460432344}},"time":2.1191560614158256,"velocity":3.0099160358936414,"position":3.0346763097605085,"holonomicRotation":187.29133066228718,"angularVelocity":-0.15352960856436676,"angularAcceleration":1.725129523111395,"curveRadius":-20.049713574060085},{"acceleration":3.004747207232461,"curvature":-0.0487591091680837,"pose":{"rotation":{"radians":-2.9804357627671108},"translation":{"x":5.567429068088491,"y":1.9857300803381228}},"time":2.1208637382412676,"velocity":3.015047173065744,"position":3.0398250359455674,"holonomicRotation":187.34420700191524,"angularVelocity":-0.15048815916975974,"angularAcceleration":1.7810450720496973,"curveRadius":-20.50898831134862},{"acceleration":3.0046190871744454,"curvature":-0.047618721597278015,"pose":{"rotation":{"radians":-2.9806866370193608},"translation":{"x":5.562353856748303,"y":1.9849063267990263}},"time":2.122566172604787,"velocity":3.0201623398490356,"position":3.044966664096333,"holonomicRotation":187.39708334154332,"angularVelocity":-0.1473620702365332,"angularAcceleration":1.836246377666126,"curveRadius":-21.000143776584757},{"acceleration":3.0044907972512345,"curvature":-0.04645552436094055,"pose":{"rotation":{"radians":-2.980931315459857},"translation":{"x":5.557285049266023,"y":1.984084885515339}},"time":2.124263525323666,"velocity":3.025262020472597,"position":3.050101600812104,"holonomicRotation":187.44995968117138,"angularVelocity":-0.14415297290578805,"angularAcceleration":1.890648475741957,"curveRadius":-21.525965184041542},{"acceleration":3.004362359209548,"curvature":-0.04527021245059497,"pose":{"rotation":{"radians":-2.9811697156594663},"translation":{"x":5.552222250257659,"y":1.9832656565764548}},"time":2.1259559560487484,"velocity":3.0303466956386047,"position":3.055230252667455,"holonomicRotation":187.50283602079944,"angularVelocity":-0.140862604345468,"angularAcceleration":1.944167351464049,"curveRadius":-22.089580451855323},{"acceleration":3.004233795328399,"curvature":-0.04406350480797115,"pose":{"rotation":{"radians":-2.9814017577633525},"translation":{"x":5.547165064339219,"y":1.982448540071767}},"time":2.127643623282254,"velocity":3.035416842576771,"position":3.060353026212703,"holonomicRotation":187.55571236042752,"angularVelocity":-0.13749280621165264,"angularAcceleration":1.9967195350562725,"curveRadius":-22.694517931744244},{"acceleration":3.0041051277400816,"curvature":-0.04283615398909604,"pose":{"rotation":{"radians":-2.9816273645701057},"translation":{"x":5.542113096126717,"y":1.9816334360906698}},"time":2.129326684395088,"velocity":3.040472935096135,"position":3.065470327974387,"holonomicRotation":187.60858870005558,"angularVelocity":-0.1340455227875553,"angularAcceleration":2.048222371612589,"curveRadius":-23.344766205074112},{"acceleration":3.0039763802796644,"curvature":-0.04158893654221479,"pose":{"rotation":{"radians":-2.981846461608171},"translation":{"x":5.537065950236162,"y":1.9808202447225567}},"time":2.1310052956436616,"velocity":3.045515443638522,"position":3.0705825644557834,"holonomicRotation":187.66146503968363,"angularVelocity":-0.13052279868330766,"angularAcceleration":2.0985943631922357,"curveRadius":-24.044856232016212},{"acceleration":3.0038475750118243,"curvature":-0.04032265701569884,"pose":{"rotation":{"radians":-2.982058977209157},"translation":{"x":5.5320232312835635,"y":1.980008866056821}},"time":2.132679612186237,"velocity":3.0505448353247386,"position":3.075690142137435,"holonomicRotation":187.71434137931172,"angularVelocity":-0.1269267761395737,"angularAcceleration":2.1477554884591994,"curveRadius":-24.799953029153546},{"acceleration":3.003718737226406,"curvature":-0.039038144869958886,"pose":{"rotation":{"radians":-2.9822648425792453},"translation":{"x":5.5269845438849305,"y":1.9791992001828573}},"time":2.1343497880988016,"velocity":3.0555615740077737,"position":3.0807934674777013,"holonomicRotation":187.76721771893978,"angularVelocity":-0.1232596929099097,"angularAcceleration":2.1956269408967066,"curveRadius":-25.615971336013263},{"acceleration":3.0035898893424795,"curvature":-0.03773625358839024,"pose":{"rotation":{"radians":-2.9824639918655502},"translation":{"x":5.521949492656275,"y":1.978391147190059}},"time":2.136015976390496,"velocity":3.060566120314448,"position":3.085892946913326,"holonomicRotation":187.82009405856786,"angularVelocity":-0.11952387812208912,"angularAcceleration":2.242132420713087,"curveRadius":-26.499715920598316},{"acceleration":3.003461055496261,"curvature":-0.036417861140805474,"pose":{"rotation":{"radians":-2.982656362222182},"translation":{"x":5.516917682213605,"y":1.9775846071678198}},"time":2.1376783290185997,"velocity":3.065558931693459,"position":3.090988986860033,"holonomicRotation":187.87297039819592,"angularVelocity":-0.1157217508364786,"angularAcceleration":2.2871966039767484,"curveRadius":-27.459053570818313},{"acceleration":3.003332261888179,"curvature":-0.03508386469353477,"pose":{"rotation":{"radians":-2.982841893870354},"translation":{"x":5.5118887171729325,"y":1.9767794802055334}},"time":2.1393369969030847,"velocity":3.0705404624626906,"position":3.0960819937131316,"holonomicRotation":187.92584673782397,"angularVelocity":-0.11185581508345034,"angularAcceleration":2.3307473359735478,"curveRadius":-28.503131246663347},{"acceleration":3.0032035312099397,"curvature":-0.033735181951192864,"pose":{"rotation":{"radians":-2.9830205301568284},"translation":{"x":5.506862202150267,"y":1.9759756663925936}},"time":2.140992129940758,"velocity":3.0755111638460533,"position":3.1011723738481463,"holonomicRotation":187.97872307745206,"angularVelocity":-0.10792865733968485,"angularAcceleration":2.372714249777846,"curveRadius":-29.64264433038401},{"acceleration":3.0030748891340293,"curvature":-0.03237275137687268,"pose":{"rotation":{"radians":-2.983192217607971},"translation":{"x":5.501837741761617,"y":1.9751730658183941}},"time":2.142643877018994,"velocity":3.0804714840199043,"position":3.1062605336214655,"holonomicRotation":188.03159941708012,"angularVelocity":-0.1039429422366247,"angularAcceleration":2.4130299097103323,"curveRadius":-30.890176381931102},{"acceleration":3.002946360434136,"curvature":-0.03099752754317262,"pose":{"rotation":{"radians":-2.983356905980234},"translation":{"x":5.496814940622994,"y":1.9743715785723288}},"time":2.1442923860290684,"velocity":3.08542186815185,"position":3.1113468793709944,"holonomicRotation":188.08447575670817,"angularVelocity":-0.09990140864051988,"angularAcceleration":2.451629667418319,"curveRadius":-32.2606375172092},{"acceleration":3.0028179715809737,"curvature":-0.02961048248320636,"pose":{"rotation":{"radians":-2.98351454830759},"translation":{"x":5.4917934033504086,"y":1.9735711047437912}},"time":2.1459378038791117,"velocity":3.0903627584427205,"position":3.1164318174168453,"holonomicRotation":188.13735209633626,"angularVelocity":-0.0958068659287853,"angularAcceleration":2.48845161830881,"curveRadius":-33.77182389942993},{"acceleration":3.0026897456710326,"curvature":-0.02821259642586811,"pose":{"rotation":{"radians":-2.9836651009444215},"translation":{"x":5.486772734559869,"y":1.9727715444221754}},"time":2.1475802765066843,"velocity":3.095294594159078,"position":3.121515754062025,"holonomicRotation":188.19022843596431,"angularVelocity":-0.09166218925304546,"angularAcceleration":2.523437289707131,"curveRadius":-35.4451602009626},{"acceleration":3.002561709491434,"curvature":-0.02680487342401615,"pose":{"rotation":{"radians":-2.9838085236044467},"translation":{"x":5.481752538867386,"y":1.9719727976968746}},"time":2.149219948890984,"velocity":3.100217811676287,"position":3.1265990955931446,"holonomicRotation":188.24310477559237,"angularVelocity":-0.08747031504495169,"angularAcceleration":2.5565315658371683,"curveRadius":-37.30664883886517},{"acceleration":3.0024338893861944,"curvature":-0.02538831876277781,"pose":{"rotation":{"radians":-2.983944779396623},"translation":{"x":5.47673242088897,"y":1.9711747646572828}},"time":2.150856965064697,"velocity":3.1051328445137165,"position":3.1316822482811415,"holonomicRotation":188.29598111522046,"angularVelocity":-0.08323423700034813,"angularAcceleration":2.587682463145809,"curveRadius":-39.38819302466435},{"acceleration":3.002306308999096,"curvature":-0.023963952715664545,"pose":{"rotation":{"radians":-2.9840738348561606},"translation":{"x":5.471711985240631,"y":1.9703773453927942}},"time":2.1524914681255054,"velocity":3.1100401233652595,"position":3.1367656183820185,"holonomicRotation":188.3488574548485,"angularVelocity":-0.07895700083538369,"angularAcceleration":2.6168419426815603,"curveRadius":-41.729342895353355},{"acceleration":3.0021789956653473,"curvature":-0.022532804016480154,"pose":{"rotation":{"radians":-2.9841956599712316},"translation":{"x":5.466690836538379,"y":1.9695804399928019}},"time":2.1541236002472477,"velocity":3.114940076139305,"position":3.141849612137588,"holonomicRotation":188.40173379447657,"angularVelocity":-0.07464169931348758,"angularAcceleration":2.643965806695575,"curveRadius":-44.37974072239811},{"acceleration":3.0020519735878617,"curvature":-0.021095903529514223,"pose":{"rotation":{"radians":-2.9843102282068092},"translation":{"x":5.461668579398224,"y":1.9687839485467}},"time":2.1557535026907555,"velocity":3.119833127986593,"position":3.14693463577623,"holonomicRotation":188.45461013410466,"angularVelocity":-0.07029146807773444,"angularAcceleration":2.6690132609352766,"curveRadius":-47.40256792514006},{"acceleration":3.0019252705140387,"curvature":-0.0196542916188859,"pose":{"rotation":{"radians":-2.9844175165229276},"translation":{"x":5.4566448184361755,"y":1.9679877711438822}},"time":2.157381315814364,"velocity":3.124719701338028,"position":3.152021095513666,"holonomicRotation":188.5074864737327,"angularVelocity":-0.06590947975684007,"angularAcceleration":2.6919480236039024,"curveRadius":-50.87947301235193},{"acceleration":3.0017989094389903,"curvature":-0.018209009117199894,"pose":{"rotation":{"radians":-2.9845175053895585},"translation":{"x":5.451619158268244,"y":1.967191807873742}},"time":2.15900717908411,"velocity":3.1296002159280487,"position":3.1571093975537328,"holonomicRotation":188.5603628133608,"angularVelocity":-0.06149893935821975,"angularAcceleration":2.712737584205979,"curveRadius":-54.917870245636735},{"acceleration":3.001672917558974,"curvature":-0.016761096676159545,"pose":{"rotation":{"radians":-2.984610178797225},"translation":{"x":5.446591203510439,"y":1.9663959588256734}},"time":2.160631231083622,"velocity":3.134475088831691,"position":3.16219994808917,"holonomicRotation":188.61323915298885,"angularVelocity":-0.05706307907280864,"angularAcceleration":2.7313536061310515,"curveRadius":-59.66196719230004},{"acceleration":3.001547320423566,"curvature":-0.015311604498496056,"pose":{"rotation":{"radians":-2.9846955242629583},"translation":{"x":5.441560558778772,"y":1.96560012408907}},"time":2.1622536095237113,"velocity":3.139344734491254,"position":3.1672931533024165,"holonomicRotation":188.6661154926169,"angularVelocity":-0.052605152795637315,"angularAcceleration":2.7477721393573287,"curveRadius":-65.30994188742417},{"acceleration":3.0014221424948606,"curvature":-0.013861567007009747,"pose":{"rotation":{"radians":-2.9847735328326084},"translation":{"x":5.43652682868925,"y":1.9648042037533255}},"time":2.163874451251673,"velocity":3.1442095647430386,"position":3.172389419366409,"holonomicRotation":188.718991832245,"angularVelocity":-0.04812843123690502,"angularAcceleration":2.7619732892497315,"curveRadius":-72.14191580896326},{"acceleration":3.0012974101701775,"curvature":-0.012412015461179452,"pose":{"rotation":{"radians":-2.9848441990783443},"translation":{"x":5.4314896178578875,"y":1.9640080979078343}},"time":2.1654938922603004,"velocity":3.149069988848155,"position":3.177489152445387,"holonomicRotation":188.77186817187305,"angularVelocity":-0.0436361962920971,"angularAcceleration":2.773941700177128,"curveRadius":-80.56709267948132},{"acceleration":3.001173147532702,"curvature":-0.010963996215455591,"pose":{"rotation":{"radians":-2.9849075210924867},"translation":{"x":5.426448530900691,"y":1.9632117066419892}},"time":2.167112067696624,"velocity":3.1539264135156455,"position":3.1825927586957095,"holonomicRotation":188.8247445115011,"angularVelocity":-0.03913173610289088,"angularAcceleration":2.7836661514531107,"curveRadius":-91.20761995433128},{"acceleration":3.001049380168739,"curvature":-0.009518529537889094,"pose":{"rotation":{"radians":-2.984963500477047},"translation":{"x":5.4214031724336715,"y":1.9624149300451843}},"time":2.1687291118703764,"velocity":3.1587792429309913,"position":3.1877006442666618,"holonomicRotation":188.8776208511292,"angularVelocity":-0.03461833972682781,"angularAcceleration":2.7911398150546103,"curveRadius":-105.0582441352352},{"acceleration":3.000926132102669,"curvature":-0.008076628785420141,"pose":{"rotation":{"radians":-2.985012142328798},"translation":{"x":5.416353147072839,"y":1.9616176682068134}},"time":2.170345158262198,"velocity":3.1636288787788995,"position":3.1928132153012756,"holonomicRotation":188.93049719075725,"angularVelocity":-0.03009929170169038,"angularAcceleration":2.7963603322322204,"curveRadius":-123.81403510895427},{"acceleration":3.000803429014669,"curvature":-0.0066392982633189926,"pose":{"rotation":{"radians":-2.9850534552207755},"translation":{"x":5.411298059434204,"y":1.9608198212162704}},"time":2.17196033953158,"velocity":3.168475720270541,"position":3.197930877937148,"holonomicRotation":188.9833735303853,"angularVelocity":-0.025577867178603962,"angularAcceleration":2.7993294677177403,"curveRadius":-150.61832747066538},{"acceleration":3.000681294896907,"curvature":-0.005207548655406601,"pose":{"rotation":{"radians":-2.9850874511792127},"translation":{"x":5.4062375141337755,"y":1.960021289162949}},"time":2.1735747875245575,"velocity":3.173320164164652,"position":3.203054038307258,"holonomicRotation":189.0362498700134,"angularVelocity":-0.0210573264577768,"angularAcceleration":2.800053479883438,"curveRadius":-192.02893072574102},{"acceleration":3.000559752185968,"curvature":-0.0037823399998785207,"pose":{"rotation":{"radians":-2.985114145657133},"translation":{"x":5.401171115787564,"y":1.9592219721362425}},"time":2.17518863328116,"velocity":3.1781626047881493,"position":3.208183102540788,"holonomicRotation":189.08912620964145,"angularVelocity":-0.0165409103137224,"angularAcceleration":2.79854262749542,"curveRadius":-264.3865966655873},{"acceleration":3.0004388278357363,"curvature":-0.0023646704359831343,"pose":{"rotation":{"radians":-2.9851335575035534},"translation":{"x":5.396098469011581,"y":1.9584217702255449}},"time":2.1768020070426166,"velocity":3.1830034340658355,"position":3.2133184767639364,"holonomicRotation":189.14200254926953,"angularVelocity":-0.012031834708273965,"angularAcceleration":2.7948115391296966,"curveRadius":-422.89191118687137},{"acceleration":3.000318542434053,"curvature":-0.0009554905040638311,"pose":{"rotation":{"radians":-2.9851457089292346},"translation":{"x":5.391019178421835,"y":1.95762058352025}},"time":2.178415038258335,"velocity":3.18784304153188,"position":3.218460567100738,"holonomicRotation":189.1948788888976,"angularVelocity":-0.007533286127892439,"angularAcceleration":2.7888788118574763,"curveRadius":-1046.5828762785857},{"acceleration":3.0001989199715102,"curvature":0.0004443814669934172,"pose":{"rotation":{"radians":-2.9851506254682216},"translation":{"x":5.385932848634336,"y":1.956818312109752}},"time":2.1800278555926456,"velocity":3.19268181435639,"position":3.22360977967387,"holonomicRotation":189.24775522852565,"angularVelocity":-0.0030484165084601147,"angularAcceleration":2.7807672474882716,"curveRadius":2250.3188685292616},{"acceleration":3.0000799845211366,"curvature":0.0018337959820961796,"pose":{"rotation":{"radians":-2.9851483359361626},"translation":{"x":5.3808390842650935,"y":1.9560148560834438}},"time":2.1816405869313265,"velocity":3.1975201373659767,"position":3.2287665206054634,"holonomicRotation":189.30063156815373,"angularVelocity":0.001419661169928537,"angularAcceleration":2.7705034131991484,"curveRadius":545.3169326158725},{"acceleration":2.9999617574708477,"curvature":0.0032120099700976993,"pose":{"rotation":{"radians":-2.9851388723854306},"translation":{"x":5.375737489930119,"y":1.9552101155307198}},"time":2.183253359387911,"velocity":3.202358393059233,"position":3.233931196017902,"holonomicRotation":189.3535079077818,"angularVelocity":0.0058678772032034025,"angularAcceleration":2.758117560300366,"curveRadius":311.3315367354178},{"acceleration":2.99984426054091,"curvature":0.004578124516223097,"pose":{"rotation":{"radians":-2.9851222700557734},"translation":{"x":5.370627670245422,"y":1.9544039905409734}},"time":2.184866299309784,"velocity":3.207196961626461,"position":3.239104212034619,"holonomicRotation":189.40638424740985,"angularVelocity":0.010293210200910343,"angularAcceleration":2.743644036393024,"curveRadius":218.430057211504},{"acceleration":2.999727517058003,"curvature":0.005931287758735295,"pose":{"rotation":{"radians":-2.985098567322811},"translation":{"x":5.365509229827012,"y":1.9535963812035984}},"time":2.1864795322840695,"velocity":3.2120362209708504,"position":3.2442859747808885,"holonomicRotation":189.45926058703793,"angularVelocity":0.014692690603257473,"angularAcceleration":2.7271203059159155,"curveRadius":168.5974514602249},{"acceleration":2.9996115469296862,"curvature":0.007270662649525199,"pose":{"rotation":{"radians":-2.985067805642582},"translation":{"x":5.360381773290899,"y":1.9527871876079885}},"time":2.188093183143319,"velocity":3.216876546720968,"position":3.2494768903846043,"holonomicRotation":189.512136926666,"angularVelocity":0.019063405229812362,"angularAcceleration":2.708587549470126,"curveRadius":137.53904536683513},{"acceleration":2.9994963721990735,"curvature":0.008595437251698979,"pose":{"rotation":{"radians":-2.9850300294933385},"translation":{"x":5.355244905253094,"y":1.9519763098435376}},"time":2.1897073759710013,"velocity":3.221718312251631,"position":3.2546773649770535,"holonomicRotation":189.56501326629405,"angularVelocity":0.023402500987211958,"angularAcceleration":2.6880900986469265,"curveRadius":116.34079462360563},{"acceleration":2.9993820122497112,"curvature":0.009904831868652153,"pose":{"rotation":{"radians":-2.984985286314407},"translation":{"x":5.350098230329607,"y":1.9511636479996395}},"time":2.1913222341068015,"velocity":3.226561888696485,"position":3.259887804693678,"holonomicRotation":189.61788960592213,"angularVelocity":0.027707188600495668,"angularAcceleration":2.665675403833931,"curveRadius":100.96082530839362},{"acceleration":2.9992684884929735,"curvature":0.011198079575605108,"pose":{"rotation":{"radians":-2.984933626442364},"translation":{"x":5.344941353136447,"y":1.9503491021656878}},"time":2.1929378801517334,"velocity":3.2314076449676077,"position":3.2651086156748326,"holonomicRotation":189.6707659455502,"angularVelocity":0.031974746080590595,"angularAcceleration":2.641393821054883,"curveRadius":89.30102641693036},{"acceleration":2.9991558202148068,"curvature":0.012474458291215618,"pose":{"rotation":{"radians":-2.984875103044089},"translation":{"x":5.339773878289624,"y":1.9495325724310764}},"time":2.1945544359730667,"velocity":3.2362559477678614,"position":3.270340204066521,"holonomicRotation":189.72364228517824,"angularVelocity":0.03620252236436217,"angularAcceleration":2.6152986664479974,"curveRadius":80.16380163811918},{"acceleration":2.9990440248046015,"curvature":0.013733265839591734,"pose":{"rotation":{"radians":-2.9848097720479396},"translation":{"x":5.334595410405149,"y":1.9487139588851985}},"time":2.1961720227090806,"velocity":3.2411071616031073,"position":3.27558297602113,"holonomicRotation":189.77651862480633,"angularVelocity":0.04038794006826927,"angularAcceleration":2.587445613099373,"curveRadius":72.81589184104283},{"acceleration":2.9989331239017383,"curvature":0.01497382753578129,"pose":{"rotation":{"radians":-2.9847376920723803},"translation":{"x":5.329405554099032,"y":1.9478931616174484}},"time":2.197790760773639,"velocity":3.2459616488038323,"position":3.280837337698146,"holonomicRotation":189.82939496443439,"angularVelocity":0.04452849854928104,"angularAcceleration":2.5578928250761392,"curveRadius":66.78319204695067},{"acceleration":2.998823134418345,"curvature":0.01619549432101742,"pose":{"rotation":{"radians":-2.9846589243519195},"translation":{"x":5.324203913987281,"y":1.9470700807172197}},"time":2.1994107698606005,"velocity":3.25081976953178,"position":3.286103695264861,"holonomicRotation":189.88227130406247,"angularVelocity":0.04862177693615644,"angularAcceleration":2.526700880766749,"curveRadius":61.745568253651115},{"acceleration":2.9987140728813646,"curvature":0.017397649931491444,"pose":{"rotation":{"radians":-2.9845735326616105},"translation":{"x":5.31899009468591,"y":1.9462446162739062}},"time":2.20103216894806,"velocity":3.255681881793102,"position":3.291382454897059,"holonomicRotation":189.93514764369053,"angularVelocity":0.052665436270077824,"angularAcceleration":2.4939321633990312,"curveRadius":57.47902756624057},{"acceleration":2.9986059583053937,"curvature":0.018579705051664133,"pose":{"rotation":{"radians":-2.984481583239517},"translation":{"x":5.313763700810925,"y":1.9454166683769014}},"time":2.2026550763024355,"velocity":3.26054834145571,"position":3.2966740227797042,"holonomicRotation":189.98802398331858,"angularVelocity":0.056657221896107626,"angularAcceleration":2.4596509562100293,"curveRadius":53.82216764040787},{"acceleration":2.998498806796416,"curvature":0.019741107886320393,"pose":{"rotation":{"radians":-2.9843831447070284},"translation":{"x":5.308524336978339,"y":1.9445861371155995}},"time":2.204279609482388,"velocity":3.2654195022573993,"position":3.301978805107586,"holonomicRotation":190.04090032294667,"angularVelocity":0.06059496580509497,"angularAcceleration":2.4239233507695968,"curveRadius":50.6557182990196},{"acceleration":2.998392634195152,"curvature":0.02088132662359242,"pose":{"rotation":{"radians":-2.984278287988129},"translation":{"x":5.303271607804159,"y":1.9437529225793935}},"time":2.205905885342603,"velocity":3.270295715817836,"position":3.3072972080859837,"holonomicRotation":190.09377666257473,"angularVelocity":0.06447658817577528,"angularAcceleration":2.3868166930597856,"curveRadius":47.88967760650641},{"acceleration":2.9982874559222377,"curvature":0.02199986911546244,"pose":{"rotation":{"radians":-2.984167086226915},"translation":{"x":5.298005117904397,"y":1.942916924857678}},"time":2.207534020037407,"velocity":3.27517733164982,"position":3.3126296379312796,"holonomicRotation":190.14665300220278,"angularVelocity":0.06830009922937674,"angularAcceleration":2.348399715209584,"curveRadius":45.454815878752555},{"acceleration":2.998183288223802,"curvature":0.02309627059205742,"pose":{"rotation":{"radians":-2.9840496147035958},"translation":{"x":5.292724471895063,"y":1.9420780440398464}},"time":2.209164129024256,"velocity":3.2800646971721736,"position":3.317976500871586,"holonomicRotation":190.19952934183087,"angularVelocity":0.0720636008188036,"angularAcceleration":2.3087423109677694,"curveRadius":43.29703343291666},{"acceleration":2.99808014503998,"curvature":0.024170092629606267,"pose":{"rotation":{"radians":-2.983925950750115},"translation":{"x":5.287429274392167,"y":1.9412361802152922}},"time":2.210796327067069,"velocity":3.2849581577171048,"position":3.3233382031473346,"holonomicRotation":190.25240568145892,"angularVelocity":0.07576528719996528,"angularAcceleration":2.2679149735909343,"curveRadius":41.37344508043328},{"acceleration":2.997978039552131,"curvature":0.025220936497285636,"pose":{"rotation":{"radians":-2.983796173664032},"translation":{"x":5.282119130011719,"y":1.9403912334734092}},"time":2.212430728239435,"velocity":3.2898580565396753,"position":3.3287151510118598,"holonomicRotation":190.305282021087,"angularVelocity":0.07940344652042627,"angularAcceleration":2.225989176938122,"curveRadius":39.64959826561648},{"acceleration":2.9978769865935986,"curvature":0.026248430841977297,"pose":{"rotation":{"radians":-2.9836603646220925},"translation":{"x":5.276793643369729,"y":1.9395431039035917}},"time":2.214067445927679,"velocity":3.2947647348308124,"position":3.3341077507319596,"holonomicRotation":190.35815836071507,"angularVelocity":0.08297646131334493,"angularAcceleration":2.1830367072969414,"curveRadius":38.09751546750632},{"acceleration":2.9977769980055005,"curvature":0.027252232290233575,"pose":{"rotation":{"radians":-2.9835186065923684},"translation":{"x":5.271452419082206,"y":1.9386916915952328}},"time":2.2157065928338033,"velocity":3.2996785317223445,"position":3.339516408588438,"holonomicRotation":190.41103470034312,"angularVelocity":0.08648280956049795,"angularAcceleration":2.139129954765992,"curveRadius":36.694241754220315},{"acceleration":2.997678086735972,"curvature":0.028232031971419824,"pose":{"rotation":{"radians":-2.9833709842473843},"translation":{"x":5.266095061765162,"y":1.9378368966377266}},"time":2.217348280978302,"velocity":3.304599784298362,"position":3.344941530876633,"holonomicRotation":190.4639110399712,"angularVelocity":0.08992106416727903,"angularAcceleration":2.094340888251587,"curveRadius":35.42075898087433},{"acceleration":2.99758026435035,"curvature":0.029187550071874135,"pose":{"rotation":{"radians":-2.98321758387494},"translation":{"x":5.260721176034606,"y":1.9369786191204665}},"time":2.218992621702849,"velocity":3.3095288276021315,"position":3.3503835239069213,"holonomicRotation":190.51678737959926,"angularVelocity":0.09328989433526143,"angularAcceleration":2.048742160120419,"curveRadius":34.26118319411897},{"acceleration":2.9974835414664347,"curvature":0.030118540089545058,"pose":{"rotation":{"radians":-2.9830584932905273},"translation":{"x":5.255330366506547,"y":1.9361167591328468}},"time":2.2206397256728736,"velocity":3.3144659946433648,"position":3.3558427940052105,"holonomicRotation":190.56966371922732,"angularVelocity":0.0965880644501681,"angularAcceleration":2.00240554022651,"curveRadius":33.202140509696434},{"acceleration":2.9973879304097837,"curvature":0.03102477984318885,"pose":{"rotation":{"radians":-2.982893801747996},"translation":{"x":5.249922237796995,"y":1.9352512167642606}},"time":2.2222897028800137,"velocity":3.319411616409498,"position":3.3613197475134022,"holonomicRotation":190.6225400588554,"angularVelocity":0.0998144349017844,"angularAcceleration":1.9554030429356952,"curveRadius":32.2322996344981},{"acceleration":2.997293439456012,"curvature":0.03190608398091235,"pose":{"rotation":{"radians":-2.9827235998518264},"translation":{"x":5.2444963945219625,"y":1.934381892104102}},"time":2.223942662644461,"velocity":3.324366021867161,"position":3.366814790789845,"holonomicRotation":190.67541639848346,"angularVelocity":0.10296796076354338,"angularAcceleration":1.9078055797765376,"curveRadius":31.341984826412563},{"acceleration":2.9972000786137634,"curvature":0.03276229108867417,"pose":{"rotation":{"radians":-2.982547979468475},"translation":{"x":5.239052441297458,"y":1.933508685241765}},"time":2.225598713617198,"velocity":3.329329537972836,"position":3.372328330209766,"holonomicRotation":190.72829273811152,"angularVelocity":0.10604769191443564,"angularAcceleration":1.8596837908936321,"curveRadius":30.522895889466565},{"acceleration":2.9971078572121304,"curvature":0.03359327160982157,"pose":{"rotation":{"radians":-2.9823670336384165},"translation":{"x":5.233589982739492,"y":1.9326314962666424}},"time":2.2272579637821246,"velocity":3.334302489679218,"position":3.3778607721656817,"holonomicRotation":190.7811690777396,"angularVelocity":0.1090527720794692,"angularAcceleration":1.8111073474966002,"curveRadius":29.767865768323468},{"acceleration":2.9970167835540775,"curvature":0.03439892236500867,"pose":{"rotation":{"radians":-2.9821808564890127},"translation":{"x":5.228108623464073,"y":1.9317502252681291}},"time":2.2289205204580878,"velocity":3.3392851999406896,"position":3.383412523067788,"holonomicRotation":190.83404541736766,"angularVelocity":0.11198243770906377,"angularAcceleration":1.7621448170465217,"curveRadius":29.070678127324758},{"acceleration":2.9969268648171106,"curvature":0.035179170003703325,"pose":{"rotation":{"radians":-2.9819895431468613},"translation":{"x":5.222607968087213,"y":1.9308647723356183}},"time":2.230586490300808,"velocity":3.3442779897183135,"position":3.3889839893443323,"holonomicRotation":190.88692175699572,"angularVelocity":0.11483601758300206,"angularAcceleration":1.712864063180547,"curveRadius":28.425912262703456},{"acceleration":2.996838109345446,"curvature":0.035933968229925686,"pose":{"rotation":{"radians":-2.9817931896524024},"translation":{"x":5.217087621224921,"y":1.9299750375585036}},"time":2.2322559793047128,"velocity":3.349281177988348,"position":3.3945755774419686,"holonomicRotation":190.9397980966238,"angularVelocity":0.1176129306630152,"angularAcceleration":1.6633311591262117,"curveRadius":27.828821843483556},{"acceleration":2.9967505231080587,"curvature":0.03666329545745223,"pose":{"rotation":{"radians":-2.9815918928739147},"translation":{"x":5.211547187493206,"y":1.9290809210261792}},"time":2.2339290928046736,"velocity":3.3542950817445747,"position":3.4001876938260875,"holonomicRotation":190.99267443625186,"angularVelocity":0.12031268559628326,"angularAcceleration":1.6136113499361007,"curveRadius":27.275235014280167},{"acceleration":2.9966641116561608,"curvature":0.0373671590025006,"pose":{"rotation":{"radians":-2.9813857504230135},"translation":{"x":5.20598627150808,"y":1.9281823228280381}},"time":2.235605935477657,"velocity":3.3593200160035983,"position":3.4058207449811304,"holonomicRotation":191.04555077587995,"angularVelocity":0.12293487887831119,"angularAcceleration":1.5637682200454892,"curveRadius":26.761467199930298},{"acceleration":2.996578881987426,"curvature":0.038045590443846845,"pose":{"rotation":{"radians":-2.9811748605717012},"translation":{"x":5.200404477885552,"y":1.9272791430534748}},"time":2.237286611344287,"velocity":3.3643562938130067,"position":3.4114751374108856,"holonomicRotation":191.098427115508,"angularVelocity":0.1254791929244157,"angularAcceleration":1.5138636167881223,"curveRadius":26.284254977615443},{"acceleration":2.9964948382277394,"curvature":0.038698644611729255,"pose":{"rotation":{"radians":-2.9809593221691624},"translation":{"x":5.194801411241633,"y":1.926371281791883}},"time":2.2389712237703208,"velocity":3.3694042262520316,"position":3.417151277638761,"holonomicRotation":191.15130345513606,"angularVelocity":0.12794539515910752,"angularAcceleration":1.463958235484479,"curveRadius":25.840698299208853},{"acceleration":2.996411985227643,"curvature":0.03952805999838324,"pose":{"rotation":{"radians":-2.980739234561077},"translation":{"x":5.189176676192331,"y":1.925458639132656}},"time":2.2406598754680496,"velocity":3.374464122437981,"position":3.4228495722080408,"holonomicRotation":191.20417979476414,"angularVelocity":0.13033333539494985,"angularAcceleration":1.4141105824570244,"curveRadius":25.298484166460522},{"acceleration":2.247228757607179,"curvature":-0.02959345745154144,"pose":{"rotation":{"radians":-2.9804000250455847},"translation":{"x":5.177860619341625,"y":1.923618609978872}},"time":2.2440497042460925,"velocity":3.3820818431513637,"position":3.434314250569652,"holonomicRotation":-168.6900675259797,"angularVelocity":0.10006685815211414,"angularAcceleration":-8.928615344492261,"curveRadius":-33.79125273339472},{"acceleration":3.9896106106653826,"curvature":-0.14538197959933158,"pose":{"rotation":{"radians":-2.9806721196266164},"translation":{"x":5.171025923027808,"y":1.9225091739889826}},"time":2.2460920891657645,"velocity":3.39023016369795,"position":3.4412384055302057,"holonomicRotation":-168.57515056491204,"angularVelocity":-0.13322394736219406,"angularAcceleration":-114.22470038202808,"curveRadius":-6.878431582483402},{"acceleration":3.004418010900507,"curvature":-0.14590713862253685,"pose":{"rotation":{"radians":-2.9816781945710047},"translation":{"x":5.164197888684282,"y":1.921407868768533}},"time":2.2481284762317126,"velocity":3.3963483216760495,"position":3.4481546853239213,"holonomicRotation":-168.46023360384436,"angularVelocity":-0.4940489758610312,"angularAcceleration":-177.18882354560765,"curveRadius":-6.853674257755198},{"acceleration":3.0043788759833157,"curvature":-0.146423843432626,"pose":{"rotation":{"radians":-2.9826867641665866},"translation":{"x":5.157376394720548,"y":1.9203146762447043}},"time":2.2501589358773195,"velocity":3.4024485917438474,"position":3.455063219885709,"holonomicRotation":-168.34531664277668,"angularVelocity":-0.4967198426051357,"angularAcceleration":-1.315400062189464,"curveRadius":-6.829488808358798},{"acceleration":3.004339797473111,"curvature":-0.14693196433076153,"pose":{"rotation":{"radians":-2.9836977808644187},"translation":{"x":5.150561319546102,"y":1.9192295783446771}},"time":2.252183537947727,"velocity":3.4085311843180186,"position":3.4619641391785274,"holonomicRotation":-168.230399681709,"angularVelocity":-0.49936563466454076,"angularAcceleration":-1.306820781267284,"curveRadius":-6.8058710339492885},{"acceleration":3.0043007752835384,"curvature":-0.14743137259183406,"pose":{"rotation":{"radians":-2.984711196621077},"translation":{"x":5.143752541570441,"y":1.9181525569956321}},"time":2.2542023517084986,"velocity":3.414596308064658,"position":3.4688575731927287,"holonomicRotation":-168.11548272064132,"angularVelocity":-0.5019857583450226,"angularAcceleration":-1.2978530914511983,"curveRadius":-6.782816861974926},{"acceleration":3.00426180905371,"curvature":-0.14792194148940527,"pose":{"rotation":{"radians":-2.9857269629048484},"translation":{"x":5.136949939203066,"y":1.9170835941247502}},"time":2.256215445854102,"velocity":3.4206441699243246,"position":3.4757436519453964,"holonomicRotation":-168.00056575957365,"angularVelocity":-0.5045796223637421,"angularAcceleration":-1.2884961313827772,"curveRadius":-6.760322301959671},{"acceleration":3.0042228975298326,"curvature":-0.14840354544985637,"pose":{"rotation":{"radians":-2.986745030702839},"translation":{"x":5.130153390853472,"y":1.9160226716592124}},"time":2.2582228885162183,"velocity":3.4266749751353323,"position":3.482622505479689,"holonomicRotation":-167.88564879850597,"angularVelocity":-0.507146638458561,"angularAcceleration":-1.2787493975608062,"curveRadius":-6.738383486517759},{"acceleration":3.004184041629352,"curvature":-0.1488760603581877,"pose":{"rotation":{"radians":-2.987765350527021},"translation":{"x":5.123362774931159,"y":1.914969771526199}},"time":2.260224747271869,"velocity":3.4326889272626535,"position":3.489494263864154,"holonomicRotation":-167.77073183743832,"angularVelocity":-0.5096862210194815,"angularAcceleration":-1.2686122603566088,"curveRadius":-6.716996658791577},{"acceleration":3.004145238675565,"curvature":-0.14933936371963044,"pose":{"rotation":{"radians":-2.9887878724220345},"translation":{"x":5.116577969845625,"y":1.9139248756528913}},"time":2.2622210891513843,"velocity":3.4386862282147685,"position":3.4963590571920524,"holonomicRotation":-167.65581487637064,"angularVelocity":-0.5121977881170623,"angularAcceleration":-1.2580846614260282,"curveRadius":-6.696158166827327},{"acceleration":3.0041064904505124,"curvature":-0.14979333482137636,"pose":{"rotation":{"radians":-2.9898125459717773},"translation":{"x":5.109798854006367,"y":1.91288796596647}},"time":2.264211980646199,"velocity":3.4446670782761237,"position":3.50321701558066,"holonomicRotation":-167.54089791530296,"angularVelocity":-0.5146807610618772,"angularAcceleration":-1.2471663831414275,"curveRadius":-6.675864458138056},{"acceleration":3.004067795880625,"curvature":-0.150237854462779,"pose":{"rotation":{"radians":-2.990839320306937},"translation":{"x":5.103025305822882,"y":1.9118590243941154}},"time":2.2661974877164894,"velocity":3.450631676124477,"position":3.510068269170574,"holonomicRotation":-167.42598095423529,"angularVelocity":-0.5171345650306401,"angularAcceleration":-1.235857582921555,"curveRadius":-6.6561120935585985},{"acceleration":3.00402915341367,"curvature":-0.1506728054047702,"pose":{"rotation":{"radians":-2.9918681441126895},"translation":{"x":5.0962572037046705,"y":1.9108380328630088}},"time":2.268177675798656,"velocity":3.456580218852547,"position":3.5169129481249977,"holonomicRotation":-167.3110639931676,"angularVelocity":-0.5195586293130042,"angularAcceleration":-1.2241586060411438,"curveRadius":-6.636897728913864},{"acceleration":3.00399056479117,"curvature":-0.15109807166869205,"pose":{"rotation":{"radians":-2.9928989656361806},"translation":{"x":5.089494426061228,"y":1.9098249733003312}},"time":2.2701526098126465,"velocity":3.4625129019966603,"position":3.5237511826290326,"holonomicRotation":-167.19614703209993,"angularVelocity":-0.5219523873651476,"angularAcceleration":-1.2120698895181399,"curveRadius":-6.618218147698591},{"acceleration":3.003952028954994,"curvature":-0.15151353984844332,"pose":{"rotation":{"radians":-2.9939317326942554},"translation":{"x":5.082736851302056,"y":1.9088198276332624}},"time":2.272122354169135,"velocity":3.468429919552856,"position":3.530583102888947,"holonomicRotation":-167.08123007103225,"angularVelocity":-0.5243152770931032,"angularAcceleration":-1.1995920791306065,"curveRadius":-6.600070204948579},{"acceleration":3.003913545082865,"curvature":-0.15191909826562452,"pose":{"rotation":{"radians":-2.9949663926824455},"translation":{"x":5.0759843578366475,"y":1.9078225777889843}},"time":2.2740869727765527,"velocity":3.4743314639986003,"position":3.537408839131456,"holonomicRotation":-166.96631310996457,"angularVelocity":-0.5266467416543406,"angularAcceleration":-1.186726295085686,"curveRadius":-6.582450866391661},{"acceleration":3.0038751142035256,"curvature":-0.15231463669960635,"pose":{"rotation":{"radians":-2.9960028925816156},"translation":{"x":5.069236824074506,"y":1.906833205694677}},"time":2.2760465290479726,"velocity":3.4802177263172,"position":3.5442285216029674,"holonomicRotation":-166.8513961488969,"angularVelocity":-0.5289462284331677,"angularAcceleration":-1.1734732053195998,"curveRadius":-6.565357221526856},{"acceleration":3.0038367351972157,"curvature":-0.15270004755583713,"pose":{"rotation":{"radians":-2.9970411789680864},"translation":{"x":5.062494128425124,"y":1.9058516932775216}},"time":2.278001085907862,"velocity":3.486088896013967,"position":3.5510422805688555,"holonomicRotation":-166.73647918782922,"angularVelocity":-0.5312131909683344,"angularAcceleration":-1.159834529088624,"curveRadius":-6.548786434623307},{"acceleration":3.003798409006889,"curvature":-0.15307522530848722,"pose":{"rotation":{"radians":-2.9980811980209143},"translation":{"x":5.055756149298003,"y":1.9048780224646988}},"time":2.279950705798689,"velocity":3.4919451611402024,"position":3.5578502463126926,"holonomicRotation":-166.62156222676154,"angularVelocity":-0.5334470876713221,"angularAcceleration":-1.1458114032883275,"curveRadius":-6.532735770825975},{"acceleration":3.003760134753981,"curvature":-0.15344006608638835,"pose":{"rotation":{"radians":-2.999122895531251},"translation":{"x":5.04902276510264,"y":1.9039121751833892}},"time":2.2818954506874065,"velocity":3.497786708309198,"position":3.5646525491355003,"holonomicRotation":-166.50664526569386,"angularVelocity":-0.5356473830477354,"angularAcceleration":-1.1314056610605308,"curveRadius":-6.517202615365075},{"acceleration":3.003721913211918,"curvature":-0.1537944685536997,"pose":{"rotation":{"radians":-3.000166216911261},"translation":{"x":5.042293854248533,"y":1.902954133360774}},"time":2.283835382071796,"velocity":3.5036137227186157,"position":3.5714493193549792,"holonomicRotation":-166.39172830462618,"angularVelocity":-0.537813547636523,"angularAcceleration":-1.1166191785022928,"curveRadius":-6.502184437477572},{"acceleration":3.0036837444160467,"curvature":-0.15413833363967264,"pose":{"rotation":{"radians":-3.0012111072027707},"translation":{"x":5.035569295145181,"y":1.9020038789240337}},"time":2.285770560986691,"velocity":3.5094263881678236,"position":3.578240687304739,"holonomicRotation":-166.2768113435585,"angularVelocity":-0.5399450580341654,"angularAcceleration":-1.1014539178965883,"curveRadius":-6.487678803753569},{"acceleration":3.0036456278794503,"curvature":-0.15447156470002396,"pose":{"rotation":{"radians":-3.0022575110870147},"translation":{"x":5.02884896620208,"y":1.901061393800349}},"time":2.287701048010077,"velocity":3.5152248870752945,"position":3.5850267833335208,"holonomicRotation":-166.16189438249083,"angularVelocity":-0.5420413976203111,"angularAcceleration":-1.085912290914565,"curveRadius":-6.473683373001043},{"acceleration":3.0036075643288327,"curvature":-0.15479406667067785,"pose":{"rotation":{"radians":-3.003305372893597},"translation":{"x":5.0221327458287295,"y":1.9001266599169013}},"time":2.289626903269063,"velocity":3.5210094004989867,"position":3.59180773780441,"holonomicRotation":-166.04697742142318,"angularVelocity":-0.5441020563166118,"angularAcceleration":-1.0699966608009044,"curveRadius":-6.46019593326846},{"acceleration":3.00356955354083,"curvature":-0.1551057482434303,"pose":{"rotation":{"radians":-3.0043546366101084},"translation":{"x":5.015420512434628,"y":1.8991996592008706}},"time":2.291548186445742,"velocity":3.526780108152191,"position":3.59858368109405,"holonomicRotation":-165.9320604603555,"angularVelocity":-0.5461265310847655,"angularAcceleration":-1.0537097252122836,"curveRadius":-6.44721431233195},{"acceleration":3.0035315964271287,"curvature":-0.15540651900461022,"pose":{"rotation":{"radians":-3.005405245892104},"translation":{"x":5.008712144429271,"y":1.898280373579438}},"time":2.293464956782934,"velocity":3.5325371884230408,"position":3.6053547435918465,"holonomicRotation":-165.81714349928782,"angularVelocity":-0.5481143262760064,"angularAcceleration":-1.0370544413542726,"curveRadius":-6.434736498861637},{"acceleration":3.0034936929142577,"curvature":-0.15569629218656997,"pose":{"rotation":{"radians":-3.0064571440724697},"translation":{"x":5.0020075202221586,"y":1.8973687849797845}},"time":2.295377273089811,"velocity":3.538280818389603,"position":3.612121055699163,"holonomicRotation":-165.70222653822015,"angularVelocity":-0.5500649534717285,"angularAcceleration":-1.0200337615211512,"curveRadius":-6.422760529208401},{"acceleration":3.003455842709334,"curvature":-0.15597498310092128,"pose":{"rotation":{"radians":-3.007510274171619},"translation":{"x":4.995306518222788,"y":1.8964648753290907}},"time":2.297285193747419,"velocity":3.5440111738361217,"position":3.618882747828519,"holonomicRotation":-165.58730957715247,"angularVelocity":-0.551977932074879,"angularAcceleration":-1.0026510250949583,"curveRadius":-6.411284554222166},{"acceleration":3.003418047145883,"curvature":-0.15624250973088452,"pose":{"rotation":{"radians":-3.008564578907533},"translation":{"x":4.988609016840656,"y":1.8955686265545373}},"time":2.299188776714086,"velocity":3.5497284292724487,"position":3.625639950402775,"holonomicRotation":-165.4723926160848,"angularVelocity":-0.5538527893847233,"angularAcceleration":-0.9849096901339919,"curveRadius":-6.400306816131037},{"acceleration":3.0033803059518736,"curvature":-0.1564987927475185,"pose":{"rotation":{"radians":-3.0096200007060983},"translation":{"x":4.981914894485264,"y":1.8946800205833054}},"time":2.3010880795307265,"velocity":3.5554327579469858,"position":3.63239279385432,"holonomicRotation":-165.3574756550171,"angularVelocity":-0.5556890609114457,"angularAcceleration":-0.9668134594621275,"curveRadius":-6.38982564941132},{"acceleration":3.0033426202709155,"curvature":-0.15674375523757766,"pose":{"rotation":{"radians":-3.010676481711217},"translation":{"x":4.975224029566108,"y":1.8937990393425752}},"time":2.3029831593260437,"velocity":3.5611243318650763,"position":3.63914140862425,"holonomicRotation":-165.24255869394943,"angularVelocity":-0.5574862904080105,"angularAcceleration":-0.9483661326587872,"curveRadius":-6.379839493345637},{"acceleration":3.003304989763977,"curvature":-0.15697732315164115,"pose":{"rotation":{"radians":-3.011733963795698},"translation":{"x":4.968536300492684,"y":1.892925664759528}},"time":2.304874072821629,"velocity":3.5668033218015798,"position":3.645885925161543,"holonomicRotation":-165.12764173288176,"angularVelocity":-0.5592440304381755,"angularAcceleration":-0.9295718890730773,"curveRadius":-6.3703468750960495},{"acceleration":3.0032674152801566,"curvature":-0.15719942531977704,"pose":{"rotation":{"radians":-3.012792388571334},"translation":{"x":4.961851585674493,"y":1.8920598787613447}},"time":2.3067608763369636,"velocity":3.57246989731822,"position":3.65262647392223,"holonomicRotation":-165.01272477181408,"angularVelocity":-0.5609618420963854,"angularAcceleration":-0.9104348408558921,"curveRadius":-6.361346410559628},{"acceleration":3.003229897224913,"curvature":-0.1574099930342328,"pose":{"rotation":{"radians":-3.0138516974000336},"translation":{"x":4.955169763521032,"y":1.891201663275206}},"time":2.3086436257943235,"velocity":3.5781242267775473,"position":3.6593631853685618,"holonomicRotation":-164.8978078107464,"angularVelocity":-0.5626392957165292,"angularAcceleration":-0.8909595557636977,"curveRadius":-6.352836822643939},{"acceleration":3.0031924356749933,"curvature":-0.15760896107439293,"pose":{"rotation":{"radians":-3.014911831404428},"translation":{"x":4.948490712441799,"y":1.8903510002282922}},"time":2.3105223767235907,"velocity":3.58376647735684,"position":3.6660961899681728,"holonomicRotation":-164.78289084967872,"angularVelocity":-0.5642759707419008,"angularAcceleration":-0.8711506138868599,"curveRadius":-6.344816901165857},{"acceleration":3.003155032655027,"curvature":-0.15779626627876986,"pose":{"rotation":{"radians":-3.015972731479215},"translation":{"x":4.941814310846292,"y":1.8895078715477847}},"time":2.3123971842669713,"velocity":3.589396815066003,"position":3.6728256181932446,"holonomicRotation":-164.66797388861104,"angularVelocity":-0.5658714562637368,"angularAcceleration":-0.851012962620732,"curveRadius":-6.337285561835511},{"acceleration":3.003117687091952,"curvature":-0.15797184885822285,"pose":{"rotation":{"radians":-3.0170343383014564},"translation":{"x":4.935140437144008,"y":1.8886722591608636}},"time":2.314268103183623,"velocity":3.5950154047557152,"position":3.679551600519657,"holonomicRotation":-164.55305692754337,"angularVelocity":-0.5674253506085174,"angularAcceleration":-0.8305514102991408,"curveRadius":-6.330241794520514},{"acceleration":3.003080400830714,"curvature":-0.15813565168843094,"pose":{"rotation":{"radians":-3.018096592342719},"translation":{"x":4.928468969744445,"y":1.8878441449947108}},"time":2.3161351878541967,"velocity":3.600622410136606,"position":3.6862742674261466,"holonomicRotation":-164.4381399664757,"angularVelocity":-0.5689372624630479,"angularAcceleration":-0.8097714465547357,"curveRadius":-6.323684693001832},{"acceleration":3.003043173870569,"curvature":-0.15828762119083387,"pose":{"rotation":{"radians":-3.01915943387918},"translation":{"x":4.921799787057103,"y":1.887023510976506}},"time":2.317998492285288,"velocity":3.606217993789237,"position":3.692993749393455,"holonomicRotation":-164.323223005408,"angularVelocity":-0.5704068099265037,"angularAcceleration":-0.7886781348956813,"curveRadius":-6.317613420915496},{"acceleration":3.003006007123892,"curvature":-0.1584277060457351,"pose":{"rotation":{"radians":-3.020222803004196},"translation":{"x":4.915132767491478,"y":1.8862103390334302}},"time":2.3198580701138085,"velocity":3.611802317178999,"position":3.6997101769034804,"holonomicRotation":-164.20830604434036,"angularVelocity":-0.5718336219689667,"angularAcceleration":-0.7672774005904636,"curveRadius":-6.312027264418755},{"acceleration":3.0029689007485225,"curvature":-0.15855585850638687,"pose":{"rotation":{"radians":-3.021286639638793},"translation":{"x":4.90846778945707,"y":1.8854046110926646}},"time":2.3217139746112725,"velocity":3.6173755406676427,"position":3.7064236804384216,"holonomicRotation":-164.09338908327268,"angularVelocity":-0.5732173374495629,"angularAcceleration":-0.7455747224531385,"curveRadius":-6.306925580802291},{"acceleration":3.002931856543117,"curvature":-0.158672033689403,"pose":{"rotation":{"radians":-3.0223508835436474},"translation":{"x":4.901804731363375,"y":1.8846063090813898}},"time":2.3235662586880026,"velocity":3.622937823529023,"position":3.7131343904799277,"holonomicRotation":-163.978472122205,"angularVelocity":-0.5745576060521089,"angularAcceleration":-0.7235761616609099,"curveRadius":-6.302307827965941},{"acceleration":3.0028948743875294,"curvature":-0.15877618958701015,"pose":{"rotation":{"radians":-3.023415474330461},"translation":{"x":4.895143471619891,"y":1.883815414926787}},"time":2.325414974897256,"velocity":3.6284893239579876,"position":3.719842437508232,"holonomicRotation":-163.86355516113733,"angularVelocity":-0.5758540880882432,"angularAcceleration":-0.701287752898426,"curveRadius":-6.2981735649475015},{"acceleration":3.0028579553979324,"curvature":-0.15886828736863054,"pose":{"rotation":{"radians":-3.0244803514736702},"translation":{"x":4.888483888636117,"y":1.883031910556036}},"time":2.3272601754392763,"velocity":3.6340301990848975,"position":3.7265479520013014,"holonomicRotation":-163.74863820006965,"angularVelocity":-0.5771064548047778,"angularAcceleration":-0.6787157753397763,"curveRadius":-6.294522440968013},{"acceleration":3.002821100270296,"curvature":-0.15894829197315427,"pose":{"rotation":{"radians":-3.0255454543225135},"translation":{"x":4.881825860821551,"y":1.8822557778963185}},"time":2.329101912165266,"velocity":3.6395606049868423,"position":3.733251064433971,"holonomicRotation":-163.63372123900197,"angularVelocity":-0.5783143887033725,"angularAcceleration":-0.6558667596452977,"curveRadius":-6.291354173021853},{"acceleration":3.0027843099713247,"curvature":-0.15901617067140417,"pose":{"rotation":{"radians":-3.0266107221122556},"translation":{"x":4.87516926658569,"y":1.8814869988748146}},"time":2.3309402365812892,"velocity":3.645080696699914,"position":3.7399519052770893,"holonomicRotation":-163.5188042779343,"angularVelocity":-0.5794775832040128,"angularAcceleration":-0.6327471313015675,"curveRadius":-6.2886686038140756},{"acceleration":3.00274758531832,"curvature":-0.15907189394618915,"pose":{"rotation":{"radians":-3.027676093976531},"translation":{"x":4.868513984338033,"y":1.8807255554187057}},"time":2.3327751998520974,"velocity":3.6505906282304807,"position":3.7466506049966486,"holonomicRotation":-163.40388731686662,"angularVelocity":-0.5805957433721682,"angularAcceleration":-0.6093637872451959,"curveRadius":-6.286465667770826},{"acceleration":3.0027109264864724,"curvature":-0.1591154363748311,"pose":{"rotation":{"radians":-3.0287415089589835},"translation":{"x":4.861859892488078,"y":1.8799714294551724}},"time":2.3346068528048893,"velocity":3.6560905525653604,"position":3.7533472940529298,"holonomicRotation":-163.28897035579894,"angularVelocity":-0.5816685856501865,"angularAcceleration":-0.5857235544446172,"curveRadius":-6.284745357102135},{"acceleration":3.002674335665291,"curvature":-0.15914677446219982,"pose":{"rotation":{"radians":-3.0298069060253017},"translation":{"x":4.855206869445321,"y":1.8792246029113953}},"time":2.336435245932998,"velocity":3.6615806216866384,"position":3.7600421028996367,"holonomicRotation":-163.17405339473126,"angularVelocity":-0.5826958381868008,"angularAcceleration":-0.5618335142601537,"curveRadius":-6.283507808306336},{"acceleration":3.002637812881181,"curvature":-0.15916588926480713,"pose":{"rotation":{"radians":-3.030872224075268},"translation":{"x":4.848554793619264,"y":1.8784850577145553}},"time":2.3382604293995093,"velocity":3.6670609865786314,"position":3.7667351619830294,"holonomicRotation":-163.05913643366358,"angularVelocity":-0.5836772409529947,"angularAcceleration":-0.5377008855277535,"curveRadius":-6.282753199313215},{"acceleration":3.002601359385573,"curvature":-0.15917276363949553,"pose":{"rotation":{"radians":-3.0319374019548713},"translation":{"x":4.8419035434194,"y":1.8777527757918333}},"time":2.3400824530408215,"velocity":3.672531797240868,"position":3.773426601741073,"holonomicRotation":-162.9442194725959,"angularVelocity":-0.5846125458811247,"angularAcceleration":-0.5133330363684939,"curveRadius":-6.28248185892445},{"acceleration":3.002564975116303,"curvature":-0.15916738486979756,"pose":{"rotation":{"radians":-3.033002378468085},"translation":{"x":4.835252997255231,"y":1.8770277390704098}},"time":2.3419013663701302,"velocity":3.6779932026962228,"position":3.780116552602564,"holonomicRotation":-162.82930251152823,"angularVelocity":-0.5855015167866975,"angularAcceleration":-0.4887373638141846,"curveRadius":-6.282694163870457},{"acceleration":3.0025286631192043,"curvature":-0.1591497430754032,"pose":{"rotation":{"radians":-3.0340670923894675},"translation":{"x":4.828603033536253,"y":1.876309929477466}},"time":2.3437172185808555,"velocity":3.6834453510069136,"position":3.7868051449862756,"holonomicRotation":-162.71438555046055,"angularVelocity":-0.5863439299155191,"angularAcceleration":-0.4639216362686038,"curveRadius":-6.283390602309752},{"acceleration":3.002492421783999,"curvature":-0.15911983151111922,"pose":{"rotation":{"radians":-3.03513148247565},"translation":{"x":4.821953530671965,"y":1.8755993289401824}},"time":2.3455300585500076,"velocity":3.6888883892762,"position":3.793492509300097,"holonomicRotation":-162.59946858939287,"angularVelocity":-0.5871395734286586,"angularAcceleration":-0.4388934085073464,"curveRadius":-6.284571762697728},{"acceleration":3.002456254309328,"curvature":-0.15907764701229046,"pose":{"rotation":{"radians":-3.0361954874781945},"translation":{"x":4.815304367071865,"y":1.87489591938574}},"time":2.347339934841488,"velocity":3.6943224636670817,"position":3.8001787759401715,"holonomicRotation":-162.48455162832522,"angularVelocity":-0.5878882482482943,"angularAcceleration":-0.41366076961166104,"curveRadius":-6.286238316831146},{"acceleration":3.0024201608150807,"curvature":-0.15902318927337417,"pose":{"rotation":{"radians":-3.0372590461552327},"translation":{"x":4.808655421145449,"y":1.8741996827413194}},"time":2.3491468957093353,"velocity":3.6997477194065103,"position":3.8068640752900462,"holonomicRotation":-162.36963466725754,"angularVelocity":-0.5885897674725532,"angularAcceleration":-0.388231553179474,"curveRadius":-6.288391048936369},{"acceleration":3.0023841418876174,"curvature":-0.15895646158456403,"pose":{"rotation":{"radians":-3.038322097283728},"translation":{"x":4.802006571302217,"y":1.8735106009341012}},"time":2.3509509891009093,"velocity":3.705164300795856,"position":3.8135485377198077,"holonomicRotation":-162.25471770618987,"angularVelocity":-0.5892439568042733,"angularAcceleration":-0.36261389503200175,"curveRadius":-6.2910308271300135},{"acceleration":3.002348198861507,"curvature":-0.15887747040083186,"pose":{"rotation":{"radians":-3.0393845796720402},"translation":{"x":4.795357695951666,"y":1.8728286558912668}},"time":2.3527522626600206,"velocity":3.710572351221711,"position":3.820232293585233,"holonomicRotation":-162.1398007451222,"angularVelocity":-0.589850654797974,"angularAcceleration":-0.33681613247021125,"curveRadius":-6.294158620961806},{"acceleration":3.002312332812778,"curvature":-0.1587862254944068,"pose":{"rotation":{"radians":-3.040446432171417},"translation":{"x":4.788708673503295,"y":1.8721538295399967}},"time":2.3545507637300043,"velocity":3.7159720131647,"position":3.826915473226939,"holonomicRotation":-162.0248837840545,"angularVelocity":-0.5904097123425537,"angularAcceleration":-0.31084637863724035,"curveRadius":-6.297775495867712},{"acceleration":3.0022765456766236,"curvature":-0.15868273981442235,"pose":{"rotation":{"radians":-3.041507593688717},"translation":{"x":4.7820593823666,"y":1.8714861038074713}},"time":2.356346539356737,"velocity":3.721363428210137,"position":3.833598206969533,"holonomicRotation":-161.90996682298683,"angularVelocity":-0.5909209934153785,"angularAcceleration":-0.28471322653771675,"curveRadius":-6.301882619177666},{"acceleration":3.002240836922919,"curvature":-0.15856702963863972,"pose":{"rotation":{"radians":-3.0425680031984372},"translation":{"x":4.775409700951081,"y":1.8708254606208718}},"time":2.358139636291603,"velocity":3.726746737052553,"position":3.840280625120764,"holonomicRotation":-161.79504986191915,"angularVelocity":-0.5913843747657739,"angularAcceleration":-0.2584251533673922,"curveRadius":-6.3064812545137015},{"acceleration":3.0022052085929434,"curvature":-0.15843911487230922,"pose":{"rotation":{"radians":-3.0436275997545885},"translation":{"x":4.768759507666236,"y":1.870171881907379}},"time":2.3599301009944074,"velocity":3.7321220795091143,"position":3.846962857970682,"holonomicRotation":-161.68013290085148,"angularVelocity":-0.5917997458936969,"angularAcceleration":-0.23199068223596062,"curveRadius":-6.311572750238662},{"acceleration":3.002169661562207,"curvature":-0.15829901802617846,"pose":{"rotation":{"radians":-3.044686322503227},"translation":{"x":4.762108680921562,"y":1.8695253495941737}},"time":2.3617179796362384,"velocity":3.7374895945261746,"position":3.853645035790801,"holonomicRotation":-161.5652159397838,"angularVelocity":-0.5921670094755341,"angularAcceleration":-0.20541863035016691,"curveRadius":-6.317158580444425},{"acceleration":3.002134196972824,"curvature":-0.15814676524714,"pose":{"rotation":{"radians":-3.045744110693949},"translation":{"x":4.7554570991265575,"y":1.8688858456084363}},"time":2.363503318102278,"velocity":3.742849420188243,"position":3.860327288833257,"holonomicRotation":-161.45029897871612,"angularVelocity":-0.5924860808431653,"angularAcceleration":-0.17871757859953952,"curveRadius":-6.323240304265942},{"acceleration":3.0020988154848602,"curvature":-0.15798238588214655,"pose":{"rotation":{"radians":-3.046800903692698},"translation":{"x":4.74880464069072,"y":1.868253351877348}},"time":2.365286161994566,"velocity":3.748201693725475,"position":3.867009747329979,"holonomicRotation":-161.33538201764844,"angularVelocity":-0.5927568887665363,"angularAcceleration":-0.1518965987669484,"curveRadius":-6.329819583469204},{"acceleration":3.002063519132211,"curvature":-0.15780591233417543,"pose":{"rotation":{"radians":-3.047856640993003},"translation":{"x":4.742151184023547,"y":1.8676278503280896}},"time":2.367066556634714,"velocity":3.7535465515243227,"position":3.87369254149186,"holonomicRotation":-161.22046505658076,"angularVelocity":-0.5929793746272679,"angularAcceleration":-0.12496435100089273,"curveRadius":-6.33689818846815},{"acceleration":3.0020283077392316,"curvature":-0.15761738035920955,"pose":{"rotation":{"radians":-3.0489112622284393},"translation":{"x":4.735496607534539,"y":1.8670093228878417}},"time":2.3688445470665753,"velocity":3.7588841291316593,"position":3.8803758015079306,"holonomicRotation":-161.1055480955131,"angularVelocity":-0.5931534931447248,"angularAcceleration":-0.09792995189214694,"curveRadius":-6.344477986634487},{"acceleration":3.0019931840060736,"curvature":-0.15741682892183043,"pose":{"rotation":{"radians":-3.049964707184421},"translation":{"x":4.728840789633191,"y":1.8663977514837853}},"time":2.3706201780588643,"velocity":3.7642145612678206,"position":3.887059657544543,"holonomicRotation":-160.9906311344454,"angularVelocity":-0.5932792120414626,"angularAcceleration":-0.07080237801874856,"curveRadius":-6.352560948210797},{"acceleration":3.0019581482754516,"curvature":-0.15720429990191892,"pose":{"rotation":{"radians":-3.0510169158098814},"translation":{"x":4.722183608729002,"y":1.8657931180431009}},"time":2.372393494107736,"velocity":3.769537981830198,"position":3.8937442397445534,"holonomicRotation":-160.87571417337773,"angularVelocity":-0.5933565120160578,"angularAcceleration":-0.04359063611043708,"curveRadius":-6.3611491582858},{"acceleration":3.0019232005456047,"curvature":-0.15697983898218787,"pose":{"rotation":{"radians":-3.052067828229296},"translation":{"x":4.715524943231471,"y":1.8651954044929693}},"time":2.374164539439318,"velocity":3.774854523900293,"position":3.900429678226509,"holonomicRotation":-160.76079721231008,"angularVelocity":-0.5933853869655549,"angularAcceleration":-0.0163039019849975,"curveRadius":-6.370244781009538},{"acceleration":3.0018883441322703,"curvature":-0.15674349417231123,"pose":{"rotation":{"radians":-3.053117384754405},"translation":{"x":4.708864671550094,"y":1.8646045927605714}},"time":2.375933358012203,"velocity":3.7801643197571204,"position":3.907116103083852,"holonomicRotation":-160.6458802512424,"angularVelocity":-0.5933658438453885,"angularAcceleration":0.01104868552715067,"curveRadius":-6.379850119333694},{"acceleration":3.0018535787139355,"curvature":-0.15649531699116795,"pose":{"rotation":{"radians":-3.0541655258956406},"translation":{"x":4.70220267209437,"y":1.8640206647730884}},"time":2.3776999935198924,"velocity":3.7854675008781613,"position":3.913803644384108,"holonomicRotation":-160.53096329017472,"angularVelocity":-0.5932979025233847,"angularAcceleration":0.03845803036795342,"curveRadius":-6.389967567249546},{"acceleration":3.0018189054026365,"curvature":-0.15623536217232054,"pose":{"rotation":{"radians":-3.055212192373871},"translation":{"x":4.6955388232737985,"y":1.8634436024577006}},"time":2.3794644893932073,"velocity":3.790764197949183,"position":3.9204924321680994,"holonomicRotation":-160.41604632910705,"angularVelocity":-0.5931815959785248,"angularAcceleration":0.06591488629629359,"curveRadius":-6.40059962159556},{"acceleration":3.001784326458921,"curvature":-0.15596368707071445,"pose":{"rotation":{"radians":-3.056257325131988},"translation":{"x":4.688873003497875,"y":1.8628733877415886}},"time":2.381226888802653,"velocity":3.796054540873418,"position":3.9271825964491587,"holonomicRotation":-160.30112936803937,"angularVelocity":-0.5930169702255905,"angularAcceleration":0.09341001367338715,"curveRadius":-6.4117489063117405},{"acceleration":3.001749842113224,"curvature":-0.15568035255182713,"pose":{"rotation":{"radians":-3.0573008653462623},"translation":{"x":4.682205091176099,"y":1.8623100025519337}},"time":2.3829872346607455,"velocity":3.8013386587750113,"position":3.9338742672123397,"holonomicRotation":-160.1862124069717,"angularVelocity":-0.5928040841958069,"angularAcceleration":0.12093420665319757,"curveRadius":-6.423418135998199},{"acceleration":3.00171545335578,"curvature":-0.15538542210015446,"pose":{"rotation":{"radians":-3.05834275443757},"translation":{"x":4.6755349647179685,"y":1.8617534288159165}},"time":2.3847455696243003,"velocity":3.8066166800072896,"position":3.9405675744136475,"holonomicRotation":-160.071295445904,"angularVelocity":-0.5925430096670271,"angularAcceleration":0.14847826733306638,"curveRadius":-6.435610152382538},{"acceleration":3.00168116200975,"curvature":-0.1550789622629608,"pose":{"rotation":{"radians":-3.0593829340827168},"translation":{"x":4.6688625025329795,"y":1.8612036484607177}},"time":2.386501936096683,"velocity":3.8118887321610258,"position":3.947262647979268,"holonomicRotation":-159.95637848483634,"angularVelocity":-0.5922338313233084,"angularAcceleration":0.17603293423113556,"curveRadius":-6.448327906040166},{"acceleration":3.0016469695369055,"curvature":-0.15476104279806033,"pose":{"rotation":{"radians":-3.0604213462256373},"translation":{"x":4.662187583030633,"y":1.8606606434135182}},"time":2.3882563762300193,"velocity":3.817154942070489,"position":3.9539596178048,"holonomicRotation":-159.84146152376866,"angularVelocity":-0.5918766466803117,"angularAcceleration":0.2035889604950224,"curveRadius":-6.461574450004503},{"acceleration":3.001612874991236,"curvature":-0.15443173607569455,"pose":{"rotation":{"radians":-3.0614579330883642},"translation":{"x":4.655510084620426,"y":1.8601243956014988}},"time":2.3900089319273774,"velocity":3.8224154358158184,"position":3.9606586137545086,"holonomicRotation":-159.72654456270098,"angularVelocity":-0.5914715659476626,"angularAcceleration":0.23113715202304286,"curveRadius":-6.475352964431165},{"acceleration":3.001578882718406,"curvature":-0.15409111707443163,"pose":{"rotation":{"radians":-3.06249263718197},"translation":{"x":4.648829885711854,"y":1.8595948869518402}},"time":2.391759644844904,"velocity":3.827670338738769,"position":3.9673597656605724,"holonomicRotation":-159.6116276016333,"angularVelocity":-0.5910187120042526,"angularAcceleration":0.2586683052808876,"curveRadius":-6.489666756825207},{"acceleration":3.0015449908168943,"curvature":-0.1537392639754562,"pose":{"rotation":{"radians":-3.063525401317368},"translation":{"x":4.642146864714418,"y":1.8590720993917234}},"time":2.3935085563939333,"velocity":3.8329197754381394,"position":3.9740632033223386,"holonomicRotation":-159.49671064056562,"angularVelocity":-0.5905182203017911,"angularAcceleration":0.28617325029346274,"curveRadius":-6.504519236931208},{"acceleration":3.001511203061693,"curvature":-0.15337625816145578,"pose":{"rotation":{"radians":-3.0645561686159652},"translation":{"x":4.635460900037614,"y":1.8585560148483287}},"time":2.3952557077430576,"velocity":3.8381638697859803,"position":3.9807690565055953,"holonomicRotation":-159.38179367949795,"angularVelocity":-0.5899702387625634,"angularAcceleration":0.3136428561282969,"curveRadius":-6.519913916189833},{"acceleration":3.0014775185103817,"curvature":-0.15300218271419774,"pose":{"rotation":{"radians":-3.0655848825205454},"translation":{"x":4.628771870090943,"y":1.8580466152488375}},"time":2.397001139820168,"velocity":3.8434027449255135,"position":3.9874774549418417,"holonomicRotation":-159.26687671843027,"angularVelocity":-0.5893749278879554,"angularAcceleration":0.34106791230374073,"curveRadius":-6.535854471226479},{"acceleration":3.0014439387857452,"curvature":-0.1526171242076513,"pose":{"rotation":{"radians":-3.066611486805206},"translation":{"x":4.622079653283899,"y":1.8575438825204302}},"time":2.39874489331446,"velocity":3.848636523281693,"position":3.9941885283275744,"holonomicRotation":-159.1519597573626,"angularVelocity":-0.58873246019057,"angularAcceleration":0.36843951825095406,"curveRadius":-6.552344667688779},{"acceleration":3.0014104671816915,"curvature":-0.1522211715043429,"pose":{"rotation":{"radians":-3.067635925586179},"translation":{"x":4.615384128025982,"y":1.8570477985902878}},"time":2.4004870086784065,"velocity":3.85386532657008,"position":4.000902406323573,"holonomicRotation":-159.0370427962949,"angularVelocity":-0.5880430206713156,"angularAcceleration":0.39574848688122644,"curveRadius":-6.569388411069152},{"acceleration":3.0013771009006254,"curvature":-0.15181441665224016,"pose":{"rotation":{"radians":-3.068658143331725},"translation":{"x":4.608685172726691,"y":1.856558345385591}},"time":2.402227526129703,"velocity":3.859089275792119,"position":4.0076192185542,"holonomicRotation":-158.92212583522723,"angularVelocity":-0.5873068062515265,"angularAcceleration":0.4229859454961371,"curveRadius":-6.58698970790561},{"acceleration":3.0013438445594334,"curvature":-0.151396953374096,"pose":{"rotation":{"radians":-3.0696780848723444},"translation":{"x":4.601982665795522,"y":1.8560755048335205}},"time":2.4039664856531773,"velocity":3.864308491253837,"position":4.014339094606709,"holonomicRotation":-158.80720887415958,"angularVelocity":-0.5865240259196562,"angularAcceleration":0.4501429281725222,"curveRadius":-6.60515273070944},{"acceleration":3.0013106980954363,"curvature":-0.1509688784160291,"pose":{"rotation":{"radians":-3.0706956954106177},"translation":{"x":4.595276485641974,"y":1.855599258861257}},"time":2.405703927002674,"velocity":3.869523092563395,"position":4.021062164030561,"holonomicRotation":-158.6922919130919,"angularVelocity":-0.5856949004742077,"angularAcceleration":0.4772106095487325,"curveRadius":-6.6238817595522725},{"acceleration":3.0012776624502187,"curvature":-0.15053029139347088,"pose":{"rotation":{"radians":-3.071710920531036},"translation":{"x":4.5885665106755456,"y":1.8551295893959818}},"time":2.4074398897029057,"velocity":3.874733198638447,"position":4.027788556336747,"holonomicRotation":-158.57737495202423,"angularVelocity":-0.5848196624746853,"angularAcceleration":0.504180187400125,"curveRadius":-6.643181187938458},{"acceleration":3.0012447382689134,"curvature":-0.15008129342363546,"pose":{"rotation":{"radians":-3.0727237062095596},"translation":{"x":4.581852619305733,"y":1.8546664783648752}},"time":2.409174413051278,"velocity":3.8799389277111547,"position":4.034518400997121,"holonomicRotation":-158.46245799095655,"angularVelocity":-0.5838985560350513,"angularAcceleration":0.5310429752924958,"curveRadius":-6.663055582665411},{"acceleration":3.001211927747109,"curvature":-0.14962198893377793,"pose":{"rotation":{"radians":-3.0737339988232195},"translation":{"x":4.575134689942035,"y":1.8542099076951182}},"time":2.410907536119686,"velocity":3.8851403973363134,"position":4.041251827443747,"holonomicRotation":-158.34754102988887,"angularVelocity":-0.5829318367957236,"angularAcceleration":0.5577903017676978,"curveRadius":-6.68350960394328},{"acceleration":3.0011792314485835,"curvature":-0.14915248398877964,"pose":{"rotation":{"radians":-3.0747417451592716},"translation":{"x":4.56841260099395,"y":1.8537598593138915}},"time":2.412639297756279,"velocity":3.8903377243938766,"position":4.047988965068244,"holonomicRotation":-158.2326240688212,"angularVelocity":-0.5819197716115775,"angularAcceleration":0.5844136760859477,"curveRadius":-6.704548078966137},{"acceleration":3.001146650433587,"curvature":-0.14867288703997655,"pose":{"rotation":{"radians":-3.075746892424496},"translation":{"x":4.5616862308709765,"y":1.853316315148376}},"time":2.414369736587207,"velocity":3.895531025095096,"position":4.054729943221153,"holonomicRotation":-158.11770710775352,"angularVelocity":-0.5808626385745539,"angularAcceleration":0.61090459722103,"curveRadius":-6.726175968662737},{"acceleration":3.001114186300953,"curvature":-0.1481833095283346,"pose":{"rotation":{"radians":-3.0767493882541874},"translation":{"x":4.554955457982611,"y":1.8528792571257524}},"time":2.4160988910183314,"velocity":3.9007204149886485,"position":4.061474891211308,"holonomicRotation":-158.00279014668584,"angularVelocity":-0.5797607267728858,"angularAcceleration":0.6372547077542007,"curveRadius":-6.748398339752202},{"acceleration":3.0010818389420675,"curvature":-0.14768386405000383,"pose":{"rotation":{"radians":-3.077749180720907},"translation":{"x":4.548220160738352,"y":1.8524486671732014}},"time":2.417826799236916,"velocity":3.9059060089628015,"position":4.068223938305214,"holonomicRotation":-157.88787318561816,"angularVelocity":-0.5786143360892888,"angularAcceleration":0.6634557734415246,"curveRadius":-6.771220447356476},{"acceleration":3.001049611099975,"curvature":-0.14717466586976502,"pose":{"rotation":{"radians":-3.078746218343321},"translation":{"x":4.541480217547697,"y":1.8520245272179041}},"time":2.4195534992132894,"velocity":3.9110879212553833,"position":4.07497721372644,"holonomicRotation":-157.77295622455048,"angularVelocity":-0.5774237771799003,"angularAcceleration":0.6894995805171572,"curveRadius":-6.7946476663646775},{"acceleration":3.0010175024577066,"curvature":-0.14665583199781865,"pose":{"rotation":{"radians":-3.079740450094399},"translation":{"x":4.534735506820146,"y":1.8516068191870407}},"time":2.4212790287024837,"velocity":3.916266265453462,"position":4.081734846655016,"holonomicRotation":-157.6580392634828,"angularVelocity":-0.5761893710330567,"angularAcceleration":0.7153781807693648,"curveRadius":-6.818685533179983},{"acceleration":3.0009855154018314,"curvature":-0.14612748163882752,"pose":{"rotation":{"radians":-3.080731825410328},"translation":{"x":4.5279859069651955,"y":1.851195525007793}},"time":2.4230034252458497,"velocity":3.9214411545029124,"position":4.088496966226854,"holonomicRotation":-157.54312230241513,"angularVelocity":-0.574911449308678,"angularAcceleration":0.7410834412160274,"curveRadius":-6.843339724909692},{"acceleration":3.0009536489930837,"curvature":-0.14558973633827413,"pose":{"rotation":{"radians":-3.081720294197782},"translation":{"x":4.521231296392343,"y":1.8507906266073406}},"time":2.424726726172647,"velocity":3.9266127007074982,"position":4.095263701533158,"holonomicRotation":-157.42820534134745,"angularVelocity":-0.5735903533056841,"angularAcceleration":0.766607841062932,"curveRadius":-6.868616051865943},{"acceleration":3.0009219068047863,"curvature":-0.14504271889890233,"pose":{"rotation":{"radians":-3.0827058068429043},"translation":{"x":4.514471553511088,"y":1.8503921059128652}},"time":2.42644896860161,"velocity":3.9317810157414024,"position":4.1020351816198595,"holonomicRotation":-157.31328838027977,"angularVelocity":-0.5722264348786784,"angularAcceleration":0.7919433432068078,"curveRadius":-6.894520508106442},{"acceleration":3.000890288065911,"curvature":-0.14448655413705142,"pose":{"rotation":{"radians":-3.083688314218309},"translation":{"x":4.507706556730927,"y":1.8499999448515472}},"time":2.4281701894424947,"velocity":3.9369462106464295,"position":4.108811535487066,"holonomicRotation":-157.1983714192121,"angularVelocity":-0.5708200551998427,"angularAcceleration":0.817082645892767,"curveRadius":-6.921059236082681},{"acceleration":3.0008587943442295,"curvature":-0.14392136872005518,"pose":{"rotation":{"radians":-3.0846677676911205},"translation":{"x":4.5009361844613585,"y":1.8496141253505674}},"time":2.429890425397598,"velocity":3.942108395840648,"position":4.115592892088505,"holonomicRotation":-157.08345445814444,"angularVelocity":-0.569371585279194,"angularAcceleration":0.8420181640499743,"curveRadius":-6.94823853395338},{"acceleration":3.0008274261124352,"curvature":-0.14334729115696965,"pose":{"rotation":{"radians":-3.0856441191303365},"translation":{"x":4.49416031511188,"y":1.8492346293371067}},"time":2.4316097129632595,"velocity":3.947267681121059,"position":4.122379380330994,"holonomicRotation":-156.96853749707677,"angularVelocity":-0.5678814054822571,"angularAcceleration":0.8667426128702956,"curveRadius":-6.976064855700479},{"acceleration":3.000796186205136,"curvature":-0.14276445116974948,"pose":{"rotation":{"radians":-3.086617320913906},"translation":{"x":4.48737882709199,"y":1.8488614387383457}},"time":2.433328088431338,"velocity":3.9524241756721383,"position":4.12917112907391,"holonomicRotation":-156.8536205360091,"angularVelocity":-0.566349905272815,"angularAcceleration":0.8912488788927847,"curveRadius":-7.004544841565511},{"acceleration":3.000765073010787,"curvature":-0.14217298092085884,"pose":{"rotation":{"radians":-3.087587325936091},"translation":{"x":4.480591598811188,"y":1.8484945354814655}},"time":2.4350455878906727,"velocity":3.9575779880626243,"position":4.135968267128682,"holonomicRotation":-156.7387035749414,"angularVelocity":-0.564777483284258,"angularAcceleration":0.9155298303070591,"curveRadius":-7.033685258077652},{"acceleration":3.000734090169033,"curvature":-0.14157301329985178,"pose":{"rotation":{"radians":-3.088554087614073},"translation":{"x":4.473798508678969,"y":1.8481339014936466}},"time":2.436762247228516,"velocity":3.9627292262588982,"position":4.1427709232582846,"holonomicRotation":-156.62378661387373,"angularVelocity":-0.5631645467856861,"angularAcceleration":0.9395786706279107,"curveRadius":-7.063493081707593},{"acceleration":3.000703236414793,"curvature":-0.14096468299588816,"pose":{"rotation":{"radians":-3.0895175598947144},"translation":{"x":4.466999435104833,"y":1.84777951870207}},"time":2.438478102131953,"velocity":3.9678779976208594,"position":4.1495792261767415,"holonomicRotation":-156.50886965280606,"angularVelocity":-0.5615115116735584,"angularAcceleration":0.9633886343283753,"curveRadius":-7.093975446524923},{"acceleration":3.0006725142104367,"curvature":-0.14034812586554,"pose":{"rotation":{"radians":-3.090477697261132},"translation":{"x":4.460194256498278,"y":1.8474313690339164}},"time":2.4401931880892973,"velocity":3.9730244089125706,"position":4.156393304548653,"holonomicRotation":-156.39395269173838,"angularVelocity":-0.5598188022623395,"angularAcceleration":0.9869531051609758,"curveRadius":-7.125139675595286},{"acceleration":3.0006419232950936,"curvature":-0.13972347954504402,"pose":{"rotation":{"radians":-3.0914344547388715},"translation":{"x":4.453382851268801,"y":1.8470894344163664}},"time":2.4419075403914694,"velocity":3.9781685663017656,"position":4.1632132869887215,"holonomicRotation":-156.2790357306707,"angularVelocity":-0.5580868509508708,"angularAcceleration":1.0102656900068,"curveRadius":-7.1569932502118965},{"acceleration":3.0006114651626485,"curvature":-0.13909088281646506,"pose":{"rotation":{"radians":-3.0923877879021004},"translation":{"x":4.446565097825899,"y":1.8467536967766012}},"time":2.443621194133355,"velocity":3.9833105753669864,"position":4.170039302061292,"holonomicRotation":-156.16411876960302,"angularVelocity":-0.5563160981284366,"angularAcceleration":1.0333200804532428,"curveRadius":-7.189543841773817},{"acceleration":3.000581141737345,"curvature":-0.13845047543804628,"pose":{"rotation":{"radians":-3.093337652879345},"translation":{"x":4.439740874579074,"y":1.8464241380418012}},"time":2.445334184215144,"velocity":3.9884505411023854,"position":4.176871478279906,"holonomicRotation":-156.04920180853534,"angularVelocity":-0.554506991804872,"angularAcceleration":1.0561102149963226,"curveRadius":-7.222799321100774},{"acceleration":3.00055095316105,"curvature":-0.13780239844492984,"pose":{"rotation":{"radians":-3.094284006359528},"translation":{"x":4.43291005993782,"y":1.8461007401391476}},"time":2.4470465453436545,"velocity":3.9935885679186938,"position":4.183709944106874,"holonomicRotation":-155.93428484746767,"angularVelocity":-0.5526599876781696,"angularAcceleration":1.0786300249112069,"curveRadius":-7.2567677434121824},{"acceleration":3.0005208991487007,"curvature":-0.13714679445380243,"pose":{"rotation":{"radians":-3.0952268055969383},"translation":{"x":4.426072532311635,"y":1.8457834849958206}},"time":2.4487583120336365,"velocity":3.9987247596464512,"position":4.190554827952843,"holonomicRotation":-155.8193678864,"angularVelocity":-0.5507755484015091,"angularAcceleration":1.1008739027865668,"curveRadius":-7.291457332142368},{"acceleration":3.000490981615207,"curvature":-0.13648380670859414,"pose":{"rotation":{"radians":-3.096166008417247},"translation":{"x":4.41922817011002,"y":1.8454723545390017}},"time":2.450469518609057,"velocity":4.003859219543681,"position":4.197406258176384,"holonomicRotation":-155.7044509253323,"angularVelocity":-0.5488541440871709,"angularAcceleration":1.1228359813109976,"curveRadius":-7.326876529280098},{"acceleration":3.000461203015915,"curvature":-0.135813578906587,"pose":{"rotation":{"radians":-3.097101573221761},"translation":{"x":4.41237685174247,"y":1.845167330695871}},"time":2.452180199204371,"velocity":4.008992050300673,"position":4.204264363083602,"holonomicRotation":-155.58953396426463,"angularVelocity":-0.5468962511626773,"angularAcceleration":1.1445110968446486,"curveRadius":-7.363034006252079},{"acceleration":3.00043156072977,"curvature":-0.13513625676599594,"pose":{"rotation":{"radians":-3.098033458993269},"translation":{"x":4.405518455618486,"y":1.8448683953936098}},"time":2.453890387765774,"velocity":4.014123354035106,"position":4.211129270927733,"holonomicRotation":-155.47461700319695,"angularVelocity":-0.544902353190597,"angularAcceleration":1.165893643005354,"curveRadius":-7.399938580003852},{"acceleration":3.0004020587370586,"curvature":-0.1344519862782848,"pose":{"rotation":{"radians":-3.09896162529986},"translation":{"x":4.398652860147563,"y":1.844575530559399}},"time":2.4556001180524385,"velocity":4.019253232307099,"position":4.218001109908783,"holonomicRotation":-155.3597000421293,"angularVelocity":-0.5428729395684678,"angularAcceleration":1.186978810610185,"curveRadius":-7.437599307236927},{"acceleration":3.000372696536453,"curvature":-0.13376091400847928,"pose":{"rotation":{"radians":-3.0998860322999278},"translation":{"x":4.391779943739201,"y":1.8442887181204186}},"time":2.4573094236377333,"velocity":4.024381786115255,"position":4.224880008173148,"holonomicRotation":-155.24478308106163,"angularVelocity":-0.5408085061094333,"angularAcceleration":1.2077614891069655,"curveRadius":-7.476025469866397},{"acceleration":3.0003434747192106,"curvature":-0.13306318771853948,"pose":{"rotation":{"radians":-3.100806640746546},"translation":{"x":4.384899584802897,"y":1.84400794000385}},"time":2.4590183379104293,"velocity":4.029509115902193,"position":4.231766093813272,"holonomicRotation":-155.12986611999395,"angularVelocity":-0.5387095545558586,"angularAcceleration":1.2282368911714825,"curveRadius":-7.515226541207171},{"acceleration":3.0003143948064017,"curvature":-0.1323589557207942,"pose":{"rotation":{"radians":-3.101723411991163},"translation":{"x":4.3780116617481495,"y":1.843733178136874}},"time":2.4607268940758877,"velocity":4.034635321559753,"position":4.238659494867299,"holonomicRotation":-155.01494915892627,"angularVelocity":-0.5365765920672753,"angularAcceleration":1.248400568681942,"curveRadius":-7.555212222355842},{"acceleration":3.0002854565982404,"curvature":-0.13164836686447434,"pose":{"rotation":{"radians":-3.1026363079878188},"translation":{"x":4.371116052984456,"y":1.8434644144466712}},"time":2.462435125157235,"velocity":4.039760502429628,"position":4.245560339318748,"holonomicRotation":-154.9000321978586,"angularVelocity":-0.534410131406576,"angularAcceleration":1.268248004825352,"curveRadius":-7.595992444246968},{"acceleration":3.0002566622880824,"curvature":-0.13093157036214936,"pose":{"rotation":{"radians":-3.103545291296727},"translation":{"x":4.364212636921315,"y":1.8432016308604227}},"time":2.46414306399652,"velocity":4.044884757310974,"position":4.252468755096192,"holonomicRotation":-154.78511523679092,"angularVelocity":-0.5322106904535897,"angularAcceleration":1.2877750083292916,"curveRadius":-7.6375773790389605},{"acceleration":3.00022801068405,"curvature":-0.13020871625778815,"pose":{"rotation":{"radians":-3.1044503250877233},"translation":{"x":4.3573012919682235,"y":1.842944809305309}},"time":2.4658507432558614,"velocity":4.050008184458114,"position":4.259384870072954,"holonomicRotation":-154.67019827572324,"angularVelocity":-0.5299787920040856,"angularAcceleration":1.3069775470394596,"curveRadius":-7.679977414263057},{"acceleration":3.000199505034762,"curvature":-0.12947995493465494,"pose":{"rotation":{"radians":-3.1053513731437032},"translation":{"x":4.35038189653468,"y":1.842693931708511}},"time":2.4675581954185746,"velocity":4.055130881591556,"position":4.2663088120668125,"holonomicRotation":-154.55528131465556,"angularVelocity":-0.5277149636497692,"angularAcceleration":1.3258517010040916,"curveRadius":-7.723203182335623},{"acceleration":3.000171143847816,"curvature":-0.12874543726334808,"pose":{"rotation":{"radians":-3.1062483998635084},"translation":{"x":4.343454329030183,"y":1.8424489799972092}},"time":2.46926545279029,"velocity":4.060252945893299,"position":4.273240708839719,"holonomicRotation":-154.44036435358788,"angularVelocity":-0.5254197373321412,"angularAcceleration":1.3443938539398714,"curveRadius":-7.767265553298836},{"acceleration":3.00014292865504,"curvature":-0.1280053137813567,"pose":{"rotation":{"radians":-3.1071413702650346},"translation":{"x":4.33651846786423,"y":1.8422099360985846}},"time":2.4709725475000566,"velocity":4.065374474015349,"position":4.28018068809753,"holonomicRotation":-154.3254473925202,"angularVelocity":-0.5230936493549004,"angularAcceleration":1.3626004251158976,"curveRadius":-7.81217568598816},{"acceleration":3.000114860743661,"curvature":-0.12725973629589687,"pose":{"rotation":{"radians":-3.1080302499878303},"translation":{"x":4.329574191446319,"y":1.8419767819398183}},"time":2.4726795115014277,"velocity":4.070495562082617,"position":4.287128877489746,"holonomicRotation":-154.21053043145253,"angularVelocity":-0.5207372399662255,"angularAcceleration":1.3804681216370962,"curveRadius":-7.857944932990106},{"acceleration":3.00008693930268,"curvature":-0.126508856094151,"pose":{"rotation":{"radians":-3.1089150052954038},"translation":{"x":4.322621378185948,"y":1.8417494994480905}},"time":2.4743863765735408,"velocity":4.075616305692615,"position":4.294085404609267,"holonomicRotation":-154.09561347038485,"angularVelocity":-0.5183510530672382,"angularAcceleration":1.397993864877245,"curveRadius":-7.90458495060437},{"acceleration":3.0000591661526816,"curvature":-0.1257528249007184,"pose":{"rotation":{"radians":-3.1097956030779272},"translation":{"x":4.315659906492615,"y":1.8415280705505825}},"time":2.476093174322178,"velocity":4.080736799923184,"position":4.301050396992157,"holonomicRotation":-153.98069650931717,"angularVelocity":-0.5159356363262781,"angularAcceleration":1.4151745529828579,"curveRadius":-7.952107642826299},{"acceleration":3.000031542702231,"curvature":-0.1249917942151058,"pose":{"rotation":{"radians":-3.1106720108538886},"translation":{"x":4.308689654775819,"y":1.8413124771744749}},"time":2.4777999361808174,"velocity":4.0858571393349825,"position":4.308023982117423,"holonomicRotation":-153.8657795482495,"angularVelocity":-0.5134915404425788,"angularAcceleration":1.4320075594189152,"curveRadius":-8.000525204710964},{"acceleration":3.0000040671727892,"curvature":-0.12422591562332772,"pose":{"rotation":{"radians":-3.111544196772357},"translation":{"x":4.301710501445056,"y":1.8411027012469485}},"time":2.479506693411671,"velocity":4.09097741796922,"position":4.315006287406801,"holonomicRotation":-153.7508625871818,"angularVelocity":-0.5110193193862701,"angularAcceleration":1.4484901611182022,"curveRadius":-8.049850105610455},{"acceleration":2.999976742105958,"curvature":-0.1234553412788253,"pose":{"rotation":{"radians":-3.112412129614445},"translation":{"x":4.2947223249098245,"y":1.8408987246951842}},"time":2.4812134771067105,"velocity":4.096097729358144,"position":4.321997440224558,"holonomicRotation":-153.63594562611416,"angularVelocity":-0.5085195298094738,"angularAcceleration":1.4646200242371266,"curveRadius":-8.10009505981186},{"acceleration":2.9999495672619036,"curvature":-0.12268022258072352,"pose":{"rotation":{"radians":-3.1132757787948617},"translation":{"x":4.287725003579625,"y":1.8407005294463623}},"time":2.4829203181886808,"velocity":4.1012181665233856,"position":4.328997567877303,"holonomicRotation":-153.5210286650465,"angularVelocity":-0.5059927309810636,"angularAcceleration":1.4803948973933976,"curveRadius":-8.151273114474508},{"acceleration":2.9999225435793457,"curvature":-0.12190071114335607,"pose":{"rotation":{"radians":-3.114135114363579},"translation":{"x":4.2807184158639515,"y":1.8405080974276644}},"time":2.4846272474121034,"velocity":4.1063388219810255,"position":4.336006797613817,"holonomicRotation":-153.4061117039788,"angularVelocity":-0.5034394847340725,"angularAcceleration":1.4958126042692172,"curveRadius":-8.203397589895872},{"acceleration":2.9998956718606196,"curvature":-0.12111695796155617,"pose":{"rotation":{"radians":-3.1149901070062205},"translation":{"x":4.273702440172304,"y":1.8403214105662706}},"time":2.4863342953642653,"velocity":4.111459787744375,"position":4.343025256624882,"holonomicRotation":-153.29119474291113,"angularVelocity":-0.5008603546013496,"angularAcceleration":1.5108715191371997,"curveRadius":-8.256482137847376},{"acceleration":2.999868952230207,"curvature":-0.12032911405623485,"pose":{"rotation":{"radians":-3.115840728045817},"translation":{"x":4.266676954914181,"y":1.840140450789362}},"time":2.4880414924661993,"velocity":4.116581155325804,"position":4.3500530720431305,"holonomicRotation":-153.17627778184345,"angularVelocity":-0.49825590649890455,"angularAcceleration":1.525569660055401,"curveRadius":-8.310540702000498},{"acceleration":2.9998423852192717,"curvature":-0.11953733029949633,"pose":{"rotation":{"radians":-3.116686949443075},"translation":{"x":4.25964183849908,"y":1.8399652000241193}},"time":2.489748868973652,"velocity":4.121703015740389,"position":4.357090370942903,"holonomicRotation":-153.06136082077577,"angularVelocity":-0.4956267077379421,"angularAcceleration":1.5399056678393446,"curveRadius":-8.365587532317623},{"acceleration":2.9998159704543443,"curvature":-0.11874175673790331,"pose":{"rotation":{"radians":-3.1175287437970316},"translation":{"x":4.2525969693364996,"y":1.8397956401977236}},"time":2.491456454978043,"velocity":4.126825459507285,"position":4.364137280340122,"holonomicRotation":-152.9464438597081,"angularVelocity":-0.49297332713672987,"angularAcceleration":1.55387816156216,"curveRadius":-8.421637235899105},{"acceleration":2.9997897107564464,"curvature":-0.11794254407810173,"pose":{"rotation":{"radians":-3.1183660843454537},"translation":{"x":4.245542225835935,"y":1.839631753237355}},"time":2.493164280407409,"velocity":4.131948576658065,"position":4.371193927192171,"holonomicRotation":-152.83152689864042,"angularVelocity":-0.4902963347565423,"angularAcceleration":1.5674859585511494,"curveRadius":-8.478704676217587},{"acceleration":2.999763604658397,"curvature":-0.11713984100840341,"pose":{"rotation":{"radians":-3.1191989449652278},"translation":{"x":4.238477486406888,"y":1.8394735210701947}},"time":2.494872375027341,"velocity":4.13707245673225,"position":4.378260438397785,"holonomicRotation":-152.71660993757274,"angularVelocity":-0.48759630178282365,"angularAcceleration":1.580727989077016,"curveRadius":-8.536805167152837},{"acceleration":2.9997376528047655,"curvature":-0.11633379702157713,"pose":{"rotation":{"radians":-3.1200273001720884},"translation":{"x":4.231402629458854,"y":1.8393209256234238}},"time":2.4965807684419126,"velocity":4.142197188783744,"position":4.385336940796959,"holonomicRotation":-152.60169297650506,"angularVelocity":-0.48487380002483554,"angularAcceleration":1.5936035194042888,"curveRadius":-8.5959542764217},{"acceleration":2.999711856264112,"curvature":-0.11552456039953295,"pose":{"rotation":{"radians":-3.120851125120576},"translation":{"x":4.224317533401332,"y":1.839173948824223}},"time":2.4982894900945927,"velocity":4.147322861384343,"position":4.392423561170862,"holonomicRotation":-152.48677601543739,"angularVelocity":-0.48212940193951775,"angularAcceleration":1.6061118444968776,"curveRadius":-8.656167974511876},{"acceleration":2.9996862156903967,"curvature":-0.11471227886814343,"pose":{"rotation":{"radians":-3.121670395603659},"translation":{"x":4.21722207664382,"y":1.8390325725997723}},"time":2.499998569269154,"velocity":4.152449562625799,"position":4.399520426241763,"holonomicRotation":-152.3718590543697,"angularVelocity":-0.4793636803240144,"angularAcceleration":1.6182524816107,"curveRadius":-8.717462593079985},{"acceleration":2.9996607299164952,"curvature":-0.1138970997553871,"pose":{"rotation":{"radians":-3.1224850880525676},"translation":{"x":4.210116137595816,"y":1.8388967788772532}},"time":2.5017080350905694,"velocity":4.157577380119433,"position":4.406627662672966,"holonomicRotation":-152.25694209330203,"angularVelocity":-0.4765772083317144,"angularAcceleration":1.6300249805481337,"curveRadius":-8.779854817617531},{"acceleration":1.983594705008582,"curvature":-0.11307916947381688,"pose":{"rotation":{"radians":-3.1232951795355617},"translation":{"x":4.202999594666816,"y":1.8387665495838466}},"time":2.5034186298626495,"velocity":4.160970506851746,"position":4.413745397068766,"holonomicRotation":-152.14202513223435,"angularVelocity":-0.47357299122863106,"angularAcceleration":1.7562412513573495,"curveRadius":-8.843361731901885},{"acceleration":-1.0163401398558753,"curvature":-0.1122586341869518,"pose":{"rotation":{"radians":-3.1241006477574036},"translation":{"x":4.195872326266321,"y":1.8386418666467328}},"time":2.505132495468203,"velocity":4.159228636442504,"position":4.420873755974398,"holonomicRotation":-152.02710817116667,"angularVelocity":-0.46997163560077676,"angularAcceleration":2.1013057361000924,"curveRadius":-8.908000771990805},{"acceleration":-2.995887068072403,"curvature":-0.11143563809718128,"pose":{"rotation":{"radians":-3.1249014710584313},"translation":{"x":4.188734210803828,"y":1.8385227119930931}},"time":2.5068510733364815,"velocity":4.154079971231453,"position":4.428012865876015,"holonomicRotation":-151.91219121009902,"angularVelocity":-0.46598022458529503,"angularAcceleration":2.3225080976284453,"curveRadius":-8.973789867186973},{"acceleration":-2.9958565884460646,"curvature":-0.11061032581491641,"pose":{"rotation":{"radians":-3.1256976284130187},"translation":{"x":4.181585126688835,"y":1.838409067550108}},"time":2.5085744115370927,"velocity":4.148917097129031,"position":4.435162853200667,"holonomicRotation":-151.79727424903135,"angularVelocity":-0.46198555472454994,"angularAcceleration":2.317983701242339,"curveRadius":-9.0407472596482},{"acceleration":-2.9958261563114723,"curvature":-0.10978284081936536,"pose":{"rotation":{"radians":-3.1264890994286723},"translation":{"x":4.174424952330838,"y":1.838300915244958}},"time":2.51030255841434,"velocity":4.143739869512226,"position":4.442323844316289,"holonomicRotation":-151.68235728796367,"angularVelocity":-0.4579882798586688,"angularAcceleration":2.3130411647929296,"curveRadius":-9.1088916313013},{"acceleration":-2.9957957702417084,"curvature":-0.10895332527127204,"pose":{"rotation":{"radians":-3.1272758643442087},"translation":{"x":4.167253566139339,"y":1.8381982370048247}},"time":2.5120355625906154,"velocity":4.138548142931128,"position":4.449495965531706,"holonomicRotation":-151.567440326896,"angularVelocity":-0.45398904763593095,"angularAcceleration":2.307687585227149,"curveRadius":-9.178242128087414},{"acceleration":-2.9957654294696283,"curvature":-0.10812192051400209,"pose":{"rotation":{"radians":-3.128057904028143},"translation":{"x":4.160070846523832,"y":1.8381010147568881}},"time":2.513773472969856,"velocity":4.1333417710974825,"position":4.456679343096646,"holonomicRotation":-151.4525233658283,"angularVelocity":-0.44998849956582393,"angularAcceleration":2.3019300177347137,"curveRadius":-9.248818326996858},{"acceleration":-2.9957351339579876,"curvature":-0.10728876706436247,"pose":{"rotation":{"radians":-3.1288351999770008},"translation":{"x":4.152876671893817,"y":1.8380092304283293}},"time":2.515516338741058,"velocity":4.12812060687292,"position":4.463874103201758,"holonomicRotation":-151.33760640476063,"angularVelocity":-0.44598727090819246,"angularAcceleration":2.2957755690342183,"curveRadius":-9.320640243727478},{"acceleration":-2.9957048860111035,"curvature":-0.1064540042564985,"pose":{"rotation":{"radians":-3.129607734313314},"translation":{"x":4.145670920658791,"y":1.8379228659463294}},"time":2.5172642093818567,"velocity":4.1228845022541645,"position":4.471080371978651,"holonomicRotation":-151.22268944369296,"angularVelocity":-0.4419859904280346,"angularAcceleration":2.2892314721470917,"curveRadius":-9.39372837108619},{"acceleration":-2.995674681887282,"curvature":-0.10561777075150384,"pose":{"rotation":{"radians":-3.1303754897832294},"translation":{"x":4.138453471228253,"y":1.8378419032380684}},"time":2.5190171346621635,"velocity":4.117633308372709,"position":4.478298275499931,"holonomicRotation":-151.10777248262528,"angularVelocity":-0.4379852801146682,"angularAcceleration":2.2823051035388167,"curveRadius":-9.468103642830972},{"acceleration":-2.995644523855335,"curvature":-0.10478020365844032,"pose":{"rotation":{"radians":-3.1311384497548493},"translation":{"x":4.1312242020117,"y":1.837766324230728}},"time":2.520775164647874,"velocity":4.112366875473242,"position":4.485527939779256,"holonomicRotation":-150.9928555215576,"angularVelocity":-0.43398575554532026,"angularAcceleration":2.2750036130535776,"curveRadius":-9.54378751982362},{"acceleration":-2.995614410026673,"curvature":-0.10394143904279783,"pose":{"rotation":{"radians":-3.1318965982150053},"translation":{"x":4.1239829914186314,"y":1.8376961108514884}},"time":2.5225383497046363,"velocity":4.107085052909661,"position":4.492769490771398,"holonomicRotation":-150.87793856048992,"angularVelocity":-0.4299880249371825,"angularAcceleration":2.2673346696112824,"curveRadius":-9.62080195549583},{"acceleration":-2.9955843407481564,"curvature":-0.10310161174128847,"pose":{"rotation":{"radians":-3.1326499197674824},"translation":{"x":4.1167297178585445,"y":1.8376312450275305}},"time":2.5243067405016886,"velocity":4.101787689129688,"position":4.500023054372317,"holonomicRotation":-150.76302159942225,"angularVelocity":-0.42599268992623474,"angularAcceleration":2.25930547569441,"curveRadius":-9.69916942238776},{"acceleration":-2.995554316828776,"curvature":-0.10226085570331202,"pose":{"rotation":{"radians":-3.133398399629835},"translation":{"x":4.109464259740936,"y":1.837571708686035}},"time":2.5260803880157647,"velocity":4.096474631662365,"position":4.507288756419241,"holonomicRotation":-150.64810463835457,"angularVelocity":-0.42200034472045267,"angularAcceleration":2.250923689232333,"curveRadius":-9.778912890199999},{"acceleration":-2.9955243355104653,"curvature":-0.10141930345437145,"pose":{"rotation":{"radians":-3.134142023630799},"translation":{"x":4.102186495475306,"y":1.8375174837541832}},"time":2.527859343535067,"velocity":4.0911457271125045,"position":4.514566722690757,"holonomicRotation":-150.5331876772869,"angularVelocity":-0.41801157639704384,"angularAcceleration":2.242196772279879,"curveRadius":-9.86005588620415},{"acceleration":-2.995494397972748,"curvature":-0.10057708626024624,"pose":{"rotation":{"radians":-3.134880778207063},"translation":{"x":4.094896303471151,"y":1.8374685521591554}},"time":2.529643658663311,"velocity":4.085800821141631,"position":4.521857078906913,"holonomicRotation":-150.4182707162192,"angularVelocity":-0.41402696450330834,"angularAcceleration":2.233132382650644,"curveRadius":-9.942622491692292},{"acceleration":-2.995464504048286,"curvature":-0.0997343339386406,"pose":{"rotation":{"radians":-3.1356146504005404},"translation":{"x":4.087593562137969,"y":1.8374248958281323}},"time":2.5314333853238447,"velocity":4.080439758458054,"position":4.529159950729326,"holonomicRotation":-150.30335375515153,"angularVelocity":-0.41004708130040807,"angularAcceleration":2.2237380102019397,"curveRadius":-10.02663737259456},{"acceleration":-2.995434651805125,"curvature":-0.09889117538267088,"pose":{"rotation":{"radians":-3.1363436278549957},"translation":{"x":4.08027814988526,"y":1.8373864966882953}},"time":2.533228575763834,"velocity":4.07506238280752,"position":4.536475463761303,"holonomicRotation":-150.18843679408388,"angularVelocity":-0.406072491372815,"angularAcceleration":2.2140213311386785,"curveRadius":-10.11212573953524},{"acceleration":-2.995404842311804,"curvature":-0.09804773766062148,"pose":{"rotation":{"radians":-3.137067698812404},"translation":{"x":4.072949945122518,"y":1.8373533366668247}},"time":2.535029282558533,"velocity":4.069668536955095,"position":4.543803743547971,"holonomicRotation":-150.07351983301618,"angularVelocity":-0.4021037514490903,"angularAcceleration":2.2039900862305997,"curveRadius":-10.199113450851462},{"acceleration":-2.9953750739039235,"curvature":-0.09720414707768776,"pose":{"rotation":{"radians":-3.137786852110054},"translation":{"x":4.065608826259245,"y":1.8373253976909012}},"time":2.53683555861562,"velocity":4.064258062677108,"position":4.5511449155764065,"holonomicRotation":-149.95860287194853,"angularVelocity":-0.39814141079283255,"angularAcceleration":2.1936517625375855,"curveRadius":-10.287626917818406},{"acceleration":-2.9953453460713044,"curvature":-0.09636052791242745,"pose":{"rotation":{"radians":-3.1385010771765467},"translation":{"x":4.058254671704937,"y":1.837302661687706}},"time":2.538647457179618,"velocity":4.058830800745883,"position":4.558499105275788,"holonomicRotation":-149.84368591088085,"angularVelocity":-0.3941860105661601,"angularAcceleration":2.183014162749278,"curveRadius":-10.377693249136213},{"acceleration":-2.9953156589725545,"curvature":-0.09551700312100139,"pose":{"rotation":{"radians":-3.139210364028154},"translation":{"x":4.050887359869093,"y":1.8372851105844195}},"time":2.540465031836393,"velocity":4.0533865909150935,"position":4.565866438017547,"holonomicRotation":-149.72876894981317,"angularVelocity":-0.39023808401132754,"angularAcceleration":2.1720849485420906,"curveRadius":-10.469340194155748},{"acceleration":-2.995286011561959,"curvature":-0.09467369505638042,"pose":{"rotation":{"radians":-3.1399147032651613},"translation":{"x":4.043506769161209,"y":1.8372727263082225}},"time":2.5422883365177333,"velocity":4.047925271908259,"position":4.573247039115534,"holonomicRotation":-149.6138519887455,"angularVelocity":-0.38629815642734683,"angularAcceleration":2.160871753526151,"curveRadius":-10.562596077025159},{"acceleration":-2.9952564038414544,"curvature":-0.09383072310167873,"pose":{"rotation":{"radians":-3.1406140860679073},"translation":{"x":4.036112777990785,"y":1.8372654907862964}},"time":2.5441174255060095,"velocity":4.042446681402929,"position":4.580641033826182,"holonomicRotation":-149.49893502767782,"angularVelocity":-0.382366744990953,"angularAcceleration":2.149382267124681,"curveRadius":-10.657490073015424},{"acceleration":-2.99522683331929,"curvature":-0.09298820638045312,"pose":{"rotation":{"radians":-3.1413085041924043},"translation":{"x":4.028705264767318,"y":1.8372633859458212}},"time":2.5459523534389192,"velocity":4.03695065602107,"position":4.588048547348693,"holonomicRotation":-149.38401806661014,"angularVelocity":-0.3784443585181164,"angularAcceleration":2.1376242644127617,"curveRadius":-10.754051926849598},{"acceleration":-2.99519730087196,"curvature":-0.09214626229908547,"pose":{"rotation":{"radians":3.141187357212696},"translation":{"x":4.021284107900307,"y":1.837266393713978}},"time":2.547793175314319,"velocity":4.031437031308487,"position":4.595469704825223,"holonomicRotation":-149.26910110554246,"angularVelocity":3412.8754907590555,"angularAcceleration":1854201.0939414022,"curveRadius":-10.852312129104392},{"acceleration":-2.9951678051828394,"curvature":-0.09130500634937613,"pose":{"rotation":{"radians":3.1405028908925576},"translation":{"x":4.013849185799248,"y":1.837274496017948}},"time":2.549639946495143,"velocity":4.025905641724143,"position":4.602904631341076,"holonomicRotation":-149.15418414447478,"angularVelocity":-0.37062865570208453,"angularAcceleration":-1848223.621234782,"curveRadius":-10.952301960020977},{"acceleration":-2.995138345599622,"curvature":-0.09046455246234868,"pose":{"rotation":{"radians":3.1398234105679497},"translation":{"x":4.006400376873642,"y":1.8372876747849114}},"time":2.5514927227144097,"velocity":4.0203563206240025,"position":4.610353451924906,"holonomicRotation":-149.0392671834071,"angularVelocity":-0.36673631577424076,"angularAcceleration":2.1008149216123333,"curveRadius":-11.054053469354196},{"acceleration":-2.9951089210235717,"curvature":-0.08962501337017457,"pose":{"rotation":{"radians":3.1391489222210267},"translation":{"x":3.9989375595329837,"y":1.8373059119420492}},"time":2.5533515600803214,"velocity":4.014788900246629,"position":4.617816291548932,"holonomicRotation":-148.92435022233943,"angularVelocity":-0.3628549540116285,"angularAcceleration":2.088058823106737,"curveRadius":-11.157599451279749},{"acceleration":-2.9950795310146434,"curvature":-0.08878650041728502,"pose":{"rotation":{"radians":3.1384794312796718},"translation":{"x":3.9914606121867733,"y":1.837329189416542}},"time":2.5552165150814554,"velocity":4.009203211696469,"position":4.625293275129148,"holonomicRotation":-148.80943326127175,"angularVelocity":-0.35898503768071094,"angularAcceleration":2.0750722288550296,"curveRadius":-11.26297348470916},{"acceleration":-2.9950501748293443,"curvature":-0.08794912261921467,"pose":{"rotation":{"radians":3.1378149426219553},"translation":{"x":3.9839694132445076,"y":1.8373574891355713}},"time":2.5570876445920523,"velocity":4.003599084928627,"position":4.632784527525557,"holonomicRotation":-148.69451630020407,"angularVelocity":-0.355127025656576,"angularAcceleration":2.0618626355287804,"curveRadius":-11.370210073949336},{"acceleration":-2.9950208509011182,"curvature":-0.08711298776679609,"pose":{"rotation":{"radians":3.137155460581208},"translation":{"x":3.9764638411156854,"y":1.837390793026317}},"time":2.5589650058773974,"velocity":3.997976348734344,"position":4.640290173542396,"holonomicRotation":-148.5795993391364,"angularVelocity":-0.35128136810695615,"angularAcceleration":2.0484376553620742,"curveRadius":-11.479344534445634},{"acceleration":-2.9949915580749864,"curvature":-0.08627820223583987,"pose":{"rotation":{"radians":3.136500988950091},"translation":{"x":3.968943774209804,"y":1.8374290830159603}},"time":2.560848656599304,"velocity":3.9923348307238724,"position":4.647810337928381,"holonomicRotation":-148.46468237806874,"angularVelocity":-0.347448507043182,"angularAcceleration":2.034804552244667,"curveRadius":-11.590413036962898},{"acceleration":-2.9949622964511513,"curvature":-0.08544487041437733,"pose":{"rotation":{"radians":3.135851530986183},"translation":{"x":3.9614090909363617,"y":1.837472341031682}},"time":2.5627386548216964,"velocity":3.986674357307447,"position":4.65534514537695,"holonomicRotation":-148.34976541700104,"angularVelocity":-0.3436288755264842,"angularAcceleration":2.020970957243815,"curveRadius":-11.703452707580391},{"acceleration":-2.9949330641961764,"curvature":-0.08461309544699312,"pose":{"rotation":{"radians":3.1352070894164146},"translation":{"x":3.953859669704857,"y":1.837520549000663}},"time":2.5646350590162976,"velocity":3.9809947536819554,"position":4.662894720526518,"holonomicRotation":-148.2348484559334,"angularVelocity":-0.33982289830577167,"angularAcceleration":2.0069441058754904,"curveRadius":-11.818501553656809},{"acceleration":-2.994903860562068,"curvature":-0.08378297828004383,"pose":{"rotation":{"radians":3.134567666442366},"translation":{"x":3.946295388924787,"y":1.8375736888500838}},"time":2.5665379280684193,"velocity":3.975295843811612,"position":4.670459187960735,"holonomicRotation":-148.1199314948657,"angularVelocity":-0.3360309913789309,"angularAcceleration":1.9927314087182535,"curveRadius":-11.935598620730683},{"acceleration":-2.99487468383295,"curvature":-0.08295461840830522,"pose":{"rotation":{"radians":3.1339332637451087},"translation":{"x":3.93871612700565,"y":1.8376317425071254}},"time":2.5684473212828616,"velocity":3.9695774504121966,"position":4.678038672208755,"holonomicRotation":-148.00501453379803,"angularVelocity":-0.33225356226188546,"angularAcceleration":1.9783400760376066,"curveRadius":-12.054783919057632},{"acceleration":-2.994845534379415,"curvature":-0.08212811444730943,"pose":{"rotation":{"radians":3.133303882490582},"translation":{"x":3.9311217623569443,"y":1.8376946918989683}},"time":2.570363298389922,"velocity":3.9638393949291433,"position":4.685633297745504,"holonomicRotation":-147.89009757273035,"angularVelocity":-0.32849100973456347,"angularAcceleration":1.9637773924629756,"curveRadius":-12.176098364483524},{"acceleration":-2.9948164086283597,"curvature":-0.08130356163077654,"pose":{"rotation":{"radians":3.1326795233345464},"translation":{"x":3.9235121733881675,"y":1.8377625189527937}},"time":2.5722859195515166,"velocity":3.9580814975268237,"position":4.693243188991965,"holonomicRotation":-147.77518061166268,"angularVelocity":-0.3247437240927523,"angularAcceleration":1.9490504508455653,"curveRadius":-12.299584174938056},{"acceleration":-2.9947873077732328,"curvature":-0.08048105525695926,"pose":{"rotation":{"radians":3.1320601864281388},"translation":{"x":3.9158872385088173,"y":1.8378352055957825}},"time":2.5742152453674154,"velocity":3.952303577060811,"position":4.7008684703154575,"holonomicRotation":-147.660263650595,"angularVelocity":-0.3210120868667631,"angularAcceleration":1.9341664301790609,"curveRadius":-12.425284395280457},{"acceleration":-2.9947582294635757,"curvature":-0.07966068799062925,"pose":{"rotation":{"radians":3.1314458714230904},"translation":{"x":3.908246836128393,"y":1.8379127337551147}},"time":2.576151336881595,"velocity":3.946505451065727,"position":4.708509266029929,"holonomicRotation":-147.54534668952732,"angularVelocity":-0.31729647103418174,"angularAcceleration":1.919132337169496,"curveRadius":-12.55324332772061},{"acceleration":-2.9947291729235888,"curvature":-0.07884255100799298,"pose":{"rotation":{"radians":3.130836577476801},"translation":{"x":3.900590844656391,"y":1.8379950853579718}},"time":2.5780942555887116,"velocity":3.9406869357329057,"position":4.716165700396255,"holonomicRotation":-147.43042972845964,"angularVelocity":-0.313597241128828,"angularAcceleration":1.9039550609111222,"curveRadius":-12.683506396166976},{"acceleration":-2.9947001352390425,"curvature":-0.07802673359993822,"pose":{"rotation":{"radians":3.130232303258408},"translation":{"x":3.89291914250231,"y":1.8380822423315346}},"time":2.580044063440694,"velocity":3.934847845894884,"position":4.723837897622537,"holonomicRotation":-147.31551276739197,"angularVelocity":-0.3099147527683591,"angularAcceleration":1.888641671395886,"curveRadius":-12.816120243187928},{"acceleration":-2.99467111749449,"curvature":-0.07721332375104693,"pose":{"rotation":{"radians":3.1296330469537983},"translation":{"x":3.885231608075648,"y":1.8381741866029835}},"time":2.5820008228534648,"velocity":3.928987994997574,"position":4.7315259818644115,"holonomicRotation":-147.2005958063243,"angularVelocity":-0.30624935324125413,"angularAcceleration":1.8731988731894453,"curveRadius":-12.95113267270069},{"acceleration":-2.994642116785922,"curvature":-0.07640240754573718,"pose":{"rotation":{"radians":3.1290388062712284},"translation":{"x":3.877528119785903,"y":1.8382709000994994}},"time":2.5839645967137863,"velocity":3.9231071950876117,"position":4.739230077225364,"holonomicRotation":-147.0856788452566,"angularVelocity":-0.3026013812367172,"angularAcceleration":1.8576334466228335,"curveRadius":-13.088592782908897},{"acceleration":-2.994613131557889,"curvature":-0.07559406875797173,"pose":{"rotation":{"radians":3.12844957844706},"translation":{"x":3.8698085560425723,"y":1.8383723647482633}},"time":2.5859354483862385,"velocity":3.9172052567889337,"position":4.746950307757045,"holonomicRotation":-146.97076188418893,"angularVelocity":-0.29897116683340835,"angularAcceleration":1.8419521134191277,"curveRadius":-13.228551081192405},{"acceleration":-2.994584161694303,"curvature":-0.07478839102666927,"pose":{"rotation":{"radians":3.1278653602512723},"translation":{"x":3.862072795255155,"y":1.8384785624764557}},"time":2.5879134417203304,"velocity":3.911281989278725,"position":4.754686797459592,"holonomicRotation":-146.85584492312125,"angularVelocity":-0.2953590316601182,"angularAcceleration":1.826161449097276,"curveRadius":-13.371059147981985},{"acceleration":-2.9945552043140524,"curvature":-0.0739854542710173,"pose":{"rotation":{"radians":3.127286147993135},"translation":{"x":3.8543207158331487,"y":1.8385894752112577}},"time":2.5898986410577476,"velocity":3.9053372002712616,"position":4.762439670281961,"holonomicRotation":-146.74092796205358,"angularVelocity":-0.2917652888656431,"angularAcceleration":1.810267980015909,"curveRadius":-13.516170304731578},{"acceleration":-2.9945262580386602,"curvature":-0.07318533846612468,"pose":{"rotation":{"radians":3.1267119375270007},"translation":{"x":3.846552196186051,"y":1.83870508487985}},"time":2.591891111239739,"velocity":3.899370695992929,"position":4.770209050122259,"holonomicRotation":-146.6260110009859,"angularVelocity":-0.2881902431082825,"angularAcceleration":1.794278172728894,"curveRadius":-13.663938993229774},{"acceleration":-2.994497322878389,"curvature":-0.07238812063793244,"pose":{"rotation":{"radians":3.1261427242580173},"translation":{"x":3.8387671147233595,"y":1.838825373409413}},"time":2.5938909176146483,"velocity":3.8933822811569883,"position":4.777995060828075,"holonomicRotation":-146.51109403991825,"angularVelocity":-0.2846341906522137,"angularAcceleration":1.778198379945844,"curveRadius":-13.81442136067814},{"acceleration":-2.994468395160687,"curvature":-0.07159387706354227,"pose":{"rotation":{"radians":3.1255785031477026},"translation":{"x":3.8309653498545737,"y":1.838950322727128}},"time":2.595898126045587,"velocity":3.8873717589480425,"position":4.785797826196828,"holonomicRotation":-146.39617707885057,"angularVelocity":-0.28109741948966155,"angularAcceleration":1.762034828091214,"curveRadius":-13.96767490483107},{"acceleration":-2.99443947430169,"curvature":-0.07080268144619707,"pose":{"rotation":{"radians":3.1250192687201013},"translation":{"x":3.8231467799891905,"y":1.8390799147601755}},"time":2.597912802918262,"velocity":3.8813389309925412,"position":4.7936174699761125,"holonomicRotation":-146.2812601177829,"angularVelocity":-0.27758020910753983,"angularAcceleration":1.7457937944417674,"curveRadius":-14.123758868651036},{"acceleration":-2.994410558107715,"curvature":-0.07001460652875076,"pose":{"rotation":{"radians":3.124465015067376},"translation":{"x":3.815311283536708,"y":1.8392141314357364}},"time":2.599935015148953,"velocity":3.8752835973382256,"position":4.801454115864046,"holonomicRotation":-146.16634315671521,"angularVelocity":-0.2740828308291971,"angularAcceleration":1.729481320141991,"curveRadius":-14.282733983363322},{"acceleration":-2.994381646114591,"curvature":-0.06922972307150017,"pose":{"rotation":{"radians":3.1239157358556997},"translation":{"x":3.8074587389066243,"y":1.8393529546809917}},"time":2.601964830192647,"velocity":3.869205556426382,"position":4.809307887509624,"holonomicRotation":-146.05142619564754,"angularVelocity":-0.27060554772360906,"angularAcceleration":1.7131034260443434,"curveRadius":-14.444662720479238},{"acceleration":-2.994352735037878,"curvature":-0.06844809921548371,"pose":{"rotation":{"radians":3.1233714243312556},"translation":{"x":3.7995890245084367,"y":1.8394963664231219}},"time":2.6040023160513313,"velocity":3.863104605072829,"position":4.817178908513078,"holonomicRotation":-145.93650923457986,"angularVelocity":-0.2671486146144655,"angularAcceleration":1.6966660624460022,"curveRadius":-14.60960949188475},{"acceleration":-2.9943238238949026,"curvature":-0.06766980357478737,"pose":{"rotation":{"radians":3.122832073325921},"translation":{"x":3.791702018751644,"y":1.839644348589308}},"time":2.6060475412824533,"velocity":3.8569805384380493,"position":4.8250673024262385,"holonomicRotation":-145.82159227351218,"angularVelocity":-0.2637122782993062,"angularAcceleration":1.680175006091643,"curveRadius":-14.777640057648743},{"acceleration":-2.9942949105906744,"curvature":-0.06689490109610331,"pose":{"rotation":{"radians":3.1222976752634324},"translation":{"x":3.7837976000457445,"y":1.8397968831067304}},"time":2.6081005750075454,"velocity":3.850833150003735,"position":4.832973192752899,"holonomicRotation":-145.7066753124445,"angularVelocity":-0.2602967773774885,"angularAcceleration":1.6636360523811728,"curveRadius":-14.948822460524585},{"acceleration":-2.994265993134537,"curvature":-0.06612345636573279,"pose":{"rotation":{"radians":3.1217682221651084},"translation":{"x":3.7758756468002352,"y":1.83995395190257}},"time":2.610161486921022,"velocity":3.8446622315463665,"position":4.840896702949186,"holonomicRotation":-145.59175835137682,"angularVelocity":-0.25690234253188554,"angularAcceleration":1.6470547932720998,"curveRadius":-15.12322638533806},{"acceleration":-2.994237070599704,"curvature":-0.06535553109808896,"pose":{"rotation":{"radians":3.121243705655853},"translation":{"x":3.7679360374246147,"y":1.840115536904008}},"time":2.612230347299153,"velocity":3.838467573108272,"position":4.84883795642393,"holonomicRotation":-145.47684139030915,"angularVelocity":-0.25352919645993754,"angularAcceleration":1.6304367890671345,"curveRadius":-15.300923781020895},{"acceleration":-2.9942081393471867,"curvature":-0.06459118664532686,"pose":{"rotation":{"radians":3.1207241169702873},"translation":{"x":3.7599786503283807,"y":1.840281620038225}},"time":2.614307227009215,"velocity":3.8322489629759584,"position":4.856797076539042,"holonomicRotation":-145.36192442924147,"angularVelocity":-0.2501775538797071,"angularAcceleration":1.6137875313587104,"curveRadius":-15.48198836307259},{"acceleration":-2.9941791983089425,"curvature":-0.06383048103358155,"pose":{"rotation":{"radians":3.1202094469584822},"translation":{"x":3.752003363921032,"y":1.8404521832324015}},"time":2.6163921975188305,"velocity":3.8260061876469806,"position":4.864774186609892,"holonomicRotation":-145.2470074681738,"angularVelocity":-0.2468476217920275,"angularAcceleration":1.5971123199694468,"curveRadius":-15.666496379275205},{"acceleration":-2.9941502460850833,"curvature":-0.06307347277306859,"pose":{"rotation":{"radians":3.1196996860919186},"translation":{"x":3.7440100566120655,"y":1.8406272084137187}},"time":2.6184853309054916,"velocity":3.81973903180222,"position":4.87276940990569,"holonomicRotation":-145.1320905071061,"angularVelocity":-0.24353959944079873,"angularAcceleration":1.5804164093457513,"curveRadius":-15.85452577818079},{"acceleration":-2.9941212795068615,"curvature":-0.06232021702296148,"pose":{"rotation":{"radians":3.119194824469833},"translation":{"x":3.7359986068109787,"y":1.840806677509357}},"time":2.62058669986628,"velocity":3.813447278280629,"position":4.880782869649871,"holonomicRotation":-145.01717354603844,"angularVelocity":-0.24025367820039153,"angularAcceleration":1.5637050426282886,"curveRadius":-16.046157214625175},{"acceleration":-2.994092296462174,"curvature":-0.06157076857271557,"pose":{"rotation":{"radians":3.1186948518245963},"translation":{"x":3.7279688929272714,"y":1.8409905724464977}},"time":2.6226963777277814,"velocity":3.8071307080474903,"position":4.8888146890204816,"holonomicRotation":-144.90225658497076,"angularVelocity":-0.23699004211049546,"angularAcceleration":1.546983143470663,"curveRadius":-16.241473400141043},{"acceleration":-2.9940632954300304,"curvature":-0.06082517925156881,"pose":{"rotation":{"radians":3.118199757528314},"translation":{"x":3.71992079337044,"y":1.8411788751523213}},"time":2.624814438456208,"velocity":3.8007891001630165,"position":4.896864991150569,"holonomicRotation":-144.7873396239031,"angularVelocity":-0.2337488673660631,"angularAcceleration":1.5302558141664364,"curveRadius":-16.440559852097895},{"acceleration":-2.9940342740772996,"curvature":-0.06008350095101097,"pose":{"rotation":{"radians":3.1177095305983924},"translation":{"x":3.7118541865499837,"y":1.8413715675540083}},"time":2.626940956667724,"velocity":3.794422231753288,"position":4.904933899128573,"holonomicRotation":-144.67242266283543,"angularVelocity":-0.23053032288500358,"angularAcceleration":1.5135278238529721,"curveRadius":-16.64350419286235},{"acceleration":-2.9940052302914477,"curvature":-0.05934578257724946,"pose":{"rotation":{"radians":3.1172241597035892},"translation":{"x":3.7037689508753995,"y":1.8415686315787398}},"time":2.6290760076389867,"velocity":3.7880298779783885,"position":4.913021535998723,"holonomicRotation":-144.55750570176775,"angularVelocity":-0.22733457015131167,"angularAcceleration":1.4968039530230974,"curveRadius":-16.850397055566937},{"acceleration":-2.9939761605168576,"curvature":-0.05861207177630763,"pose":{"rotation":{"radians":3.116743633170079},"translation":{"x":3.6956649647561854,"y":1.8417700491536968}},"time":2.631219667317904,"velocity":3.7816118120034496,"position":4.9211280247614315,"holonomicRotation":-144.44258874070007,"angularVelocity":-0.22416176328554016,"angularAcceleration":1.4800888858320864,"curveRadius":-17.061331730713935},{"acceleration":-2.9939470638743084,"curvature":-0.057882414933853536,"pose":{"rotation":{"radians":3.116267938987443},"translation":{"x":3.6875421066018403,"y":1.8419758022060595}},"time":2.6333720123346165,"velocity":3.775167804960218,"position":4.929253488373692,"holonomicRotation":-144.3276717796324,"angularVelocity":-0.22101204915677494,"angularAcceleration":1.4633871913229928,"curveRadius":-17.276404260996593},{"acceleration":-2.9939179375464997,"curvature":-0.057156856727007266,"pose":{"rotation":{"radians":3.115797064814355},"translation":{"x":3.679400254821862,"y":1.8421858726630091}},"time":2.635533120012712,"velocity":3.768697625917799,"position":4.937398049749483,"holonomicRotation":-144.21275481856472,"angularVelocity":-0.21788556760072797,"angularAcceleration":1.4467032752400155,"curveRadius":-17.49571367747185},{"acceleration":-2.9938887786968413,"curvature":-0.05643544101185793,"pose":{"rotation":{"radians":3.1153309979848434},"translation":{"x":3.6712392878257476,"y":1.8424002424517267}},"time":2.637703068380669,"velocity":3.762201041848621,"position":4.945561831760168,"holonomicRotation":-144.09783785749704,"angularVelocity":-0.21478245122964632,"angularAcceleration":1.4300415700689433,"curveRadius":-17.71936184196532},{"acceleration":-2.9938595849152927,"curvature":-0.05571820857040485,"pose":{"rotation":{"radians":3.114869725514154},"translation":{"x":3.6630590840229957,"y":1.8426188934993923}},"time":2.6398819361835457,"velocity":3.755677817592715,"position":4.9537449572349,"holonomicRotation":-143.98292089642936,"angularVelocity":-0.21170282569695967,"angularAcceleration":1.4134063244316208,"curveRadius":-17.947454264191073},{"acceleration":-2.993830354172009,"curvature":-0.05500520024591458,"pose":{"rotation":{"radians":3.11441323410433},"translation":{"x":3.654859521823104,"y":1.8428418077331874}},"time":2.6420698028949174,"velocity":3.7491277158213276,"position":4.961947548961026,"holonomicRotation":-143.86800393536168,"angularVelocity":-0.20864680990459994,"angularAcceleration":1.3968016316879308,"curveRadius":-18.180099254784068},{"acceleration":-2.9938010835247537,"curvature":-0.0542964546885708,"pose":{"rotation":{"radians":3.1139615101506295},"translation":{"x":3.646640479635571,"y":1.8430689670802924}},"time":2.6442667487290636,"velocity":3.7425504970026156,"position":4.970169729684498,"holonomicRotation":-143.753086974294,"angularVelocity":-0.20561451569700426,"angularAcceleration":1.3802316654630313,"curveRadius":-18.417408755980826},{"acceleration":-2.993771769676104,"curvature":-0.05359200832617972,"pose":{"rotation":{"radians":3.113514539747044},"translation":{"x":3.638401835869894,"y":1.843300353467888}},"time":2.6464728546534175,"velocity":3.7359459193653697,"position":4.978411622110276,"holonomicRotation":-143.63817001322633,"angularVelocity":-0.20260604835489152,"angularAcceleration":1.3637003141605037,"curveRadius":-18.65949851913834},{"acceleration":-2.993742411417045,"curvature":-0.05289189811474286,"pose":{"rotation":{"radians":3.113072308692144},"translation":{"x":3.630143468935571,"y":1.8435359488231555}},"time":2.6486882024012846,"velocity":3.729313738856543,"position":4.986673348902741,"holonomicRotation":-143.52325305215865,"angularVelocity":-0.19962150652216962,"angularAcceleration":1.3472114414522358,"curveRadius":-18.906487300391746},{"acceleration":-2.99371300444295,"curvature":-0.052196157391541126,"pose":{"rotation":{"radians":3.1126348024952923},"translation":{"x":3.6218652572421006,"y":1.843775735073275}},"time":2.6509128744848307,"velocity":3.7226537091094096,"position":4.994955032686106,"holonomicRotation":-143.40833609109097,"angularVelocity":-0.19666098212299185,"angularAcceleration":1.3307688899744075,"curveRadius":-19.1584984407695},{"acceleration":-2.993683546815698,"curvature":-0.051504820023504344,"pose":{"rotation":{"radians":3.1122020063818527},"translation":{"x":3.613567079198981,"y":1.8440196941454283}},"time":2.653146954208356,"velocity":3.7159655813988177,"position":5.003256796044827,"holonomicRotation":-143.2934191300233,"angularVelocity":-0.19372456089288048,"angularAcceleration":1.3143762056431678,"curveRadius":-19.41565856445373},{"acceleration":-2.9936540354931243,"curvature":-0.05081791620916783,"pose":{"rotation":{"radians":3.1117739052997284},"translation":{"x":3.605248813215709,"y":1.8442678079667951}},"time":2.6553905256818546,"velocity":3.709249104603261,"position":5.0115787615240155,"holonomicRotation":-143.17850216895562,"angularVelocity":-0.19081232186319375,"angularAcceleration":1.298037109174526,"curveRadius":-19.678099272783534},{"acceleration":-2.9936244673005885,"curvature":-0.050135477150251996,"pose":{"rotation":{"radians":3.111350483924339},"translation":{"x":3.5969103377017833,"y":1.8445200584645567}},"time":2.657643673834872,"velocity":3.7025040251639347,"position":5.019921051629853,"holonomicRotation":-143.06358520788797,"angularVelocity":-0.18792433814094917,"angularAcceleration":1.2817549162832116,"curveRadius":-19.94595557559132},{"acceleration":-2.9935948400057155,"curvature":-0.049457531293377016,"pose":{"rotation":{"radians":3.110931726664906},"translation":{"x":3.5885515310667024,"y":1.8447764275658942}},"time":2.6599064844306666,"velocity":3.695730087040454,"position":5.028283788830005,"holonomicRotation":-142.94866824682026,"angularVelocity":-0.1850606764045858,"angularAcceleration":1.2655331125307658,"curveRadius":-20.219367482539763},{"acceleration":-2.9935651495988216,"curvature":-0.04878410523976354,"pose":{"rotation":{"radians":3.110517617670169},"translation":{"x":3.580172271719963,"y":1.8450368971979876}},"time":2.6621790440806823,"velocity":3.6889270316717826,"position":5.0366670955540345,"holonomicRotation":-142.8337512857526,"angularVelocity":-0.18222139723992037,"angularAcceleration":1.2493749788463357,"curveRadius":-20.49847988571712},{"acceleration":-2.993535393732518,"curvature":-0.04811522565705995,"pose":{"rotation":{"radians":3.1101081408335367},"translation":{"x":3.571772438071064,"y":1.8453014492880182}},"time":2.6644614402593447,"velocity":3.6820945979284367,"position":5.04507109419382,"holonomicRotation":-142.71883432468493,"angularVelocity":-0.1794065554702473,"angularAcceleration":1.2332835972949503,"curveRadius":-20.783441963412468},{"acceleration":-2.9935055685430276,"curvature":-0.04745091687933854,"pose":{"rotation":{"radians":3.1097032797993736},"translation":{"x":3.563351908529503,"y":1.8455700657631668}},"time":2.666753761319184,"velocity":3.675232522070919,"position":5.05349590710397,"holonomicRotation":-142.60391736361726,"angularVelocity":-0.17661619973579343,"angularAcceleration":1.217262181698686,"curveRadius":-21.074408373243216},{"acceleration":-2.9934756716206357,"curvature":-0.04679120331746881,"pose":{"rotation":{"radians":3.1093030179682857},"translation":{"x":3.5549105615047787,"y":1.845842728550614}},"time":2.669056096506299,"velocity":3.668340537700375,"position":5.061941656602237,"holonomicRotation":-142.48900040254958,"angularVelocity":-0.17385037301605014,"angularAcceleration":1.2013136641539035,"curveRadius":-21.37153843245285},{"acceleration":-2.9934456989439155,"curvature":-0.04613610554592752,"pose":{"rotation":{"radians":3.108907338502687},"translation":{"x":3.546448275406388,"y":1.8461194195775408}},"time":2.6713685359761663,"velocity":3.661418375715232,"position":5.070408464969939,"holonomicRotation":-142.3740834414819,"angularVelocity":-0.17110911258631695,"angularAcceleration":1.1854409447051542,"curveRadius":-21.67499809892972},{"acceleration":-2.9934156477775655,"curvature":-0.04548564418481056,"pose":{"rotation":{"radians":3.1085162243324724},"translation":{"x":3.53796492864383,"y":1.846400120771128}},"time":2.673691170809811,"velocity":3.654465764260127,"position":5.078896454452371,"holonomicRotation":-142.25916648041422,"angularVelocity":-0.16839245005247172,"angularAcceleration":1.1696468573074037,"curveRadius":-21.984958505522037},{"acceleration":-2.9933855145559725,"curvature":-0.04483984043527321,"pose":{"rotation":{"radians":3.108129658160596},"translation":{"x":3.5294603996266014,"y":1.846684814058556}},"time":2.6760240930303403,"velocity":3.6474824286786087,"position":5.087405747259226,"holonomicRotation":-142.14424951934654,"angularVelocity":-0.1657004114730266,"angularAcceleration":1.1539341328037762,"curveRadius":-22.3015958641403},{"acceleration":-2.9933552952701277,"curvature":-0.04419871159845928,"pose":{"rotation":{"radians":3.1077476224681457},"translation":{"x":3.5209345667642014,"y":1.846973481367006}},"time":2.6783673956198566,"velocity":3.64046809146386,"position":5.095936465565004,"holonomicRotation":-142.02933255827887,"angularVelocity":-0.16303301765620015,"angularAcceleration":1.138305325466754,"curveRadius":-22.625093896059607},{"acceleration":-2.9933249873660555,"curvature":-0.04356227401829524,"pose":{"rotation":{"radians":3.107370099520424},"translation":{"x":3.5123873084661277,"y":1.8472661046236587}},"time":2.6807211725367606,"velocity":3.6334224722038058,"position":5.104488731509438,"holonomicRotation":-141.9144155972112,"angularVelocity":-0.16039028380754,"angularAcceleration":1.1227630918125653,"curveRadius":-22.955642755931912},{"acceleration":-2.9932945862544393,"curvature":-0.04293054512468095,"pose":{"rotation":{"radians":3.1069970713718003},"translation":{"x":3.503818503141877,"y":1.8475626657556947}},"time":2.683085518733451,"velocity":3.626345287533221,"position":5.113062667197903,"holonomicRotation":-141.7994986361435,"angularVelocity":-0.15777222013669764,"angularAcceleration":1.107309781666934,"curveRadius":-23.293438205728627},{"acceleration":-2.993264088488058,"curvature":-0.04230353784490082,"pose":{"rotation":{"radians":3.106628519871261},"translation":{"x":3.4952280292009488,"y":1.8478631466902953}},"time":2.6854605301744345,"velocity":3.6192362510771767,"position":5.121658394701834,"holonomicRotation":-141.68458167507583,"angularVelocity":-0.15517883163828572,"angularAcceleration":1.0919477917706297,"curveRadius":-23.63868486995912},{"acceleration":-2.993233491198405,"curvature":-0.0416812666943161,"pose":{"rotation":{"radians":3.1062644266679262},"translation":{"x":3.4866157650528407,"y":1.8481675293546407}},"time":2.6878463038548617,"velocity":3.6120950733945025,"position":5.130276036059139,"holonomicRotation":-141.56966471400816,"angularVelocity":-0.1526101181858335,"angularAcceleration":1.0766794325572084,"curveRadius":-23.99159332977675},{"acceleration":-2.9932027890664403,"curvature":-0.041063743690137336,"pose":{"rotation":{"radians":3.105904773215967},"translation":{"x":3.47798158910705,"y":1.848475795675912}},"time":2.6902429378194923,"velocity":3.6049214619271988,"position":5.13891571327462,"holonomicRotation":-141.45474775294048,"angularVelocity":-0.15006607486455983,"angularAcceleration":1.0615068295027499,"curveRadius":-24.35238266500722},{"acceleration":-2.9931719793416667,"curvature":-0.040450980395830394,"pose":{"rotation":{"radians":3.105549540780131},"translation":{"x":3.4693253797730756,"y":1.8487879275812897}},"time":2.6926505311821107,"velocity":3.5977151209365603,"position":5.1475775483203785,"holonomicRotation":-141.33983079187283,"angularVelocity":-0.14754669179262886,"angularAcceleration":1.0464321388521254,"curveRadius":-24.72127968752713},{"acceleration":-2.9931410579019255,"curvature":-0.0398429858172198,"pose":{"rotation":{"radians":3.105198710440822},"translation":{"x":3.460647015460416,"y":1.849103906997955}},"time":2.6950691841454004,"velocity":3.590475751447322,"position":5.156261663136236,"holonomicRotation":-141.22491383080512,"angularVelocity":-0.14505195438694202,"angularAcceleration":1.0314573622392134,"curveRadius":-25.098520592495564},{"acceleration":-2.9931100201055316,"curvature":-0.03923977007483701,"pose":{"rotation":{"radians":3.104852263099254},"translation":{"x":3.4519463745785672,"y":1.8494237158530884}},"time":2.6974989980212905,"velocity":3.583203051188404,"position":5.164968179630145,"holonomicRotation":-141.10999686973747,"angularVelocity":-0.14258184341006117,"angularAcceleration":1.016584439405286,"curveRadius":-25.48434912061991},{"acceleration":-2.9930788620839777,"curvature":-0.03864134071282056,"pose":{"rotation":{"radians":3.1045101794826353},"translation":{"x":3.443223335537029,"y":1.8497473360738708}},"time":2.6999400752517895,"velocity":3.5758967145290828,"position":5.173697219678599,"holonomicRotation":-140.9950799086698,"angularVelocity":-0.14013633503470654,"angularAcceleration":1.001815241566402,"curveRadius":-25.879019246043303},{"acceleration":-2.9930475800572474,"curvature":-0.038047703715392185,"pose":{"rotation":{"radians":3.1041724401490702},"translation":{"x":3.4344777767452976,"y":1.8500747495874832}},"time":2.702392519430323,"velocity":3.568556432415298,"position":5.1824489051270435,"holonomicRotation":-140.88016294760212,"angularVelocity":-0.13771540103597396,"angularAcceleration":0.987151520072653,"curveRadius":-26.282795079574022},{"acceleration":-2.993016168844741,"curvature":-0.037458865662103616,"pose":{"rotation":{"radians":3.1038390254928334},"translation":{"x":3.4257095766128733,"y":1.850405938321106}},"time":2.704856435323582,"velocity":3.5611818923081,"position":5.191223357790288,"holonomicRotation":-140.76524598653444,"angularVelocity":-0.13531900871656727,"angularAcceleration":0.9725950167223006,"curveRadius":-26.695949872600654},{"acceleration":-2.992984625058485,"curvature":-0.036874831579751056,"pose":{"rotation":{"radians":3.103509915749067},"translation":{"x":3.4169186135492526,"y":1.85074088420192}},"time":2.707331928893911,"velocity":3.553772778112674,"position":5.200020699452916,"holonomicRotation":-140.65032902546676,"angularVelocity":-0.13294712121695118,"angularAcceleration":0.9581473076905639,"curveRadius":-27.11876792812598},{"acceleration":-2.9929529435920093,"curvature":-0.03629560435615324,"pose":{"rotation":{"radians":3.1031850909988066},"translation":{"x":3.4081047659639334,"y":1.8510795691571063}},"time":2.7098191073222355,"velocity":3.5463287701143815,"position":5.208841051869691,"holonomicRotation":-140.53541206439908,"angularVelocity":-0.13059969745690742,"angularAcceleration":0.9438099548109828,"curveRadius":-27.55154564137926},{"acceleration":-2.992921119736001,"curvature":-0.03572118692191313,"pose":{"rotation":{"radians":3.1028645311739558},"translation":{"x":3.3992679122664144,"y":1.8514219751138459}},"time":2.712318079031557,"velocity":3.5388495449079302,"position":5.217684536765962,"holonomicRotation":-140.4204951033314,"angularVelocity":-0.12827669223107152,"angularAcceleration":0.9295844435416036,"curveRadius":-27.994590498518708},{"acceleration":-2.9928891492016167,"curvature":-0.03515158115379085,"pose":{"rotation":{"radians":3.1025482160621496},"translation":{"x":3.3904079308661927,"y":1.8517680839993187}},"time":2.7148289537110313,"velocity":3.531334775324727,"position":5.226551275838071,"holonomicRotation":-140.30557814226373,"angularVelocity":-0.12597805632913017,"angularAcceleration":0.9154721741917872,"curveRadius":-28.44822244623716},{"acceleration":-2.992857026894832,"curvature":-0.034399634570425476,"pose":{"rotation":{"radians":3.1022361253111077},"translation":{"x":3.3815247001727666,"y":1.8521178777407061}},"time":2.717351842340641,"velocity":3.523784130361526,"position":5.23544139075376,"holonomicRotation":-140.19066118119605,"angularVelocity":-0.1237037368114622,"angularAcceleration":0.9014744015948581,"curveRadius":-29.070076251906865},{"acceleration":-2.244614760577895,"curvature":0.019087983663383823,"pose":{"rotation":{"radians":3.1017761857031},"translation":{"x":3.3636880045442963,"y":1.852828447499948}},"time":2.7224341119180058,"velocity":3.5123763930509373,"position":5.2532922344404165,"holonomicRotation":-139.96082725906072,"angularVelocity":-0.0904988609923565,"angularAcceleration":6.5334739359346345,"curveRadius":52.388980294355775},{"acceleration":-4.227185379658958,"curvature":0.1168230990586904,"pose":{"rotation":{"radians":3.102039944335287},"translation":{"x":3.353910410027153,"y":1.8532153796485258}},"time":2.7252294497132774,"velocity":3.500559981991557,"position":5.263077482062693,"holonomicRotation":-139.95095157104524,"angularVelocity":0.09435662217028037,"angularAcceleration":66.12992657822011,"curveRadius":8.55995096909399},{"acceleration":-3.0001076772994706,"curvature":0.11860310028159808,"pose":{"rotation":{"radians":3.103181677201984},"translation":{"x":3.3441565039029104,"y":1.8535902210718882}},"time":2.728024586859511,"velocity":3.492174269580036,"position":5.272838588084718,"holonomicRotation":-139.94107588302975,"angularVelocity":0.40847114362010695,"angularAcceleration":112.3789299115671,"curveRadius":8.431482799570253},{"acceleration":-3.00009263988381,"curvature":0.12039813277876947,"pose":{"rotation":{"radians":3.104337949153396},"translation":{"x":3.334426193211047,"y":1.8539528887200294}},"time":2.730819551389263,"velocity":3.4837891170655912,"position":5.282575655096052,"holonomicRotation":-139.93120019501424,"angularVelocity":0.41369825595413456,"angularAcceleration":1.8701891485155204,"curveRadius":8.305776650519086},{"acceleration":-3.0000773925155104,"curvature":0.12220821492792208,"pose":{"rotation":{"radians":3.105508832981077},"translation":{"x":3.324719384991043,"y":1.8543032995429418}},"time":2.733614371720254,"velocity":3.475404439774443,"position":5.292288786082749,"holonomicRotation":-139.92132450699876,"angularVelocity":0.41894779950516875,"angularAcceleration":1.878311637003517,"curveRadius":8.182755967672026},{"acceleration":-3.0000619329123923,"curvature":0.12403336225996688,"pose":{"rotation":{"radians":3.106694401177187},"translation":{"x":3.3150359862823784,"y":1.854641370490619}},"time":2.7364090766615714,"velocity":3.467020151866274,"position":5.301978084432817,"holonomicRotation":-139.91144881898327,"angularVelocity":0.4242194510706531,"angularAcceleration":1.886299869280354,"curveRadius":8.062346950686194},{"acceleration":-3.0000462583891907,"curvature":0.1258735875918187,"pose":{"rotation":{"radians":3.107894725917522},"translation":{"x":3.305375904124534,"y":1.8549670185130545}},"time":2.739203695419972,"velocity":3.4586361663165097,"position":5.3116436539416885,"holonomicRotation":-139.9015731309678,"angularVelocity":0.4295128760324553,"angularAcceleration":1.894149227292632,"curveRadius":7.944478417845589},{"acceleration":-3.000030365513389,"curvature":0.12772890029879655,"pose":{"rotation":{"radians":3.1091098790436598},"translation":{"x":3.295739045556989,"y":1.8552801605602414}},"time":2.7419982576062902,"velocity":3.45025239489924,"position":5.3212855988177274,"holonomicRotation":-139.89169744295228,"angularVelocity":0.4348277279664747,"angularAcceleration":1.9018549524645783,"curveRadius":7.8290817321741395},{"acceleration":-3.0000142512504517,"curvature":0.12959930682324292,"pose":{"rotation":{"radians":3.110339932044952},"translation":{"x":3.286125317619224,"y":1.8555807135821725}},"time":2.7447927932419534,"velocity":3.4418687481666232,"position":5.330904023687754,"holonomicRotation":-139.8818217549368,"angularVelocity":0.44016364851272577,"angularAcceleration":1.9094122394273652,"curveRadius":7.716090652891174},{"acceleration":-2.999997913122339,"curvature":0.13148480995899414,"pose":{"rotation":{"radians":3.1115849560398336},"translation":{"x":3.276534627350718,"y":1.855868594528842}},"time":2.74758733276561,"velocity":3.4334851354275155,"position":5.340499033602594,"holonomicRotation":-139.8719460669213,"angularVelocity":0.4455202670572671,"angularAcceleration":1.9168161692457657,"curveRadius":7.605441269693949},{"acceleration":-2.999981347396578,"curvature":0.13338540947286673,"pose":{"rotation":{"radians":3.1128450217575985},"translation":{"x":3.2669668817909523,"y":1.8561437203502424}},"time":2.7503819070398645,"velocity":3.4251014647308375,"position":5.350070734042642,"holonomicRotation":-139.86207037890583,"angularVelocity":0.45089720082710716,"angularAcceleration":1.9240618577848787,"curveRadius":7.4970718607976385},{"acceleration":-2.999964551474173,"curvature":0.13530110151447847,"pose":{"rotation":{"radians":3.1141201995186543},"translation":{"x":3.2574219879794057,"y":1.8564060079963673}},"time":2.753176547358131,"velocity":3.4167176428419173,"position":5.359619230923461,"holonomicRotation":-139.85219469089031,"angularVelocity":0.45629405427269176,"angularAcceleration":1.931144201387626,"curveRadius":7.390922829205428},{"acceleration":-2.99994752185548,"curvature":0.13723187851719518,"pose":{"rotation":{"radians":3.1154105592154417},"translation":{"x":3.2478998529555594,"y":1.85665537441721}},"time":2.755971285451599,"velocity":3.4083335752241832,"position":5.369144630601386,"holonomicRotation":-139.84231900287483,"angularVelocity":0.46171041923514594,"angularAcceleration":1.9380581583347074,"curveRadius":7.286936612725153},{"acceleration":-2.9999302554922096,"curvature":0.1391777296830948,"pose":{"rotation":{"radians":3.116716170292478},"translation":{"x":3.2384003837588917,"y":1.8568917365627637}},"time":2.758766153496319,"velocity":3.39994916601672,"position":5.378647039879158,"holonomicRotation":-139.83244331485935,"angularVelocity":0.46714587456213535,"angularAcceleration":1.944798552210095,"curveRadius":7.1850575683119855},{"acceleration":-2.9999127489687574,"curvature":0.14113863982327085,"pose":{"rotation":{"radians":3.1180371017260944},"translation":{"x":3.2289234874288844,"y":1.8571150113830215}},"time":2.7615611841204064,"velocity":3.3915643180137613,"position":5.388126566011569,"holonomicRotation":-139.82256762684386,"angularVelocity":0.47259998592946656,"angularAcceleration":1.951360146227966,"curveRadius":7.085231948190566},{"acceleration":-2.9998949994827577,"curvature":0.14311459065809648,"pose":{"rotation":{"radians":3.1193734220038634},"translation":{"x":3.2194690710050167,"y":1.8573251158279769}},"time":2.764356410411373,"velocity":3.3831789326410675,"position":5.397583316711132,"holonomicRotation":-139.81269193882835,"angularVelocity":0.4780723056618101,"angularAcceleration":1.957737643649205,"curveRadius":6.987407750681545},{"acceleration":-2.9998770031997473,"curvature":0.1451055590905128,"pose":{"rotation":{"radians":3.120725199103733},"translation":{"x":3.210037041526769,"y":1.8575219668476235}},"time":2.767151865923577,"velocity":3.3747929099365392,"position":5.4070174001537605,"holonomicRotation":-139.80281625081287,"angularVelocity":0.48356237256079665,"angularAcceleration":1.9639256911866916,"curveRadius":6.891534730080383},{"acceleration":-2.999858757272937,"curvature":0.14711151872399914,"pose":{"rotation":{"radians":3.1220925004727986},"translation":{"x":3.20062730603362,"y":1.8577054813919538}},"time":2.769947584685804,"velocity":3.3664061485248005,"position":5.4164289249844675,"holonomicRotation":-139.79294056279738,"angularVelocity":0.4890697117104464,"angularAcceleration":1.9699188716903786,"curveRadius":6.797564246999133},{"acceleration":-2.999840258025067,"curvature":0.14913243872302823,"pose":{"rotation":{"radians":3.123475393005236},"translation":{"x":3.1912397715650513,"y":1.8578755764109616}},"time":2.7727436012089766,"velocity":3.358018545596484,"position":5.425818000323075,"holonomicRotation":-139.7830648747819,"angularVelocity":0.4945938341122973,"angularAcceleration":1.97571164407237,"curveRadius":6.705449254117142},{"acceleration":-2.9998215019282153,"curvature":0.15116828405976518,"pose":{"rotation":{"radians":3.1248739430206927},"translation":{"x":3.181874345160542,"y":1.8580321688546404}},"time":2.7755399504939975,"velocity":3.3496299968843766,"position":5.435184735769948,"holonomicRotation":-139.77318918676642,"angularVelocity":0.5001342367880481,"angularAcceleration":1.981298511394431,"curveRadius":6.6151442163929355},{"acceleration":-2.9998024858638592,"curvature":0.15321901496841192,"pose":{"rotation":{"radians":3.1262882162418055},"translation":{"x":3.1725309338595724,"y":1.8581751756729825}},"time":2.778336668039726,"velocity":3.3412403966384407,"position":5.444529241411724,"holonomicRotation":-139.7633134987509,"angularVelocity":0.5056904024050841,"angularAcceleration":1.9866738511087016,"curveRadius":6.526605070566228},{"acceleration":-2.999783206469959,"curvature":0.15528458796676353,"pose":{"rotation":{"radians":3.1277182777709434},"translation":{"x":3.1632094447016224,"y":1.8583045138159822}},"time":2.7811337898510935,"velocity":3.33284963760225,"position":5.453851627827069,"holonomicRotation":-139.75343781073542,"angularVelocity":0.5112617989413697,"angularAcceleration":1.9918319301088983,"curveRadius":6.439789119407239},{"acceleration":-2.9997636593732113,"curvature":0.15736495463620473,"pose":{"rotation":{"radians":3.129164192067746},"translation":{"x":3.1539097847261726,"y":1.8584201002336322}},"time":2.7839313524473557,"velocity":3.324457610991161,"position":5.463152006092437,"holonomicRotation":-139.74356212271994,"angularVelocity":0.5168478799132195,"angularAcceleration":1.996767106949926,"curveRadius":6.354655026665839},{"acceleration":-2.999743842126392,"curvature":0.15946006164666446,"pose":{"rotation":{"radians":3.1306260229250724},"translation":{"x":3.1446318609727015,"y":1.858521851875926}},"time":2.786729392870494,"velocity":3.3160642064618306,"position":5.47243048778784,"holonomicRotation":-139.73368643470445,"angularVelocity":0.5224480837509636,"angularAcceleration":2.0014735281996434,"curveRadius":6.271162758081862},{"acceleration":-2.9997237501280174,"curvature":0.1615698513207383,"pose":{"rotation":{"radians":3.1321038334451683},"translation":{"x":3.135375580480691,"y":1.8586096856928571}},"time":2.7895279486937565,"velocity":3.3076693120927314,"position":5.481687185002623,"holonomicRotation":-139.72381074668894,"angularVelocity":0.5280618338258263,"angularAcceleration":2.0059453623185126,"curveRadius":6.189273505085196},{"acceleration":-2.9997033807572966,"curvature":0.16369426087813022,"pose":{"rotation":{"radians":3.1335976860157544},"translation":{"x":3.126140850289619,"y":1.8586835186344182}},"time":2.7923270580303523,"velocity":3.2992728143526358,"position":5.490922210341254,"holonomicRotation":-139.71393505867346,"angularVelocity":0.5336885383701706,"angularAcceleration":2.0101767625795666,"curveRadius":6.1089496640599785},{"acceleration":-2.999682729327752,"curvature":0.16583322288535962,"pose":{"rotation":{"radians":3.1351076422847344},"translation":{"x":3.1169275774389678,"y":1.8587432676506026}},"time":2.7951267595422933,"velocity":3.2908745980799936,"position":5.500135676929107,"holonomicRotation":-139.70405937065797,"angularVelocity":0.539327589937672,"angularAcceleration":2.014161703828205,"curveRadius":6.0301547699600535},{"acceleration":-2.9996617929160125,"curvature":0.16798666429883777,"pose":{"rotation":{"radians":3.136633763135602},"translation":{"x":3.1077356689682154,"y":1.8587888496914045}},"time":2.797927092449397,"velocity":3.282474546451109,"position":5.509327698418264,"holonomicRotation":-139.6941836826425,"angularVelocity":0.5449783656065527,"angularAcceleration":2.0178942491251317,"curveRadius":5.95285348497106},{"acceleration":-2.9996405670413053,"curvature":0.17015450744879948,"pose":{"rotation":{"radians":3.138176108662181},"translation":{"x":3.0985650319168427,"y":1.858820181706816}},"time":2.80072809653844,"velocity":3.274072540957168,"position":5.518498388993308,"holonomicRotation":-139.68430799462698,"angularVelocity":0.5506402267003399,"angularAcceleration":2.0213683785524994,"curveRadius":5.877011517317024},{"acceleration":-2.999619048617801,"curvature":0.17233666898129227,"pose":{"rotation":{"radians":3.1397347381422267},"translation":{"x":3.08941557332433,"y":1.8588371806468311}},"time":2.8035298121724783,"velocity":3.2656684613724956,"position":5.527647863377122,"holonomicRotation":-139.6744323066115,"angularVelocity":0.5563125183403819,"angularAcceleration":2.0245779304396088,"curveRadius":5.802595616540281},{"acceleration":-2.9995972334244825,"curvature":0.1745330604074426,"pose":{"rotation":{"radians":3.1413097100119627},"translation":{"x":3.0802872002301567,"y":1.858839763461443}},"time":2.8063322803003317,"velocity":3.2572621857294264,"position":5.53677623683669,"holonomicRotation":-139.664556618596,"angularVelocity":0.5619945697446331,"angularAcceleration":2.0275168690691414,"curveRadius":5.729573512694545},{"acceleration":-2.999575117481063,"curvature":0.1767435875879094,"pose":{"rotation":{"radians":-3.1402842253403755},"translation":{"x":3.0711798196738034,"y":1.8588278471006447}},"time":2.809135542466232,"velocity":3.248853590288816,"position":5.545883625188896,"holonomicRotation":-139.65468093058053,"angularVelocity":-2240.815722397884,"angularAcceleration":-799560.506410165,"curveRadius":5.657913894627811},{"acceleration":-2.9995526970849187,"curvature":0.1789681509580283,"pose":{"rotation":{"radians":-3.1386763968830924},"translation":{"x":3.0620933386947495,"y":1.8588013485144297}},"time":2.811939640819648,"velocity":3.2404425495099347,"position":5.554970144806317,"holonomicRotation":-139.644805242565,"angularVelocity":0.5733851864804461,"angularAcceleration":799326.1380627409,"curveRadius":5.587586364651667},{"acceleration":-2.9995299682520167,"curvature":0.18120664502066144,"pose":{"rotation":{"radians":-3.137052056045587},"translation":{"x":3.0530276643324754,"y":1.8587601846527912}},"time":2.8147446181252844,"velocity":3.232028936021412,"position":5.564035912623017,"holonomicRotation":-139.63492955454953,"angularVelocity":0.579092327856452,"angularAcceleration":2.0346479682877243,"curveRadius":5.518561418572584},{"acceleration":-2.99950692705932,"curvature":0.18345895836595363,"pose":{"rotation":{"radians":-3.135411148027676},"translation":{"x":3.043982703626461,"y":1.8587042724657223}},"time":2.817550517773256,"velocity":3.223612620590688,"position":5.573081046140329,"holonomicRotation":-139.62505386653405,"angularVelocity":0.5848063807618272,"angularAcceleration":2.0364423615455616,"curveRadius":5.450810409624458},{"acceleration":-2.9994835689630994,"curvature":0.18572497399376597,"pose":{"rotation":{"radians":-3.1337536190072726},"translation":{"x":3.0349583636161857,"y":1.8586335289032165}},"time":2.82035738378945,"velocity":3.215193472094833,"position":5.582105663432641,"holonomicRotation":-139.61517817851856,"angularVelocity":0.5905265911662048,"angularAcceleration":2.037934967816529,"curveRadius":5.384305505588957},{"acceleration":-2.999459890558974,"curvature":0.18800456881125197,"pose":{"rotation":{"radians":-3.132079416168492},"translation":{"x":3.0259545513411306,"y":1.8585478709152674}},"time":2.8231652608460718,"velocity":3.2067713574858754,"position":5.591109883153157,"holonomicRotation":-139.60530249050305,"angularVelocity":0.5962521880479571,"angularAcceleration":2.039119507832347,"curveRadius":5.319019672356763},{"acceleration":-2.999435887585541,"curvature":0.19029761344691878,"pose":{"rotation":{"radians":-3.1303884877302557},"translation":{"x":3.016971173840775,"y":1.8584472154518674}},"time":2.8259741942723835,"velocity":3.1983461417611574,"position":5.600093824539665,"holonomicRotation":-139.59542680248757,"angularVelocity":0.6019823832054153,"angularAcceleration":2.039989664326882,"curveRadius":5.254926648246894},{"acceleration":-2.999411555433724,"curvature":0.19260397216843936,"pose":{"rotation":{"radians":-3.128680782975696},"translation":{"x":3.008008138154599,"y":1.8583314794630106}},"time":2.8287842300656347,"velocity":3.1899176879316973,"position":5.6090576074202785,"holonomicRotation":-139.58555111447208,"angularVelocity":0.6077163709661856,"angularAcceleration":2.0405390474176177,"curveRadius":5.192000916395757},{"acceleration":-2.9993868902475285,"curvature":0.19492350310006104,"pose":{"rotation":{"radians":-3.1269562522809022},"translation":{"x":2.999065351322083,"y":1.8582005798986898}},"time":2.831595414902196,"velocity":3.1814858569868534,"position":5.618001352219173,"holonomicRotation":-139.5756754264566,"angularVelocity":0.6134533284205356,"angularAcceleration":2.0407613827940376,"curveRadius":5.130217670501566},{"acceleration":-2.9993618876736012,"curvature":0.19725605783486994,"pose":{"rotation":{"radians":-3.1252148471450316},"translation":{"x":2.990142720382706,"y":1.8580544337088982}},"time":2.8344077961488927,"velocity":3.1730505078619027,"position":5.626925179962306,"holonomicRotation":-139.56579973844111,"angularVelocity":0.6191924149387167,"angularAcceleration":2.0406502585385797,"curveRadius":5.069552798409545},{"acceleration":-2.999336543442812,"curvature":0.19960148145198198,"pose":{"rotation":{"radians":-3.123456520220229},"translation":{"x":2.9812401523759493,"y":1.8578929578436298}},"time":2.837221421874551,"velocity":3.1646114974033654,"position":5.635829212283114,"holonomicRotation":-139.5559240504256,"angularVelocity":0.6249327722475246,"angularAcceleration":2.0401993258947884,"curveRadius":5.009982855465777},{"acceleration":-2.999310853167905,"curvature":0.20195961253102834,"pose":{"rotation":{"radians":-3.121681225341604},"translation":{"x":2.9723575543412917,"y":1.8577160692528771}},"time":2.8400363408617526,"velocity":3.156168680334263,"position":5.644713571428198,"holonomicRotation":-139.54604836241012,"angularVelocity":0.6306735244234174,"angularAcceleration":2.039402271253102,"curveRadius":4.951485039348467},{"acceleration":-2.9992848125044467,"curvature":0.20433028218579327,"pose":{"rotation":{"radians":-3.1198889175584004},"translation":{"x":2.9634948333182143,"y":1.8575236848866334}},"time":2.8428526026188106,"velocity":3.1477219092182818,"position":5.653578380262983,"holonomicRotation":-139.53617267439463,"angularVelocity":0.6364137774878511,"angularAcceleration":2.038252676636966,"curveRadius":4.894037189704074},{"acceleration":-2.9992584173939716,"curvature":0.20671331546074764,"pose":{"rotation":{"radians":-3.1180795531646353},"translation":{"x":2.9546518963461956,"y":1.8573157216948926}},"time":2.8456702573919674,"velocity":3.1392710344225807,"position":5.662423762277357,"holonomicRotation":-139.52629698637915,"angularVelocity":0.642152619619158,"angularAcceleration":2.036744240628594,"curveRadius":4.837617730483782},{"acceleration":-2.9992316625947213,"curvature":0.2091085300689386,"pose":{"rotation":{"radians":-3.1162530897302463},"translation":{"x":2.9458286504647173,"y":1.8570920966276476}},"time":2.8484893561778186,"velocity":3.1308159040840735,"position":5.671249841591284,"holonomicRotation":-139.51642129836364,"angularVelocity":0.6478891210041432,"angularAcceleration":2.0348706522013966,"curveRadius":4.782205678889912},{"acceleration":-2.999204544153012,"curvature":0.21151573680368105,"pose":{"rotation":{"radians":-3.1144094861328346},"translation":{"x":2.9370250027132583,"y":1.8568527266348915}},"time":2.8513099507359727,"velocity":3.1223563640680445,"position":5.680056742960392,"holonomicRotation":-139.50654561034816,"angularVelocity":0.6536223336608068,"angularAcceleration":2.0326255824643042,"curveRadius":4.727780613922608},{"acceleration":-2.999177057401962,"curvature":0.2139347388814231,"pose":{"rotation":{"radians":-3.1125487025895153},"translation":{"x":2.9282408601312997,"y":1.8565975286666179}},"time":2.8541320936019483,"velocity":3.1138922579317,"position":5.688844591781531,"holonomicRotation":-139.49666992233267,"angularVelocity":0.6593512914435854,"angularAcceleration":2.030002751401508,"curveRadius":4.674322670682608},{"acceleration":-2.999149197431141,"curvature":0.2163653328288426,"pose":{"rotation":{"radians":-3.110670700688822},"translation":{"x":2.91947612975832,"y":1.8563264196728197}},"time":2.856955838100316,"velocity":3.10542342688567,"position":5.697613514098301,"holonomicRotation":-139.4867942343172,"angularVelocity":0.6650750100722879,"angularAcceleration":2.0269959381988176,"curveRadius":4.621812500762576},{"acceleration":-2.9991209604150764,"curvature":0.21880730734828543,"pose":{"rotation":{"radians":-3.1087754434232506},"translation":{"x":2.9107307186337996,"y":1.8560393166034905}},"time":2.8597812383580905,"velocity":3.096949709751016,"position":5.706363636606547,"holonomicRotation":-139.47691854630168,"angularVelocity":0.6707924869604425,"angularAcceleration":2.023598912197314,"curveRadius":4.570231278465737},{"acceleration":-2.9990923406199803,"curvature":0.22126044391535313,"pose":{"rotation":{"radians":-3.1068628952217803},"translation":{"x":2.9020045337972196,"y":1.8557361364086233}},"time":2.8626083493183776,"velocity":3.0884709429239363,"position":5.715095086659815,"holonomicRotation":-139.4670428582862,"angularVelocity":0.6765027012863105,"angularAcceleration":2.0198055209294554,"curveRadius":4.519560669337564},{"acceleration":-2.999063333881656,"curvature":0.22372451641741006,"pose":{"rotation":{"radians":-3.1049330219829088},"translation":{"x":2.8932974822880593,"y":1.855416796038212}},"time":2.8654372267542856,"velocity":3.0799869603298595,"position":5.723807992274783,"holonomicRotation":-139.4571671702707,"angularVelocity":0.6822046138778981,"angularAcceleration":2.0156096263525276,"curveRadius":4.469782820467774},{"acceleration":-2.9990339354816484,"curvature":0.226199291175516,"pose":{"rotation":{"radians":-3.102985791107421},"translation":{"x":2.884609471145798,"y":1.8550812124422489}},"time":2.8682679272831053,"velocity":3.0714975933827433,"position":5.73250248213664,"holonomicRotation":-139.44729148225522,"angularVelocity":0.6878971673841763,"angularAcceleration":2.0110052081884144,"curveRadius":4.420880343184033},{"acceleration":-2.999004140335792,"curvature":0.22868452668471945,"pose":{"rotation":{"radians":-3.101021171532286},"translation":{"x":2.875940407409917,"y":1.854729302570728}},"time":2.8711005083807626,"velocity":3.0630026709430322,"position":5.741178685604427,"holonomicRotation":-139.4374157942397,"angularVelocity":0.6935792859592607,"angularAcceleration":2.005986193928874,"curveRadius":4.3728363020322325},{"acceleration":-2.9989739435980423,"curvature":0.23117997354601547,"pose":{"rotation":{"radians":-3.0990391337635663},"translation":{"x":2.8672901981198953,"y":1.8543609833736423}},"time":2.873935028396557,"velocity":3.0545020192730576,"position":5.749836732716341,"holonomicRotation":-139.42754010622423,"angularVelocity":0.6992498757021942,"angularAcceleration":2.000546727959605,"curveRadius":4.325634200321223},{"acceleration":-2.9989433406072035,"curvature":0.23368537476856385,"pose":{"rotation":{"radians":-3.097039649910763},"translation":{"x":2.8586587503152137,"y":1.8539761718009853}},"time":2.876771546568187,"velocity":3.045995461991737,"position":5.758476754194983,"holonomicRotation":-139.41766441820874,"angularVelocity":0.704907824247895,"angularAcceleration":1.9946808739990132,"curveRadius":4.279257959512336},{"acceleration":-2.998912326076853,"curvature":0.23620046523540345,"pose":{"rotation":{"radians":-3.095022693720293},"translation":{"x":2.8500459710353505,"y":1.8535747848027502}},"time":2.879610123037073,"velocity":3.0374828200306827,"position":5.767098881452568,"holonomicRotation":-139.40778873019326,"angularVelocity":0.7105520011802441,"angularAcceleration":1.9883829074944706,"curveRadius":4.2336919150577215},{"acceleration":-2.998880894775151,"curvature":0.23872497164030232,"pose":{"rotation":{"radians":-3.0929882406098415},"translation":{"x":2.841451767319788,"y":1.85315673932893}},"time":2.8824508188639824,"velocity":3.0289639115874967,"position":5.775703246596073,"holonomicRotation":-139.39791304217778,"angularVelocity":0.7161812578381256,"angularAcceleration":1.9816471036978358,"curveRadius":4.188920803420369},{"acceleration":-2.9988490425004954,"curvature":0.24125861288128872,"pose":{"rotation":{"radians":-3.090936267702597},"translation":{"x":2.832876046208005,"y":1.852721952329518}},"time":2.885293696044971,"velocity":3.0204385520753427,"position":5.784289982432346,"holonomicRotation":-139.38803735416226,"angularVelocity":0.7217944274788676,"angularAcceleration":1.9744678659632355,"curveRadius":4.1449297418121605},{"acceleration":-2.9988167630675417,"curvature":0.24380109944541895,"pose":{"rotation":{"radians":-3.088866753861804},"translation":{"x":2.8243187147394817,"y":1.8522703407545078}},"time":2.8881388175276386,"velocity":3.0119065540801553,"position":5.792859222473147,"holonomicRotation":-139.37816166614678,"angularVelocity":0.7273903252991056,"angularAcceleration":1.966839677788079,"curveRadius":4.101704226415416},{"acceleration":-2.998784052264147,"curvature":0.24635213371248368,"pose":{"rotation":{"radians":-3.086779679724931},"translation":{"x":2.815779679953698,"y":1.8518018215538927}},"time":2.890986247227718,"velocity":3.0033677273056134,"position":5.801411100940138,"holonomicRotation":-139.3682859781313,"angularVelocity":0.7329677487084996,"angularAcceleration":1.958757193983785,"curveRadius":4.059230114755551},{"acceleration":-2.998750903996166,"curvature":0.24891140953100063,"pose":{"rotation":{"radians":-3.084675027738626},"translation":{"x":2.8072588488901338,"y":1.8513163116776654}},"time":2.8938360500459965,"velocity":2.9948218785280902,"position":5.809945752769809,"holonomicRotation":-139.3584102901158,"angularVelocity":0.7385254772035402,"angularAcceleration":1.9502151023901877,"curveRadius":4.017493621060609},{"acceleration":-2.9987173134265874,"curvature":0.25147861270075994,"pose":{"rotation":{"radians":-3.0825527821936287},"translation":{"x":2.7987561285882694,"y":1.85081372807582}},"time":2.896688291885586,"velocity":2.9862688115416334,"position":5.8184633136183495,"holonomicRotation":-139.3485346021003,"angularVelocity":0.7440622725394798,"angularAcceleration":1.9412082310440832,"curveRadius":3.976481296999687},{"acceleration":-2.9986832755350217,"curvature":0.25405342046200946,"pose":{"rotation":{"radians":-3.080412929259109},"translation":{"x":2.7902714260875845,"y":1.850293987698349}},"time":2.8995430396695485,"velocity":2.9777083271059945,"position":5.826963919866442,"holonomicRotation":-139.33865891408482,"angularVelocity":0.7495768790997768,"angularAcceleration":1.9317316196118157,"curveRadius":3.936180029308197},{"acceleration":-2.998648784183859,"curvature":0.25663550144181796,"pose":{"rotation":{"radians":-3.078255457018004},"translation":{"x":2.7818046484275594,"y":1.849757007495246}},"time":2.9024003613588825,"velocity":2.969140222896251,"position":5.835447708623997,"holonomicRotation":-139.32878322606933,"angularVelocity":0.7550680237226671,"angularAcceleration":1.921780331346017,"curveRadius":3.896577029997195},{"acceleration":-2.9986138345639652,"curvature":0.25922451613283615,"pose":{"rotation":{"radians":-3.0760803555018645},"translation":{"x":2.773355702647674,"y":1.8492027044165047}},"time":2.905260325970889,"velocity":2.9605642934443246,"position":5.843914817734818,"holonomicRotation":-139.31890753805385,"angularVelocity":0.7605344160580981,"angularAcceleration":1.911349641349434,"curveRadius":3.857659819056479},{"acceleration":-2.9985784210290722,"curvature":0.2618201158631898,"pose":{"rotation":{"radians":-3.0738876167255462},"translation":{"x":2.764924495787408,"y":1.8486309954121176}},"time":2.9081230035979186,"velocity":2.951980330085551,"position":5.8523653857811855,"holonomicRotation":-139.30903185003834,"angularVelocity":0.7659747488206096,"angularAcceleration":1.900435002231334,"curveRadius":3.819416230502835},{"acceleration":-2.9985425377357853,"curvature":0.2644219441610929,"pose":{"rotation":{"radians":-3.071677234722636},"translation":{"x":2.7565109348862418,"y":1.8480417974320784}},"time":2.910988465426515,"velocity":2.9433881209022474,"position":5.860799552088374,"holonomicRotation":-139.29915616202285,"angularVelocity":0.7713876977355965,"angularAcceleration":1.8890319392734016,"curveRadius":3.781834382817991},{"acceleration":-2.9985061795071726,"curvature":0.2670296353783167,"pose":{"rotation":{"radians":-3.069449205579984},"translation":{"x":2.7481149269836553,"y":1.8474350274263802}},"time":2.913856783756964,"velocity":2.934787450663601,"position":5.869217456729086,"holonomicRotation":-139.28928047400737,"angularVelocity":0.7767719220702077,"angularAcceleration":1.8771362569675596,"curveRadius":3.7449026906067586},{"acceleration":-2.9984693403902805,"curvature":0.2696428152625605,"pose":{"rotation":{"radians":-3.0672035274729414},"translation":{"x":2.7397363791191283,"y":1.8468106023450168}},"time":2.916728032023265,"velocity":2.9261781007684498,"position":5.877619240527804,"holonomicRotation":-139.2794047859919,"angularVelocity":0.7821260646108007,"angularAcceleration":1.86474384797495,"curveRadius":3.7086098475357687},{"acceleration":-2.9984320148025088,"curvature":0.27226110117044705,"pose":{"rotation":{"radians":-3.0649402006998034},"translation":{"x":2.7313751983321413,"y":1.8461684391379807}},"time":2.9196022848135232,"velocity":2.9175598491835038,"position":5.886005045065065,"holonomicRotation":-139.26952909797637,"angularVelocity":0.7874487521797241,"angularAcceleration":1.8518508834586613,"curveRadius":3.672944815476807},{"acceleration":-2.99839419685278,"curvature":0.2748841014997895,"pose":{"rotation":{"radians":-3.062659227717181},"translation":{"x":2.7230312916621733,"y":1.8455084547552656}},"time":2.922479617890794,"velocity":2.908932470382202,"position":5.894375012681643,"holonomicRotation":-139.2596534099609,"angularVelocity":0.7927385955559155,"angularAcceleration":1.838453607605541,"curveRadius":3.6378968246760017},{"acceleration":-2.998355880785827,"curvature":0.27751141608269614,"pose":{"rotation":{"radians":-3.0603606131740526},"translation":{"x":2.7147045661487055,"y":1.8448305661468647}},"time":2.9253601082143743,"velocity":2.900295735280949,"position":5.902729286482641,"holonomicRotation":-139.2497777219454,"angularVelocity":0.7979941901945219,"angularAcceleration":1.8245486178457837,"curveRadius":3.6034553609211093},{"acceleration":-2.998317060686575,"curvature":0.28014263614276697,"pose":{"rotation":{"radians":-3.058044363946714},"translation":{"x":2.7063949288312172,"y":1.8441346902627713}},"time":2.9282438339615657,"velocity":2.8916494111748037,"position":5.911068010341497,"holonomicRotation":-139.23990203392992,"angularVelocity":0.8032141161809995,"angularAcceleration":1.8101326007029193,"curveRadius":3.5696101591989646},{"acceleration":-2.9982777305756674,"curvature":0.28277734416987266,"pose":{"rotation":{"radians":-3.055710489172946},"translation":{"x":2.698102286749189,"y":1.8434207440529786}},"time":2.931130874549919,"velocity":2.8829932616714755,"position":5.919391328903892,"holonomicRotation":-139.23002634591444,"angularVelocity":0.8083969387832086,"angularAcceleration":1.7952025417020812,"curveRadius":3.5363511986281},{"acceleration":-2.9982378843143294,"curvature":0.28541511396978164,"pose":{"rotation":{"radians":-3.053359000286398},"translation":{"x":2.6898265469420997,"y":1.8426886444674802}},"time":2.9340213106599733,"velocity":2.874327046624121,"position":5.927699387591559,"holonomicRotation":-139.22015065789893,"angularVelocity":0.8135412086669819,"angularAcceleration":1.7797556105389647,"curveRadius":3.5036686953651484},{"acceleration":-2.9981975160832692,"curvature":0.28805551063011364,"pose":{"rotation":{"radians":-3.050989911050337},"translation":{"x":2.6815676164494304,"y":1.8419383084562688}},"time":2.9369152242585064,"velocity":2.8656505220612396,"position":5.935992332605996,"holonomicRotation":-139.21027496988344,"angularVelocity":0.8186454624153037,"angularAcceleration":1.763789268245303,"curveRadius":3.471553096875415},{"acceleration":-2.9981566195582654,"curvature":0.29069809057380736,"pose":{"rotation":{"radians":-3.0486032375917436},"translation":{"x":2.6733254023106605,"y":1.841169652969338}},"time":2.9398126986223128,"velocity":2.856963440117393,"position":5.944270310932068,"holonomicRotation":-139.20039928186796,"angularVelocity":0.8237082227219382,"angularAcceleration":1.7473011564401384,"curveRadius":3.439995075392843},{"acceleration":-2.998115188059281,"curvature":0.2933424018661688,"pose":{"rotation":{"radians":-3.046198998434622},"translation":{"x":2.66509981156527,"y":1.8403825949566812}},"time":2.9427138183625208,"velocity":2.848265548961897,"position":5.952533470341516,"holonomicRotation":-139.19052359385248,"angularVelocity":0.8287279989860488,"angularAcceleration":1.7302892378205041,"curveRadius":3.408985518759844},{"acceleration":-2.9980732163019175,"curvature":0.29598798368008794,"pose":{"rotation":{"radians":-3.043777214533192},"translation":{"x":2.6568907512527398,"y":1.8395770513682914}},"time":2.945618669449472,"velocity":2.839556592720763,"position":5.96078195939634,"holonomicRotation":-139.18064790583696,"angularVelocity":0.8337032876861957,"angularAcceleration":1.712751721593026,"curveRadius":3.3785155314981563},{"acceleration":-2.9980306967529144,"curvature":0.298634366944432,"pose":{"rotation":{"radians":-3.04133790930508},"translation":{"x":2.648698128412549,"y":1.8387529391541622}},"time":2.948527339238173,"velocity":2.8308363114075195,"position":5.969015927452089,"holonomicRotation":-139.17077221782148,"angularVelocity":0.8386325727271,"angularAcceleration":1.6946870559361602,"curveRadius":3.3485764221707064},{"acceleration":-2.9979876239242276,"curvature":0.3012810739833645,"pose":{"rotation":{"radians":-3.0388811086636034},"translation":{"x":2.6405218500841783,"y":1.8379101752642866}},"time":2.9514399164943446,"velocity":2.822104440839794,"position":5.97723552466102,"holonomicRotation":-139.160896529806,"angularVelocity":0.8435143261078795,"angularAcceleration":1.676094040230296,"curveRadius":3.319159702860113},{"acceleration":-2.997943990433307,"curvature":0.3039276186639947,"pose":{"rotation":{"radians":-3.036406841050212},"translation":{"x":2.6323618233071064,"y":1.8370486766486578}},"time":2.95435649142108,"velocity":2.813360712565539,"position":5.985440901975151,"holonomicRotation":-139.1510208417905,"angularVelocity":0.8483470082357066,"angularAcceleration":1.6569717045590877,"curveRadius":3.2902570829061237},{"acceleration":-2.9978997901867697,"curvature":0.30657350662669797,"pose":{"rotation":{"radians":-3.033915137466254},"translation":{"x":2.6242179551208147,"y":1.8361683602572694}},"time":2.9572771556861372,"velocity":2.804604853778118,"position":5.993632211149187,"holonomicRotation":-139.141145153775,"angularVelocity":0.8531290685372269,"angularAcceleration":1.6373194135090379,"curveRadius":3.2618604621229035},{"acceleration":-2.9978550164599453,"curvature":0.30921823534956633,"pose":{"rotation":{"radians":-3.031406031504276},"translation":{"x":2.616090152564783,"y":1.8352691430401142}},"time":2.960202002449884,"velocity":2.795836587235043,"position":6.001809604743326,"holonomicRotation":-139.13126946575952,"angularVelocity":0.8578589460062804,"angularAcceleration":1.6171368454853285,"curveRadius":3.233961926176559},{"acceleration":-2.997809662452755,"curvature":0.3118612937235132,"pose":{"rotation":{"radians":-3.028879559379241},"translation":{"x":2.6079783226784903,"y":1.8343509419471862}},"time":2.9631311263939146,"velocity":2.7870556311731063,"position":6.009973236125941,"holonomicRotation":-139.12139377774403,"angularVelocity":0.8625350696353945,"angularAcceleration":1.596423954214651,"curveRadius":3.2065537472135603},{"acceleration":-2.9977637209767414,"curvature":0.3145021628656415,"pose":{"rotation":{"radians":-3.0263357599585756},"translation":{"x":2.5998823725014173,"y":1.833413673928478}},"time":2.9660646237503605,"velocity":2.7782616992223717,"position":6.018123259476124,"holonomicRotation":-139.11151808972855,"angularVelocity":0.867155859225788,"angularAcceleration":1.575181099188667,"curveRadius":3.17962837167263},{"acceleration":-2.9977171854172,"curvature":0.31714031594269,"pose":{"rotation":{"radians":-3.023774674792495},"translation":{"x":2.591802209073044,"y":1.8324572559339831}},"time":2.969002592331922,"velocity":2.7694545003152093,"position":6.026259829786114,"holonomicRotation":-139.10164240171304,"angularVelocity":0.871719725715845,"angularAcceleration":1.5534088821438587,"curveRadius":3.153178418920125},{"acceleration":-2.9976700485055416,"curvature":0.3197752181648555,"pose":{"rotation":{"radians":-3.021196348143344},"translation":{"x":2.5837377394328502,"y":1.8314816049136953}},"time":2.9719451315626384,"velocity":2.760633738596738,"position":6.034383102863575,"holonomicRotation":-139.09176671369755,"angularVelocity":0.8762250719502539,"angularAcceleration":1.5311082983630528,"curveRadius":3.127196678150539},{"acceleration":-2.997622303063352,"curvature":0.32240632694584276,"pose":{"rotation":{"radians":-3.0186008270139566},"translation":{"x":2.5756888706203163,"y":1.8304866378176068}},"time":2.974892342509426,"velocity":2.7517991133308155,"position":6.042493235333743,"holonomicRotation":-139.08189102568207,"angularVelocity":0.8806702934572035,"angularAcceleration":1.508280739726177,"curveRadius":3.10167610379426},{"acceleration":-2.9975739421564414,"curvature":0.32503309206426423,"pose":{"rotation":{"radians":-3.0159881611766832},"translation":{"x":2.567655509674922,"y":1.8294722715957117}},"time":2.977844327914407,"velocity":2.742950318803218,"position":6.050590384641438,"holonomicRotation":-139.07201533766658,"angularVelocity":0.885053778675477,"angularAcceleration":1.4849278085443476,"curveRadius":3.076609811170501},{"acceleration":-2.9975249582550005,"curvature":0.3276549559070413,"pose":{"rotation":{"radians":-3.0133584032001095},"translation":{"x":2.5596375636361475,"y":1.8284384231980029}},"time":2.9808011922280584,"velocity":2.734087044224874,"position":6.058674709052924,"holonomicRotation":-139.0621396496511,"angularVelocity":0.8893739102036018,"angularAcceleration":1.4610516648259049,"curveRadius":3.051991071618978},{"acceleration":-2.9974753434467005,"curvature":0.33027135323226375,"pose":{"rotation":{"radians":-3.0107116084765098},"translation":{"x":2.5516349395434728,"y":1.827385009574474}},"time":2.983763041643205,"velocity":2.72520897363197,"position":6.066746367657628,"holonomicRotation":-139.0522639616356,"angularVelocity":0.8936290650241203,"angularAcceleration":1.4366546789171697,"curveRadius":3.0278133123363826},{"acceleration":-2.9974250908621207,"curvature":0.332881712059454,"pose":{"rotation":{"radians":-3.0080478352476865},"translation":{"x":2.5436475444363773,"y":1.826311947675118}},"time":2.9867299841298913,"velocity":2.7163157857792317,"position":6.074805520369713,"holonomicRotation":-139.0423882736201,"angularVelocity":0.8978176155340291,"angularAcceleration":1.411739704663725,"curveRadius":3.004070105904154},{"acceleration":-2.9973741924121593,"curvature":0.335485452876682,"pose":{"rotation":{"radians":-3.00536714463052},"translation":{"x":2.535675285354342,"y":1.825219154449928}},"time":2.9897021294711563,"velocity":2.707407154037226,"position":6.082852327929492,"holonomicRotation":-139.03251258560462,"angularVelocity":0.9019379301368249,"angularAcceleration":1.3863099309410447,"curveRadius":2.9807551755979738},{"acceleration":-2.9973226403221807,"curvature":0.3380819897719845,"pose":{"rotation":{"radians":-3.0026696006416906},"translation":{"x":2.5277180693368457,"y":1.824106546848898}},"time":2.9926795892997493,"velocity":2.6984827462823344,"position":6.090886951904699,"holonomicRotation":-139.02263689758914,"angularVelocity":0.9059883740242515,"angularAcceleration":1.3603689455453198,"curveRadius":2.957862383247444},{"acceleration":-2.997270426530992,"curvature":0.3406707298883171,"pose":{"rotation":{"radians":-2.999955270221234},"translation":{"x":2.5197758034233693,"y":1.8229740418220204}},"time":2.9956624771358134,"velocity":2.6895422247856406,"position":6.098909554691593,"holonomicRotation":-139.01276120957363,"angularVelocity":0.9099673100809679,"angularAcceleration":1.3339207759037481,"curveRadius":2.9353857325160644},{"acceleration":-2.99721754328165,"curvature":0.34325107391901305,"pose":{"rotation":{"radians":-2.9972242232558752},"translation":{"x":2.5118483946533927,"y":1.821821556319289}},"time":2.9986509084255775,"velocity":2.680585246097068,"position":6.1069202995159095,"holonomicRotation":-139.00288552155814,"angularVelocity":0.9138730994797417,"angularAcceleration":1.3069697844992563,"curveRadius":2.9133193629452148},{"acceleration":-2.9971639822873937,"curvature":0.34582241628548444,"pose":{"rotation":{"radians":-2.994476532600823},"translation":{"x":2.503935750066396,"y":1.820649007290697}},"time":3.001645000581088,"velocity":2.6716114609289225,"position":6.114919350433649,"holonomicRotation":-138.99300983354266,"angularVelocity":0.9177041027261259,"angularAcceleration":1.279520818800916,"curveRadius":2.89165754707606},{"acceleration":-2.997109734989273,"curvature":0.3483841453959026,"pose":{"rotation":{"radians":-2.991712274101169},"translation":{"x":2.4960377767018582,"y":1.8194563116862374}},"time":3.0046448730210193,"velocity":2.662620514035478,"position":6.1229068723317,"holonomicRotation":-138.98313414552717,"angularVelocity":0.9214586803288684,"angularAcceleration":1.251579084752126,"curveRadius":2.8703946870590316},{"acceleration":-2.997054792802446,"curvature":0.3509356438268833,"pose":{"rotation":{"radians":-2.9889315266119816},"translation":{"x":2.4881543815992604,"y":1.818243386455904}},"time":3.0076506472126026,"velocity":2.653612044088512,"position":6.130883030928295,"holonomicRotation":-138.97325845751166,"angularVelocity":0.925135193779396,"angularAcceleration":1.2231502488851829,"curveRadius":2.849525312091981},{"acceleration":-2.9969991477125046,"curvature":0.35347628835231887,"pose":{"rotation":{"radians":-2.98613437201764},"translation":{"x":2.4802854717980822,"y":1.8170101485496897}},"time":3.0106624467147163,"velocity":2.644585683547596,"position":6.138847992773301,"holonomicRotation":-138.96338276949618,"angularVelocity":0.9287320063564684,"angularAcceleration":1.194240378401035,"curveRadius":2.8290440772176333},{"acceleration":-2.9969427900355745,"curvature":0.35600545067656814,"pose":{"rotation":{"radians":-2.983320895250063},"translation":{"x":2.472430954337804,"y":1.8157565149175876}},"time":3.0136803972221755,"velocity":2.635541058533582,"position":6.146801925248332,"holonomicRotation":-138.9535070814807,"angularVelocity":0.9322474840535983,"angularAcceleration":1.1648559803883352,"curveRadius":2.808945756587594},{"acceleration":-2.9968857115989564,"curvature":0.35852249715464674,"pose":{"rotation":{"radians":-2.980491184306004},"translation":{"x":2.464590736257905,"y":1.8144824025095916}},"time":3.016704626611272,"velocity":2.626477788688801,"position":6.154744996566694,"holonomicRotation":-138.9436313934652,"angularVelocity":0.935679996451689,"angularAcceleration":1.1350039816642932,"curveRadius":2.789225245099906},{"acceleration":-2.996827902872877,"curvature":0.36102678937266836,"pose":{"rotation":{"radians":-2.977645330262826},"translation":{"x":2.456764724597866,"y":1.8131877282756945}},"time":3.0197352649866054,"velocity":2.6173954870420846,"position":6.162677375773148,"holonomicRotation":-138.9337557054497,"angularVelocity":0.9390279177947581,"angularAcceleration":1.1046917937548095,"curveRadius":2.7698775532354034},{"acceleration":-2.9967693546277148,"curvature":0.3635176842627777,"pose":{"rotation":{"radians":-2.974783427293872},"translation":{"x":2.4489528263971665,"y":1.8118724091658895}},"time":3.022772444729259,"velocity":2.608293759864804,"position":6.170599232743499,"holonomicRotation":-138.92388001743421,"angularVelocity":0.9422896276970391,"angularAcceleration":1.0739271885934345,"curveRadius":2.750897805778069},{"acceleration":-2.9967100570154246,"curvature":0.36599453445289065,"pose":{"rotation":{"radians":-2.9719055726821875},"translation":{"x":2.441154948695287,"y":1.8105363621301702}},"time":3.0258163005463694,"velocity":2.5991722065255645,"position":6.178510738184004,"holonomicRotation":-138.91400432941873,"angularVelocity":0.9454635122685675,"angularAcceleration":1.0427184341935982,"curveRadius":2.732281238830128},{"acceleration":-2.9966500010815564,"curvature":0.36845668869347137,"pose":{"rotation":{"radians":-2.969011866833024},"translation":{"x":2.4333709985317067,"y":1.8091795041185297}},"time":3.0288669695221455,"velocity":2.5900304193360055,"position":6.186412063630589,"holonomicRotation":-138.90412864140325,"angularVelocity":0.9485479650990983,"angularAcceleration":1.0110742447059915,"curveRadius":2.714023196446641},{"acceleration":-2.9965891762401338,"curvature":0.3709034918259835,"pose":{"rotation":{"radians":-2.966102413285454},"translation":{"x":2.425600882945906,"y":1.807801752080961}},"time":3.0319245911703905,"velocity":2.580867983399837,"position":6.194303381447894,"holonomicRotation":-138.89425295338773,"angularVelocity":0.9515413881374045,"angularAcceleration":0.9790037429988663,"curveRadius":2.696119130820071},{"acceleration":-2.996527572572799,"curvature":0.37333428536701985,"pose":{"rotation":{"radians":-2.963177318722574},"translation":{"x":2.4178445089773652,"y":1.8064030229674581}},"time":3.0349893074885865,"velocity":2.571684476450249,"position":6.202184864828123,"holonomicRotation":-138.88437726537225,"angularVelocity":0.9544421927448754,"angularAcceleration":0.9465165145132768,"curveRadius":2.6785645979900123},{"acceleration":-2.9964651798325503,"curvature":0.3757484077860222,"pose":{"rotation":{"radians":-2.9602366929801835},"translation":{"x":2.410101783665564,"y":1.8049832337280136}},"time":3.038061263013607,"velocity":2.5624794686855314,"position":6.210056687789702,"holonomicRotation":-138.87450157735677,"angularVelocity":0.957248800785003,"angularAcceleration":0.9136226150634267,"curveRadius":2.661355256013409},{"acceleration":-2.9964019874141017,"curvature":0.37814519463392215,"pose":{"rotation":{"radians":-2.9572806490547747},"translation":{"x":2.402372614049982,"y":1.803542301312621}},"time":3.0411406048791148,"velocity":2.553252522599796,"position":6.217919025175758,"holonomicRotation":-138.86462588934128,"angularVelocity":0.9599596454423571,"angularAcceleration":0.8803324787411971,"curveRadius":2.644486864279971},{"acceleration":-2.996337984436362,"curvature":0.3805239792042641,"pose":{"rotation":{"radians":-2.954309303109437},"translation":{"x":2.3946569071701003,"y":1.8020801426712738}},"time":3.044227482874721,"velocity":2.5440031928082405,"position":6.225772052652389,"holonomicRotation":-138.8547502013258,"angularVelocity":0.9625731724956987,"angularAcceleration":0.8466570616207395,"curveRadius":2.6279552791683676},{"acceleration":-2.9962731600005883,"curvature":0.38288409243808535,"pose":{"rotation":{"radians":-2.9513227744789408},"translation":{"x":2.3869545700653982,"y":1.800596674753965}},"time":3.0473220495069686,"velocity":2.5347310258662032,"position":6.233615946706758,"holonomicRotation":-138.8448745133103,"angularVelocity":0.9650878411776037,"angularAcceleration":0.812607702707135,"curveRadius":2.611756455151518},{"acceleration":-2.9962075024238137,"curvature":0.38522486388766813,"pose":{"rotation":{"radians":-2.948321185673211},"translation":{"x":2.3792655097753554,"y":1.7990918145106878}},"time":3.050424460062221,"velocity":2.525435560084958,"position":6.2414508846449746,"holonomicRotation":-138.8349988252948,"angularVelocity":0.9675021252903705,"angularAcceleration":0.7781962025237311,"curveRadius":2.5958864386583334},{"acceleration":-2.9961410003890876,"curvature":0.3875456214740296,"pose":{"rotation":{"radians":-2.945304662379386},"translation":{"x":2.3715896333394526,"y":1.7975654788914357}},"time":3.0535348726715283,"velocity":2.5161163253380843,"position":6.249277044589791,"holonomicRotation":-138.82512313727932,"angularVelocity":0.9698145142539109,"angularAcceleration":0.7434347959562653,"curveRadius":2.5803413703824094},{"acceleration":-2.996073641801353,"curvature":0.3898456922999372,"pose":{"rotation":{"radians":-2.9422733334623863},"translation":{"x":2.3639268477971696,"y":1.796017584846202}},"time":3.0566534483775607,"velocity":2.5067728428652787,"position":6.257094605478092,"holonomicRotation":-138.81524744926384,"angularVelocity":0.9720235141754849,"angularAcceleration":0.7083361540016965,"curveRadius":2.5651174804584627},{"acceleration":-2.9960054147241983,"curvature":0.3921244025265093,"pose":{"rotation":{"radians":-2.939227330964035},"translation":{"x":2.3562770601879857,"y":1.79444804932498}},"time":3.0597803512036847,"velocity":2.4974046250668946,"position":6.264903747058189,"holonomicRotation":-138.80537176124832,"angularVelocity":0.9741276489000653,"angularAcceleration":0.6729133719798249,"curveRadius":2.550211090044047},{"acceleration":-2.9959363063454614,"curvature":0.3943810784460195,"pose":{"rotation":{"radians":-2.936166790100781},"translation":{"x":2.3486401775513817,"y":1.7928567892777625}},"time":3.0629157482252816,"velocity":2.4880111752950853,"position":6.272704649886909,"holonomicRotation":-138.79549607323284,"angularVelocity":0.9761254610414697,"angularAcceleration":0.6371799576395957,"curveRadius":2.535618605081922},{"acceleration":-2.9958663036913085,"curvature":0.3966150462487813,"pose":{"rotation":{"radians":-2.933091849259718},"translation":{"x":2.3410161069268374,"y":1.7912437216545432}},"time":3.066059809643397,"velocity":2.478591987635818,"position":6.280497495326484,"holonomicRotation":-138.78562038521736,"angularVelocity":0.9780155131021278,"angularAcceleration":0.6011498534246366,"curveRadius":2.521336518768223},{"acceleration":-2.995795393998869,"curvature":0.3988256327974498,"pose":{"rotation":{"radians":-2.9300026499930927},"translation":{"x":2.3334047553538326,"y":1.7896087634053153}},"time":3.0692127088608263,"velocity":2.4691465466825,"position":6.288282465541238,"holonomicRotation":-138.77574469720187,"angularVelocity":0.9797963885265439,"angularAcceleration":0.5648374088747837,"curveRadius":2.507361407504784},{"acceleration":-2.9957235633523447,"curvature":0.4010121658063524,"pose":{"rotation":{"radians":-2.9268993370112613},"translation":{"x":2.3258060298718477,"y":1.7879518314800722}},"time":3.0723746225607345,"velocity":2.4596743273063986,"position":6.296059743494061,"holonomicRotation":-138.76586900918636,"angularVelocity":0.9814666927568481,"angularAcceleration":0.5282573747514494,"curveRadius":2.4936899308009948},{"acceleration":-2.9956507977799416,"curvature":0.4031739743919801,"pose":{"rotation":{"radians":-2.9237820581740164},"translation":{"x":2.3182198375203624,"y":1.7862728428288068}},"time":3.075545730787925,"velocity":2.4501747944157692,"position":6.303829512942687,"holonomicRotation":-138.75599332117088,"angularVelocity":0.9830250543062784,"angularAcceleration":0.4914249018902366,"curveRadius":2.4803188288829485},{"acceleration":-2.9955770829622277,"curvature":0.4053103895115403,"pose":{"rotation":{"radians":-2.920650964480445},"translation":{"x":2.3106460853388566,"y":1.7845717144015125}},"time":3.078726217032872,"velocity":2.4406474027077283,"position":6.311591958435765,"holonomicRotation":-138.7461176331554,"angularVelocity":0.9844701257694467,"angularAcceleration":0.45435551418088604,"curveRadius":2.467244921121192},{"acceleration":-2.9955024042417047,"curvature":0.4074207442181881,"pose":{"rotation":{"radians":-2.9175062100568963},"translation":{"x":2.3030846803668106,"y":1.782848363148183}},"time":3.0819162683186394,"velocity":2.4310915964115583,"position":6.319347265308716,"holonomicRotation":-138.7362419451399,"angularVelocity":0.9858005849559431,"angularAcceleration":0.41706514012249085,"curveRadius":2.4544651056463267},{"acceleration":-2.995426746145267,"curvature":0.4095043743197916,"pose":{"rotation":{"radians":-2.914347952143275},"translation":{"x":2.295535529643704,"y":1.7811027060188114}},"time":3.0851160752908084,"velocity":2.421506809024621,"position":6.327095619679388,"holonomicRotation":-138.7263662571244,"angularVelocity":0.9870151359412304,"angularAcceleration":0.3795700790238354,"curveRadius":2.441976356567748},{"acceleration":-2.9953500930161403,"curvature":0.4115606185972961,"pose":{"rotation":{"radians":-2.9111763510780477},"translation":{"x":2.2879985402090175,"y":1.7793346599633906}},"time":3.0883258323105585,"velocity":2.4118924630369536,"position":6.334837208443503,"holonomicRotation":-138.7164905691089,"angularVelocity":0.9881125099850756,"angularAcceleration":0.34188695190725427,"curveRadius":2.429775723946222},{"acceleration":-2.9952724289341677,"curvature":0.41358881946114767,"pose":{"rotation":{"radians":-2.907991570281233},"translation":{"x":2.2804736191022306,"y":1.7775441419319142}},"time":3.0915457375510367,"velocity":2.4022479696463686,"position":6.342572219269895,"holonomicRotation":-138.70661488109343,"angularVelocity":0.9890914666612473,"angularAcceleration":0.30403275968029925,"curveRadius":2.4178603311928732},{"acceleration":-2.9951937367503474,"curvature":0.41558832309705607,"pose":{"rotation":{"radians":-2.904793776235591},"translation":{"x":2.2729606733628227,"y":1.7757310688743755}},"time":3.0947759930971666,"velocity":2.3925727284664973,"position":6.350300840595543,"holonomicRotation":-138.69673919307795,"angularVelocity":0.989950794906313,"angularAcceleration":0.26602484936378684,"curveRadius":2.4062273755618997},{"acceleration":-2.9951139995590124,"curvature":0.4175584801928278,"pose":{"rotation":{"radians":-2.9015831384663535},"translation":{"x":2.265459610030275,"y":1.7738953577407675}},"time":3.0980168050490553,"velocity":2.382866127219457,"position":6.358023261620387,"holonomicRotation":-138.68686350506246,"angularVelocity":0.9906893139438158,"angularAcceleration":0.22788086703776902,"curveRadius":2.3948741252679184},{"acceleration":-2.995033199460145,"curvature":0.41949864633587025,"pose":{"rotation":{"radians":-2.8983598295192765},"translation":{"x":2.257970336144067,"y":1.7720369254810835}},"time":3.101268383629167,"velocity":2.3731275414213697,"position":6.365739672301945,"holonomicRotation":-138.67698781704695,"angularVelocity":0.9913058742583075,"angularAcceleration":0.1896187649478898,"curveRadius":2.3837979186215374},{"acceleration":-2.994951317948669,"curvature":0.4214081822305118,"pose":{"rotation":{"radians":-2.8951240249365764},"translation":{"x":2.2504927587436785,"y":1.770155689045317}},"time":3.1045309432934336,"velocity":2.3633563340549877,"position":6.3734502633497225,"holonomicRotation":-138.66711212903147,"angularVelocity":0.9917993586876824,"angularAcceleration":0.1512568290412594,"curveRadius":2.3729961642106807},{"acceleration":-2.994868336254372,"curvature":0.42328645456260755,"pose":{"rotation":{"radians":-2.8918759032314454},"translation":{"x":2.2430267848685896,"y":1.7682515653834612}},"time":3.1078047028464946,"velocity":2.353551855229015,"position":6.381155226219403,"holonomicRotation":-138.65723644101598,"angularVelocity":0.9921686832785261,"angularAcceleration":0.11281359698466313,"curveRadius":2.3624663374435757},{"acceleration":-2.9947842345642424,"curvature":0.42513283603374746,"pose":{"rotation":{"radians":-2.888615645860755},"translation":{"x":2.2355723215582803,"y":1.7663244714455095}},"time":3.1110898855612548,"velocity":2.3437134418271883,"position":6.388854753106845,"holonomicRotation":-138.6473607530005,"angularVelocity":0.9924127982417458,"angularAcceleration":0.0743078800831485,"curveRadius":2.3522059818513266},{"acceleration":-2.994698992418577,"curvature":0.42694670614923524,"pose":{"rotation":{"radians":-2.8853434371958433},"translation":{"x":2.2281292758522313,"y":1.764374324181455}},"time":3.114386719302972,"velocity":2.3338404171426963,"position":6.396549036941864,"holonomicRotation":-138.637485064985,"angularVelocity":0.9925306889170434,"angularAcceleration":0.03575875659300188,"curveRadius":2.3422127061696063},{"acceleration":-2.994612589127348,"curvature":0.4287274513939991,"pose":{"rotation":{"radians":-2.8820594644920186},"translation":{"x":2.220697554789921,"y":1.7624010405412909}},"time":3.117695436658093,"velocity":2.3239320904971863,"position":6.404238271381815,"holonomicRotation":-138.6276093769695,"angularVelocity":0.9925213765212894,"angularAcceleration":-0.002814503251438556,"curveRadius":2.3324841848790396},{"acceleration":-2.9945250024435914,"curvature":0.4304744660142234,"pose":{"rotation":{"radians":-2.8787639178554003},"translation":{"x":2.213277065410831,"y":1.7604045374750106}},"time":3.1210162750680626,"velocity":2.313987756849458,"position":6.41192265080496,"holonomicRotation":-138.61773368895402,"angularVelocity":0.9923839192912033,"angularAcceleration":-0.04139232721273353,"curveRadius":2.323018155429825},{"acceleration":-2.994436209899728,"curvature":0.43218715204728236,"pose":{"rotation":{"radians":-2.8754569902091607},"translation":{"x":2.2058677147544405,"y":1.7583847319326074}},"time":3.1243494769683595,"velocity":2.304006696384302,"position":6.419602370303645,"holonomicRotation":-138.60785800093853,"angularVelocity":0.9921174129730987,"angularAcceleration":-0.07995504805178447,"curveRadius":2.3138124196033423},{"acceleration":-2.9943461882797906,"curvature":0.4338649202753091,"pose":{"rotation":{"radians":-2.8721388772569503},"translation":{"x":2.1984694098602295,"y":1.7563415408640743}},"time":3.127695289933011,"velocity":2.2939881740869006,"position":6.427277625677262,"holonomicRotation":-138.59798231292302,"angularVelocity":0.9917209919580762,"angularAcceleration":-0.11848271831413094,"curveRadius":2.3048648398802323},{"acceleration":-2.994254913082756,"curvature":0.43550719025063217,"pose":{"rotation":{"radians":-2.868809777445388},"translation":{"x":2.1910820577676784,"y":1.7542748812194053}},"time":3.131053966824862,"velocity":2.2839314393020183,"position":6.434948613425018,"holonomicRotation":-138.58810662490754,"angularVelocity":0.99119382982023,"angularAcceleration":-0.15695529960778162,"curveRadius":2.2961733408454292},{"acceleration":-2.994162359074298,"curvature":0.4371133909937656,"pose":{"rotation":{"radians":-2.8654698919240746},"translation":{"x":2.183705565516267,"y":1.7521846699485928}},"time":3.1344257659518897,"velocity":2.2738357252735124,"position":6.442615530738499,"holonomicRotation":-138.57823093689206,"angularVelocity":0.9905351402879503,"angularAcceleration":-0.19535254250460232,"curveRadius":2.287735906984059},{"acceleration":-2.9940684999109686,"curvature":0.43868296140354734,"pose":{"rotation":{"radians":-2.862119424504846},"translation":{"x":2.176339840145475,"y":1.7500708240016307}},"time":3.1378109512298678,"velocity":2.263700248666356,"position":6.45027857549404,"holonomicRotation":-138.56835524887657,"angularVelocity":0.9897441776746893,"angularAcceleration":-0.23365415724999786,"curveRadius":2.2795505820434485},{"acceleration":-2.9939733088695637,"curvature":0.44021535052384525,"pose":{"rotation":{"radians":-2.8587585816179955},"translation":{"x":2.168984788694783,"y":1.7479332603285118}},"time":3.141209792351713,"velocity":2.253524209066463,"position":6.457937946244889,"holonomicRotation":-138.55847956086106,"angularVelocity":0.9888202379479505,"angularAcceleration":-0.271839634044777,"curveRadius":2.271615469133516},{"acceleration":-2.9938767571418454,"curvature":0.44171001833449886,"pose":{"rotation":{"radians":-2.855387572268251},"translation":{"x":2.16164031820367,"y":1.7457718958792299}},"time":3.144622564963852,"velocity":2.2433067884655693,"position":6.46559384221319,"holonomicRotation":-138.54860387284558,"angularVelocity":0.9877626589459761,"angularAcceleration":-0.3098885047930134,"curveRadius":2.2639287281066793},{"acceleration":-2.993778815742658,"curvature":0.4431664357298646,"pose":{"rotation":{"radians":-2.8520066079875868},"translation":{"x":2.1543063357116172,"y":1.7435866476037776}},"time":3.14804955084998,"velocity":2.23304715071783,"position":6.473246463281758,"holonomicRotation":-138.5387281848301,"angularVelocity":0.9865708214176946,"angularAcceleration":-0.3477801099520033,"curveRadius":2.2564885771483776},{"acceleration":-2.9936794536221125,"curvature":0.44458408551085205,"pose":{"rotation":{"radians":-2.8486159027879245},"translation":{"x":2.146982748258104,"y":1.741377432452149}},"time":3.1514910381226002,"velocity":2.2227444409798855,"position":6.480896009985678,"holonomicRotation":-138.5288524968146,"angularVelocity":0.9852441491323104,"angularAcceleration":-0.38549388107257854,"curveRadius":2.249293289144491},{"acceleration":-2.9935786394090096,"curvature":0.44596246221703845,"pose":{"rotation":{"radians":-2.8452156731104257},"translation":{"x":2.13966946288261,"y":1.7391441673743366}},"time":3.1549473214227586,"velocity":2.2123977851207854,"position":6.488542683503698,"holonomicRotation":-138.51897680879912,"angularVelocity":0.9837821099164783,"angularAcceleration":-0.42300907907784013,"curveRadius":2.2423411939844518},{"acceleration":-2.993476339799431,"curvature":0.4473010730384968,"pose":{"rotation":{"radians":-2.8418061377748263},"translation":{"x":2.132366386624616,"y":1.736886769320334}},"time":3.1584187021284134,"velocity":2.2020062891119716,"position":6.496186685649452,"holonomicRotation":-138.5091011207836,"angularVelocity":0.9821842156480747,"angularAcceleration":-0.46030510735993224,"curveRadius":2.235630675345899},{"acceleration":-2.9933725202155745,"curvature":0.4485994379543675,"pose":{"rotation":{"radians":-2.8383875179260585},"translation":{"x":2.1250734265236018,"y":1.7346051552401347}},"time":3.161905488571909,"velocity":2.191569038388151,"position":6.5038282188624885,"holonomicRotation":-138.49922543276813,"angularVelocity":0.9804500230132742,"angularAcceleration":-0.49736129897929804,"curveRadius":2.229160171399328},{"acceleration":-2.9932671446754724,"curvature":0.4498570901122183,"pose":{"rotation":{"radians":-2.8349600369795276},"translation":{"x":2.117790489619047,"y":1.7322992420837315}},"time":3.1654079962670525,"velocity":2.1810850971803055,"position":6.511467486199125,"holonomicRotation":-138.48934974475264,"angularVelocity":0.9785791338255969,"angularAcceleration":-0.53415705275152,"curveRadius":2.222928174257622},{"acceleration":-2.9931601758176924,"curvature":0.4510735764099044,"pose":{"rotation":{"radians":-2.8315239205651888},"translation":{"x":2.110517482950432,"y":1.7299689468011181}},"time":3.1689265481463216,"velocity":2.170553507818729,"position":6.519104691323115,"holonomicRotation":-138.47947405673716,"angularVelocity":0.976571195264747,"angularAcceleration":-0.5706718643770637,"curveRadius":2.2169332284081062},{"acceleration":-2.993051574439004,"curvature":0.45224845782875245,"pose":{"rotation":{"radians":-2.8280793964695476},"translation":{"x":2.103254313557237,"y":1.7276141863422876}},"time":3.1724614748087756,"velocity":2.1599732900061444,"position":6.526740038496146,"holonomicRotation":-138.46959836872165,"angularVelocity":0.9744259003240084,"angularAcceleration":-0.606885275308441,"curveRadius":2.211173930367847},{"acceleration":-2.9929412997090834,"curvature":0.4533813097279257,"pose":{"rotation":{"radians":-2.824626694576679},"translation":{"x":2.0960008884789407,"y":1.7252348776572333}},"time":3.1760131147792685,"velocity":2.1493434400567586,"position":6.534373732568168,"holonomicRotation":-138.45972268070616,"angularVelocity":0.9721429879023833,"angularAcceleration":-0.6427769820678988,"curveRadius":2.205648928492664},{"acceleration":-2.9928293090548705,"curvature":0.45447172223702104,"pose":{"rotation":{"radians":-2.821166046807209},"translation":{"x":2.088757114755025,"y":1.7228309376959485}},"time":3.179581814779607,"velocity":2.138662930100521,"position":6.542005978967542,"holonomicRotation":-138.44984699269068,"angularVelocity":0.9697222431534552,"angularAcceleration":-0.6783267712888112,"curveRadius":2.2003569222695645},{"acceleration":-2.9927155579318994,"curvature":0.4555193006428587,"pose":{"rotation":{"radians":-2.8176976870564467},"translation":{"x":2.0815228994249684,"y":1.7204022834084263}},"time":3.183167930012348,"velocity":2.1279307072509606,"position":6.549636983691032,"holonomicRotation":-138.4399713046752,"angularVelocity":0.9671634974516221,"angularAcceleration":-0.7135146351327314,"curveRadius":2.1952966616095835},{"acceleration":-2.992599999936501,"curvature":0.456523665736066,"pose":{"rotation":{"radians":-2.814221851130754},"translation":{"x":2.0742981495282518,"y":1.71794883174466}},"time":3.1867718244579617,"velocity":2.117145692733246,"position":6.557266953293628,"holonomicRotation":-138.43009561665968,"angularVelocity":0.9644666285726262,"angularAcceleration":-0.7483207179606302,"curveRadius":2.190466946303149},{"acceleration":-2.992482586195148,"curvature":0.4574844541856708,"pose":{"rotation":{"radians":-2.810738776682551},"translation":{"x":2.0670827721043548,"y":1.7154704996546433}},"time":3.1903938711861524,"velocity":2.1063067809727505,"position":6.5648960948782165,"holonomicRotation":-138.4202199286442,"angularVelocity":0.9616315607124144,"angularAcceleration":-0.7827253685454323,"curveRadius":2.185866625304274},{"acceleration":-2.9923632662098174,"curvature":0.4584013187369274,"pose":{"rotation":{"radians":-2.8072487031440865},"translation":{"x":2.059876674192757,"y":1.7129672040883688}},"time":3.194034452682176,"velocity":2.095412838636406,"position":6.5725246160850865,"holonomicRotation":-138.41034424062872,"angularVelocity":0.958658264421876,"angularAcceleration":-0.8167091696164386,"curveRadius":2.181494596820502},{"acceleration":-2.992241986537652,"curvature":0.459273928710376,"pose":{"rotation":{"radians":-2.803751871660064},"translation":{"x":2.05267976283294,"y":1.7104388619958302}},"time":3.1976939611890507,"velocity":2.084462703632044,"position":6.580152725081291,"holonomicRotation":-138.40046855261323,"angularVelocity":0.9555467564711502,"angularAcceleration":-0.8502529628994074,"curveRadius":2.1773498069179817},{"acceleration":-2.992118691588758,"curvature":0.4601019700170493,"pose":{"rotation":{"radians":-2.8002485250188194},"translation":{"x":2.0454919450643816,"y":1.707885390327021}},"time":3.201372799066631,"velocity":2.0734551840552107,"position":6.587780630549859,"holonomicRotation":-138.39059286459772,"angularVelocity":0.9522970997429474,"angularAcceleration":-0.8833378464451396,"curveRadius":2.173431250387701},{"acceleration":-2.9919933229205506,"curvature":0.4608851458146598,"pose":{"rotation":{"radians":-2.7967389075820432},"translation":{"x":2.038313127926563,"y":1.7053067060319338}},"time":3.205071379168574,"velocity":2.0623890570859107,"position":6.595408541678862,"holonomicRotation":-138.38071717658224,"angularVelocity":0.9489094030794397,"angularAcceleration":-0.915945192515391,"curveRadius":2.169737968517952},{"acceleration":-2.9918658194786643,"curvature":0.4616231764758931,"pose":{"rotation":{"radians":-2.7932232652144204},"translation":{"x":2.0311432184589644,"y":1.7027027260605625}},"time":3.208790125238308,"velocity":2.0512630678285526,"position":6.60303666815034,"holonomicRotation":-138.37084148856675,"angularVelocity":0.9453838207012026,"angularAcceleration":-0.9480567675569109,"curveRadius":2.1662690500814183},{"acceleration":-2.9917361172836525,"curvature":0.46231579995908745,"pose":{"rotation":{"radians":-2.7897018452106197},"translation":{"x":2.023982123701065,"y":1.7000733673629}},"time":3.2125294723252007,"velocity":2.040075928093637,"position":6.610665220129096,"holonomicRotation":-138.36096580055127,"angularVelocity":0.9417205522708335,"angularAcceleration":-0.9796545614099187,"curveRadius":2.1630236303593664},{"acceleration":-2.991604149029162,"curvature":0.46296277196822205,"pose":{"rotation":{"radians":-2.786174896222566},"translation":{"x":2.016829750692346,"y":1.6974185468889398}},"time":3.216289867222196,"velocity":2.0288263151177977,"position":6.618294408251355,"holonomicRotation":-138.35109011253576,"angularVelocity":0.9379198421080701,"angularAcceleration":-1.0107210191675082,"curveRadius":2.160000891105431},{"acceleration":-2.991469844218514,"curvature":0.4635638664439579,"pose":{"rotation":{"radians":-2.7826426681851393},"translation":{"x":2.009686006472286,"y":1.6947381815886753}},"time":3.2200717689263105,"velocity":2.0175128702161405,"position":6.6259244436132985,"holonomicRotation":-138.34121442452027,"angularVelocity":0.933981978850402,"angularAcceleration":-1.0412389231015433,"curveRadius":2.1572000589068647},{"acceleration":-2.991333128855594,"curvature":0.46411887537237384,"pose":{"rotation":{"radians":-2.779105412240568},"translation":{"x":2.002550798080366,"y":1.692032188412099}},"time":3.223875649123459,"velocity":2.0061341973642124,"position":6.633555537759475,"holonomicRotation":-138.3313387365048,"angularVelocity":0.9299072949834402,"angularAcceleration":-1.0711914297449114,"curveRadius":2.1546204066742076},{"acceleration":-2.991193925136914,"curvature":0.46462760926216207,"pose":{"rotation":{"radians":-2.77556338066313},"translation":{"x":1.9954240325560655,"y":1.689300484309205}},"time":3.2277019926992168,"velocity":1.9946888617049192,"position":6.641187902671095,"holonomicRotation":-138.3214630484893,"angularVelocity":0.9256961658850786,"angularAcceleration":-1.1005621986069543,"curveRadius":2.152261251947597},{"acceleration":-2.9910521514365023,"curvature":0.4650898972768742,"pose":{"rotation":{"radians":-2.7720168267813983},"translation":{"x":1.9883056169388647,"y":1.6865429862299863}},"time":3.2315512982772345,"velocity":1.9831753879742526,"position":6.648821750754212,"holonomicRotation":-138.31158736047382,"angularVelocity":0.9213490095421226,"angularAcceleration":-1.1293352151051146,"curveRadius":2.1501219567551404},{"acceleration":-2.9909077218224343,"curvature":0.4655055873604949,"pose":{"rotation":{"radians":-2.7684660049010854},"translation":{"x":1.9811954582682434,"y":1.6837596111244362}},"time":3.235424078787169,"velocity":1.9715922588421666,"position":6.656457294827793,"holonomicRotation":-138.3017116724583,"angularVelocity":0.9168662853999604,"angularAcceleration":-1.15749501699445,"curveRadius":2.1482019274359088},{"acceleration":-2.9907605458072246,"curvature":0.4658745463562,"pose":{"rotation":{"radians":-2.764911170226478},"translation":{"x":1.974093463583682,"y":1.680950275942548}},"time":3.2393208620641336,"velocity":1.959937913161859,"position":6.664094748111691,"holonomicRotation":-138.29183598444283,"angularVelocity":0.9122484936797398,"angularAcceleration":-1.1850265698680187,"curveRadius":2.1465006144281094},{"acceleration":-2.9906105284414393,"curvature":0.46619666015167394,"pose":{"rotation":{"radians":-2.7613525787812314},"translation":{"x":1.96699953992466,"y":1.6781148976343148}},"time":3.2432421914818477,"velocity":1.9482107441197563,"position":6.671734324214515,"holonomicRotation":-138.28196029642734,"angularVelocity":0.9074961744277503,"angularAcceleration":-1.2119153342541307,"curveRadius":2.145017511868611},{"acceleration":-2.9904575693823032,"curvature":0.46647183378368823,"pose":{"rotation":{"radians":-2.7577904873289625},"translation":{"x":1.959913594330658,"y":1.67525339314973}},"time":3.2471886266218233,"velocity":1.9364090972833399,"position":6.679376237121402,"holonomicRotation":-138.27208460841186,"angularVelocity":0.9026099063903394,"angularAcceleration":-1.2381473061384392,"curveRadius":2.1437521573140015},{"acceleration":-2.9903015632221015,"curvature":0.4666999916354278,"pose":{"rotation":{"radians":-2.7542251532927295},"translation":{"x":1.9528355338411554,"y":1.672365679438787}},"time":3.2511607439811505,"velocity":1.924531268534442,"position":6.687020701181716,"holonomicRotation":-138.26220892039635,"angularVelocity":0.8975903060519861,"angularAcceleration":-1.2637089703723008,"curveRadius":2.142704130968081},{"acceleration":-2.9901423986184774,"curvature":0.4668810773600381,"pose":{"rotation":{"radians":-2.7506568346744387},"translation":{"x":1.9457652654956326,"y":1.6694516734514788}},"time":3.255159137721629,"velocity":1.9125755018846662,"position":6.694667931096644,"holonomicRotation":-138.25233323238086,"angularVelocity":0.8924380263419845,"angularAcceleration":-1.2885873789370244,"curveRadius":2.141873056099132},{"acceleration":-2.9899799580865203,"curvature":0.46701505396416243,"pose":{"rotation":{"radians":-2.7470857899737418},"translation":{"x":1.9387026963335694,"y":1.666511292137799}},"time":3.2591844204632525,"velocity":1.9005399871615807,"position":6.702318141906731,"holonomicRotation":-138.24245754436538,"angularVelocity":0.8871537553798553,"angularAcceleration":-1.3127701335082125,"curveRadius":2.1412585986505213},{"acceleration":-2.9898141178410853,"curvature":0.46710190401673596,"pose":{"rotation":{"radians":-2.743512278106519},"translation":{"x":1.931647733394446,"y":1.6635444524477405}},"time":3.263237224125301,"velocity":1.8884228575559496,"position":6.70997154897933,"holonomicRotation":-138.2325818563499,"angularVelocity":0.8817382151239715,"angularAcceleration":-1.336245401324544,"curveRadius":2.1408604662081845},{"acceleration":-2.989644746819483,"curvature":0.46714162932011927,"pose":{"rotation":{"radians":-2.7399365583230484},"translation":{"x":1.924600283717742,"y":1.6605510713312968}},"time":3.2673182008185857,"velocity":1.8762221870229787,"position":6.717628367995994,"holonomicRotation":-138.22270616833438,"angularVelocity":0.8761921599196414,"angularAcceleration":-1.359001930458574,"curveRadius":2.140678409362501},{"acceleration":-2.989471706795161,"curvature":0.4671342514027932,"pose":{"rotation":{"radians":-2.7363588901260982},"translation":{"x":1.9175602543429378,"y":1.6575310657384614}},"time":3.2714280237927054,"velocity":1.8639359875219113,"position":6.7252888149398,"holonomicRotation":-138.2128304803189,"angularVelocity":0.8705163749094346,"angularAcceleration":-1.381029072528994,"curveRadius":2.14071221923253},{"acceleration":-2.9892948514452597,"curvature":0.4670798109128498,"pose":{"rotation":{"radians":-2.7327795331883835},"translation":{"x":1.9105275523095133,"y":1.6544843526192268}},"time":3.275567388442526,"velocity":1.8515622060859485,"position":6.732953106082616,"holonomicRotation":-138.20295479230342,"angularVelocity":0.8647116745005716,"angularAcceleration":-1.4023167562960948,"curveRadius":2.1409617299570787},{"acceleration":-2.9891140258705207,"curvature":0.4669783682280066,"pose":{"rotation":{"radians":-2.7291987472710093},"translation":{"x":1.9035020846569484,"y":1.651410848923587}},"time":3.2797370133784765,"velocity":1.839098721707279,"position":6.740621457972321,"holonomicRotation":-138.19307910428793,"angularVelocity":0.8587789003515789,"angularAcceleration":-1.4228555901611621,"curveRadius":2.1414268155387886},{"acceleration":-2.9889290661361994,"curvature":0.46683000283682086,"pose":{"rotation":{"radians":-2.7256167921402175},"translation":{"x":1.8964837584247232,"y":1.6483104716015353}},"time":3.2839376415656836,"velocity":1.8265433420225046,"position":6.748294087419977,"holonomicRotation":-138.18320341627242,"angularVelocity":0.8527189199226382,"angularAcceleration":-1.442636710241628,"curveRadius":2.1421073922481955},{"acceleration":-2.9887397983985102,"curvature":0.4666348135718117,"pose":{"rotation":{"radians":-2.7220339274857053},"translation":{"x":1.8894724806523175,"y":1.6451831376030648}},"time":3.288170041537443,"velocity":1.8138937997841669,"position":6.7559712114869575,"holonomicRotation":-138.17332772825694,"angularVelocity":0.8465326241420648,"angularAcceleration":-1.4616519756760924,"curveRadius":2.1430034170523955},{"acceleration":-2.9885460384731704,"curvature":0.46639291850560477,"pose":{"rotation":{"radians":-2.718450412838158},"translation":{"x":1.8824681583792118,"y":1.6420287638781685}},"time":3.2924350086890457,"velocity":1.801147749099026,"position":6.763653047472048,"holonomicRotation":-138.16345204024145,"angularVelocity":0.840220925546962,"angularAcceleration":-1.4798938352270015,"curveRadius":2.1441148875162064},{"acceleration":-2.9883475905902337,"curvature":0.46610445480811125,"pose":{"rotation":{"radians":-2.7148665074873066},"translation":{"x":1.8754706986448855,"y":1.63884726737684}},"time":3.296733366658572,"velocity":1.7883027614172975,"position":6.771339812898512,"holonomicRotation":-138.15357635222597,"angularVelocity":0.8337847560068179,"angularAcceleration":-1.4973554054301632,"curveRadius":2.145441841811373},{"acceleration":-2.9881442470111907,"curvature":0.4657695785651232,"pose":{"rotation":{"radians":-2.711282470399864},"translation":{"x":1.8684800084888187,"y":1.6356385650490721}},"time":3.3010659688019057,"velocity":1.7753563212481067,"position":6.779031725501133,"holonomicRotation":-138.14370066421048,"angularVelocity":0.8272250644931848,"angularAcceleration":-1.5140304363570942,"curveRadius":2.14698435883395},{"acceleration":-2.9879357869488645,"curvature":0.4653884647217145,"pose":{"rotation":{"radians":-2.707698560138159},"translation":{"x":1.861495994950492,"y":1.6324025738448589}},"time":3.3054336997699623,"velocity":1.7623058215808858,"position":6.786729003213238,"holonomicRotation":-138.13382497619497,"angularVelocity":0.8205428145451249,"angularAcceleration":-1.5299133570566985,"curveRadius":2.1487425576780548},{"acceleration":-2.987721975216449,"curvature":0.464961306921407,"pose":{"rotation":{"radians":-2.704115034778689},"translation":{"x":1.8545185650693845,"y":1.629139210714193}},"time":3.309837477196926,"velocity":1.7491485589883844,"position":6.794431864153717,"holonomicRotation":-138.1239492881795,"angularVelocity":0.8137389817951937,"angularAcceleration":-1.544999233674357,"curveRadius":2.1507165975190086},{"acceleration":-2.9875025616636948,"curvature":0.4644883171766511,"pose":{"rotation":{"radians":-2.70053215183139},"translation":{"x":1.847547625884977,"y":1.625848392607068}},"time":3.3142782535092032,"velocity":1.7358817283796804,"position":6.8021405266140205,"holonomicRotation":-138.114073600164,"angularVelocity":0.8068145511840985,"angularAcceleration":-1.5592838107948113,"curveRadius":2.1529066782097055},{"acceleration":-2.9872772796225298,"curvature":0.4639697260552453,"pose":{"rotation":{"radians":-2.6969501681593973},"translation":{"x":1.8405830844367492,"y":1.6225300364734772}},"time":3.318757017865828,"velocity":1.7225024173763517,"position":6.809855209045166,"holonomicRotation":-138.10419791214852,"angularVelocity":0.7997705140915561,"angularAcceleration":-1.5727634971737408,"curveRadius":2.1553130384220998},{"acceleration":-2.9870458445010994,"curvature":0.4634057819489673,"pose":{"rotation":{"radians":-2.6933693398988203},"translation":{"x":1.8336248477641808,"y":1.6191840592634135}},"time":3.323274798242187,"velocity":1.70900760027678,"position":6.817576130044745,"holonomicRotation":-138.094322224133,"angularVelocity":0.7926078654276766,"angularAcceleration":-1.5854353393008709,"curveRadius":2.157935957972413},{"acceleration":-2.9868079524052393,"curvature":0.4627967513142431,"pose":{"rotation":{"radians":-2.689789922379883},"translation":{"x":1.8266728229067521,"y":1.6158103779268704}},"time":3.3278326636702316,"velocity":1.6953941315703038,"position":6.825303508343938,"holonomicRotation":-138.08444653611753,"angularVelocity":0.7853276002650968,"angularAcceleration":-1.5972970851189165,"curveRadius":2.160775755577833},{"acceleration":-2.986563278765563,"curvature":0.4621429182236767,"pose":{"rotation":{"radians":-2.6862121700480945},"translation":{"x":1.8197269169039432,"y":1.6124089094138414}},"time":3.332431726649798,"velocity":1.6816587389588011,"position":6.833037562794548,"holonomicRotation":-138.07457084810204,"angularVelocity":0.777930710600052,"angularAcceleration":-1.6083471128595932,"curveRadius":2.163832789743196},{"acceleration":-2.9863114759999974,"curvature":0.4614445840115926,"pose":{"rotation":{"radians":-2.682636336386285},"translation":{"x":1.812787036795234,"y":1.608979570674319}},"time":3.337073145747292,"velocity":1.6677980158430281,"position":6.840778512356045,"holonomicRotation":-138.06469516008656,"angularVelocity":0.7704181817452862,"angularAcceleration":-1.6185844667251417,"curveRadius":2.1671074591589043},{"acceleration":-2.9860521718891992,"curvature":0.4607020673681413,"pose":{"rotation":{"radians":-2.6790626738378274},"translation":{"x":1.8058530896201044,"y":1.6055222786582977}},"time":3.3417581283998645,"velocity":1.6538084132180513,"position":6.84852657608265,"holonomicRotation":-138.05481947207105,"angularVelocity":0.7627909884566058,"angularAcceleration":-1.6280088645563422,"curveRadius":2.170600200934007},{"acceleration":-2.985784967575332,"curvature":0.45991570355451544,"pose":{"rotation":{"radians":-2.675491433729697},"translation":{"x":1.7989249824180344,"y":1.6020369503157699}},"time":3.3464879339453013,"velocity":1.6396862309209317,"position":6.856281973110436,"holonomicRotation":-138.04494378405556,"angularVelocity":0.7550500911344475,"angularAcceleration":-1.636620628014289,"curveRadius":2.174311492891798},{"acceleration":-2.9855094344462496,"curvature":0.45908584458537943,"pose":{"rotation":{"radians":-2.6719228661976104},"translation":{"x":1.792002622228504,"y":1.598523502596729}},"time":3.3512638769002607,"velocity":1.6254276081705232,"position":6.864044922644474,"holonomicRotation":-138.03506809604008,"angularVelocity":0.7471964313101798,"angularAcceleration":-1.6444207768671946,"curveRadius":2.1782418512667143},{"acceleration":-2.985225112291555,"curvature":0.45821285859824,"pose":{"rotation":{"radians":-2.6683572201111456},"translation":{"x":1.7850859160909933,"y":1.5949818524511685}},"time":3.3560873305122185,"velocity":1.6110285133201334,"position":6.871815643946015,"holonomicRotation":-138.0251924080246,"angularVelocity":0.7392309273225394,"angularAcceleration":-1.6514109242997932,"curveRadius":2.1823918321698557},{"acceleration":-2.9849315055269394,"curvature":0.45729712963990093,"pose":{"rotation":{"radians":-2.6647947430003427},"translation":{"x":1.7781747710449824,"y":1.5914119168290812}},"time":3.3609597306136005,"velocity":1.5964847327499856,"position":6.879594356319721,"holonomicRotation":-138.01531672000908,"angularVelocity":0.7311544693943476,"angularAcceleration":-1.6575933339097024,"curveRadius":2.186762031039755},{"acceleration":-2.9846280802256144,"curvature":0.4563390573522179,"pose":{"rotation":{"radians":-2.661235680983315},"translation":{"x":1.7712690941299511,"y":1.5878136126804612}},"time":3.365882579810155,"velocity":1.581791858803233,"position":6.887381279100947,"holonomicRotation":-138.0054410319936,"angularVelocity":0.7229679144993082,"angularAcceleration":-1.6629708870158264,"curveRadius":2.191353082513308},{"acceleration":-2.9843142605610646,"curvature":0.45533905662232843,"pose":{"rotation":{"radians":-2.6576802786943934},"translation":{"x":1.7643687923853795,"y":1.584186856955301}},"time":3.370857452039725,"velocity":1.5669452766640575,"position":6.895176631643079,"holonomicRotation":-137.99556534397811,"angularVelocity":0.7146720809810426,"angularAcceleration":-1.6675470515515833,"curveRadius":2.196165660415617},{"acceleration":-2.983989424099231,"curvature":0.4542975571337028,"pose":{"rotation":{"radians":-2.654128779214396},"translation":{"x":1.7574737728507475,"y":1.5805315666035944}},"time":3.3758859975422846,"velocity":1.5519401500658185,"position":6.902980633304934,"holonomicRotation":-137.98568965596263,"angularVelocity":0.7062677424693912,"angularAcceleration":-1.6713259345816598,"curveRadius":2.2012004781828343},{"acceleration":-2.9836528974614107,"curvature":0.4532150030753136,"pose":{"rotation":{"radians":-2.6505814240010923},"translation":{"x":1.750583942565535,"y":1.5768476585753342}},"time":3.380969948287558,"velocity":1.536771405694132,"position":6.910793503438228,"holonomicRotation":-137.97581396794715,"angularVelocity":0.6977556217675285,"angularAcceleration":-1.674312189152543,"curveRadius":2.2064582884821746},{"acceleration":-2.9833039510519765,"curvature":0.4520918529117567,"pose":{"rotation":{"radians":-2.6470384528216004},"translation":{"x":1.7436992085692224,"y":1.573135049820514}},"time":3.3861111239128334,"velocity":1.5214337161381961,"position":6.91861546137511,"holonomicRotation":-137.96593827993163,"angularVelocity":0.6891363839184487,"angularAcceleration":-1.6765110700956278,"curveRadius":2.21193988248045},{"acceleration":-2.9829417927895334,"curvature":0.45092857863865177,"pose":{"rotation":{"radians":-2.6435001036855343},"translation":{"x":1.7368194779012893,"y":1.569393657289127}},"time":3.391311438230887,"velocity":1.505921481223232,"position":6.926446726415779,"holonomicRotation":-137.95606259191615,"angularVelocity":0.6804106289849028,"angularAcceleration":-1.6779283712242359,"curveRadius":2.217646091580597},{"acceleration":-2.9825655617963838,"curvature":0.4497256654216822,"pose":{"rotation":{"radians":-2.6399666127799195},"translation":{"x":1.7299446576012159,"y":1.5656233979311662}},"time":3.396572906376445,"velocity":1.4902288075278025,"position":6.93428751781618,"holonomicRotation":-137.94618690390067,"angularVelocity":0.6715788840417285,"angularAcceleration":-1.6785704481800918,"curveRadius":2.2235777872769544},{"acceleration":-2.9821743204023394,"curvature":0.44848361183982627,"pose":{"rotation":{"radians":-2.636438214405076},"translation":{"x":1.7230746547084825,"y":1.5618241886966255}},"time":3.401897652669529,"velocity":1.4743494858699095,"position":6.942138054775776,"holonomicRotation":-137.93631121588518,"angularVelocity":0.6626415946664527,"angularAcceleration":-1.6784441705483266,"curveRadius":2.2297358779681455},{"acceleration":-2.981767045747283,"curvature":0.447202928529398,"pose":{"rotation":{"radians":-2.6329151409121505},"translation":{"x":1.7162093762625683,"y":1.5579959465354978}},"time":3.4072879192856744,"velocity":1.4582769665060955,"position":6.949998556425427,"holonomicRotation":-137.92643552786967,"angularVelocity":0.6535991155563351,"angularAcceleration":-1.6775569288229202,"curveRadius":2.2361213136247664},{"acceleration":-2.9813426197793462,"curvature":0.44588413836125856,"pose":{"rotation":{"radians":-2.629397622641822},"translation":{"x":1.7093487293029541,"y":1.554138588397776}},"time":3.412746075836661,"velocity":1.442004331755212,"position":6.957869241815348,"holonomicRotation":-137.9165598398542,"angularVelocity":0.6444517003992424,"angularAcceleration":-1.6759165977823893,"curveRadius":2.2427350828743604},{"acceleration":-2.9808998178878694,"curvature":0.44452777578612757,"pose":{"rotation":{"radians":-2.62588588786499},"translation":{"x":1.7024926208691193,"y":1.550252031233454}},"time":3.418274629981539,"velocity":1.4255242657115608,"position":6.965750329903172,"holonomicRotation":-137.9066841518387,"angularVelocity":0.6351994906453252,"angularAcceleration":-1.673531543954998,"curveRadius":2.249578214165683},{"acceleration":-2.9804372964706642,"curvature":0.4431343864986346,"pose":{"rotation":{"radians":-2.622380162724122},"translation":{"x":1.6956409580005443,"y":1.546336191992525}},"time":3.423876239206815,"velocity":1.4088290206562941,"position":6.973642039542117,"holonomicRotation":-137.89680846382322,"angularVelocity":0.6258425034451804,"angularAcceleration":-1.6704105595091359,"curveRadius":2.2566517753256803},{"acceleration":-2.979953577453338,"curvature":0.44170452697321644,"pose":{"rotation":{"radians":-2.6188806711768664},"translation":{"x":1.688793647736709,"y":1.5423909876249817}},"time":3.429553723937343,"velocity":1.3919103797226215,"position":6.981544589469255,"holonomicRotation":-137.8869327758077,"angularVelocity":0.6163806180646921,"angularAcceleration":-1.6665628935313668,"curveRadius":2.2639568737330076},{"acceleration":-2.9794470317393817,"curvature":0.4402387639365582,"pose":{"rotation":{"radians":-2.6153876349410363},"translation":{"x":1.6819505971170934,"y":1.5384163350808182}},"time":3.435310082166569,"velocity":1.3747596152829251,"position":6.989458198293897,"holonomicRotation":-137.87705708779222,"angularVelocity":0.6068135610628358,"angularAcceleration":-1.6619981976247624,"curveRadius":2.271494656804251},{"acceleration":-2.9789158590778166,"curvature":0.4387376740308556,"pose":{"rotation":{"radians":-2.6119012734407896},"translation":{"x":1.6751117131811772,"y":1.5344121513100273}},"time":3.441148505827224,"velocity":1.357367442448184,"position":6.997383084486089,"holonomicRotation":-137.86718139977674,"angularVelocity":0.5971408898845582,"angularAcceleration":-1.6567264968215911,"curveRadius":2.2792663114899767},{"acceleration":-2.9783580654013195,"curvature":0.4372018432867329,"pose":{"rotation":{"radians":-2.608421803754928},"translation":{"x":1.6682769029684408,"y":1.530378353262602}},"time":3.447072399162643,"velocity":1.3397239669540628,"position":7.005319466365229,"holonomicRotation":-137.85730571176126,"angularVelocity":0.5873619744397153,"angularAcceleration":-1.6507581907957822,"curveRadius":2.287273064729884},{"acceleration":-2.977771435768641,"curvature":0.4356318666603518,"pose":{"rotation":{"radians":-2.604949440566641},"translation":{"x":1.661446073518364,"y":1.5263148578885362}},"time":3.453085399406182,"velocity":1.3218186265855818,"position":7.013267562088803,"holonomicRotation":-137.84743002374574,"angularVelocity":0.5774759766587165,"angularAcceleration":-1.6441040047555153,"curveRadius":2.295516183575404},{"acceleration":-2.9771535032067264,"curvature":0.4340283474449653,"pose":{"rotation":{"radians":-2.6014843961147025},"translation":{"x":1.654619131870427,"y":1.5222215821378229}},"time":3.4591914001336903,"velocity":1.3036401251290979,"position":7.02122758964125,"holonomicRotation":-137.83755433573026,"angularVelocity":0.5674818275615312,"angularAcceleration":-1.6367749601077766,"curveRadius":2.303996975973556},{"acceleration":-2.9765015119448424,"curvature":0.43239189718979887,"pose":{"rotation":{"radians":-2.598026880146583},"translation":{"x":1.6477959850641097,"y":1.5180984429604552}},"time":3.4653945777242514,"velocity":1.2851763576519304,"position":7.0291997668229556,"holonomicRotation":-137.82767864771478,"angularVelocity":0.5573782013560952,"angularAcceleration":-1.628782355160997,"curveRadius":2.3127167888649147},{"acceleration":-2.9758123737130373,"curvature":0.4307231349236336,"pose":{"rotation":{"radians":-2.594577099873292},"translation":{"x":1.640976540138892,"y":1.5139453573064268}},"time":3.471699421450775,"velocity":1.266414325676215,"position":7.037184311239375,"holonomicRotation":-137.8178029596993,"angularVelocity":0.547163486190544,"angularAcceleration":-1.620137724045341,"curveRadius":2.3216770099365527},{"acceleration":-2.975082616363276,"curvature":0.42902268669699223,"pose":{"rotation":{"radians":-2.591135259925487},"translation":{"x":1.634160704134254,"y":1.5097622421257304}},"time":3.4781107678287766,"velocity":1.2473400405195383,"position":7.045181440290296,"holonomicRotation":-137.8079272716838,"angularVelocity":0.5368357510077049,"angularAcceleration":-1.6108527872203302,"curveRadius":2.330879067722296},{"acceleration":-2.974308322439147,"curvature":0.4272911851891256,"pose":{"rotation":{"radians":-2.58770156231204},"translation":{"x":1.6273483840896756,"y":1.5055490143683596}},"time":3.4846338399844945,"velocity":1.2279384127189155,"position":7.053191371159239,"holonomicRotation":-137.7980515836683,"angularVelocity":0.5263927075276862,"angularAcceleration":-1.6009394393812832,"curveRadius":2.340324431353258},{"acceleration":-2.973485055192195,"curvature":0.4255292691275255,"pose":{"rotation":{"radians":-2.584276206379489},"translation":{"x":1.620539487044637,"y":1.5013055909843076}},"time":3.4912742929697798,"velocity":1.2081931250074633,"position":7.061214320802996,"holonomicRotation":-137.7881758956528,"angularVelocity":0.51583166692714,"angularAcceleration":-1.5904096639112804,"curveRadius":2.350014611334087},{"acceleration":-2.9726077700995006,"curvature":0.42373758315093,"pose":{"rotation":{"radians":-2.5808593887740034},"translation":{"x":1.6137339200386176,"y":1.4970318889235679}},"time":3.498038266160922,"velocity":1.1880864857427293,"position":7.069250505941318,"holonomicRotation":-137.77830020763733,"angularVelocity":0.5051494896461357,"angularAcceleration":-1.579275520339615,"curveRadius":2.359951157893428},{"acceleration":-2.9716707068164117,"curvature":0.4219167769181933,"pose":{"rotation":{"radians":-2.577451303404302},"translation":{"x":1.6069315901110985,"y":1.4927278251361338}},"time":3.5049324441449525,"velocity":1.167599258980007,"position":7.077300143046749,"holonomicRotation":-137.76842451962185,"angularVelocity":0.49434252750592583,"angularAcceleration":-1.5675490486672556,"curveRadius":2.3701356634934028},{"acceleration":-2.9706672579819746,"curvature":0.4200675049133379,"pose":{"rotation":{"radians":-2.5740521414072},"translation":{"x":1.6001324043015586,"y":1.4883933165719978}},"time":3.5119641278381537,"velocity":1.1467104664641286,"position":7.085363448334608,"holonomicRotation":-137.75854883160633,"angularVelocity":0.4834065560128198,"angularAcceleration":-1.555242239306052,"curveRadius":2.3805697615346495},{"acceleration":-2.9695898073536022,"curvature":0.4181904259379765,"pose":{"rotation":{"radians":-2.570662091114216},"translation":{"x":1.5933362696494786,"y":1.4840282801811542}},"time":3.5191413180220597,"velocity":1.1253971556485631,"position":7.093440637753124,"holonomicRotation":-137.74867314359085,"angularVelocity":0.47233669529697236,"angularAcceleration":-1.5423669196714838,"curveRadius":2.391255126793156},{"acceleration":-2.9684295299787347,"curvature":0.41628620248123727,"pose":{"rotation":{"radians":-2.567281338020093},"translation":{"x":1.5865430931943385,"y":1.4796326329135958}},"time":3.526472814056508,"velocity":1.1036341263209846,"position":7.1015319269737285,"holonomicRotation":-137.73879745557537,"angularVelocity":0.4611273167492571,"angularAcceleration":-1.5289346805953286,"curveRadius":2.4021934766023665},{"acceleration":-2.9671761422745178,"curvature":0.4143555006584118,"pose":{"rotation":{"radians":-2.5639100647533786},"translation":{"x":1.5797527819756176,"y":1.4752062917193158}},"time":3.533968331285018,"velocity":1.0813936064265426,"position":7.109637531381499,"holonomicRotation":-137.72892176755988,"angularVelocity":0.4497719322012471,"angularAcceleration":-1.5149567670685669,"curveRadius":2.4133865688062492},{"acceleration":-2.965817587986681,"curvature":0.4123989892734606,"pose":{"rotation":{"radians":-2.5605484510483163},"translation":{"x":1.5729652430327963,"y":1.4707491735483076}},"time":3.541638641653003,"velocity":1.0586448650318556,"position":7.117757666065767,"holonomicRotation":-137.71904607954437,"angularVelocity":0.4382630615696068,"angularAcceleration":-1.5004439298410635,"curveRadius":2.424836204767958},{"acceleration":-2.9643396388991023,"curvature":0.4104173397638617,"pose":{"rotation":{"radians":-2.557196673718797},"translation":{"x":1.5661803834053551,"y":1.4662611953505644}},"time":3.5494957434116334,"velocity":1.0353537468418836,"position":7.125892545810883,"holonomicRotation":-137.7091703915289,"angularVelocity":0.4265920733224099,"angularAcceleration":-1.4854062739326561,"curveRadius":2.4365442273354274},{"acceleration":-2.962725382551391,"curvature":0.4084112255843112,"pose":{"rotation":{"radians":-2.553854906634083},"translation":{"x":1.5593981101327734,"y":1.4617422740760797}},"time":3.5575530676220244,"velocity":1.0114821078883125,"position":7.134042385087149,"holonomicRotation":-137.6992947035134,"angularVelocity":0.4147489907883001,"angularAcceleration":-1.469853046106378,"curveRadius":2.448512522076999},{"acceleration":-2.9609545578962106,"curvature":0.4063813217824893,"pose":{"rotation":{"radians":-2.5505233206958158},"translation":{"x":1.552618330254531,"y":1.4571923266748465}},"time":3.5658257317170103,"velocity":0.9869871254303195,"position":7.14220739804191,"holonomicRotation":-137.68941901549792,"angularVelocity":0.4027222548884469,"angularAcceleration":-1.45379236504267,"curveRadius":2.46074301745403},{"acceleration":-2.959002683090536,"curvature":0.40432830457853597,"pose":{"rotation":{"radians":-2.54720208381733},"translation":{"x":1.5458409508101085,"y":1.452611270096858}},"time":3.574330853939473,"velocity":0.9618204459540391,"position":7.150387798490812,"holonomicRotation":-137.6795433274824,"angularVelocity":0.39049843042985977,"angularAcceleration":-1.4372308990813647,"curveRadius":2.4732376850104045},{"acceleration":-2.956839895326982,"curvature":0.40225285088606166,"pose":{"rotation":{"radians":-2.5438913609044196},"translation":{"x":1.539065878838986,"y":1.447999021292108}},"time":3.583087947546367,"velocity":0.9359271222100624,"position":7.158583799909237,"holonomicRotation":-137.66966763946692,"angularVelocity":0.3780618389535107,"angularAcceleration":-1.420173408510617,"curveRadius":2.4859985399662228},{"acceleration":-2.95442938599437,"curvature":0.40015563814972843,"pose":{"rotation":{"radians":-2.5405913138376985},"translation":{"x":1.5322930213806432,"y":1.443355497210589}},"time":3.592119421014128,"velocity":0.9092442715980814,"position":7.166795615423888,"holonomicRotation":-137.65979195145144,"angularVelocity":0.365394094164265,"angularAcceleration":-1.4026221562256858,"curveRadius":2.4990276399050124},{"acceleration":-2.951725254844096,"curvature":0.3980373435620867,"pose":{"rotation":{"radians":-2.5373021014568846},"translation":{"x":1.5255222854745598,"y":1.438680614802295}},"time":3.6014512213368195,"velocity":0.8816993609124302,"position":7.175023457804568,"holonomicRotation":-137.64991626343595,"angularVelocity":0.3524735064053734,"angularAcceleration":-1.3845761066568558,"curveRadius":2.5123270873302315},{"acceleration":-2.948669516086292,"curvature":0.3958986438473427,"pose":{"rotation":{"radians":-2.534023879546501},"translation":{"x":1.518753578160216,"y":1.4339742910172188}},"time":3.6111136739035286,"velocity":0.8532079815783454,"position":7.183267539456106,"holonomicRotation":-137.64004057542044,"angularVelocity":0.33927430823086263,"angularAcceleration":-1.3660298028253388,"curveRadius":2.5258990288069714},{"acceleration":-2.9451878363194415,"curvature":0.3937402149865039,"pose":{"rotation":{"radians":-2.530756800823557},"translation":{"x":1.5119868064770918,"y":1.4292364428053541}},"time":3.621142597816332,"velocity":0.823670916858984,"position":7.191528072410474,"holonomicRotation":-137.63016488740496,"angularVelocity":0.32576563062493424,"angularAcceleration":-1.3469717911293257,"curveRadius":2.539745654464776},{"acceleration":-2.9411833296679957,"curvature":0.3915627315729146,"pose":{"rotation":{"radians":-2.527501014926532},"translation":{"x":1.5052218774646673,"y":1.4244669871166935}},"time":3.631580815883028,"velocity":0.7929702038897785,"position":7.199805268319068,"holonomicRotation":-137.62028919938948,"angularVelocity":0.31191012452718164,"angularAcceleration":-1.327382318439942,"curveRadius":2.553869199918444},{"acceleration":-2.9365272904644146,"curvature":0.3893668666712538,"pose":{"rotation":{"radians":-2.5242566684063723},"translation":{"x":1.4984586981624228,"y":1.419665840901231}},"time":3.642480244807186,"velocity":0.7609637334035108,"position":7.2080993384451615,"holonomicRotation":-137.610413511374,"angularVelocity":0.2976620649333955,"angularAcceleration":-1.3072299193773231,"curveRadius":2.5682719450402276},{"acceleration":-2.931044938108739,"curvature":0.38715329124479925,"pose":{"rotation":{"radians":-2.5210239047186285},"translation":{"x":1.4916971756098376,"y":1.4148329211089596}},"time":3.653904863944492,"velocity":0.7274776613112892,"position":7.216410493656541,"holonomicRotation":-137.6005378233585,"angularVelocity":0.2829646790751649,"angularAcceleration":-1.286466155378204,"curveRadius":2.58295621557223},{"acceleration":-2.9244927271735484,"curvature":0.3849226738990748,"pose":{"rotation":{"radians":-2.51780286421748},"translation":{"x":1.4849372168463921,"y":1.4099681446898726}},"time":3.6659350613467008,"velocity":0.6922954365020682,"position":7.224738944418309,"holonomicRotation":-137.590662135343,"angularVelocity":0.26774627160791564,"angularAcceleration":-1.2650172693305441,"curveRadius":2.597924382761084},{"acceleration":-2.91652074560379,"curvature":0.3826756805675985,"pose":{"rotation":{"radians":-2.514593684151344},"translation":{"x":1.4781787289115664,"y":1.4050714285939632}},"time":3.6786742295935277,"velocity":0.6551413880284602,"position":7.2330849007858635,"holonomicRotation":-137.5807864473275,"angularVelocity":0.25191441104760737,"angularAcceleration":-1.2427703483900232,"curveRadius":2.6131788634092548},{"acceleration":-2.906607318203407,"curvature":0.3804129740781095,"pose":{"rotation":{"radians":-2.511396498659884},"translation":{"x":1.4714216188448406,"y":1.4001426897712246}},"time":3.692259223872293,"velocity":0.6156551442400494,"position":7.241448572398057,"holonomicRotation":-137.57091075931203,"angularVelocity":0.23534684121712082,"angularAcceleration":-1.2195492681497284,"curveRadius":2.628722120804092},{"acceleration":-2.8939383573289588,"curvature":0.37813521391028243,"pose":{"rotation":{"radians":-2.50821143877258},"translation":{"x":1.4646657936856937,"y":1.39518184517165}},"time":3.7068778698912763,"velocity":0.5733496837934996,"position":7.24983016847053,"holonomicRotation":-137.56103507129654,"angularVelocity":0.21787653132637747,"angularAcceleration":-1.19507031417664,"curveRadius":2.6445566644244436},{"acceleration":-2.877167682092558,"curvature":0.37584305564733617,"pose":{"rotation":{"radians":-2.5050386324086027},"translation":{"x":1.4579111604736072,"y":1.390188811745233}},"time":3.722800381952552,"velocity":0.5275379466730679,"position":7.258229897789213,"holonomicRotation":-137.55115938328103,"angularVelocity":0.1992654395089761,"angularAcceleration":-1.168853994004142,"curveRadius":2.6606850518433616},{"acceleration":-2.8538928516985065,"curvature":0.37353715105395957,"pose":{"rotation":{"radians":-2.5018782043787233},"translation":{"x":1.45115762624806,"y":1.3851635064419667}},"time":3.7404411930861134,"velocity":0.4771929618808338,"position":7.266647968704017,"holonomicRotation":-137.54128369526555,"angularVelocity":0.17915434874004832,"angularAcceleration":-1.1400320890385145,"curveRadius":2.6771098863350926},{"acceleration":-2.81934820881874,"curvature":0.37121814728940666,"pose":{"rotation":{"radians":-2.4987302763877923},"translation":{"x":1.444405098048533,"y":1.3801058462118447}},"time":3.7604974727880873,"velocity":0.4206473256275061,"position":7.27508458912269,"holonomicRotation":-137.53140800725006,"angularVelocity":0.1569547312715822,"angularAcceleration":-1.1068661685188461,"curveRadius":2.6938338206305055},{"acceleration":-2.7624488344088847,"curvature":0.3688866871810081,"pose":{"rotation":{"radians":-2.4955949670393722},"translation":{"x":1.4376534829145053,"y":1.3750157480048595}},"time":3.7843276817700167,"velocity":0.3548175926016553,"position":7.283539966504852,"holonomicRotation":-137.52153231923458,"angularVelocity":0.13156868875122474,"angularAcceleration":-1.0652882876355771,"curveRadius":2.71085955321915},{"acceleration":-2.6490382965491235,"curvature":0.3665434083232514,"pose":{"rotation":{"radians":-2.492472391841525},"translation":{"x":1.430902687885457,"y":1.3698931287710052}},"time":3.8154365782969952,"velocity":0.27240893433830504,"position":7.292014307856207,"holonomicRotation":-137.51165663121907,"angularVelocity":0.10037563354712471,"angularAcceleration":-1.0027052929070779,"curveRadius":2.7281898331618852},{"acceleration":-2.1201230094984758,"curvature":0.3665434083232514,"pose":{"rotation":{"radians":-2.489362663213364},"translation":{"x":1.4241526200008687,"y":1.3647379054602746}},"time":3.890685108146272,"velocity":0.11287279477392073,"position":7.300507819722924,"holonomicRotation":-137.50178094320358,"angularVelocity":0.04132610476762181,"angularAcceleration":-0.7847266770231861,"curveRadius":2.7281898331618852},{"acceleration":-0.0,"curvature":0.8310381791117515,"pose":{"rotation":{"radians":-2.4883302541401253},"translation":{"x":1.4174031863002212,"y":1.359549995022662}},"time":3.890685108146272,"velocity":0,"position":-0.0,"holonomicRotation":-137.4919052551881,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":1.2033141498611315},{"acceleration":-1.5,"curvature":0.8310381791117515,"pose":{"rotation":{"radians":-2.4883302541401253},"translation":{"x":1.4241912703385033,"y":1.3647453569033579}},"time":3.966175026231804,"velocity":-0.11323487712829851,"position":-0.008548091598840573,"holonomicRotation":-137.56787380398205,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":1.2033141498611315},{"acceleration":-5.102999518119493,"curvature":0.8118274928819394,"pose":{"rotation":{"radians":-2.495455235183698},"translation":{"x":1.4310568871041398,"y":1.3699229066528429}},"time":3.997602973018597,"velocity":-0.27361167443678586,"position":-0.017147144743285082,"holonomicRotation":-137.643842352776,"angularVelocity":-0.22670844811812446,"angularAcceleration":-7.213593991873429,"curveRadius":1.2317887836614887},{"acceleration":-3.4460989983865495,"curvature":0.7931173248407836,"pose":{"rotation":{"radians":-2.502456902081079},"translation":{"x":1.4379995263598728,"y":1.3750826854853844}},"time":4.021826776750716,"velocity":-0.35708930021515334,"position":-0.02579720586653666,"holonomicRotation":-137.71981090156996,"angularVelocity":-0.28904077059117866,"angularAcceleration":-2.5731847550600078,"curveRadius":1.260847504750634},{"acceleration":-3.271426258731833,"curvature":0.7748964493704271,"pose":{"rotation":{"radians":-2.509337669264867},"translation":{"x":1.445018677868444,"y":1.3802247346152505}},"time":4.042338895400346,"velocity":-0.42419318378777726,"position":-0.03449830678275603,"holonomicRotation":-137.7957794503639,"angularVelocity":-0.3354488778716089,"angularAcceleration":-2.26247264230145,"curveRadius":1.2904950084781788},{"acceleration":-3.1951291717382193,"curvature":0.7571536135759012,"pose":{"rotation":{"radians":-2.516099916461286},"translation":{"x":1.4521138313925954,"y":1.3853490952567085}},"time":4.06048982955181,"velocity":-0.4821877629894183,"position":-0.04325046511741853,"holonomicRotation":-137.87174799915786,"angularVelocity":-0.37255642822514196,"angularAcceleration":-2.0443879110508925,"curveRadius":1.320735953800945},{"acceleration":-3.151963943987217,"curvature":0.7398775705342209,"pose":{"rotation":{"radians":-2.5227459876166383},"translation":{"x":1.4592844766950692,"y":1.3904558086240255}},"time":4.076971061679359,"velocity":-0.5341360124079377,"position":-0.052053684725597356,"holonomicRotation":-137.9477165479518,"angularVelocity":-0.4032508676485957,"angularAcceleration":-1.862387422609386,"curveRadius":1.3515749629738882},{"acceleration":-3.1241267774185633,"curvature":0.7230571093553998,"pose":{"rotation":{"radians":-2.5292781899948187},"translation":{"x":1.466530103538607,"y":1.39554491593147}},"time":4.0921926863302485,"velocity":-0.5816902975755965,"position":-0.060907956098357384,"holonomicRotation":-138.02368509674577,"angularVelocity":-0.42913963049263865,"angularAcceleration":-1.7007884137078542,"curveRadius":1.383016620763874},{"acceleration":-3.104667148908645,"curvature":0.7066810816559205,"pose":{"rotation":{"radians":-2.5356987934320534},"translation":{"x":1.4738502016859512,"y":1.400616458393309}},"time":4.106421454577834,"velocity":-0.6258658869233094,"position":-0.06981325675745864,"holonomicRotation":-138.09965364553972,"angularVelocity":-0.451240987660635,"angularAcceleration":-1.5532867486085378,"curveRadius":1.4150654743109354},{"acceleration":-3.0902945538353848,"curvature":0.6907384251512971,"pose":{"rotation":{"radians":-2.5420100297349806},"translation":{"x":1.4812442608998428,"y":1.4056704772238104}},"time":4.119842334577646,"velocity":-0.6673403592944053,"position":-0.07876955163857999,"holonomicRotation":-138.17562219433367,"angularVelocity":-0.4702550282109515,"angularAcceleration":-1.4167506564832926,"curveRadius":1.4477260328770087},{"acceleration":-3.0792455117047175,"curvature":0.6752181844826326,"pose":{"rotation":{"radians":-2.548214092212237},"translation":{"x":1.4887117709430246,"y":1.4107070136372415}},"time":4.132589763555921,"velocity":-0.7065928227615346,"position":-0.08777679346329181,"holonomicRotation":-138.25159074312762,"angularVelocity":-0.4866912761647649,"angularAcceleration":-1.28937748794871,"curveRadius":1.4810027676701607},{"acceleration":-3.070488550221279,"curvature":0.6601095296661285,"pose":{"rotation":{"radians":-2.5543131353257866},"translation":{"x":1.4962522215782383,"y":1.4157261088478705}},"time":4.14476504714186,"velocity":-0.7439768916078553,"position":-0.09683492310000236,"holonomicRotation":-138.32755929192157,"angularVelocity":-0.5009364316239396,"angularAcceleration":-1.170006050259642,"curveRadius":1.5149001113584621},{"acceleration":-3.063379620195275,"curvature":0.6454017716579872,"pose":{"rotation":{"radians":-2.560309274454153},"translation":{"x":1.503865102568226,"y":1.4207278040699645}},"time":4.1564467430927285,"velocity":-0.7797623609130645,"position":-0.10594386991412041,"holonomicRotation":-138.40352784071553,"angularVelocity":-0.5132935451825652,"angularAcceleration":-1.0578184546659521,"curveRadius":1.5494224588678729},{"acceleration":-3.0574956113009044,"curvature":0.6310843766219002,"pose":{"rotation":{"radians":-2.56620458575509},"translation":{"x":1.5115499036757294,"y":1.425712140517791}},"time":4.167697204281296,"velocity":-0.8141605966222233,"position":-0.11510355210768036,"holonomicRotation":-138.47949638950948,"angularVelocity":-0.524006189802024,"angularAcceleration":-0.9521960424470384,"curveRadius":1.5845741663782735},{"acceleration":-3.052547000603346,"curvature":0.6171469773527858,"pose":{"rotation":{"radians":-2.5720011061206494},"translation":{"x":1.5193061146634903,"y":1.4306791594056179}},"time":4.178566886021235,"velocity":-0.8473408110149837,"position":-0.12431387704867411,"holonomicRotation":-138.55546493830343,"angularVelocity":-0.5332741568928708,"angularAcceleration":-0.852643831952693,"curveRadius":1.62035955241884},{"acceleration":-3.0483289399796614,"curvature":0.6035793837306891,"pose":{"rotation":{"radians":-2.5777008332148297},"translation":{"x":1.5271332252942513,"y":1.4356289019477129}},"time":4.189097285724362,"velocity":-0.879440933179579,"position":-0.1335747415903461,"holonomicRotation":-138.63143348709738,"angularVelocity":-0.5412640787498096,"angularAcceleration":-0.7587482035051513,"curveRadius":1.6567828970881313},{"acceleration":-3.044692383474272,"curvature":0.5903715907204926,"pose":{"rotation":{"radians":-2.5833057255861833},"translation":{"x":1.5350307253307536,"y":1.4405614093583432}},"time":4.199323010744875,"velocity":-0.910575120265038,"position":-0.14288603238069714,"holonomicRotation":-138.70740203589133,"angularVelocity":-0.5481168680078918,"angularAcceleration":-0.6701519202144804,"curveRadius":1.693848443451682},{"acceleration":-3.041526282138921,"curvature":0.5775137858113584,"pose":{"rotation":{"radians":-2.5888177028480914},"translation":{"x":1.5429981045357395,"y":1.4454767228517769}},"time":4.209273270891909,"velocity":-0.9408390980163643,"position":-0.1522476261624617,"holonomicRotation":-138.7833705846853,"angularVelocity":-0.5539530806690102,"angularAcceleration":-0.5865387009863687,"curveRadius":1.731560396597432},{"acceleration":-3.0387461914239458,"curvature":0.564996354247177,"pose":{"rotation":{"radians":-2.5942386459197344},"translation":{"x":1.5510348526719508,"y":1.450374883642281}},"time":4.218972979852188,"velocity":-0.970314051677329,"position":-0.16165939006379967,"holonomicRotation":-138.85933913347924,"angularVelocity":-0.5588768790736758,"angularAcceleration":-0.5076233137333882,"curveRadius":1.7699229251353996},{"acceleration":-3.0362867479646702,"curvature":0.5528098836930215,"pose":{"rotation":{"radians":-2.5995703973211826},"translation":{"x":1.5591404595021296,"y":1.4552559329441235}},"time":4.228443583865205,"velocity":-0.9990695211372734,"position":-0.17112118187996528,"holonomicRotation":-138.9353076822732,"angularVelocity":-0.5629790237370148,"angularAcceleration":-0.43314498818668684,"curveRadius":1.8089401609818279},{"acceleration":-3.0340965639568904,"curvature":0.5409451675109106,"pose":{"rotation":{"radians":-2.6048147615172828},"translation":{"x":1.5673144147890177,"y":1.460119911971572}},"time":4.237703695877244,"velocity":-1.027165595174856,"position":-0.18063285034619683,"holonomicRotation":-139.01127623106714,"angularVelocity":-0.56633917486983,"angularAcceleration":-0.3628629036502784,"curveRadius":1.848616200051053},{"acceleration":-3.0321346784675205,"curvature":0.5293932071393094,"pose":{"rotation":{"radians":-2.6099735053042505},"translation":{"x":1.5755562082953574,"y":1.4649668619388938}},"time":4.2467695881994185,"velocity":-1.0546546016761766,"position":-0.19019423540207991,"holonomicRotation":-139.0872447798611,"angularVelocity":-0.569027692326472,"angularAcceleration":-0.2965529879574899,"curveRadius":1.8889551027745823},{"acceleration":-3.030368038323862,"curvature":0.5181452134295963,"pose":{"rotation":{"radians":-2.6150483582341044},"translation":{"x":1.58386532978389,"y":1.4697968240603567}},"time":4.255655580420058,"velocity":-1.081582428490396,"position":-0.1998051684476256,"holonomicRotation":-139.16321332865505,"angularVelocity":-0.5711070642248253,"angularAcceleration":-0.2340055951797474,"curveRadius":1.929960895288433},{"acceleration":-3.028769676047538,"curvature":0.5071926075924633,"pose":{"rotation":{"radians":-2.6200410130729},"translation":{"x":1.5922412690173577,"y":1.4746098395502285}},"time":4.264374348550925,"velocity":-1.1079895690176567,"position":-0.20946547259131015,"holonomicRotation":-139.239181877449,"angularVelocity":-0.5726330559382696,"angularAcceleration":-0.17502377520992343,"curveRadius":1.9716375692989487},{"acceleration":-3.0273173696452025,"curvature":0.49652702106977,"pose":{"rotation":{"radians":-2.6249531262876022},"translation":{"x":1.600683515758503,"y":1.479405949622777}},"time":4.2729371741012825,"velocity":-1.1339119595394944,"position":-0.2191749628903104,"holonomicRotation":-139.31515042624295,"angularVelocity":-0.5736556450688451,"angularAcceleration":-0.11942192732548064,"curveRadius":2.0139890833040566},{"acceleration":-3.0259926418226235,"curvature":0.48614029485754046,"pose":{"rotation":{"radians":-2.629786318558182},"translation":{"x":1.609191559770067,"y":1.4841851954922691}},"time":4.2813541467481455,"velocity":-1.159381656835324,"position":-0.22893344658316794,"holonomicRotation":-139.3911189750369,"angularVelocity":-0.5742197905776631,"angularAcceleration":-0.06702475254309703,"curveRadius":2.0570193637066065},{"acceleration":-3.0247800023535545,"curvature":0.4760244785209588,"pose":{"rotation":{"radians":-2.634542175311472},"translation":{"x":1.6177648908147924,"y":1.4889476183729728}},"time":4.289634330742432,"velocity":-1.1844273917970505,"position":-0.2387407233151207,"holonomicRotation":-139.46708752383086,"angularVelocity":-0.5743660716442857,"angularAcceleration":-0.01766640291126907,"curveRadius":2.100732305000511},{"acceleration":-3.023666367343749,"curvature":0.4661718283460194,"pose":{"rotation":{"radians":-2.639222247272973},"translation":{"x":1.6264029986554203,"y":1.4936932594791557}},"time":4.297785902672896,"velocity":-1.2090750256841774,"position":-0.24859658535631268,"holonomicRotation":-139.5430560726248,"angularVelocity":-0.5741312229621054,"angularAcceleration":0.02881023245376712,"curveRadius":2.145131771578747},{"acceleration":-3.022640608993353,"curvature":0.4565748054382834,"pose":{"rotation":{"radians":-2.6438280510343506},"translation":{"x":1.6351053730546934,"y":1.498422160025085}},"time":4.3058162663867465,"velocity":-1.2333479291506493,"position":-0.258500817813117,"holonomicRotation":-139.61902462141876,"angularVelocity":-0.5735485870252146,"angularAcceleration":0.07255411556090005,"curveRadius":2.190221598057874},{"acceleration":-3.02169320286892,"curvature":0.44722607320956886,"pose":{"rotation":{"radians":-2.6483610696328963},"translation":{"x":1.6438715037753533,"y":1.503134361225029}},"time":4.313732149528019,"velocity":-1.2572672994333383,"position":-0.2684531988327751,"holonomicRotation":-139.6949931702127,"angularVelocity":-0.5726484989287994,"angularAcceleration":0.11370659222117296,"curveRadius":2.2360055906923897},{"acceleration":-3.0208159488924236,"curvature":0.4381184946045422,"pose":{"rotation":{"radians":-2.6528227531415296},"translation":{"x":1.652700880580142,"y":1.507829904293255}},"time":4.321539685160815,"velocity":-1.2808524275944329,"position":-0.27845349980157125,"holonomicRotation":-139.77096171900666,"angularVelocity":-0.5714586161979225,"angularAcceleration":0.15240183162006318,"curveRadius":2.2824875286368074},{"acceleration":-3.0200017486908943,"curvature":0.42924512914903873,"pose":{"rotation":{"radians":-2.6572145192661982},"translation":{"x":1.661592993231801,"y":1.5125088304440304}},"time":4.329244481197586,"velocity":-1.3041209250987877,"position":-0.28850148553674243,"holonomicRotation":-139.84693026780062,"angularVelocity":-0.5700042030585938,"angularAcceleration":0.18876724735963873,"curveRadius":2.3296711647781767},{"acceleration":-3.019244426412897,"curvature":0.4205992295525542,"pose":{"rotation":{"radians":-2.661537753948937},"translation":{"x":1.6705473314930732,"y":1.517171180891623}},"time":4.336851679785406,"velocity":-1.327088917035679,"position":-0.29859691447232767,"holonomicRotation":-139.92289881659457,"angularVelocity":-0.5683083769708518,"angularAcceleration":0.2229238619400879,"curveRadius":2.377560227734676},{"acceleration":-3.01853858347197,"curvature":0.4121742385098269,"pose":{"rotation":{"radians":-2.6657938119748072},"translation":{"x":1.6795633851266996,"y":1.5218169968503004}},"time":4.344366008368108,"velocity":-1.349771207791452,"position":-0.30873953883914357,"holonomicRotation":-139.99886736538852,"angularVelocity":-0.5663923235493636,"angularAcceleration":0.25498664323767206,"curveRadius":2.4261584217766643},{"acceleration":-3.017879479911495,"curvature":0.4039637846678405,"pose":{"rotation":{"radians":-2.669984017580968},"translation":{"x":1.688640643895423,"y":1.52644631953433}},"time":4.35179182380552,"velocity":-1.3721814238216288,"position":-0.31892910483908865,"holonomicRotation":-140.07483591418247,"angularVelocity":-0.564275484824204,"angularAcceleration":0.28506481786427457,"curveRadius":2.4754694305635607},{"acceleration":-3.017262936859282,"curvature":0.3959616793303406,"pose":{"rotation":{"radians":-2.6741096650659943},"translation":{"x":1.6977785975619843,"y":1.5310591901579798}},"time":4.359133150668204,"velocity":-1.3943321372717739,"position":-0.32916535281394516,"holonomicRotation":-140.1508044629764,"angularVelocity":-0.5619757248511885,"angularAcceleration":0.31326216854683736,"curveRadius":2.5254969159925342},{"acceleration":-3.0166852558674924,"curvature":0.3881619122187696,"pose":{"rotation":{"radians":-2.67817201939875},"translation":{"x":1.7069767358891264,"y":1.5356556499355172}},"time":4.366393714619375,"velocity":-1.4162349734925523,"position":-0.3394480174088718,"holonomicRotation":-140.22677301177035,"angularVelocity":-0.5595094761338774,"angularAcceleration":0.3396772942015933,"curveRadius":2.5762445219931727},{"acceleration":-3.0161431517698722,"curvature":0.3805586478401916,"pose":{"rotation":{"radians":-2.6821723168248703},"translation":{"x":1.716234548639591,"y":1.5402357400812094}},"time":4.373576971631773,"velocity":-1.437900704937901,"position":-0.3497768277307497,"holonomicRotation":-140.3027415605643,"angularVelocity":-0.5568918694146087,"angularAcceleration":0.3644038790134676,"curveRadius":2.6277158742163995},{"acceleration":-3.0156336965144455,"curvature":0.37314622124548535,"pose":{"rotation":{"radians":-2.686111765469967},"translation":{"x":1.7255515255761193,"y":1.544799501809325}},"time":4.380686133656463,"velocity":-1.4593393334935358,"position":-0.36015150750155783,"holonomicRotation":-140.37871010935825,"angularVelocity":-0.5541368492397702,"angularAcceleration":0.38753093054714727,"curveRadius":2.679914583248909},{"acceleration":-3.0151542719181434,"curvature":0.36591913409438187,"pose":{"rotation":{"radians":-2.6899915459393715},"translation":{"x":1.7349271564614546,"y":1.5493469763341305}},"time":4.387724191255397,"velocity":-1.4805601629289673,"position":-0.37057177520693885,"holonomicRotation":-140.4546786581522,"angularVelocity":-0.5512572772908717,"angularAcceleration":0.4091429927107633,"curveRadius":2.7328442456962883},{"acceleration":-3.0147025297547816,"curvature":0.35887205058203214,"pose":{"rotation":{"radians":-2.693812811911486},"translation":{"x":1.7443609310583374,"y":1.553878204869894}},"time":4.39469393362463,"velocity":-1.5015718628812362,"position":-0.3810373442401119,"holonomicRotation":-140.53064720694616,"angularVelocity":-0.5482650246847446,"angularAcceleration":0.42932040348228345,"curveRadius":2.7865084460552514},{"acceleration":-3.01427635782862,"curvature":0.3519997934321967,"pose":{"rotation":{"radians":-2.697576690726803},"translation":{"x":1.7538523391295109,"y":1.558393228630883}},"time":4.401597966365944,"velocity":-1.5223825255470531,"position":-0.3915479230412927,"holonomicRotation":-140.6066157557401,"angularVelocity":-0.5451710552868705,"angularAcceleration":0.44813944455387017,"curveRadius":2.8409107580701556},{"acceleration":-3.013873851101254,"curvature":0.34529733959401937,"pose":{"rotation":{"radians":-2.7012842839690983},"translation":{"x":1.763400870437716,"y":1.5628920888313655}},"time":4.408438727308102,"velocity":-1.5429997160722573,"position":-0.4021032152327604,"holonomicRotation":-140.68258430453406,"angularVelocity":-0.541985500391671,"angularAcceleration":0.4656725943407434,"curveRadius":2.896054748570441},{"acceleration":-3.0134932868998336,"curvature":0.33875981652393444,"pose":{"rotation":{"radians":-2.7049366680405194},"translation":{"x":1.7730060147456954,"y":1.5673748266856087}},"time":4.4152185006325375,"velocity":-1.5634305174721448,"position":-0.41270291974972567,"holonomicRotation":-140.758552853328,"angularVelocity":-0.5387177264846775,"angularAcceleration":0.48198866696857035,"curveRadius":2.95194397688944},{"acceleration":-3.0131331036485256,"curvature":0.3323824979499578,"pose":{"rotation":{"radians":-2.708534894728018},"translation":{"x":1.7826672618161907,"y":1.5718414834078804}},"time":4.4219394295198375,"velocity":-1.5836815707897365,"position":-0.42334673096713127,"holonomicRotation":-140.83452140212196,"angularVelocity":-0.5353763963040836,"angularAcceleration":0.4971530329546679,"curveRadius":3.008581998654322},{"acceleration":-3.0127918825062667,"curvature":0.3261607999298764,"pose":{"rotation":{"radians":-2.7120799917626366},"translation":{"x":1.7923841014119437,"y":1.576292100212448}},"time":4.4286035275015525,"velocity":-1.6037591110932754,"position":-0.43403433882252584,"holonomicRotation":-140.91048995091592,"angularVelocity":-0.531969524509582,"angularAcceleration":0.5112277466281471,"curveRadius":3.0659723676634254},{"acceleration":-3.0124683314328493,"curvature":0.32009027683754554,"pose":{"rotation":{"radians":-2.715572963369501},"translation":{"x":1.8021560232956968,"y":1.580726718313579}},"time":4.435212688675266,"velocity":-1.6236689998264218,"position":-0.44476542893514026,"holonomicRotation":-140.98645849970987,"angularVelocity":-0.5285045280416338,"angularAcceleration":0.5242717459712802,"curveRadius":3.1241186389036333},{"acceleration":-3.0121612714008164,"curvature":0.3141666176980434,"pose":{"rotation":{"radians":-2.7190147908093913},"translation":{"x":1.8119825172301915,"y":1.5851453789255414}},"time":4.441768696918604,"velocity":-1.643416753951991,"position":-0.4555396827212904,"holonomicRotation":-141.06242704850382,"angularVelocity":-0.5249882721528795,"angularAcceleration":0.5363409804017724,"curveRadius":3.1830243688116324},{"acceleration":-3.0118696243216303,"curvature":0.3083856421483242,"pose":{"rotation":{"radians":-2.722406432911279},"translation":{"x":1.8218630729781702,"y":1.5895481232626025}},"time":4.448273234219172,"velocity":-1.6630075722678381,"position":-0.4663567775062332,"holonomicRotation":-141.13839559729777,"angularVelocity":-0.5214271123622819,"angularAcceleration":0.5474885646803379,"curveRadius":3.2426931196719924},{"acceleration":-3.011592402513638,"curvature":0.3027432967546087,"pose":{"rotation":{"radians":-2.7257488265950127},"translation":{"x":1.8317971803023743,"y":1.59393499253903}},"time":4.45472788822156,"velocity":-1.6824463592222847,"position":-0.4772163866325908,"holonomicRotation":-141.21436414609173,"angularVelocity":-0.5178269327057488,"angularAcceleration":0.5577649328997473,"curveRadius":3.3031284613728675},{"acceleration":-3.011328699439457,"curvature":0.29723565127489376,"pose":{"rotation":{"radians":-2.729042887385083},"translation":{"x":1.841784328965546,"y":1.598306027969092}},"time":4.461134159079225,"velocity":-1.7017377465123509,"position":-0.48811817956545966,"holonomicRotation":-141.29033269488568,"angularVelocity":-0.5141931809095223,"angularAcceleration":0.5672179458162218,"curveRadius":3.3643339744436163},{"acceleration":-3.0110776816198803,"curvature":0.2918588950449754,"pose":{"rotation":{"radians":-2.73228950991446},"translation":{"x":1.8518240087304272,"y":1.602661270767055}},"time":4.467493465687614,"velocity":-1.7208861127114512,"position":-0.4990618219943118,"holonomicRotation":-141.36630124367963,"angularVelocity":-0.5105309005063529,"angularAcceleration":0.5758930381400044,"curveRadius":3.426313252662387},{"acceleration":-3.0108385813967287,"curvature":0.2866093334580404,"pose":{"rotation":{"radians":-2.7354895684183345},"translation":{"x":1.86191570935976,"y":1.6070007621471873}},"time":4.473807151365242,"velocity":-1.7398956011404656,"position":-0.5100469759318004,"holonomicRotation":-141.44226979247358,"angularVelocity":-0.5068447602979985,"angularAcceleration":0.5838333418174181,"curveRadius":3.4890699054865215},{"acceleration":-3.0106106906628622,"curvature":0.2814833845422383,"pose":{"rotation":{"radians":-2.7386439172187593},"translation":{"x":1.8720589206162859,"y":1.6113245433237566}},"time":4.480076489041042,"velocity":-1.758770136170602,"position":-0.5210732998095652,"holonomicRotation":-141.51823834126753,"angularVelocity":-0.5031390815972865,"angularAcceleration":0.5910797746652966,"curveRadius":3.552607560216201},{"acceleration":-3.0103933551810527,"curvature":0.2764775753092318,"pose":{"rotation":{"radians":-2.7417533911987486},"translation":{"x":1.8822531322627476,"y":1.6156326555110305}},"time":4.486302685999236,"velocity":-1.777513438121599,"position":-0.5321404485711475,"holonomicRotation":-141.59420689006149,"angularVelocity":-0.49941786308203256,"angularAcceleration":0.597671185193777,"curveRadius":3.6169298681150917},{"acceleration":-3.0101859696135196,"curvature":0.27158853875182865,"pose":{"rotation":{"radians":-2.7448188062667516},"translation":{"x":1.8924978340618865,"y":1.619925139923276}},"time":4.492486888226778,"velocity":-1.7961290369001985,"position":-0.5432480737620986,"holonomicRotation":-141.67017543885544,"angularVelocity":-0.4956848038297964,"angularAcceleration":0.6036444338140459,"curveRadius":3.682040503608206},{"acceleration":-3.00998797307911,"curvature":0.26681301040133554,"pose":{"rotation":{"radians":-2.7478409598110387},"translation":{"x":1.9027925157764443,"y":1.6242020377747615}},"time":4.498630184403104,"velocity":-1.8146202845060018,"position":-0.5543958236173874,"holonomicRotation":-141.7461439876494,"angularVelocity":-0.49194332448654493,"angularAcceleration":0.6090345045824003,"curveRadius":3.74794316999691},{"acceleration":-3.0097988451622344,"curvature":0.262147825249249,"pose":{"rotation":{"radians":-2.7508206311448955},"translation":{"x":1.9131366671691639,"y":1.6284633902797538}},"time":4.50473360956734,"velocity":-1.8329903665168534,"position":-0.5655833431461885,"holonomicRotation":-141.82211253644334,"angularVelocity":-0.4881965869454173,"angularAcceleration":0.613874577029673,"curveRadius":3.8146416017344578},{"acceleration":-3.009618102370767,"curvature":0.25758991459526304,"pose":{"rotation":{"radians":-2.7537585819407013},"translation":{"x":1.923529778002786,"y":1.6327092386525213}},"time":4.510798148494098,"velocity":-1.851242312653359,"position":-0.5768102742141379,"holonomicRotation":-141.8980810852373,"angularVelocity":-0.48444751221606924,"angularAcceleration":0.6181961686824748,"curveRadius":3.882139568900612},{"acceleration":-3.0094452949405475,"curvature":0.25313630315993346,"pose":{"rotation":{"radians":-2.7566555566558284},"translation":{"x":1.9339713380400536,"y":1.6369396241073313}},"time":4.516824738805519,"velocity":-1.8693790065105964,"position":-0.5880762556231467,"holonomicRotation":-141.97404963403125,"angularVelocity":-0.48069879740082194,"angularAcceleration":0.6220291444307561,"curveRadius":3.950440879150362},{"acceleration":-3.0092800040168353,"curvature":0.24878410597410236,"pose":{"rotation":{"radians":-2.7595122829476084},"translation":{"x":1.944460837043708,"y":1.641154587858451}},"time":4.52281427384415,"velocity":-1.8874031945357088,"position":-0.5993809231888436,"holonomicRotation":-142.0500181828252,"angularVelocity":-0.4769529309628452,"angularAcceleration":0.6254018740714347,"curveRadius":4.019549384332843},{"acceleration":-3.0091218389795715,"curvature":0.24453052576716422,"pose":{"rotation":{"radians":-2.762329472079346},"translation":{"x":1.9549977647764913,"y":1.6453541711201485}},"time":4.5287676053286425,"velocity":-1.9053174943203786,"position":-0.6107239098157347,"holonomicRotation":-142.12598673161915,"angularVelocity":-0.4732122071610188,"angularAcceleration":0.6283412592714954,"curveRadius":4.08946898086734},{"acceleration":-3.0089704352560642,"curvature":0.24037285017620957,"pose":{"rotation":{"radians":-2.765107819316829},"translation":{"x":1.9655816110011457,"y":1.6495384151066914}},"time":4.53468554581183,"velocity":-1.9231244022718967,"position":-0.6221048455701466,"holonomicRotation":-142.2019552804131,"angularVelocity":-0.46947873933097756,"angularAcceleration":0.6308728248699657,"curveRadius":4.16020361395612},{"acceleration":-3.0088254521125974,"curvature":0.23630844880396823,"pose":{"rotation":{"radians":-2.7678480043153906},"translation":{"x":1.9762118654804126,"y":1.653707361032347}},"time":4.540568870958787,"velocity":-1.9408263007171154,"position":-0.6335233577510313,"holonomicRotation":-142.27792382920705,"angularVelocity":-0.4657544721931247,"angularAcceleration":0.6330207909347076,"curveRadius":4.231757286128855},{"acceleration":-3.0086865708141506,"curvature":0.23233477094635704,"pose":{"rotation":{"radians":-2.770550691497686},"translation":{"x":1.9868880179770345,"y":1.6578610501113829}},"time":4.546418321660581,"velocity":-1.9584254644902397,"position":-0.6449790709587032,"holonomicRotation":-142.353892378001,"angularVelocity":-0.462041193281069,"angularAcceleration":0.6348081386372604,"curveRadius":4.304134055900253},{"acceleration":-3.008553492893382,"curvature":0.22844934290665303,"pose":{"rotation":{"radians":-2.7732165304225305},"translation":{"x":1.9976095582537532,"y":1.6619995235580671}},"time":4.552234605997879,"velocity":-1.9759240670488796,"position":-0.6564716071615704,"holonomicRotation":-142.42986092679496,"angularVelocity":-0.45834054359228893,"angularAcceleration":0.6362566673449566,"curveRadius":4.377338044734982},{"acceleration":-3.0084259385814995,"curvature":0.22464976547450757,"pose":{"rotation":{"radians":-2.775846156144865},"translation":{"x":2.00837597607331,"y":1.6661228225866669}},"time":4.558018401067149,"velocity":-1.9933241861587108,"position":-0.6680005857609315,"holonomicRotation":-142.5058294755889,"angularVelocity":-0.45465402747517675,"angularAcceleration":0.6373870569341543,"curveRadius":4.451373442958151},{"acceleration":-3.0083036454198377,"curvature":0.2209337116976879,"pose":{"rotation":{"radians":-2.7784401895665964},"translation":{"x":2.019186761198448,"y":1.6702309884114501}},"time":4.563770354680915,"velocity":-2.010627809183288,"position":-0.679565623653901,"holonomicRotation":-142.58179802438286,"angularVelocity":-0.45098302175512667,"angularAcceleration":0.6382189368260136,"curveRadius":4.52624451160418},{"acceleration":-3.0081863669024864,"curvature":0.21729892447080926,"pose":{"rotation":{"radians":-2.780999237779176},"translation":{"x":2.0300414033919085,"y":1.674324062246684}},"time":4.569491086952448,"velocity":-2.0278368380112153,"position":-0.6911663352945171,"holonomicRotation":-142.65776657317681,"angularVelocity":-0.44732878434342443,"angularAcceleration":0.6387709192205238,"curveRadius":4.601955589220298},{"acceleration":-3.0080738714000375,"curvature":0.21374321433954377,"pose":{"rotation":{"radians":-2.783523894397389},"translation":{"x":2.0409393924164334,"y":1.6784020853066361}},"time":4.57518119177427,"velocity":-2.0449530936512637,"position":-0.7028023327531008,"holonomicRotation":-142.73373512197077,"angularVelocity":-0.44369246213723257,"angularAcceleration":0.6390606711227281,"curveRadius":4.678511096082988},{"acceleration":-3.0079659409706343,"curvature":0.21026445732287247,"pose":{"rotation":{"radians":-2.786014739884989},"translation":{"x":2.0518802180347646,"y":1.6824650988055747}},"time":4.580841238198941,"velocity":-2.061978320520987,"position":-0.7144732257739149,"holonomicRotation":-142.80970367076472,"angularVelocity":-0.44007509845557413,"angularAcceleration":0.6391049490143774,"curveRadius":4.755915539564758},{"acceleration":-3.007862370483943,"curvature":0.2068605928353229,"pose":{"rotation":{"radians":-2.7884723418722155},"translation":{"x":2.0628633700096444,"y":1.686513143957767}},"time":4.586471771729865,"velocity":-2.0789141904544017,"position":-0.7261786218311824,"holonomicRotation":-142.88567221955867,"angularVelocity":-0.4364776399481064,"angularAcceleration":0.638919649036756,"curveRadius":4.834173518955724},{"acceleration":-3.007762966623642,"curvature":0.2035296215025642,"pose":{"rotation":{"radians":-2.7908972554650138},"translation":{"x":2.0738883381038145,"y":1.6905462619774803}},"time":4.592073315529085,"velocity":-2.095762306449615,"position":-0.7379181261835137,"holonomicRotation":-142.96164076835262,"angularVelocity":-0.43290094297505305,"angularAcceleration":0.6385198618908535,"curveRadius":4.91328973452349},{"acceleration":-3.007667547144725,"curvature":0.20026960345444206,"pose":{"rotation":{"radians":-2.793290023546649},"translation":{"x":2.0849546120800166,"y":1.6945644940789824}},"time":4.597646371548446,"velocity":-2.112524206177468,"position":-0.7496913419267978,"holonomicRotation":-143.03760931714658,"angularVelocity":-0.4293457796444873,"angularAcceleration":0.6379198985645816,"curveRadius":4.993268987160516},{"acceleration":-3.0075759400735214,"curvature":0.19707865622424314,"pose":{"rotation":{"radians":-2.7956511770716155},"translation":{"x":2.0960616817009927,"y":1.6985678814765413}},"time":4.603191421589927,"velocity":-2.129201365268731,"position":-0.7614978700456032,"holonomicRotation":-143.11357786594053,"angularVelocity":-0.4258128434014659,"angularAcceleration":0.637133338129005,"curveRadius":5.074116188727024},{"acceleration":-3.007487983009977,"curvature":0.19395495283182415,"pose":{"rotation":{"radians":-2.7979812353520854},"translation":{"x":2.1072090367294853,"y":1.702556465384424}},"time":4.6087089283004214,"velocity":-2.145795200396719,"position":-0.7733373094631382,"holonomicRotation":-143.18954641473448,"angularVelocity":-0.4223027542564209,"angularAcceleration":0.6361730631643734,"curveRadius":5.15583637024772},{"acceleration":-3.007403522491753,"curvature":0.19089672027486715,"pose":{"rotation":{"radians":-2.8002807063365993},"translation":{"x":2.118396166928236,"y":1.7065302870168986}},"time":4.614199336105802,"velocity":-2.1623070721705373,"position":-0.7852092570898134,"holonomicRotation":-143.26551496352843,"angularVelocity":-0.41881606358280393,"angularAcceleration":0.635051310796964,"curveRadius":5.2384346811203795},{"acceleration":-3.007322413429215,"curvature":0.1879022374891784,"pose":{"rotation":{"radians":-2.802550086882171},"translation":{"x":2.1296225620599865,"y":1.7104893875882325}},"time":4.619663072088692,"velocity":-2.1787382878529433,"position":-0.7971133078704565,"holonomicRotation":-143.34148351232238,"angularVelocity":-0.4153532587735025,"angularAcceleration":0.6337796738614674,"curveRadius":5.32191640377668},{"acceleration":-3.007244518526438,"curvature":0.18496983388940508,"pose":{"rotation":{"radians":-2.8047898630189447},"translation":{"x":2.1408877118874785,"y":1.714433808312693}},"time":4.625100546813976,"velocity":-2.1950901039151787,"position":-0.8090490548302156,"holonomicRotation":-143.41745206111634,"angularVelocity":-0.4119147674119985,"angularAcceleration":0.6323691667963754,"curveRadius":5.406286954865883},{"acceleration":-3.007169707816434,"curvature":0.18209788763445509,"pose":{"rotation":{"radians":-2.8070005102080224},"translation":{"x":2.152191106173455,"y":1.7183635904045484}},"time":4.6305121551057615,"velocity":-2.211363728440804,"position":-0.8210160891191994,"holonomicRotation":-143.4934206099103,"angularVelocity":-0.408500961245359,"angularAcceleration":0.6308302416901629,"curveRadius":5.4915518954695886},{"acceleration":-3.0070978581300323,"curvature":0.1792848240913241,"pose":{"rotation":{"radians":-2.8091824935927816},"translation":{"x":2.163532234680657,"y":1.7222787750780657}},"time":4.635898276779196,"velocity":-2.2275603233886145,"position":-0.833014000055884,"holonomicRotation":-143.56938915870424,"angularVelocity":-0.40511215992788807,"angularAcceleration":0.6291728117071105,"curveRadius":5.577716937662387},{"acceleration":-3.007028852766777,"curvature":0.17652911428155954,"pose":{"rotation":{"radians":-2.8113362682433958},"translation":{"x":2.1749105871718273,"y":1.7261794035475129}},"time":4.641259277330255,"velocity":-2.243681006725347,"position":-0.8450423751693388,"holonomicRotation":-143.6453577074982,"angularVelocity":-0.401748634438919,"angularAcceleration":0.6274062942046814,"curveRadius":5.664787953362893},{"acceleration":-3.006962581011164,"curvature":0.17382927348897004,"pose":{"rotation":{"radians":-2.8134622793951882},"translation":{"x":2.186325653409707,"y":1.7300655170271568}},"time":4.646595508586383,"velocity":-2.259726854436148,"position":-0.8571008002402943,"holonomicRotation":-143.72132625629214,"angularVelocity":-0.39841061036301834,"angularAcceleration":0.62553962069521,"curveRadius":5.752770979989472},{"acceleration":-3.0068989377864126,"curvature":0.17118385966993377,"pose":{"rotation":{"radians":-2.815560962680398},"translation":{"x":2.197776923157038,"y":1.733937156731266}},"time":4.651907309320629,"velocity":-2.275698902421685,"position":-0.8691888593411004,"holonomicRotation":-143.7972948050861,"angularVelocity":-0.3950982708518073,"angularAcceleration":0.623581281928732,"curveRadius":5.841672234334117},{"acceleration":-3.006837823368411,"curvature":0.16859147229879434,"pose":{"rotation":{"radians":-2.8176327443544116},"translation":{"x":2.209263886176563,"y":1.7377943638741078}},"time":4.657195005831705,"velocity":-2.2915981482896806,"position":-0.8813061348745991,"holonomicRotation":-143.87326335388005,"angularVelocity":-0.3918117595580395,"angularAcceleration":0.621539319982509,"curveRadius":5.931498114137718},{"acceleration":-3.00677914297062,"curvature":0.16605075106714642,"pose":{"rotation":{"radians":-2.8196780415153797},"translation":{"x":2.2207860322310236,"y":1.74163717966995}},"time":4.662458912492231,"velocity":-2.307425553047096,"position":-0.8934522076119529,"holonomicRotation":-143.949231902674,"angularVelocity":-0.38855118315557907,"angularAcceleration":0.6194213941730967,"curveRadius":6.02225520555235},{"acceleration":-3.006722806530867,"curvature":0.16356037419261793,"pose":{"rotation":{"radians":-2.821697262318651},"translation":{"x":2.2323428510831613,"y":1.7454656453330595}},"time":4.667699332267237,"velocity":-2.3231820427004015,"position":-0.9056266567294586,"holonomicRotation":-144.02520045146795,"angularVelocity":-0.38531661392892297,"angularAcceleration":0.6172347570481543,"curveRadius":6.113950306951142},{"acceleration":-3.0066687284017584,"curvature":0.16111905758853928,"pose":{"rotation":{"radians":-2.8236908061850245},"translation":{"x":2.2439338324957188,"y":1.749279802077704}},"time":4.67291655720483,"velocity":-2.338868509769299,"position":-0.917829059844377,"holonomicRotation":-144.1011690002619,"angularVelocity":-0.38210809198755746,"angularAcceleration":0.6149863154733053,"curveRadius":6.206590424292129},{"acceleration":-3.006616827103603,"curvature":0.15872555351383286,"pose":{"rotation":{"radians":-2.825659064003803},"translation":{"x":2.255558466231437,"y":1.7530796911181519}},"time":4.6781108689008155,"velocity":-2.3544858147196717,"position":-0.9300589930498087,"holonomicRotation":-144.17713754905586,"angularVelocity":-0.37892562748968367,"angularAcceleration":0.6126826197844594,"curveRadius":6.300182786339128},{"acceleration":-3.0065670250679015,"curvature":0.15637864939159882,"pose":{"rotation":{"radians":-2.8276024183306245},"translation":{"x":2.2672162420530593,"y":1.7568653536686702}},"time":4.683282538938915,"velocity":-2.3700347873207526,"position":-0.9423160309486484,"holonomicRotation":-144.2531060978498,"angularVelocity":-0.3757692026956355,"angularAcceleration":0.6103298877915707,"curveRadius":6.394734856008568},{"acceleration":-3.006519248481545,"curvature":0.15407716675635924,"pose":{"rotation":{"radians":-2.8295212435795083},"translation":{"x":2.278906649723327,"y":1.7606368309435267}},"time":4.6884318293080876,"velocity":-2.3855162279316895,"position":-0.954599746686641,"holonomicRotation":-144.32907464664376,"angularVelocity":-0.37263877375635784,"angularAcceleration":0.607934048159127,"curveRadius":6.490254338472425},{"acceleration":-3.0064734269440665,"curvature":0.1518199601406063,"pose":{"rotation":{"radians":-2.831415906210285},"translation":{"x":2.2906291790049806,"y":1.764394164156989}},"time":4.693558992798389,"velocity":-2.4009309087208774,"position":-0.9669097119845701,"holonomicRotation":-144.4050431954377,"angularVelocity":-0.36953427257793153,"angularAcceleration":0.6055007187305459,"curveRadius":6.586749193412128},{"acceleration":-3.0064294934575617,"curvature":0.14960591579715043,"pose":{"rotation":{"radians":-2.8332867649109432},"translation":{"x":2.302383319660764,"y":1.7681373945233243}},"time":4.698664273376666,"velocity":-2.4162795748237884,"position":-0.9792454971696077,"holonomicRotation":-144.48101174423167,"angularVelocity":-0.3664556084573598,"angularAcceleration":0.6030352442666672,"curveRadius":6.684227656852104},{"acceleration":-3.00638738405122,"curvature":0.14743395118997987,"pose":{"rotation":{"radians":-2.8351341707748863},"translation":{"x":2.314168561453419,"y":1.771866563256801}},"time":4.703747906543313,"velocity":-2.4315629454411405,"position":-0.9916066712058423,"holonomicRotation":-144.55698029302562,"angularVelocity":-0.36340266958355677,"angularAcceleration":0.6005427169357733,"curveRadius":6.782698231504519},{"acceleration":-3.0063470378082116,"curvature":0.14530301344434496,"pose":{"rotation":{"radians":-2.83695846747387},"translation":{"x":2.3259843941456864,"y":1.7755817115716857}},"time":4.708810119671209,"velocity":-2.446781714882942,"position":-1.0039928017240165,"holonomicRotation":-144.63294884181957,"angularVelocity":-0.3603753245652457,"angularAcceleration":0.5980279656004658,"curveRadius":6.882169724463611},{"acceleration":-3.0063083965431767,"curvature":0.1432120788145778,"pose":{"rotation":{"radians":-2.83875999142588},"translation":{"x":2.337830307500309,"y":1.779282880682247}},"time":4.713851132327908,"velocity":-2.4619365535598567,"position":-1.016403455050502,"holonomicRotation":-144.70891739061352,"angularVelocity":-0.3573734236941631,"angularAcceleration":0.5954956028712435,"curveRadius":6.9826512419719755},{"acceleration":-3.006271404729984,"curvature":0.14116015154796055,"pose":{"rotation":{"radians":-2.840539071959064},"translation":{"x":2.3497057912800283,"y":1.7829701118027517}},"time":4.718871156582057,"velocity":-2.4770281089261563,"position":-1.0288381962355204,"holonomicRotation":-144.78488593940747,"angularVelocity":-0.3543968003169802,"angularAcceleration":0.5929499991404752,"curveRadius":7.084152213170728},{"acceleration":-3.00623600935202,"curvature":0.13914626292906018,"pose":{"rotation":{"radians":-2.8422960314706796},"translation":{"x":2.3616103352475863,"y":1.7866434461474678}},"time":4.7238703972949505,"velocity":-2.492057006376676,"position":-1.0412965890806507,"holonomicRotation":-144.86085448820143,"angularVelocity":-0.3514452718957765,"angularAcceleration":0.5903953401546121,"curveRadius":7.186682408494304},{"acceleration":-3.0062021598148365,"curvature":0.13716947082594783,"pose":{"rotation":{"radians":-2.844031185582361},"translation":{"x":2.3735434291657254,"y":1.790302924930663}},"time":4.728849052398083,"velocity":-2.5070238501006856,"position":-1.053778196165629,"holonomicRotation":-144.93682303699538,"angularVelocity":-0.3485186412269368,"angularAcceleration":0.5878355917842941,"curveRadius":7.290251934185007},{"acceleration":-3.006169807746856,"curvature":0.13522885825010156,"pose":{"rotation":{"radians":-2.845744843290837},"translation":{"x":2.3855045627971867,"y":1.7939485893666047}},"time":4.733807313157491,"velocity":-2.5219292238945545,"position":-1.06628257887447,"holonomicRotation":-145.01279158578933,"angularVelocity":-0.34561669739224027,"angularAcceleration":0.5852745499901704,"curveRadius":7.394871279254101},{"acceleration":-3.0061389068853503,"curvature":0.1333235331381726,"pose":{"rotation":{"radians":-2.8474373071148853},"translation":{"x":2.3974932259047135,"y":1.7975804806695606}},"time":4.738745364425636,"velocity":-2.5367736919359203,"position":-1.0788092974209316,"holonomicRotation":-145.08876013458328,"angularVelocity":-0.34273921677691077,"angularAcceleration":0.5827158243357679,"curveRadius":7.500551301499258},{"acceleration":-3.006109413043666,"curvature":0.13145262714006484,"pose":{"rotation":{"radians":-2.8491088732380567},"translation":{"x":2.409508908251046,"y":1.8011986400537983}},"time":4.743663384881512,"velocity":-2.5515577995218703,"position":-1.09135791087333,"holonomicRotation":-145.16472868337723,"angularVelocity":-0.3398859639093755,"angularAcceleration":0.5801628710442377,"curveRadius":7.607303267773297},{"acceleration":-3.006081284037825,"curvature":0.1296152951235611,"pose":{"rotation":{"radians":-2.8507598316480367},"translation":{"x":2.4215510995989273,"y":1.8048031087335852}},"time":4.748561547259639,"velocity":-2.5662820737729355,"position":-1.1039279771787458,"holonomicRotation":-145.2406972321712,"angularVelocity":-0.33705669239396513,"angularAcceleration":0.5776189715646683,"curveRadius":7.7151388580083005},{"acceleration":-3.0060544793596042,"curvature":0.12781071424662566,"pose":{"rotation":{"radians":-2.8523904662717143},"translation":{"x":2.4336192897110998,"y":1.808393927923189}},"time":4.753440018568544,"velocity":-2.580947024303499,"position":-1.116519053186616,"holonomicRotation":-145.31666578096514,"angularVelocity":-0.3342511455793291,"angularAcceleration":0.5750872839027352,"curveRadius":7.824070195479728},{"acceleration":-3.006028960375287,"curvature":0.1260380833349471,"pose":{"rotation":{"radians":-2.854001055107022},"translation":{"x":2.445712968350304,"y":1.8119711388368775}},"time":4.758298960299307,"velocity":-2.5955531438629453,"position":-1.129130694671742,"holonomicRotation":-145.3926343297591,"angularVelocity":-0.33146905736919563,"angularAcceleration":0.5725708115658362,"curveRadius":7.934109862195326},{"acceleration":-3.00600469011719,"curvature":0.12429662247317294,"pose":{"rotation":{"radians":-2.855591870351183},"translation":{"x":2.4578316252792822,"y":1.8155347826889183}},"time":4.7631385286246894,"velocity":-2.6101009089471883,"position":-1.1417624563567355,"holonomicRotation":-145.46860287855304,"angularVelocity":-0.3287101528906462,"angularAcceleration":0.5700724306503664,"curveRadius":8.045270901997606},{"acceleration":-3.005981633117437,"curvature":0.1225855718186966,"pose":{"rotation":{"radians":-2.857163178525385},"translation":{"x":2.4699747502607776,"y":1.8190849006935788}},"time":4.767958874589375,"velocity":-2.6245907803823063,"position":-1.1544138919339035,"holonomicRotation":-145.54457142734697,"angularVelocity":-0.3259741490991221,"angularAcceleration":0.5675949011892767,"curveRadius":8.157566874827607},{"acceleration":-3.0059597554775426,"curvature":0.12090419133119276,"pose":{"rotation":{"radians":-2.858715240596063},"translation":{"x":2.4821418330575304,"y":1.8226215340651264}},"time":4.7727601442917615,"velocity":-2.6390232038828727,"position":-1.1670845540866004,"holonomicRotation":-145.62053997614095,"angularVelocity":-0.3232607553595257,"angularAcceleration":0.5651408706009337,"curveRadius":8.271011856493054},{"acceleration":-3.005939024760722,"curvature":0.11925176005703893,"pose":{"rotation":{"radians":-2.860248312093205},"translation":{"x":2.494332363432284,"y":1.8261447240178292}},"time":4.777542479057763,"velocity":-2.6533986105854663,"position":-1.1797739945100632,"holonomicRotation":-145.69650852493487,"angularVelocity":-0.32056967405140274,"angularAcceleration":0.5627128672075383,"curveRadius":8.385620468173327},{"acceleration":-3.0059194098304385,"curvature":0.1176275755689902,"pose":{"rotation":{"radians":-2.861762643225178},"translation":{"x":2.506545831147779,"y":1.8296545117659546}},"time":4.782306015607036,"velocity":-2.6677174175583613,"position":-1.1924817639317333,"holonomicRotation":-145.77247707372885,"angularVelocity":-0.3179006010155319,"angularAcceleration":0.5603133319672838,"curveRadius":8.501407898299206},{"acceleration":-3.005900880933275,"curvature":0.11603095316524749,"pose":{"rotation":{"radians":-2.863258478990574},"translation":{"x":2.518781725966759,"y":1.83315093852377}},"time":4.78705088621201,"velocity":-2.681980028289769,"position":-1.2052074121310945,"holonomicRotation":-145.84844562252277,"angularVelocity":-0.31525322604741474,"angularAcceleration":0.5579446076657191,"curveRadius":8.618389944412787},{"acceleration":-3.005883409500749,"curvature":0.11446122562956469,"pose":{"rotation":{"radians":-2.8647360592869466},"translation":{"x":2.531039537651964,"y":1.8366340455055434}},"time":4.791777218850102,"velocity":-2.6961868331543926,"position":-1.2179504879590268,"holonomicRotation":-145.92441417131673,"angularVelocity":-0.3126272333148945,"angularAcceleration":0.5556089538336361,"curveRadius":8.736583017521923},{"acceleration":-3.0058669681930894,"curvature":0.11291774270410983,"pose":{"rotation":{"radians":-2.866195619016857},"translation":{"x":2.5433187559661374,"y":1.8401038739255422}},"time":4.796485137349444,"velocity":-2.7103382098605113,"position":-1.230710539356704,"holonomicRotation":-146.00038272011068,"angularVelocity":-0.3100223018122262,"angularAcceleration":0.5533085381644,"curveRadius":8.856004167745406},{"acceleration":-3.005851530835727,"curvature":0.11139987001608946,"pose":{"rotation":{"radians":-2.8676373881906927},"translation":{"x":2.555618870672021,"y":1.843560464998034}},"time":4.801174761528463,"velocity":-2.7244345238780574,"position":-1.2434871133740344,"holonomicRotation":-146.07635126890463,"angularVelocity":-0.3074381056559171,"angularAcceleration":0.5510454692448469,"curveRadius":8.976671156398748},{"acceleration":-3.0058370722858756,"curvature":0.10990698922583103,"pose":{"rotation":{"radians":-2.8690615920269056},"translation":{"x":2.5679393715323564,"y":1.8470038599372864}},"time":4.805846207329604,"velocity":-2.738476128848301,"position":-1.2562797561876673,"holonomicRotation":-146.15231981769858,"angularVelocity":-0.30487431447134994,"angularAcceleration":0.5488217767486548,"curveRadius":9.09860243687736},{"acceleration":-3.005823568466769,"curvature":0.10843849723101308,"pose":{"rotation":{"radians":-2.8704684510496117},"translation":{"x":2.580279748309885,"y":1.8504340999575668}},"time":4.810499586947504,"velocity":-2.7524633669768073,"position":-1.2690880131185733,"holonomicRotation":-146.22828836649254,"angularVelocity":-0.3023305937246999,"angularAcceleration":0.5466394224243494,"curveRadius":9.221817210078443},{"acceleration":-3.005810996351521,"curvature":0.10699380552681345,"pose":{"rotation":{"radians":-2.871858181183197},"translation":{"x":2.5926394907673496,"y":1.853851226273143}},"time":4.815135008951867,"velocity":-2.7663965694102526,"position":-1.281911428649213,"holonomicRotation":-146.3042569152865,"angularVelocity":-0.2998066049384622,"angularAcceleration":0.5445003246439799,"curveRadius":9.346335473125988},{"acceleration":-3.005799333750294,"curvature":0.10557234029059698,"pose":{"rotation":{"radians":-2.873230993844743},"translation":{"x":2.605018088667492,"y":1.857255280098283}},"time":4.819752578405312,"velocity":-2.780276056596965,"position":-1.2947495464403014,"holonomicRotation":-146.38022546408044,"angularVelocity":-0.2973020060416419,"angularAcceleration":0.5424063291460266,"curveRadius":9.472178008438704},{"acceleration":-3.005788559498828,"curvature":0.10417354104915662,"pose":{"rotation":{"radians":-2.8745870960336846},"translation":{"x":2.617415031773054,"y":1.8606463026472535}},"time":4.824352396976428,"velocity":-2.794102138633794,"position":-1.3076019093471822,"holonomicRotation":-146.4561940128744,"angularVelocity":-0.29481645155687974,"angularAcceleration":0.5403592438124105,"curveRadius":9.599366498717055},{"acceleration":-3.005778653258729,"curvature":0.10279686130727737,"pose":{"rotation":{"radians":-2.8759266904189285},"translation":{"x":2.629829809846777,"y":1.8640243351343229}},"time":4.8289345630482625,"velocity":-2.8078751155982014,"position":-1.3204680594358256,"holonomicRotation":-146.53216256166834,"angularVelocity":-0.29234959280022005,"angularAcceleration":0.5383608358987092,"curveRadius":9.72792347239892},{"acceleration":-3.0057695955434536,"curvature":0.10144176705861682,"pose":{"rotation":{"radians":-2.8772499754239256},"translation":{"x":2.6422619126514038,"y":1.8673894187737583}},"time":4.833499171822475,"velocity":-2.821595277867279,"position":-1.3333475379984538,"holonomicRotation":-146.6081311104623,"angularVelocity":-0.2899010781544028,"angularAcceleration":0.5364128158474897,"curveRadius":9.857872442444371},{"acceleration":-3.005761367666289,"curvature":0.10010773735245984,"pose":{"rotation":{"radians":-2.878557145308981},"translation":{"x":2.654710829949676,"y":1.8707415947798278}},"time":4.838046315419334,"velocity":-2.8352629064239485,"position":-1.3462398855688111,"holonomicRotation":-146.68409965925625,"angularVelocity":-0.28747055315308095,"angularAcceleration":0.5345168784642748,"curveRadius":9.989237859599152},{"acceleration":-3.0057539516667258,"curvature":0.09879426308476287,"pose":{"rotation":{"radians":-2.8798483902516447},"translation":{"x":2.6671760515043355,"y":1.8740809043667983}},"time":4.842576082973775,"velocity":-2.8488782731508393,"position":-1.3591446419370798,"holonomicRotation":-146.7600682080502,"angularVelocity":-0.2850576607176861,"angularAcceleration":0.5326746695930505,"curveRadius":10.1220452359873},{"acceleration":-3.0057473304432687,"curvature":0.09750084731166313,"pose":{"rotation":{"radians":-2.881123896424494},"translation":{"x":2.6796570670781246,"y":1.8774073887489384}},"time":4.847088560727683,"velocity":-2.8624416411133358,"position":-1.3720613461644664,"holonomicRotation":-146.83603675684415,"angularVelocity":-0.2826620412132102,"angularAcceleration":0.5308878259622902,"curveRadius":10.256321125122973},{"acceleration":-3.0057414875061093,"curvature":0.09622700399865539,"pose":{"rotation":{"radians":-2.8823838460712903},"translation":{"x":2.6921533664337844,"y":1.8807210891405148}},"time":4.851583832118591,"velocity":-2.875953264830586,"position":-1.3849895365974465,"holonomicRotation":-146.9120053056381,"angularVelocity":-0.2802833326915242,"angularAcceleration":0.5291579339341603,"curveRadius":10.39209326327954},{"acceleration":-3.0057364070567734,"curvature":0.09497225865817732,"pose":{"rotation":{"radians":-2.883628417580355},"translation":{"x":2.7046644393340578,"y":1.884022046755795}},"time":4.8560619778649325,"velocity":-2.8894133905364714,"position":-1.3979287508817,"holonomicRotation":-146.98797385443206,"angularVelocity":-0.2779211708510151,"angularAcceleration":0.5274865925118382,"curveRadius":10.529390520227432},{"acceleration":-3.0057320739881233,"curvature":0.09373614740891868,"pose":{"rotation":{"radians":-2.884857785556264},"translation":{"x":2.717189775541686,"y":1.8873103028090479}},"time":4.860523076048033,"velocity":-2.902822256430627,"position":-1.4108785259757266,"holonomicRotation":-147.063942403226,"angularVelocity":-0.27557518921368696,"angularAcceleration":0.5258753654459157,"curveRadius":10.668243016619364},{"acceleration":-3.005728473816952,"curvature":0.09251821660733246,"pose":{"rotation":{"radians":-2.886072120889839},"translation":{"x":2.7297288648194113,"y":1.8905858985145396}},"time":4.864967202190963,"velocity":-2.916180092919666,"position":-1.423838398164163,"holonomicRotation":-147.13991095201996,"angularVelocity":-0.2732450192726915,"angularAcceleration":0.5243257878047471,"curveRadius":10.808682188981427},{"acceleration":-3.005725592656087,"curvature":0.09131802274716426,"pose":{"rotation":{"radians":-2.8872715908251387},"translation":{"x":2.7422811969299756,"y":1.8938488750865385}},"time":4.869394429334404,"velocity":-2.9294871228492076,"position":-1.4368079030708012,"holonomicRotation":-147.2158795008139,"angularVelocity":-0.27093029032332866,"angularAcceleration":0.5228394375003474,"curveRadius":10.95074082767581},{"acceleration":-3.0057234172179506,"curvature":0.09013513187334667,"pose":{"rotation":{"radians":-2.8884563590257692},"translation":{"x":2.7548462616361213,"y":1.897099273739312}},"time":4.873804828109656,"velocity":-2.942743561727253,"position":-1.4497865756713246,"holonomicRotation":-147.29184804960786,"angularVelocity":-0.2686306297921422,"angularAcceleration":0.5214178237329383,"curveRadius":11.094453175096582},{"acceleration":-3.0057219347740656,"curvature":0.08896911968118269,"pose":{"rotation":{"radians":-2.889626585638285},"translation":{"x":2.7674235487005894,"y":1.900337135687128}},"time":4.8781984668089144,"velocity":-2.955949617939085,"position":-1.462773950305759,"holonomicRotation":-147.36781659840182,"angularVelocity":-0.2663456630407796,"angularAcceleration":0.520062505765074,"curveRadius":11.23985494723855},{"acceleration":-0.8138848947470786,"curvature":0.08781957077179527,"pose":{"rotation":{"radians":-2.8907824273545373},"translation":{"x":2.7800125478861224,"y":1.9035625021442535}},"time":4.882589582631885,"velocity":-2.959523480778486,"position":-1.4757695606906585,"holonomicRotation":-147.44378514719577,"angularVelocity":-0.26322278046188446,"angularAcceleration":0.7111820104035705,"curveRadius":11.386983461790807},{"acceleration":2.1843327601715794,"curvature":0.0866860785968519,"pose":{"rotation":{"radians":-2.8919240374715067},"translation":{"x":2.792612748955462,"y":1.9067754143249565}},"time":4.886997665051684,"velocity":-2.949894761939382,"position":-1.4887729399310214,"holonomicRotation":-147.51975369598972,"angularVelocity":-0.2589811188288604,"angularAcceleration":0.962246443934962,"curveRadius":11.535877688627112},{"acceleration":2.992420501145426,"curvature":0.0855682451909303,"pose":{"rotation":{"radians":-2.8930515659499663},"translation":{"x":2.8052236416713505,"y":1.9099759134435046}},"time":4.891428134630868,"velocity":-2.9366369339409317,"position":-1.5017836205319537,"holonomicRotation":-147.59572224478367,"angularVelocity":-0.2544941249020633,"angularAcceleration":1.0127580940582628,"curveRadius":11.686578330181694},{"acceleration":2.9924098173776312,"curvature":0.08446568059949748,"pose":{"rotation":{"radians":-2.8941651594711497},"translation":{"x":2.81784471579653,"y":1.9131640407141655}},"time":4.895881136943927,"velocity":-2.9233117261025297,"position":-1.5148011344100798,"holonomicRotation":-147.67169079357762,"angularVelocity":-0.2500770138649557,"angularAcceleration":0.9919399826391743,"curveRadius":11.839127949984805},{"acceleration":2.992398138672039,"curvature":0.08337800295610967,"pose":{"rotation":{"radians":-2.8952649614916726},"translation":{"x":2.8304754610937417,"y":1.9163398373512066}},"time":4.900356821613121,"velocity":-2.909918695629149,"position":-1.5278250129047095,"holonomicRotation":-147.74765934237158,"angularVelocity":-0.24572821854332932,"angularAcceleration":0.9716491761715327,"curveRadius":11.993571020481287},{"acceleration":2.992385444182501,"curvature":0.08230483796699874,"pose":{"rotation":{"radians":-2.8963511122970735},"translation":{"x":2.843115367325728,"y":1.9195033445688952}},"time":4.904855342440949,"velocity":-2.8964573873836046,"position":-1.5408547867887712,"holonomicRotation":-147.82362789116553,"angularVelocity":-0.24144621020358276,"angularAcceleration":0.9518702932879262,"curveRadius":12.14995405739045},{"acceleration":2.9923717121493953,"curvature":0.08124581890953725,"pose":{"rotation":{"radians":-2.8974237490532624},"translation":{"x":2.8557639242552306,"y":1.9226546035814998}},"time":4.909376857547956,"velocity":-2.88292733348134,"position":-1.5538899862795112,"holonomicRotation":-147.89959643995948,"angularVelocity":-0.23722949737058688,"angularAcceleration":0.9325884649729426,"curveRadius":12.308325688900311},{"acceleration":2.9923569199319973,"curvature":0.0802005860173775,"pose":{"rotation":{"radians":-2.8984830058572117},"translation":{"x":2.8684206216449915,"y":1.925793655603287}},"time":4.913921529516163,"velocity":-2.869328052868456,"position":-1.566930141048971,"holonomicRotation":-147.97556498875343,"angularVelocity":-0.23307662497088416,"angularAcceleration":0.9137892522838308,"curveRadius":12.468736821739986},{"acceleration":2.9923410438834863,"curvature":0.07916878654200953,"pose":{"rotation":{"radians":-2.899529013785008},"translation":{"x":2.8810849492577533,"y":1.9289205418485253}},"time":4.918489525538392,"velocity":-2.8556590508828434,"position":-1.5799747802342465,"holonomicRotation":-148.05153353754739,"angularVelocity":-0.22898617308468247,"angularAcceleration":0.8954587233212169,"curveRadius":12.63124071592745},{"acceleration":2.992324059472728,"curvature":0.07815007450954221,"pose":{"rotation":{"radians":-2.900561900939408},"translation":{"x":2.893756396856257,"y":1.9320353035314815}},"time":4.923081017573804,"velocity":-2.841919818796402,"position":-1.5930234324475303,"holonomicRotation":-148.12750208634134,"angularVelocity":-0.22495675619904634,"angularAcceleration":0.8775833333824753,"curveRadius":12.795893110478083},{"acceleration":2.9923059410405455,"curvature":0.0771441100651827,"pose":{"rotation":{"radians":-2.9015817924951333},"translation":{"x":2.9064344542032448,"y":1.9351379818664238}},"time":4.92769618250996,"velocity":-2.8281098333390595,"position":-1.6060756257859556,"holonomicRotation":-148.2034706351353,"angularVelocity":-0.22098702209644755,"angularAcceleration":0.8601499962653406,"curveRadius":12.962752427308487},{"acceleration":2.992286661866009,"curvature":0.07615055976128539,"pose":{"rotation":{"radians":-2.9025888107433935},"translation":{"x":2.919118611061459,"y":1.9382286180676194}},"time":4.932335202331752,"velocity":-2.8142285562021785,"position":-1.6191308878412314,"holonomicRotation":-148.27943918392924,"angularVelocity":-0.2170756510954417,"angularAcceleration":0.8431459987801293,"curveRadius":13.13187983298838},{"acceleration":2.992266194133125,"curvature":0.07516909621355201,"pose":{"rotation":{"radians":-2.9035830751342093},"translation":{"x":2.931808357193641,"y":1.941307253349336}},"time":4.936998264297566,"velocity":-2.8002754335207256,"position":-1.632188745709085,"holonomicRotation":-148.3554077327232,"angularVelocity":-0.2132213550034406,"angularAcceleration":0.826559055028201,"curveRadius":13.303339409044444},{"acceleration":2.9922445087467087,"curvature":0.07419939748865427,"pose":{"rotation":{"radians":-2.9045647023180554},"translation":{"x":2.9445031823625336,"y":1.9443739289258417}},"time":4.94168556112306,"velocity":-2.786249895333777,"position":-1.6452487259985142,"holonomicRotation":-148.43137628151715,"angularVelocity":-0.20942287642361118,"angularAcceleration":0.8103772219352858,"curveRadius":13.477198384972178},{"acceleration":2.992221575471749,"curvature":0.07324114738935983,"pose":{"rotation":{"radians":-2.9055338061857006},"translation":{"x":2.957202576330878,"y":1.9474286860114034}},"time":4.946397291172966,"velocity":-2.77215135502065,"position":-1.6583103548408527,"holonomicRotation":-148.5073448303111,"angularVelocity":-0.20567898784109762,"angularAcceleration":0.7945889392768295,"curveRadius":13.653527226763188},{"acceleration":2.9921973626661,"curvature":0.07229403516813601,"pose":{"rotation":{"radians":-2.906490497906708},"translation":{"x":2.9699060288614163,"y":1.9504715658202891}},"time":4.951133658661355,"velocity":-2.757979208713273,"position":-1.6713731578986566,"holonomicRotation":-148.58331337910505,"angularVelocity":-0.20198849083241835,"angularAcceleration":0.779182995771742,"curveRadius":13.832399833185068},{"acceleration":2.992171837448004,"curvature":0.07135775470374495,"pose":{"rotation":{"radians":-2.9074348859668238},"translation":{"x":2.98261302971689,"y":1.9535026095667662}},"time":4.95589487386082,"velocity":-2.7437328346814054,"position":-1.684436660374412,"holonomicRotation":-148.659281927899,"angularVelocity":-0.19835021534456754,"angularAcceleration":0.764148507351622,"curveRadius":14.013893852906202},{"acceleration":2.9921449653126477,"curvature":0.07043200530080884,"pose":{"rotation":{"radians":-2.9083670762038456},"translation":{"x":2.995323068660042,"y":1.9565218584651025}},"time":4.960681153321069,"velocity":-2.729411592691843,"position":-1.6975003870190777,"holonomicRotation":-148.73525047669295,"angularVelocity":-0.19476301890934988,"angularAcceleration":0.7494749241055133,"curveRadius":14.198090707897478},{"acceleration":2.9921167104234194,"curvature":0.06951649059175072,"pose":{"rotation":{"radians":-2.9092871718422946},"translation":{"x":3.0080356354536137,"y":1.959529353729565}},"time":4.965492720097459,"velocity":-2.715014823336887,"position":-1.7105638621404529,"holonomicRotation":-148.8112190254869,"angularVelocity":-0.19122578594642747,"angularAcceleration":0.7351520050140559,"curveRadius":14.385075994021287},{"acceleration":2.9920870352639075,"curvature":0.06861091890130024,"pose":{"rotation":{"radians":-2.9101952735266616},"translation":{"x":3.0207502198603464,"y":1.9625251365744223}},"time":4.970329803990025,"velocity":-2.7005418473334566,"position":-1.72362660961139,"holonomicRotation":-148.88718757428086,"angularVelocity":-0.18773742704001894,"angularAcceleration":0.721169817163956,"curveRadius":14.574939616222647},{"acceleration":2.9920559006680847,"curvature":0.06771500300534734,"pose":{"rotation":{"radians":-2.9110914793538685},"translation":{"x":3.0334663116429836,"y":1.9655092482139416}},"time":4.975192641793594,"velocity":-2.685991964789298,"position":-1.7366881528778484,"holonomicRotation":-148.9631561230748,"angularVelocity":-0.18429687836785116,"angularAcceleration":0.7075186981648949,"curveRadius":14.767776055788282},{"acceleration":2.9920232657642485,"curvature":0.06682845941176513,"pose":{"rotation":{"radians":-2.9119758849037845},"translation":{"x":3.0461834005642663,"y":1.96848172986239}},"time":4.980081477559623,"velocity":-2.6713644544348365,"position":-1.7497480149667899,"holonomicRotation":-149.03912467186876,"angularVelocity":-0.18090310091030418,"angularAcceleration":0.6941892957682874,"curveRadius":14.963684765475087},{"acceleration":2.991989087729349,"curvature":0.065951009007572,"pose":{"rotation":{"radians":-2.9128485832690236},"translation":{"x":3.058900976386936,"y":1.9714426227340356}},"time":4.984996562870448,"velocity":-2.656658572819591,"position":-1.7628057184939312,"holonomicRotation":-149.11509322066271,"angularVelocity":-0.177555079932641,"angularAcceleration":0.6811725058545558,"curveRadius":15.162770290370956},{"acceleration":2.991953321942177,"curvature":0.0650823760431731,"pose":{"rotation":{"radians":-2.913709665083499},"translation":{"x":3.071618528873736,"y":1.9743919680431463}},"time":4.989938157126643,"velocity":-2.6418735534690767,"position":-1.7758607856713486,"holonomicRotation":-149.19106176945667,"angularVelocity":-0.17425182437745212,"angularAcceleration":0.6684594857312428,"curveRadius":15.365142774391627},{"acceleration":2.99191592166258,"curvature":0.06422228859345352,"pose":{"rotation":{"radians":-2.9145592185496776},"translation":{"x":3.084335547787407,"y":1.977329807003989}},"time":4.994906527848295,"velocity":-2.6270086060022435,"position":-1.7889127383149384,"holonomicRotation":-149.26703031825062,"angularVelocity":-0.17099236626534667,"angularAcceleration":0.6560416471944736,"curveRadius":15.570918164101903},{"acceleration":2.991876837972955,"curvature":0.06337047808040568,"pose":{"rotation":{"radians":-2.9153973294645277},"translation":{"x":3.097051522890691,"y":1.9802561808308317}},"time":4.999901950990996,"velocity":-2.6120629152057258,"position":-1.801961097851745,"holonomicRotation":-149.34299886704457,"angularVelocity":-0.16777576011250933,"angularAcceleration":0.6439106479974536,"curveRadius":15.780218648992689},{"acceleration":2.991836019770413,"curvature":0.06252667886188415,"pose":{"rotation":{"radians":-2.9162240812446316},"translation":{"x":3.1097659439463308,"y":1.9831711307379416}},"time":5.004924711277448,"velocity":-2.5970356400620433,"position":-1.8150053853271517,"holonomicRotation":-149.41896741583852,"angularVelocity":-0.16460108246332067,"angularAcceleration":0.6320583639540124,"curveRadius":15.993173125489532},{"acceleration":2.9917934135392112,"curvature":0.061690629010097545,"pose":{"rotation":{"radians":-2.9170395549498727},"translation":{"x":3.1224783007170673,"y":1.986074697939587}},"time":5.009975102545647,"velocity":-2.5819259127300485,"position":-1.8280451214119413,"holonomicRotation":-149.49493596463248,"angularVelocity":-0.16146743132077812,"angularAcceleration":0.6204769048834077,"curveRadius":16.209917390148828},{"acceleration":2.9917489631875234,"curvature":0.06086206869466839,"pose":{"rotation":{"radians":-2.9178438293062463},"translation":{"x":3.1351880829656436,"y":1.9889669236500347}},"time":5.015053428114629,"velocity":-2.566732837474319,"position":-1.841079826409232,"holonomicRotation":-149.57090451342643,"angularVelocity":-0.1583739257061694,"angularAcceleration":0.6091585843774553,"curveRadius":16.43059497396942},{"acceleration":2.9917026100629296,"curvature":0.06004074114598995,"pose":{"rotation":{"radians":-2.918636980727073},"translation":{"x":3.1478947804548003,"y":1.9918478490835532}},"time":5.020160001168901,"velocity":-2.5514554895393773,"position":-1.8541090202612873,"holonomicRotation":-149.64687306222038,"angularVelocity":-0.15531970509328932,"angularAcceleration":0.5980959403538195,"curveRadius":16.655357360904077},{"acceleration":2.9916542925873473,"curvature":0.059226392334462696,"pose":{"rotation":{"radians":-2.9194190833338287},"translation":{"x":3.1605978829472807,"y":1.9947175154544095}},"time":5.025295145162719,"velocity":-2.536092913967218,"position":-1.8671322225562101,"holonomicRotation":-149.72284161101433,"angularVelocity":-0.15230392910055873,"angularAcceleration":0.5872816801946045,"curveRadius":16.884364564243757},{"acceleration":2.991603946291138,"curvature":0.0584187700883973,"pose":{"rotation":{"radians":-2.9201902089750056},"translation":{"x":3.1732968802058252,"y":1.997575963976871}},"time":5.03045919424547,"velocity":-2.5206441243524185,"position":-1.8801489525345143,"holonomicRotation":-149.79881015980828,"angularVelocity":-0.1493257768894126,"angularAcceleration":0.5767087344490405,"curveRadius":17.117785918581202},{"acceleration":2.9915515035713085,"curvature":0.057617624997952394,"pose":{"rotation":{"radians":-2.9209504272445916},"translation":{"x":3.1859912619931774,"y":2.000423235865206}},"time":5.035652493709521,"velocity":-2.5051081015322403,"position":-1.8931587290955918,"holonomicRotation":-149.87477870860224,"angularVelocity":-0.14638444689130917,"angularAcceleration":0.566370188829626,"curveRadius":17.355800417589894},{"acceleration":2.9914968934536845,"curvature":0.056822708966041933,"pose":{"rotation":{"radians":-2.9216998054990655},"translation":{"x":3.198680518072078,"y":2.0032593723336816}},"time":5.040875400461983,"velocity":-2.4894837922074498,"position":-1.9061610708040586,"holonomicRotation":-149.9507472573962,"angularVelocity":-0.1434791563377047,"angularAcceleration":0.5562593190534286,"curveRadius":17.598597782404468},{"acceleration":2.991440041441097,"curvature":0.05603377645195541,"pose":{"rotation":{"radians":-2.9224384088733277},"translation":{"x":3.21136413820527,"y":2.0060844145965655}},"time":5.046128283521977,"velocity":-2.473770107488778,"position":-1.9191554958960044,"holonomicRotation":-150.02671580619014,"angularVelocity":-0.1406091408901775,"angularAcceleration":0.5463695678637094,"curveRadius":17.84637879721389},{"acceleration":2.9913808693481125,"curvature":0.05525058331805504,"pose":{"rotation":{"radians":-2.9231663002956862},"translation":{"x":3.224041612155495,"y":2.008898403868126}},"time":5.051411524545075,"velocity":-2.457965921364129,"position":-1.9321415222851308,"holonomicRotation":-150.1026843549841,"angularVelocity":-0.13777365431111385,"angularAcceleration":0.5366945340307975,"curveRadius":18.09935642205637},{"acceleration":2.991319294992285,"curvature":0.05447288697032146,"pose":{"rotation":{"radians":-2.923883540501786},"translation":{"x":3.2367124296854937,"y":2.011701381362629}},"time":5.056725518376766,"velocity":-2.4420700690819204,"position":-1.9451186675687906,"holonomicRotation":-150.17865290377804,"angularVelocity":-0.13497196813106757,"angularAcceleration":0.5272279699192781,"curveRadius":18.357756594483995},{"acceleration":2.9912552319901935,"curvature":0.053700445808994995,"pose":{"rotation":{"radians":-2.9245901880469276},"translation":{"x":3.2493760805580094,"y":2.0144933882943437}},"time":5.062070673636912,"velocity":-2.4260813454442087,"position":-1.9580864490339338,"holonomicRotation":-150.254621452572,"angularVelocity":-0.132203371230474,"angularAcceleration":0.5179637944731952,"curveRadius":18.621819333807036},{"acceleration":2.9911885895512103,"curvature":0.052933020320329836,"pose":{"rotation":{"radians":-2.9252862993182775},"translation":{"x":3.262032054535784,"y":2.017274465877537}},"time":5.067447413337318,"velocity":-2.409998503003369,"position":-1.9710443836629497,"holonomicRotation":-150.33059000136595,"angularVelocity":-0.12946716972321595,"angularAcceleration":0.5088960336041037,"curveRadius":18.891799371137203},{"acceleration":2.991119272072064,"curvature":0.052170370975356206,"pose":{"rotation":{"radians":-2.925971928545008},"translation":{"x":3.2746798413815585,"y":2.0200446553264766}},"time":5.07285617553474,"velocity":-2.393820250156603,"position":-1.983991988139422,"holonomicRotation":-150.4065585501599,"angularVelocity":-0.1267626864899395,"angularAcceleration":0.5000188831679647,"curveRadius":19.16796797309284},{"acceleration":2.9910471789357422,"curvature":0.05141225991188507,"pose":{"rotation":{"radians":-2.9266471278079944},"translation":{"x":3.2873189308580755,"y":2.02280399785543}},"time":5.078297414021835,"velocity":-2.3775452491298634,"position":-1.996928778853795,"holonomicRotation":-150.48252709895385,"angularVelocity":-0.12408926103639786,"angularAcceleration":0.4913266455573744,"curveRadius":19.4506135640388},{"acceleration":2.990972204189298,"curvature":0.050658449500111176,"pose":{"rotation":{"radians":-2.9273119470480853},"translation":{"x":3.2999488127280774,"y":2.0255525346786656}},"time":5.083771599058737,"velocity":-2.3611721138438986,"position":-2.009854271908951,"holonomicRotation":-150.5584956477478,"angularVelocity":-0.12144624918762961,"angularAcceleration":0.4828137578381321,"curveRadius":19.740043563666617},{"acceleration":2.9908942361455444,"curvature":0.049908703218694464,"pose":{"rotation":{"radians":-2.927966434073698},"translation":{"x":3.3125689767543056,"y":2.0282903070104497}},"time":5.089279218148243,"velocity":-2.344699407654211,"position":-2.0227679831257,"holonomicRotation":-150.63446419654176,"angularVelocity":-0.11883302294084619,"angularAcceleration":0.47447476020314416,"curveRadius":20.036585515318034},{"acceleration":2.9908131569670813,"curvature":0.04916278387019824,"pose":{"rotation":{"radians":-2.928610634566496},"translation":{"x":3.325178912699502,"y":2.031017356065051}},"time":5.0948207768577625,"velocity":-2.328125640955674,"position":-2.035669428048194,"holonomicRotation":-150.7104327453357,"angularVelocity":-0.11624897011224765,"angularAcceleration":0.4663043313354105,"curveRadius":20.34058939054884},{"acceleration":2.990728842416728,"curvature":0.04842045536136301,"pose":{"rotation":{"radians":-2.929244592087228},"translation":{"x":3.3377781103264086,"y":2.0337337230567365}},"time":5.100396799691543,"velocity":-2.3114492686407124,"position":-2.04855812194926,"holonomicRotation":-150.78640129412966,"angularVelocity":-0.11369349438296436,"angularAcceleration":0.4582972138854603,"curveRadius":20.65242865927171},{"acceleration":2.990641161253619,"curvature":0.04768148155125815,"pose":{"rotation":{"radians":-2.929868348079089},"translation":{"x":3.350366059397767,"y":2.036439449199774}},"time":5.106007831016927,"velocity":-2.2946686874019346,"position":-2.0614335798356507,"holonomicRotation":-150.8623698429236,"angularVelocity":-0.1111660148891486,"angularAcceleration":0.450448295018679,"curveRadius":20.97250268796678},{"acceleration":2.990549974813942,"curvature":0.046945625672060384,"pose":{"rotation":{"radians":-2.9304819418711094},"translation":{"x":3.36294224967632,"y":2.039134575708431}},"time":5.111654436048786,"velocity":-2.2777822328661235,"position":-2.0742953164532323,"holonomicRotation":-150.93833839171754,"angularVelocity":-0.10866596628565188,"angularAcceleration":0.4427525193263778,"curveRadius":21.301239160928862},{"acceleration":2.990455136562346,"curvature":0.046212650968537036,"pose":{"rotation":{"radians":-2.931085410679676},"translation":{"x":3.3755061709248086,"y":2.041819143796975}},"time":5.117337201896616,"velocity":-2.2607881765466025,"position":-2.0871428462920867,"holonomicRotation":-151.01430694051152,"angularVelocity":-0.10619279849390566,"angularAcceleration":0.43520494385512953,"curveRadius":21.639096200753126},{"acceleration":2.99035649140343,"curvature":0.04548231997610103,"pose":{"rotation":{"radians":-2.9316787896093666},"translation":{"x":3.3880573129059757,"y":2.044493194679674}},"time":5.123056738679214,"velocity":-2.2436847226009387,"position":-2.099975683591557,"holonomicRotation":-151.09027548930544,"angularVelocity":-0.10374597668397309,"angularAcceleration":0.42780069487042793,"curveRadius":21.986565340674275},{"acceleration":2.9902538751448904,"curvature":0.04475439490187135,"pose":{"rotation":{"radians":-2.9322621116523315},"translation":{"x":3.400595165382562,"y":2.0471567695707953}},"time":5.128813680712324,"velocity":-2.226470004377447,"position":-2.112793342345216,"holonomicRotation":-151.16624403809942,"angularVelocity":-0.10132498114625546,"angularAcceleration":0.42053498607310824,"curveRadius":22.34417429154396},{"acceleration":2.990147113921337,"curvature":0.04402863655699255,"pose":{"rotation":{"radians":-2.932835407686909},"translation":{"x":3.413119218117311,"y":2.049809909684607}},"time":5.134608687775117,"velocity":-2.209142080733484,"position":-2.125595336305779,"holonomicRotation":-151.24221258689334,"angularVelocity":-0.0989293073097975,"angularAcceleration":0.41340309174765755,"curveRadius":22.712490737830528},{"acceleration":2.9900360232099423,"curvature":0.043304805163602356,"pose":{"rotation":{"radians":-2.9333987064746183},"translation":{"x":3.425628960872963,"y":2.052452656235376}},"time":5.1404424464619725,"velocity":-2.1916989321090705,"position":-2.138381178989943,"holonomicRotation":-151.3181811356873,"angularVelocity":-0.09655846563871388,"angularAcceleration":0.40640036695815873,"curveRadius":23.092125601814253},{"acceleration":2.9899204074354135,"curvature":0.042582659706062516,"pose":{"rotation":{"radians":-2.933952034656292},"translation":{"x":3.4381238834122616,"y":2.0550850504373703}},"time":5.146315671626657,"velocity":-2.1741384563317165,"position":-2.1511503836831793,"holonomicRotation":-151.39414968448125,"angularVelocity":-0.09421198168954723,"angularAcceleration":0.39952221877613486,"curveRadius":23.48373743920062},{"acceleration":2.989800058713206,"curvature":0.041861956888975885,"pose":{"rotation":{"radians":-2.9344954167470263},"translation":{"x":3.450603475497947,"y":2.0577071335048567}},"time":5.152229107926665,"velocity":-2.1564584641347553,"position":-2.1639024634444537,"holonomicRotation":-151.4701182332752,"angularVelocity":-0.09188939614237021,"angularAcceleration":0.3927641102980684,"curveRadius":23.88803759585698},{"acceleration":2.9896747562674615,"curvature":0.04114245324410253,"pose":{"rotation":{"radians":-2.9350288751295297},"translation":{"x":3.4630672268927625,"y":2.0603189466521044}},"time":5.158183531476327,"velocity":-2.138656674360207,"position":-2.1766369311109055,"holonomicRotation":-151.54608678206915,"angularVelocity":-0.08959026479292083,"angularAcceleration":0.38612156664266306,"curveRadius":24.30579416513872},{"acceleration":2.9895442650943416,"curvature":0.04042390200893784,"pose":{"rotation":{"radians":-2.9355524300471245},"translation":{"x":3.47551462735945,"y":2.0629205310933796}},"time":5.164179751618116,"velocity":-2.1207307088230793,"position":-2.1893532993024603,"holonomicRotation":-151.6220553308631,"angularVelocity":-0.08731415878914633,"angularAcceleration":0.37959013344288695,"curveRadius":24.737839503442718},{"acceleration":2.9894083351431515,"curvature":0.03970605523874939,"pose":{"rotation":{"radians":-2.9360660995941514},"translation":{"x":3.4879451666607504,"y":2.065511928042951}},"time":5.17021861282261,"velocity":-2.1026780868035932,"position":-2.2020510804263975,"holonomicRotation":-151.69802387965706,"angularVelocity":-0.08506066452474194,"angularAcceleration":0.3731654343583025,"curveRadius":25.185075525309138},{"acceleration":2.9892666998148183,"curvature":0.03898866289945227,"pose":{"rotation":{"radians":-2.936569899706652},"translation":{"x":3.5003583345594063,"y":2.0680931787150847}},"time":5.176300996728645,"velocity":-2.084496219137793,"position":-2.2147297866818723,"holonomicRotation":-151.773992428451,"angularVelocity":-0.08282938405129485,"angularAcceleration":0.36684308454011805,"curveRadius":25.648481523434047},{"acceleration":2.9891190748360197,"curvature":0.038271471486505025,"pose":{"rotation":{"radians":-2.937063844150272},"translation":{"x":3.5127536208181596,"y":2.0706643243240497}},"time":5.182427824336445,"velocity":-2.0661824018670862,"position":-2.227388930064382,"holonomicRotation":-151.84996097724496,"angularVelocity":-0.08061993502011486,"angularAcceleration":0.3606187692252338,"curveRadius":26.12912336941661},{"acceleration":2.9889651566751514,"curvature":0.03755422576117445,"pose":{"rotation":{"radians":-2.937547944508178},"translation":{"x":3.525130515199753,"y":2.073225406084113}},"time":5.188600058367911,"velocity":-2.0477338094081903,"position":-2.2400280223701943,"holonomicRotation":-151.9259295260389,"angularVelocity":-0.07843195112786813,"angularAcceleration":0.35448816118968624,"curveRadius":26.628161804199753},{"acceleration":2.988804620893193,"curvature":0.03683666718683387,"pose":{"rotation":{"radians":-2.938022210166513},"translation":{"x":3.537488507466927,"y":2.0757764652095423}},"time":5.194818705809826,"velocity":-2.0291474871980877,"position":-2.252646575200728,"holonomicRotation":-152.00189807483287,"angularVelocity":-0.07626508220078994,"angularAcceleration":0.3484469810063319,"curveRadius":27.14686415380757},{"acceleration":2.9886371203857878,"curvature":0.03611853407137934,"pose":{"rotation":{"radians":-2.9384866482994156},"translation":{"x":3.5498270873824236,"y":2.078317542914605}},"time":5.201084820657523,"velocity":-2.010420343763659,"position":-2.265244099966898,"holonomicRotation":-152.07786662362682,"angularVelocity":-0.07411899465473433,"angularAcceleration":0.342490937082694,"curveRadius":27.686616461890384},{"acceleration":2.988462283398932,"curvature":0.03539956155084558,"pose":{"rotation":{"radians":-2.938941263851816},"translation":{"x":3.562145744708986,"y":2.0808486804135695}},"time":5.207399506878561,"velocity":-1.9915491421605878,"position":-2.2778201078934197,"holonomicRotation":-152.15383517242077,"angularVelocity":-0.0719933717190815,"angularAcceleration":0.3366157654153986,"curveRadius":28.248937449794862},{"acceleration":2.9882797113248536,"curvature":0.03467948037097885,"pose":{"rotation":{"radians":-2.9393860595215875},"translation":{"x":3.574443969209356,"y":2.0833699189207024}},"time":5.213763921618266,"velocity":-1.972530490719469,"position":-2.2903741100230732,"holonomicRotation":-152.22980372121472,"angularVelocity":-0.06988791396581322,"angularAcceleration":0.33081718262843923,"curveRadius":28.83549549481829},{"acceleration":2.9880889762179095,"curvature":0.033958018614406456,"pose":{"rotation":{"radians":-2.939821035739424},"translation":{"x":3.5867212506462742,"y":2.085881299650272}},"time":5.220179278671591,"velocity":-1.9533608330299295,"position":-2.302905617220939,"holonomicRotation":-152.30577227000867,"angularVelocity":-0.06780233963926188,"angularAcceleration":0.3250909199934097,"curveRadius":29.448125679975828},{"acceleration":2.9878896181483996,"curvature":0.033234899453764566,"pose":{"rotation":{"radians":-2.9402461906479833},"translation":{"x":3.5989770787824837,"y":2.0883828638165456}},"time":5.226646852248703,"velocity":-1.9340364370842635,"position":-2.315414140178598,"holonomicRotation":-152.38174081880263,"angularVelocity":-0.0657363852904186,"angularAcceleration":0.31943267814597975,"curveRadius":30.088852875609604},{"acceleration":2.987681142141525,"curvature":0.03250984118409115,"pose":{"rotation":{"radians":-2.94066152007908},"translation":{"x":3.611210943380726,"y":2.0908746526337905}},"time":5.233167981065138,"velocity":-1.9145533834939248,"position":-2.3278991894183036,"holonomicRotation":-152.45770936759658,"angularVelocity":-0.0636898062878552,"angularAcceleration":0.3138381498315825,"curveRadius":30.759916492282183},{"acceleration":2.9874630148389927,"curvature":0.03178255886822668,"pose":{"rotation":{"radians":-2.9410670175291185},"translation":{"x":3.6234223342037435,"y":2.093356707316275}},"time":5.2397440727911935,"velocity":-1.8949075526801458,"position":-2.3403602752971233,"holonomicRotation":-152.53367791639053,"angularVelocity":-0.06166237743181524,"angularAcceleration":0.3083030073937414,"curveRadius":31.463797617620692},{"acceleration":2.987234660712849,"curvature":0.03105276070589561,"pose":{"rotation":{"radians":-2.9414626741334975},"translation":{"x":3.6356107410142777,"y":2.0958290690782664}},"time":5.246376608899745,"velocity":-1.8750946109282518,"position":-2.352796908011055,"holonomicRotation":-152.60964646518448,"angularVelocity":-0.05965389376001962,"angularAcceleration":0.30282287784398004,"curveRadius":32.20325591888975},{"acceleration":2.986995457915785,"curvature":0.030320150966548862,"pose":{"rotation":{"radians":-2.9418484786389234},"translation":{"x":3.6477756535750703,"y":2.0982917791340316}},"time":5.253067149956779,"velocity":-1.8551099951798917,"position":-2.3652085975991204,"holonomicRotation":-152.68561501397843,"angularVelocity":-0.05766417127360642,"angularAcceleration":0.2973933601859137,"curveRadius":32.98136612523019},{"acceleration":2.986744733498805,"curvature":0.029584427806574377,"pose":{"rotation":{"radians":-2.9422244173738017},"translation":{"x":3.6599165616488634,"y":2.1007448786978395}},"time":5.259817341404873,"velocity":-1.8349488964221894,"position":-2.3775948539474383,"holonomicRotation":-152.7615835627724,"angularVelocity":-0.05569304778525367,"angularAcceleration":0.29201001238408286,"curveRadius":33.801566369242934},{"acceleration":2.9864817581135763,"curvature":0.02884528350325833,"pose":{"rotation":{"radians":-2.942590474217783},"translation":{"x":3.6720329549983997,"y":2.1031884089839568}},"time":5.266628919896709,"velocity":-1.8146062415123634,"position":-2.3899551867932747,"holonomicRotation":-152.83755211156634,"angularVelocity":-0.053740384026980025,"angularAcceleration":0.2866683193350999,"curveRadius":34.667712656977045},{"acceleration":2.9862057401039213,"curvature":0.0281024045027576,"pose":{"rotation":{"radians":-2.9429466305682643},"translation":{"x":3.6841243233864205,"y":2.105622411206651}},"time":5.273503720243691,"velocity":-1.7940766732541351,"position":-2.402289105729076,"holonomicRotation":-152.9135206603603,"angularVelocity":-0.05180606454088317,"angularAcceleration":0.28136373254036434,"curveRadius":35.58414369495938},{"acceleration":2.9859158186273516,"curvature":0.027355469326331396,"pose":{"rotation":{"radians":-2.9432928653059647},"translation":{"x":3.696190156575668,"y":2.10804692658019}},"time":5.280443683054003,"velocity":-1.7733545285181398,"position":-2.4145961202064896,"holonomicRotation":-152.98948920915424,"angularVelocity":-0.04988999900487852,"angularAcceleration":0.2760916143754647,"curveRadius":36.555761046199116},{"acceleration":2.9856110560672513,"curvature":0.02660415087467187,"pose":{"rotation":{"radians":-2.9436291547583795},"translation":{"x":3.7082299443288838,"y":2.110461996318842}},"time":5.287450863145268,"velocity":-1.752433814165806,"position":-2.426875739540371,"holonomicRotation":-153.0654577579482,"angularVelocity":-0.047992123512573925,"angularAcceleration":0.2708472548993803,"curveRadius":37.588119414554846},{"acceleration":2.985290429379963,"curvature":0.025848113709612427,"pose":{"rotation":{"radians":-2.9439554726608717},"translation":{"x":3.7202431764088093,"y":2.112867661636874}},"time":5.294527438829703,"velocity":-1.7313081805022783,"position":-2.4391274729127774,"holonomicRotation":-153.14142630674215,"angularVelocity":-0.0461124019643967,"angularAcceleration":0.26562586652066894,"curveRadius":38.68754258954373},{"acceleration":2.9849528201038913,"curvature":0.02508701592910028,"pose":{"rotation":{"radians":-2.9442717901161233},"translation":{"x":3.7322293425781883,"y":2.1152639637485535}},"time":5.301675722184567,"velocity":-1.7099708919432761,"position":-2.451350829376957,"holonomicRotation":-153.2173948555361,"angularVelocity":-0.04425082772305055,"angularAcceleration":0.26042255866641395,"curveRadius":39.86125742599885},{"acceleration":2.9845970030601383,"curvature":0.024320506474156862,"pose":{"rotation":{"radians":-2.9445780755513775},"translation":{"x":3.744187932599761,"y":2.117650943868148}},"time":5.3088981704383205,"velocity":-1.6884147945303645,"position":-2.4635453178613256,"holonomicRotation":-153.29336340433005,"angularVelocity":-0.04240742536231171,"angularAcceleration":0.2552323389483137,"curveRadius":41.11756476217331},{"acceleration":2.9842216334800997,"curvature":0.023548225443974998,"pose":{"rotation":{"radians":-2.9448742946731685},"translation":{"x":3.7561184362362696,"y":2.120028643209926}},"time":5.3161973986238324,"velocity":-1.6666322798714526,"position":-2.475710447173447,"holonomicRotation":-153.369331953124,"angularVelocity":-0.040582252570069456,"angularAcceleration":0.25005010747095646,"curveRadius":42.46604494165219},{"acceleration":2.9838252319967418,"curvature":0.022769804887973154,"pose":{"rotation":{"radians":-2.945160410420638},"translation":{"x":3.7680203432504564,"y":2.122397102988154}},"time":5.32357619367473,"velocity":-1.644615245016854,"position":-2.4878457260040068,"holonomicRotation":-153.44530050191796,"angularVelocity":-0.03877540241948072,"angularAcceleration":0.24487062428561956,"curveRadius":43.917811545596194},{"acceleration":2.9834061675590795,"curvature":0.02198486700559628,"pose":{"rotation":{"radians":-2.945436382915294},"translation":{"x":3.779893143405064,"y":2.1247563644171}},"time":5.331037530170688,"velocity":-1.6223550476965762,"position":-2.4999506629307886,"holonomicRotation":-153.5212690507119,"angularVelocity":-0.03698700558614743,"angularAcceleration":0.23968853761009995,"curveRadius":45.48583349380502},{"acceleration":2.9829626375153864,"curvature":0.02119302341065787,"pose":{"rotation":{"radians":-2.9457021694094028},"translation":{"x":3.791736326462833,"y":2.127106468711032}},"time":5.3385845879729725,"velocity":-1.5998424562491926,"position":-2.51202476642265,"holonomicRotation":-153.59723759950586,"angularVelocity":-0.035217233135306746,"angularAcceleration":0.23449832997237402,"curveRadius":47.18533927995874},{"acceleration":2.982492644553258,"curvature":0.02039387582160195,"pose":{"rotation":{"radians":-2.945957724231459},"translation":{"x":3.803549382186506,"y":2.129447457084217}},"time":5.346220772034361,"velocity":-1.5770675934536484,"position":-2.524067544843512,"holonomicRotation":-153.6732061482998,"angularVelocity":-0.03346629939797008,"angularAcceleration":0.22929433382704933,"curveRadius":49.034328184972225},{"acceleration":2.9819939697913544,"curvature":0.019587015392822857,"pose":{"rotation":{"radians":-2.9462029987287632},"translation":{"x":3.815331800338825,"y":2.131779370750923}},"time":5.35394973471942,"velocity":-1.5540198733340616,"position":-2.5360785064563505,"holonomicRotation":-153.74917469709376,"angularVelocity":-0.03173446519262007,"angularAcceleration":0.22407071633273096,"curveRadius":51.05423056778847},{"acceleration":2.98146414137554,"curvature":0.018772021056329947,"pose":{"rotation":{"radians":-2.9464379412080355},"translation":{"x":3.8270830706825323,"y":2.1341022509254177}},"time":5.3617754010341345,"velocity":-1.5306879298343679,"position":-2.5480571594271963,"holonomicRotation":-153.82514324588772,"angularVelocity":-0.03002204155197237,"angularAcceleration":0.21882144877909096,"curveRadius":53.27076914090712},{"acceleration":2.9809003973180137,"curvature":0.017948460144752813,"pose":{"rotation":{"radians":-2.946662496872428},"translation":{"x":3.838802682980369,"y":2.1364161388219682}},"time":5.36970199724098,"velocity":-1.5070595360520038,"position":-2.560003011829156,"holonomicRotation":-153.90111179468167,"angularVelocity":-0.02832939366819051,"angularAcceleration":0.21354031914987076,"curveRadius":55.715085970333085},{"acceleration":2.9802996419646965,"curvature":0.017115886926332216,"pose":{"rotation":{"radians":-2.9468766077561677},"translation":{"x":3.8504901269950773,"y":2.1387210756548427}},"time":5.377734083430295,"velocity":-1.4831215124577573,"position":-2.5719155716464446,"holonomicRotation":-153.97708034347562,"angularVelocity":-0.026656945492504577,"angularAcceleration":0.20822089507837582,"curveRadius":58.42525159835765},{"acceleration":2.979658394089463,"curvature":0.01627384225140583,"pose":{"rotation":{"radians":-2.947080212656086},"translation":{"x":3.8621448924893995,"y":2.1410171026383082}},"time":5.385876590736074,"velocity":-1.4588596222151586,"position":-2.5837943467784372,"holonomicRotation":-154.05304889226957,"angularVelocity":-0.025005184800270575,"angularAcceleration":0.20285651952215403,"curveRadius":61.44830363669121},{"acceleration":2.978972725139009,"curvature":0.015421853191646323,"pose":{"rotation":{"radians":-2.947273247059721},"translation":{"x":3.873766469226077,"y":2.1433042609866324}},"time":5.3941348640301525,"velocity":-1.4342584513153547,"position":-2.5956388450437413,"holonomicRotation":-154.12901744106352,"angularVelocity":-0.023374668863689812,"angularAcceleration":0.1974402975680026,"curveRadius":64.84305015571526},{"acceleration":2.978238185106411,"curvature":0.014559432093713529,"pose":{"rotation":{"radians":-2.9474556430705117},"translation":{"x":3.885354346967853,"y":2.1455825919140836}},"time":5.402514711111575,"velocity":-1.4093012707521084,"position":-2.607448574184299,"holonomicRotation":-154.20498598985748,"angularVelocity":-0.02176603093329209,"angularAcceleration":0.19196506985955278,"curveRadius":68.68399766992148},{"acceleration":2.977449713329422,"curvature":0.013686076625427672,"pose":{"rotation":{"radians":-2.947627329329571},"translation":{"x":3.8969080154774676,"y":2.1478521366349286}},"time":5.411022459638473,"velocity":-1.383969877339619,"position":-2.6192230418695055,"holonomicRotation":-154.28095453865143,"angularVelocity":-0.020179987515673403,"angularAcceleration":0.18642340127994902,"curveRadius":73.06695902477101},{"acceleration":2.9766015301507784,"curvature":0.012801267335222521,"pose":{"rotation":{"radians":-2.9477882309335706},"translation":{"x":3.908426964517664,"y":2.1501129363634353}},"time":5.419665023342877,"velocity":-1.3582444089926642,"position":-2.6309617557003753,"holonomicRotation":-154.35692308744538,"angularVelocity":-0.018617346600248587,"angularAcceleration":0.1808075669293042,"curveRadius":78.11726556545796},{"acceleration":2.9756870047971407,"curvature":0.011904468552833109,"pose":{"rotation":{"radians":-2.947938269349375},"translation":{"x":3.9199106838511835,"y":2.152365032313871}},"time":5.428449979444317,"velocity":-1.3321031292838947,"position":-2.6426642232137256,"holonomicRotation":-154.43289163623933,"angularVelocity":-0.01707901713701334,"angularAcceleration":0.1751095219454796,"curveRadius":84.0020699422162},{"acceleration":2.974698492937233,"curvature":0.010995125246967927,"pose":{"rotation":{"radians":-2.948077362324641},"translation":{"x":3.931358663240769,"y":2.154608465700504}},"time":5.4373856596631835,"velocity":-1.3055221748034656,"position":-2.6543299518864076,"holonomicRotation":-154.50886018503329,"angularVelocity":-0.015566019805898633,"angularAcceleration":0.16932089041417692,"curveRadius":90.94939598580427},{"acceleration":2.973627135616422,"curvature":0.010072666157913789,"pose":{"rotation":{"radians":-2.9482054237943385},"translation":{"x":3.9427703924491606,"y":2.1568432777376016}},"time":5.4464812578673385,"velocity":-1.2784752571689244,"position":-2.6659584491395707,"holonomicRotation":-154.58482873382724,"angularVelocity":-0.014079499426321536,"angularAcceleration":0.16343294264009287,"curveRadius":99.278580697756},{"acceleration":2.9724626082642955,"curvature":0.009136500577897857,"pose":{"rotation":{"radians":-2.9483223637835123},"translation":{"x":3.9541453612391018,"y":2.1590695096394312}},"time":5.45574695821835,"velocity":-1.2509333093361594,"position":-2.6775492223429795,"holonomicRotation":-154.6607972826212,"angularVelocity":-0.012620739366027785,"angularAcceleration":0.15743656766694394,"curveRadius":109.4510957969076},{"acceleration":2.9711928048743492,"curvature":0.008186014152096617,"pose":{"rotation":{"radians":-2.9484280883050156},"translation":{"x":3.9654830593733346,"y":2.1612872026202608}},"time":5.465194088791907,"velocity":-1.2228640629493015,"position":-2.6891017788193707,"holonomicRotation":-154.73676583141514,"angularVelocity":-0.01119117817628125,"angularAcceleration":0.15132226432310664,"curveRadius":122.15957380722072},{"acceleration":2.9698034367392867,"curvature":0.00722057161726281,"pose":{"rotation":{"radians":-2.9485224992534715},"translation":{"x":3.9767829766146003,"y":2.1634963978943573}},"time":5.4748353071386004,"velocity":-1.194231539568937,"position":-2.700615625848863,"holonomicRotation":-154.8127343802091,"angularVelocity":-0.009792429240890192,"angularAcceleration":0.1450801014034442,"curveRadius":138.49319042958018},{"acceleration":2.9682775176111784,"curvature":0.006239521454792665,"pose":{"rotation":{"radians":-2.9486054942938753},"translation":{"x":3.9880446027256413,"y":2.165697136675989}},"time":5.484684826283711,"velocity":-1.164995433331224,"position":-2.7120902706734253,"holonomicRotation":-154.88870292900305,"angularVelocity":-0.00842630378001397,"angularAcceleration":0.13869971119903554,"curveRadius":160.26870125302412},{"acceleration":2.9665946958488534,"curvature":0.005242178461273106,"pose":{"rotation":{"radians":-2.948676966745737},"translation":{"x":3.999267427469199,"y":2.167889460179423}},"time":5.49475869247149,"velocity":-1.1351103553318682,"position":-2.7235252205014007,"holonomicRotation":-154.964671477797,"angularVelocity":-0.007094838320216549,"angularAcceleration":0.13217025469453778,"curveRadius":190.7603885269373},{"acceleration":2.964730377742533,"curvature":0.004227838727343372,"pose":{"rotation":{"radians":-2.948736805461802},"translation":{"x":4.010450940608015,"y":2.170073409618927}},"time":5.505075129893177,"velocity":-1.1045248999177146,"position":-2.7349199825120962,"holonomicRotation":-155.04064002659095,"angularVelocity":-0.005800327537398178,"angularAcceleration":0.1254804085853465,"curveRadius":236.5274705330034},{"acceleration":2.962654561611689,"curvature":0.0031957728155476654,"pose":{"rotation":{"radians":-2.9487848947012916},"translation":{"x":4.021594631904834,"y":2.172249026208769}},"time":5.515654973240133,"velocity":-1.0731804787647166,"position":-2.746274063860439,"holonomicRotation":-155.1166085753849,"angularVelocity":-0.004545364039199792,"angularAcceleration":0.11861834405699286,"curveRadius":312.91335702429404},{"acceleration":2.9603302646244463,"curvature":0.002145227207277029,"pose":{"rotation":{"radians":-2.9488211139977327},"translation":{"x":4.032697991122394,"y":2.174416351163216}},"time":5.52652221704439,"velocity":-1.0410098480379208,"position":-2.7575869716817,"holonomicRotation":-155.19257712417885,"angularVelocity":-0.003332887077306938,"angularAcceleration":0.11157170886493299,"curveRadius":466.1510895479067},{"acceleration":2.9577113663450327,"curvature":0.001075403003059987,"pose":{"rotation":{"radians":-2.9488453380210324},"translation":{"x":4.043760508023438,"y":2.1765754256965364}},"time":5.537704722774091,"velocity":-1.0079352237369663,"position":-2.7688582130963058,"holonomicRotation":-155.2685456729728,"angularVelocity":-0.0021662428694647086,"angularAcceleration":0.10432761994868596,"curveRadius":929.8839571347368},{"acceleration":2.954739599326109,"curvature":-0.000014040995586777061,"pose":{"rotation":{"radians":-2.948857436432739},"translation":{"x":4.05478167237071,"y":2.178726291022997}},"time":5.549235142790373,"velocity":-0.9738658351179974,"position":-2.780087295214723,"holonomicRotation":-155.34451422176676,"angularVelocity":-0.0010492602775615555,"angularAcceleration":0.09687267162219027,"curveRadius":-71220.02096074569},{"acceleration":2.951340265451071,"curvature":-0.0011253735426977017,"pose":{"rotation":{"radians":-2.948857273735356},"translation":{"x":4.06576097392695,"y":2.180868988356866}},"time":5.561152148358353,"velocity":-0.9386946967416133,"position":-2.791273725142426,"holonomicRotation":-155.4204827705607,"angularVelocity":0.000013652538986691613,"angularAcceleration":0.08919294452661854,"curveRadius":-888.5938420080846},{"acceleration":2.9474159995329186,"curvature":-0.002258051319778273,"pose":{"rotation":{"radians":-2.9488447091150545},"translation":{"x":4.076697902454901,"y":2.183003558912411}},"time":5.573502093610957,"velocity":-0.9022942705107316,"position":-2.802417009984972,"holonomicRotation":-155.49645131935466,"angularVelocity":0.0010173826721114757,"angularAcceleration":0.0812740552767323,"curveRadius":-442.85973097289656},{"acceleration":2.9428374548894465,"curvature":-0.0034134702948364327,"pose":{"rotation":{"radians":-2.9488195962766364},"translation":{"x":4.087591947717305,"y":2.1851300439038983}},"time":5.586341320799107,"velocity":-0.8645105118496073,"position":-2.8135166568531536,"holonomicRotation":-155.57241986814861,"angularVelocity":0.0019559462614138793,"angularAcceleration":0.07310125255580902,"curveRadius":-292.9569949715699},{"acceleration":2.9374289762379475,"curvature":-0.004592587904926311,"pose":{"rotation":{"radians":-2.9487817832713477},"translation":{"x":4.098442599476902,"y":2.1872484845455973}},"time":5.59973943722825,"velocity":-0.8251544964236355,"position":-2.8245721728682676,"holonomicRotation":-155.64838841694257,"angularVelocity":0.002822262777659166,"angularAcceleration":0.06465957515945818,"curveRadius":-217.74215773362428},{"acceleration":2.9309457952961204,"curvature":-0.005796394312561253,"pose":{"rotation":{"radians":-2.948731112317581},"translation":{"x":4.109249347496437,"y":2.189358922051775}},"time":5.613784116425581,"velocity":-0.783990302983934,"position":-2.8355830651674956,"holonomicRotation":-155.72435696573652,"angularVelocity":0.0036078398840380358,"angularAcceleration":0.0559341438377698,"curveRadius":-172.5210443038562},{"acceleration":2.92303624008732,"curvature":-0.007025923612620058,"pose":{"rotation":{"radians":-2.9486674196120295},"translation":{"x":4.12001168153865,"y":2.191461397636698}},"time":5.6285883906966845,"velocity":-0.7407168727813077,"position":-2.8465488409093838,"holonomicRotation":-155.80032551453047,"angularVelocity":0.004302318667240203,"angularAcceleration":0.04691069420118392,"curveRadius":-142.33004159108515},{"acceleration":2.913176011429469,"curvature":-0.008282256583210263,"pose":{"rotation":{"radians":-2.9485905351332895},"translation":{"x":4.130729091366282,"y":2.193555952514635}},"time":5.6443022233877755,"velocity":-0.6949397123380038,"position":-2.8574690072794584,"holonomicRotation":-155.87629406332442,"angularVelocity":0.004892789700095178,"angularAcceleration":0.03757651264733941,"curveRadius":-120.74004106890308},{"acceleration":2.900546933522132,"curvature":-0.009566513340533399,"pose":{"rotation":{"radians":-2.9485002824362567},"translation":{"x":4.141401066742078,"y":2.195642627899854}},"time":5.661131897904547,"velocity":-0.6461244515262059,"position":-2.868343071495972,"holonomicRotation":-155.95226261211837,"angularVelocity":0.005362711972999575,"angularAcceleration":0.027922243679525248,"curveRadius":-104.53129206050353},{"acceleration":2.883796089556344,"curvature":-0.010879864924751907,"pose":{"rotation":{"radians":-2.9483964784368615},"translation":{"x":4.152027097428776,"y":2.1977214650066217}},"time":5.67937483988543,"velocity":-0.5935155267797324,"position":-2.879170540815768,"holonomicRotation":-156.02823116091233,"angularVelocity":0.005690090968004199,"angularAcceleration":0.01794551533122722,"curveRadius":-91.9129058050142},{"acceleration":2.8605090902071186,"curvature":-0.01222353255044842,"pose":{"rotation":{"radians":-2.9482789331867014},"translation":{"x":4.1626066731891225,"y":2.199792505049206}},"time":5.699488202720184,"velocity":-0.5359810695562831,"position":-2.8899509225403133,"holonomicRotation":-156.10419970970628,"angularVelocity":0.005844137110525639,"angularAcceleration":0.007658895421269851,"curveRadius":-81.80941113977032},{"acceleration":2.8258968011631236,"curvature":-0.013598788983351397,"pose":{"rotation":{"radians":-2.948147449637568},"translation":{"x":4.173139283785855,"y":2.201855789241874}},"time":5.722242646524313,"velocity":-0.4716793595979503,"position":-2.900683724021852,"holonomicRotation":-156.18016825850023,"angularVelocity":0.005778367964741296,"angularAcceleration":-0.002890386877855051,"curveRadius":-73.53595979938147},{"acceleration":2.7688205263943964,"curvature":-0.015006964681912238,"pose":{"rotation":{"radians":-2.9480018233949083},"translation":{"x":4.183624418981719,"y":2.2039113587988943}},"time":5.749142956691253,"velocity":-0.3971972286413496,"position":-2.9113684526697536,"holonomicRotation":-156.25613680729418,"angularVelocity":0.00541355254850408,"angularAcceleration":-0.013561755012236276,"curveRadius":-66.63572689054777},{"acceleration":2.6549626095398913,"curvature":-0.016449445658297583,"pose":{"rotation":{"radians":-2.9478418424593826},"translation":{"x":4.194061568539453,"y":2.205959254934534}},"time":5.7840795554323075,"velocity":-0.3044418652793536,"position":-2.9220046159569963,"holonomicRotation":-156.3321053560881,"angularVelocity":0.0045791788923552025,"angularAcceleration":-0.023882509637906228,"curveRadius":-60.792322171390055},{"acceleration":2.1237763297242545,"curvature":-0.016449445658297583,"pose":{"rotation":{"radians":-2.947667286956665},"translation":{"x":4.204450222221802,"y":2.20799951886306}},"time":5.8680918778215645,"velocity":-0.12601848358388595,"position":-2.932591721426851,"holonomicRotation":-156.4080739048821,"angularVelocity":0.0020777369051735678,"angularAcceleration":-0.029774703472564595,"curveRadius":-60.792322171390055}] \ No newline at end of file diff --git a/src/main/deploy/pathplanner/generatedJSON/Blue3(3).wpilib.json b/src/main/deploy/pathplanner/generatedJSON/Blue3(3).wpilib.json new file mode 100644 index 0000000..fac8a1e --- /dev/null +++ b/src/main/deploy/pathplanner/generatedJSON/Blue3(3).wpilib.json @@ -0,0 +1 @@ +[{"acceleration":0.0,"curvature":-0.49005192957849214,"pose":{"rotation":{"radians":0.6547715377798351},"translation":{"x":1.27,"y":1.56}},"time":0.0,"velocity":0,"position":0.0,"holonomicRotation":-137.4919052551881,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-2.0406000663238464},{"acceleration":1.5000000000000004,"curvature":-0.49005192957849214,"pose":{"rotation":{"radians":0.6547715377798351},"translation":{"x":1.2767633157029699,"y":1.5651926095354833}},"time":0.0753956666456139,"velocity":0.11309349996842089,"position":0.008526759823404806,"holonomicRotation":-137.56787380398205,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-2.0406000663238464},{"acceleration":5.118311050823247,"curvature":-0.48674501036722434,"pose":{"rotation":{"radians":0.6505909436351445},"translation":{"x":1.2835548923646523,"y":1.5703619316861777}},"time":0.1066515477403831,"velocity":0.27307082157899554,"position":0.017061828953128827,"holonomicRotation":-137.643842352776,"angularVelocity":-0.13375384082166442,"angularAcceleration":-4.279317559985492,"curveRadius":-2.0544637925421174},{"acceleration":3.4533727139069503,"curvature":-0.48343650601767313,"pose":{"rotation":{"radians":0.6464344892569054},"translation":{"x":1.2903746171007615,"y":1.5755080518216216}},"time":0.13065302032591,"velocity":0.35595685209943984,"position":0.025605317580423986,"holonomicRotation":-137.71981090156996,"angularVelocity":-0.1731749734699804,"angularAcceleration":-1.642446416895573,"curveRadius":-2.068523968612835},{"acceleration":3.277935063237427,"curvature":-0.48012711312301487,"pose":{"rotation":{"radians":0.6423021907598532},"translation":{"x":1.2972223770270128,"y":1.5806310553113532}},"time":0.15090247128883455,"velocity":0.4223332374221171,"position":0.03415733376161632,"holonomicRotation":-137.7957794503639,"angularVelocity":-0.20406965623997342,"angularAcceleration":-1.5257047130097114,"curveRadius":-2.082781773133872},{"acceleration":3.201278988051706,"curvature":-0.47681751270129574,"pose":{"rotation":{"radians":0.638194060444945},"translation":{"x":1.3040980592591205,"y":1.585731027524911}},"time":0.1687562017220605,"velocity":0.4794880095163426,"position":0.04271798342948517,"holonomicRotation":-137.87174799915786,"angularVelocity":-0.23009926862472024,"angularAcceleration":-1.4579368990754729,"curveRadius":-2.0972384053906468},{"acceleration":3.1578867858992523,"curvature":-0.47350837022268566,"pose":{"rotation":{"radians":0.6341101068746324},"translation":{"x":1.3110015509128004,"y":1.5908080538318334}},"time":0.18490965434476975,"velocity":0.5304987841002458,"position":0.05128737040485336,"holonomicRotation":-137.9477165479518,"angularVelocity":-0.25282233251924985,"angularAcceleration":-1.4067001293942873,"curveRadius":-2.1118950854653558},{"acceleration":3.1298822821179,"curvature":-0.4702003358780014,"pose":{"rotation":{"radians":0.630050334949158},"translation":{"x":1.3179327391037663,"y":1.5958622196016587}},"time":0.19977586842654932,"velocity":0.5770282841569793,"position":0.05986559640837295,"holonomicRotation":-138.02368509674577,"angularVelocity":-0.27308714264045403,"angularAcceleration":-1.3631453179489237,"curveRadius":-2.1267530533186623},{"acceleration":3.11028722390555,"curvature":-0.4668940442981497,"pose":{"rotation":{"radians":0.6260147459819274},"translation":{"x":1.3248915109477337,"y":1.600893610203926}},"time":0.21362390795119096,"velocity":0.6200996645666113,"position":0.0684527610725084,"holonomicRotation":-138.09965364553972,"angularVelocity":-0.29141951537974,"angularAcceleration":-1.3238244089832891,"curveRadius":-2.141813570364198},{"acceleration":3.0957981647362143,"curvature":-0.46359011460281674,"pose":{"rotation":{"radians":0.6220033377753893},"translation":{"x":1.3318777535604176,"y":1.6059023110081723}},"time":0.2266406288285434,"velocity":0.6603968051696025,"position":0.07704896195369643,"holonomicRotation":-138.17562219433367,"angularVelocity":-0.3081734827330813,"angularAcceleration":-1.2871112095897557,"curveRadius":-2.157077919697997},{"acceleration":3.0846447777567985,"curvature":-0.46028915073960014,"pose":{"rotation":{"radians":0.6180161046972263},"translation":{"x":1.338891354057532,"y":1.6108884073839371}},"time":0.23896205353526384,"velocity":0.6984040235457113,"position":0.08565429454468551,"holonomicRotation":-138.25159074312762,"angularVelocity":-0.3236016266843081,"angularAcceleration":-1.2521396119729444,"curveRadius":-2.1725474050239586},{"acceleration":3.0757916398132377,"curvature":-0.45699174117319474,"pose":{"rotation":{"radians":0.6140530377550011},"translation":{"x":1.3459321995547928,"y":1.6158519847007589}},"time":0.2506908485060703,"velocity":0.7344793530620014,"position":0.09426885228704031,"holonomicRotation":-138.32755929192157,"angularVelocity":-0.3378920811634543,"angularAcceleration":-1.2184077319721118,"curveRadius":-2.1882233526426274},{"acceleration":3.068592271781605,"curvature":-0.45369845919106505,"pose":{"rotation":{"radians":0.6101141246722808},"translation":{"x":1.3530001771679143,"y":1.6207931283281753}},"time":0.2619067602332324,"velocity":0.7688964131089556,"position":0.1028927265838019,"holonomicRotation":-138.40352784071553,"angularVelocity":-0.35118973637972534,"angularAcceleration":-1.1856062654333748,"curveRadius":-2.204107110663279},{"acceleration":3.06262199480057,"curvature":-0.4504098628388495,"pose":{"rotation":{"radians":0.6061993499633975},"translation":{"x":1.3600951740126115,"y":1.6257119236357251}},"time":0.27267319488391645,"velocity":0.8018699326757236,"position":0.1115260068123035,"holonomicRotation":-138.47949638950948,"angularVelocity":-0.3636092017364831,"angularAcceleration":-1.1535355723325431,"curveRadius":-2.22020005001042},{"acceleration":3.0575902347029524,"curvature":-0.44712649538672933,"pose":{"rotation":{"radians":0.6023086950082623},"translation":{"x":1.3672170772045993,"y":1.6306084559929468}},"time":0.28304155211691145,"velocity":0.8335721205012409,"position":0.12016878033712552,"holonomicRotation":-138.55546493830343,"angularVelocity":-0.37524314293049593,"angularAcceleration":-1.1220621485716555,"curveRadius":-2.2365035629013184},{"acceleration":3.0532914176646972,"curvature":-0.4438488846061346,"pose":{"rotation":{"radians":0.5984421381267921},"translation":{"x":1.3743657738595925,"y":1.6354828107693784}},"time":0.2930541844360144,"velocity":0.86414360482939,"position":0.1288211325231864,"holonomicRotation":-138.63143348709738,"angularVelocity":-0.38616786857270863,"angularAcceleration":-1.0910942591359913,"curveRadius":-2.253019067260665},{"acceleration":3.0495759848364634,"curvature":-0.44057754391960846,"pose":{"rotation":{"radians":0.5945996546530963},"translation":{"x":1.3815411510933058,"y":1.640335073334559}},"time":0.30274648002243526,"velocity":0.8937009966876756,"position":0.13748314674896228,"holonomicRotation":-138.70740203589133,"angularVelocity":-0.3964472027740543,"angularAcceleration":-1.0605675517931243,"curveRadius":-2.2697480019146608},{"acceleration":3.046332517945683,"curvature":-0.43731297178441064,"pose":{"rotation":{"radians":0.5907812170087636},"translation":{"x":1.3887430960214542,"y":1.6451653290580264}},"time":0.3121483668811198,"velocity":0.9223422703553324,"position":0.14615490441982534,"holonomicRotation":-138.7833705846853,"angularVelocity":-0.4061352472887454,"angularAcceleration":-1.0304361943839189,"curveRadius":-2.286691830611845},{"acceleration":3.043476302547651,"curvature":-0.43405565199067947,"pose":{"rotation":{"radians":0.5869867947763603},"translation":{"x":1.3959714957597527,"y":1.649973663309319}},"time":0.3212854234493025,"velocity":0.9501506854956339,"position":0.15483648498149652,"holonomicRotation":-138.85933913347924,"angularVelocity":-0.4152784000064502,"angularAcceleration":-1.0006671896443495,"curveRadius":-2.303852041584458},{"acceleration":3.0409417757739914,"curvature":-0.4308060540184839,"pose":{"rotation":{"radians":0.5832163547718578},"translation":{"x":1.4032262374239162,"y":1.6547601614579752}},"time":0.3301797146339182,"velocity":0.9771977071248301,"position":0.16352796593360358,"holonomicRotation":-138.9353076822732,"angularVelocity":-0.4239168615284487,"angularAcceleration":-0.9712366441229484,"curveRadius":-2.3212301467729484},{"acceleration":3.0386774010988575,"curvature":-0.4275646329631879,"pose":{"rotation":{"radians":0.5794698611167379},"translation":{"x":1.4105072081296592,"y":1.659524908873534}},"time":0.33885043194437847,"velocity":1.0035452198674424,"position":0.17222942284333786,"holonomicRotation":-139.01127623106714,"angularVelocity":-0.4320857803310217,"angularAcceleration":-0.9421272208607331,"curveRadius":-2.33882768336009},{"acceleration":3.0366421060639848,"curvature":-0.42433182975700584,"pose":{"rotation":{"radians":0.5757472753092423},"translation":{"x":1.4178142949926966,"y":1.6642679909255327}},"time":0.3473143910630091,"velocity":1.0292472345110804,"position":0.18094092935920328,"holonomicRotation":-139.0872447798611,"angularVelocity":-0.4398161374978261,"angularAcceleration":-0.9133263828966969,"curveRadius":-2.3566462138196216},{"acceleration":3.0348027535863857,"curvature":-0.4211080712489954,"pose":{"rotation":{"radians":0.572048556295683},"translation":{"x":1.4251473851287437,"y":1.6689894929835105}},"time":0.3555864238361312,"velocity":1.0543512223487082,"position":0.18966255722485315,"holonomicRotation":-139.16321332865505,"angularVelocity":-0.4471354399824667,"angularAcceleration":-0.8848251313054287,"curveRadius":-2.374687326780573},{"acceleration":3.0331323130034633,"curvature":-0.4178937705868857,"pose":{"rotation":{"radians":0.5683736605402183},"translation":{"x":1.4325063656535149,"y":1.6736895004170058}},"time":0.3636796908388855,"velocity":1.078899172012527,"position":0.19839437629300108,"holonomicRotation":-139.239181877449,"angularVelocity":-0.4540682710967031,"angularAcceleration":-0.8566171253063856,"curveRadius":-2.39295263625397},{"acceleration":3.0316085148244443,"curvature":-0.4146893271093308,"pose":{"rotation":{"radians":0.5647225420944815},"translation":{"x":1.4398911236827254,"y":1.6783680985955571}},"time":0.3716059333392564,"velocity":1.1029284362672147,"position":0.20713645453940988,"holonomicRotation":-139.31515042624295,"angularVelocity":-0.4606367324196809,"angularAcceleration":-0.8286980019435982,"curveRadius":-2.411443783640843},{"acceleration":3.0302128462234483,"curvature":-0.41149512663776866,"pose":{"rotation":{"radians":0.5610951526664261},"translation":{"x":1.44730154633209,"y":1.6830253728887021}},"time":0.379375678430534,"velocity":1.1264724176546856,"position":0.21588885807694197,"holonomicRotation":-139.3911189750369,"angularVelocity":-0.4668608024383652,"angularAcceleration":-0.8010648928072965,"curveRadius":-2.430162437574336},{"acceleration":3.0289297906091885,"curvature":-0.4083115418767683,"pose":{"rotation":{"radians":0.5574914416884917},"translation":{"x":1.4547375207173234,"y":1.6876614086659796}},"time":0.3869984075502763,"velocity":1.1495611289712173,"position":0.22465165116967473,"holonomicRotation":-139.46708752383086,"angularVelocity":-0.47275863031797544,"angularAcceleration":-0.7737160519498573,"curveRadius":-2.4491102930952855},{"acceleration":3.02774624477229,"curvature":-0.4051389321663341,"pose":{"rotation":{"radians":0.5539113563847011},"translation":{"x":1.4621989339541404,"y":1.6922762912969278}},"time":0.3944826960692244,"velocity":1.1722216554292548,"position":0.23342489624706625,"holonomicRotation":-139.5430560726248,"angularVelocity":-0.4783467786853548,"angularAcceleration":-0.7466505805103244,"curveRadius":-2.4682890746955892},{"acceleration":3.02665106702799,"curvature":-0.40197764409218895,"pose":{"rotation":{"radians":0.5503548418372959},"translation":{"x":1.4696856731582564,"y":1.6968701061510858}},"time":0.40183632979790257,"velocity":1.1944785388006915,"position":0.2422086539181732,"holonomicRotation":-139.61902462141876,"angularVelocity":-0.4836404257578581,"angularAcceleration":-0.7198681995621852,"curveRadius":-2.487700534337829},{"acceleration":3.0256347232393215,"curvature":-0.3988280112939315,"pose":{"rotation":{"radians":0.546821841052405},"translation":{"x":1.4771976254453854,"y":1.701442938597991}},"time":0.4090664029110726,"velocity":1.2163540990634578,"position":0.25100298298590606,"holonomicRotation":-139.6949931702127,"angularVelocity":-0.488653534976741,"angularAcceleration":-0.6933690905215376,"curveRadius":-2.50734645431665},{"acceleration":3.0246890068374435,"curvature":-0.39569035503694255,"pose":{"rotation":{"radians":0.5433122950250966},"translation":{"x":1.484734677931243,"y":1.7059948740071826}},"time":0.4161794007887544,"velocity":1.23786870554974,"position":0.25980794046133004,"holonomicRotation":-139.77096171900666,"angularVelocity":-0.49339899823677097,"angularAcceleration":-0.6671537573376253,"curveRadius":-2.527228645506504},{"acceleration":3.023806815397038,"curvature":-0.39256498418008545,"pose":{"rotation":{"radians":0.5398261428031672},"translation":{"x":1.4922967177315438,"y":1.7105259977481984}},"time":0.4231812705196904,"velocity":1.2590410069626665,"position":0.26862358157798916,"holonomicRotation":-139.84693026780062,"angularVelocity":-0.4978887577023439,"angularAcceleration":-0.6412229358875474,"curveRadius":-2.54734894934302},{"acceleration":3.0229819708862444,"curvature":-0.3894521953480697,"pose":{"rotation":{"radians":0.5363633215507857},"translation":{"x":1.4998836319620024,"y":1.7150363951905774}},"time":0.4300774812412784,"velocity":1.2798881276414595,"position":0.2774499598062634,"holonomicRotation":-139.92289881659457,"angularVelocity":-0.5021339097921457,"angularAcceleration":-0.615577490477872,"curveRadius":-2.5677092386300666},{"acceleration":3.0222090739087166,"curvature":-0.3863522733149574,"pose":{"rotation":{"radians":0.5329237666101498},"translation":{"x":1.5074953077383342,"y":1.7195261517038574}},"time":0.43687307605126763,"velocity":1.3004258359388159,"position":0.2862871268677451,"holonomicRotation":-139.99886736538852,"angularVelocity":-0.5061447947985179,"angularAcceleration":-0.5902183868403167,"curveRadius":-2.588311416987036},{"acceleration":3.021483384718697,"curvature":-0.38326549108283553,"pose":{"rotation":{"radians":0.5295074115637184},"translation":{"x":1.5151316321762536,"y":1.7239953526575766}},"time":0.4435727168868941,"velocity":1.3206686894072441,"position":0.29513513274963116,"holonomicRotation":-140.07483591418247,"angularVelocity":-0.5099310739561457,"angularAcceleration":-0.5651465877832694,"curveRadius":-2.609157420290336},{"acceleration":3.020800725367698,"curvature":-0.3801921100656907,"pose":{"rotation":{"radians":0.5261141882942884},"translation":{"x":1.5227924923914757,"y":1.7284440834212744}},"time":0.45018072350196603,"velocity":1.340630160583288,"position":0.3039940257191305,"holonomicRotation":-140.1508044629764,"angularVelocity":-0.5135017966977465,"angularAcceleration":-0.5403630700757085,"curveRadius":-2.6302492175001135},{"acceleration":3.020157398820224,"curvature":-0.37713238053930825,"pose":{"rotation":{"radians":0.522744027044618},"translation":{"x":1.5304777754997154,"y":1.7328724293644886}},"time":0.45670110746371395,"velocity":1.3603227464485097,"position":0.3128638523378742,"holonomicRotation":-140.22677301177035,"angularVelocity":-0.5168654590652262,"angularAcceleration":-0.5158687566886704,"curveRadius":-2.6515888096640663},{"acceleration":3.019550121621521,"curvature":-0.3740865415193106,"pose":{"rotation":{"radians":0.519396856476471},"translation":{"x":1.5381873686166874,"y":1.7372804758567577}},"time":0.46313760192577214,"velocity":1.3797580640842337,"position":0.3217446574763325,"holonomicRotation":-140.3027415605643,"angularVelocity":-0.5200300548501694,"angularAcceleration":-0.4916644927759757,"curveRadius":-2.673178232872565},{"acceleration":3.0189759675667744,"curvature":-0.37105482111163673,"pose":{"rotation":{"radians":0.5160726037281216},"translation":{"x":1.5459211588581065,"y":1.7416683082676196}},"time":0.4694936878015348,"velocity":1.3989469345909518,"position":0.3306364843282275,"holonomicRotation":-140.37871010935825,"angularVelocity":-0.5230031206824439,"angularAcceleration":-0.4677510484261351,"curveRadius":-2.6950195580375893},{"acceleration":3.0184323203872596,"curvature":-0.36803743681660817,"pose":{"rotation":{"radians":0.5127711944715534},"translation":{"x":1.5536790333396882,"y":1.7460360119666134}},"time":0.47577261685595296,"velocity":1.4178994569862262,"position":0.3395393744249421,"holonomicRotation":-140.4546786581522,"angularVelocity":-0.5257917756285437,"angularAcceleration":-0.44412907391230494,"curveRadius":-2.71711489094599},{"acceleration":3.01791683368255,"curvature":-0.36503459562412593,"pose":{"rotation":{"radians":0.5094925529681147},"translation":{"x":1.5614608791771463,"y":1.750383672323277}},"time":0.4819774321479623,"velocity":1.436625073505872,"position":0.34845336764991536,"holonomicRotation":-140.53064720694616,"angularVelocity":-0.5284027564303155,"angularAcceleration":-0.42079911792608315,"curveRadius":-2.739466373838425},{"acceleration":3.017427396982089,"curvature":-0.36204649421631907,"pose":{"rotation":{"radians":0.506236602123634},"translation":{"x":1.569266583486196,"y":1.754711374707149}},"time":0.4881109861858801,"velocity":1.4551326275007554,"position":0.3573785022530286,"holonomicRotation":-140.6066157557401,"angularVelocity":-0.5308424486606502,"angularAcceleration":-0.3977615938903344,"curveRadius":-2.762076186277087},{"acceleration":3.0169621067798587,"curvature":-0.3590733192811396,"pose":{"rotation":{"radians":0.503003263542579},"translation":{"x":1.5770960333825532,"y":1.7590192044877682}},"time":0.4941759571009573,"velocity":1.4734304149302653,"position":0.36631481486497075,"holonomicRotation":-140.68258430453406,"angularVelocity":-0.5331169145456428,"angularAcceleration":-0.3750167835658347,"curveRadius":-2.784946545184665},{"acceleration":3.0165192417065327,"curvature":-0.35611524772252506,"pose":{"rotation":{"radians":0.4997924575810089},"translation":{"x":1.5849491159819313,"y":1.763307247034672}},"time":0.5001748630972832,"velocity":1.491526230297371,"position":0.37526234051157903,"holonomicRotation":-140.758552853328,"angularVelocity":-0.5352319178757885,"angularAcceleration":-0.3525648395625882,"curveRadius":-2.808079705643977},{"acceleration":3.0160972412552245,"curvature":-0.35317244670976694,"pose":{"rotation":{"radians":0.4966041033989623},"translation":{"x":1.592825718400046,"y":1.7675755877174}},"time":0.5061100753974132,"velocity":1.509427407742057,"position":0.38422111262816294,"holonomicRotation":-140.83452140212196,"angularVelocity":-0.5371929462366062,"angularAcceleration":-0.3304057650599542,"curveRadius":-2.8314779630070874},{"acceleration":3.0156946873578008,"curvature":-0.3502450741086155,"pose":{"rotation":{"radians":0.49343811901131973},"translation":{"x":1.600725727752612,"y":1.7718243119054895}},"time":0.5119838298708201,"velocity":1.5271408579023547,"position":0.3931911630737895,"holonomicRotation":-140.91048995091592,"angularVelocity":-0.5390052311475338,"angularAcceleration":-0.30853943914963705,"curveRadius":-2.855143652041448},{"acceleration":3.015310288482744,"curvature":-0.3473332785354671,"pose":{"rotation":{"radians":0.4902944213385325},"translation":{"x":1.608649031155344,"y":1.7760535049684794}},"time":0.5177982375053974,"velocity":1.5446731010643282,"position":0.4021725221455441,"holonomicRotation":-140.98645849970987,"angularVelocity":-0.5406737659898794,"angularAcceleration":-0.2869655770990377,"curveRadius":-2.8790791490424015},{"acceleration":3.0149428657869706,"curvature":-0.34443719957568447,"pose":{"rotation":{"radians":0.4871729262556115},"translation":{"x":1.616595515723957,"y":1.7802632522759079}},"time":0.5235552938596845,"velocity":1.5620302970476194,"position":0.41116521859275096,"holonomicRotation":-141.06242704850382,"angularVelocity":-0.5422033224664533,"angularAcceleration":-0.2656837769939391,"curveRadius":-2.903286872706867},{"acceleration":3.014591341073916,"curvature":-0.3415569680044808,"pose":{"rotation":{"radians":0.4840735486406129},"translation":{"x":1.6245650685741664,"y":1.7844536391973138}},"time":0.5292568876145486,"velocity":1.579218272211354,"position":0.4201692796311585,"holonomicRotation":-141.13839559729777,"angularVelocity":-0.5435984653158492,"angularAcceleration":-0.24469348560754337,"curveRadius":-2.92776928499635},{"acceleration":3.0142547262342942,"curvature":-0.3386927062894072,"pose":{"rotation":{"radians":0.4809962024220864},"translation":{"x":1.6325575768216858,"y":1.7886247511022353}},"time":0.5349048083270387,"velocity":1.5962425439123737,"position":0.4291847309570791,"holonomicRotation":-141.21436414609173,"angularVelocity":-0.5448635657581228,"angularAcceleration":-0.22399401597049043,"curveRadius":-2.952528889551926},{"acceleration":3.013932114037291,"curvature":-0.33584452815013055,"pose":{"rotation":{"radians":0.4779408006254542},"translation":{"x":1.6405729275822312,"y":1.7927766733602106}},"time":0.540500753475571,"velocity":1.6131083427039266,"position":0.4382115967614902,"holonomicRotation":-141.29033269488568,"angularVelocity":-0.5460028137397955,"angularAcceleration":-0.2035845512123265,"curveRadius":-2.9775682382205617},{"acceleration":3.0136226699463764,"curvature":-0.3330125393978857,"pose":{"rotation":{"radians":0.47490725541885714},"translation":{"x":1.6486110079715166,"y":1.7969094913407784}},"time":0.5460463348740541,"velocity":1.629820632524428,"position":0.4472498997440815,"holonomicRotation":-141.36630124367963,"angularVelocity":-0.547020229010947,"angularAcceleration":-0.1834641308177026,"curveRadius":-3.0028899266318407},{"acceleration":3.013325625032286,"curvature":-0.3301968376628435,"pose":{"rotation":{"radians":0.4718954781573559},"translation":{"x":1.6566717051052577,"y":1.8010232904134766}},"time":0.5515430845227223,"velocity":1.646384129095147,"position":0.45629966112725817,"holonomicRotation":-141.44226979247358,"angularVelocity":-0.5479196714427369,"angularAcceleration":-0.16363168950359222,"curveRadius":-3.028496599416489},{"acceleration":3.0130402695632204,"curvature":-0.32739751307679793,"pose":{"rotation":{"radians":0.4689053794271154},"translation":{"x":1.6647549060991689,"y":1.8051181559478442}},"time":0.5569924599550019,"velocity":1.662803316716574,"position":0.46536090067008656,"holonomicRotation":-141.51823834126753,"angularVelocity":-0.5487048501977829,"angularAcceleration":-0.14408600853502943,"curveRadius":-3.0543909469630854},{"acceleration":3.0127659474319626,"curvature":-0.3246146480000669,"pose":{"rotation":{"radians":0.46593686908770104},"translation":{"x":1.672860498068965,"y":1.8091941733134191}},"time":0.5623958491324941,"velocity":1.679082463631245,"position":0.4744336366821885,"holonomicRotation":-141.59420689006149,"angularVelocity":-0.5493793324714982,"angularAcceleration":-0.12482578092372221,"curveRadius":-3.0805757108033953},{"acceleration":3.01250205115879,"curvature":-0.32184831748315257,"pose":{"rotation":{"radians":0.4629898563143149},"translation":{"x":1.680988368130361,"y":1.81325142787974}},"time":0.5677545749339097,"velocity":1.695225636099607,"position":0.48351788603757667,"holonomicRotation":-141.67017543885544,"angularVelocity":-0.5499465512132847,"angularAcceleration":-0.10584955506339128,"curveRadius":-3.10705368236808},{"acceleration":3.012248017463751,"curvature":-0.31909858939162117,"pose":{"rotation":{"radians":0.46006424963855785},"translation":{"x":1.6891384033990717,"y":1.8172900050163452}},"time":0.573069899278398,"velocity":1.7112367113184688,"position":0.4926136641884299,"holonomicRotation":-141.7461439876494,"angularVelocity":-0.5504098124869283,"angularAcceleration":-0.0871557864806451,"curveRadius":-3.133827704806074},{"acceleration":3.0120033232803203,"curvature":-0.3163655246466565,"pose":{"rotation":{"radians":0.45715995698854917},"translation":{"x":1.6973104909908123,"y":1.8213099900927732}},"time":0.5783430269190354,"velocity":1.7271193892961498,"position":0.5017209851788081,"holonomicRotation":-141.82211253644334,"angularVelocity":-0.5507723021204254,"angularAcceleration":-0.06874281417038479,"curveRadius":-3.160900673728225},{"acceleration":3.0117674822421527,"curvature":-0.31364917717741636,"pose":{"rotation":{"radians":0.4542768857281043},"translation":{"x":1.705504518021297,"y":1.8253114684785623}},"time":0.5835751089381733,"velocity":1.7428772037858133,"position":0.5108398616583013,"holonomicRotation":-141.8980810852373,"angularVelocity":-0.5510370919070329,"angularAcceleration":-0.05060887532705704,"curveRadius":-3.188275540842078},{"acceleration":3.011540041481823,"curvature":-0.31094959457036875,"pose":{"rotation":{"radians":0.45141494269487525},"translation":{"x":1.7137203716062415,"y":1.8292945255432504}},"time":0.5887672459728122,"velocity":1.7585135323664889,"position":0.5199703048956149,"holonomicRotation":-141.97404963403125,"angularVelocity":-0.5512071453692173,"angularAcceleration":-0.03275211363836619,"curveRadius":-3.2159553106402177},{"acceleration":3.0113205787915396,"curvature":-0.30826681779276693,"pose":{"rotation":{"radians":0.44857403423815523},"translation":{"x":1.7219579388613597,"y":1.8332592466563769}},"time":0.5939204911950676,"velocity":1.774031605751826,"position":0.5291123247920857,"holonomicRotation":-142.0500181828252,"angularVelocity":-0.551285322974912,"angularAcceleration":-0.01517055803146925,"curveRadius":-3.243943046352307},{"acceleration":3.0111087000714214,"curvature":-0.30560088167228344,"pose":{"rotation":{"radians":0.44575406625473724},"translation":{"x":1.7302171069023675,"y":1.8372057171874792}},"time":0.5990358530700974,"velocity":1.7894345163977419,"position":0.5382659298951291,"holonomicRotation":-142.12598673161915,"angularVelocity":-0.5512743872888872,"angularAcceleration":0.0021378127866394574,"curveRadius":-3.272241868308377},{"acceleration":3.010904037007721,"curvature":-0.30295181485235284,"pose":{"rotation":{"radians":0.4429549442254168},"translation":{"x":1.738497762844979,"y":1.8411340225060964}},"time":0.6041142979114763,"velocity":1.8047252264723705,"position":0.547431127411614,"holonomicRotation":-142.2019552804131,"angularVelocity":-0.5511770072824933,"angularAcceleration":0.01917516275858204,"curveRadius":-3.3008549577013158},{"acceleration":3.010706244963425,"curvature":-0.3003196401599942,"pose":{"rotation":{"radians":0.440176573249095},"translation":{"x":1.746799793804909,"y":1.8450442479817668}},"time":0.6091567522519231,"velocity":1.8199065752450967,"position":0.5566079232211664,"holonomicRotation":-142.27792382920705,"angularVelocity":-0.5509957629235845,"angularAcceleration":0.035943678746866124,"curveRadius":-3.329785556040403},{"acceleration":3.0105150011561066,"curvature":-0.29770437456087384,"pose":{"rotation":{"radians":0.43741885807716274},"translation":{"x":1.7551230868978727,"y":1.8489364789840286}},"time":0.6141641050454387,"velocity":1.8349812859460564,"position":0.5657963218893972,"holonomicRotation":-142.353892378001,"angularVelocity":-0.5507331489611458,"angularAcceleration":0.05244566805415444,"curveRadius":-3.3590369690571094},{"acceleration":3.0103300028658126,"curvature":-0.29510602983233913,"pose":{"rotation":{"radians":0.43468170314667187},"translation":{"x":1.763467529239585,"y":1.85281080088242}},"time":0.619137209715291,"velocity":1.8499519721411046,"position":0.5749963266810545,"holonomicRotation":-142.42986092679496,"angularVelocity":-0.550391578742339,"angularAcceleration":0.06868349682591997,"curveRadius":-3.388612562637699},{"acceleration":3.0101509659617465,"curvature":-0.2925246119200852,"pose":{"rotation":{"radians":0.4319650126125727},"translation":{"x":1.771833007945761,"y":1.8566672990464796}},"time":0.6240768860608435,"velocity":1.8648211436642081,"position":0.5842079395730989,"holonomicRotation":-142.5058294755889,"angularVelocity":-0.5499733877392863,"angularAcceleration":0.08465959585171057,"curveRadius":-3.41851577354862},{"acceleration":3.0099776234414124,"curvature":-0.28996012173261293,"pose":{"rotation":{"radians":0.42926869037933146},"translation":{"x":1.7802194101321147,"y":1.8605060588457458}},"time":0.6289839220349482,"velocity":1.8795912121436853,"position":0.593431161267699,"holonomicRotation":-142.58179802438286,"angularVelocity":-0.5494808367964306,"angularAcceleration":0.10037646869821176,"curveRadius":-3.4487501040648314},{"acceleration":3.0098097241702995,"curvature":-0.2874125552217492,"pose":{"rotation":{"radians":0.42659264013161247},"translation":{"x":1.7886266229143621,"y":1.8643271656497575}},"time":0.6338590754024905,"velocity":1.8942644961561357,"position":0.6026659912051504,"holonomicRotation":-142.65776657317681,"angularVelocity":-0.5489161152417388,"angularAcceleration":0.11583667468834423,"curveRadius":-3.4793191244845367},{"acceleration":3.00964703172069,"curvature":-0.28488190327710416,"pose":{"rotation":{"radians":0.4239367653642523},"translation":{"x":1.7970545334082169,"y":1.8681307048280522}},"time":0.6387030752896619,"velocity":1.9088432260382162,"position":0.6119124275767073,"holonomicRotation":-142.73373512197077,"angularVelocity":-0.5482813437700322,"angularAcceleration":0.13104283371014255,"curveRadius":-3.510226478047999},{"acceleration":3.0094893232684528,"curvature":-0.2823681520462326,"pose":{"rotation":{"radians":0.42130096941160344},"translation":{"x":1.8055030287293947,"y":1.8719167617501689}},"time":0.643516623632646,"velocity":1.9233295483834634,"position":0.6211704673373408,"holonomicRotation":-142.80970367076472,"angularVelocity":-0.5475785771406262,"angularAcceleration":0.1459976257287112,"curveRadius":-3.541475880878621},{"acceleration":3.0093363886598015,"curvature":-0.2798712832609328,"pose":{"rotation":{"radians":0.41868515547578067},"translation":{"x":1.8139719959936103,"y":1.8756854217856456}},"time":0.6483003965335853,"velocity":1.9377255302493448,"position":0.630440106218406,"holonomicRotation":-142.88567221955867,"angularVelocity":-0.5468098068177805,"angularAcceleration":0.16070376641306874,"curveRadius":-3.573071121654409},{"acceleration":3.0091880295110585,"curvature":-0.27739127400758684,"pose":{"rotation":{"radians":0.41608922665448},"translation":{"x":1.8224613223165784,"y":1.879436770304021}},"time":0.6530550455309923,"velocity":1.9520331630968686,"position":0.6397213387402296,"holonomicRotation":-142.96164076835262,"angularVelocity":-0.5459769633292388,"angularAcceleration":0.17516403187613439,"curveRadius":-3.605016068287171},{"acceleration":3.0090440583715106,"curvature":-0.2749280971145102,"pose":{"rotation":{"radians":0.4135130859678493},"translation":{"x":1.8309708948140138,"y":1.8831708926748332}},"time":0.6577811987911134,"velocity":1.9662543664831893,"position":0.6490141582246116,"holonomicRotation":-143.03760931714658,"angularVelocity":-0.5450819186013152,"angularAcceleration":0.18938123219066585,"curveRadius":-3.637314666981783},{"acceleration":3.008904297967174,"curvature":-0.27248172129526116,"pose":{"rotation":{"radians":0.41095663638472146},"translation":{"x":1.8395006006016317,"y":1.886887874267621}},"time":0.6624794622261841,"velocity":1.9803909915259557,"position":0.6583185568072415,"holonomicRotation":-143.11357786594053,"angularVelocity":-0.5441264881072702,"angularAcceleration":0.2033582210212147,"curveRadius":-3.6699709442762956},{"acceleration":3.0087685805801256,"curvature":-0.2700521113561885,"pose":{"rotation":{"radians":0.4084197808481469},"translation":{"x":1.8480503267951467,"y":1.8905878004519223}},"time":0.6671504205449854,"velocity":1.9944448241567643,"position":0.6676345254500267,"holonomicRotation":-143.18954641473448,"angularVelocity":-0.5431124329162531,"angularAcceleration":0.21709788908527272,"curveRadius":-3.7029890082252974},{"acceleration":3.0086367473055593,"curvature":-0.2676392279604205,"pose":{"rotation":{"radians":0.40590242230024787},"translation":{"x":1.8566199605102736,"y":1.894270756597276}},"time":0.6717946382406532,"velocity":2.008417588178437,"position":0.6769620539533354,"holonomicRotation":-143.26551496352843,"angularVelocity":-0.5420414616324418,"angularAcceleration":0.2306031616068087,"curveRadius":-3.7363730557012507},{"acceleration":3.00850864758161,"curvature":-0.26524302827840057,"pose":{"rotation":{"radians":0.40340446370613936},"translation":{"x":1.8652093888627272,"y":1.8979368280732203}},"time":0.6764126605202633,"velocity":2.0223109481413686,"position":0.6863011309681516,"holonomicRotation":-143.34148351232238,"angularVelocity":-0.5409152322927799,"angularAcceleration":0.24387698271498737,"curveRadius":-3.7701273676848324},{"acceleration":3.008384138541645,"curvature":-0.2628634658176759,"pose":{"rotation":{"radians":0.4009258080776137},"translation":{"x":1.8738184989682227,"y":1.9015861002492935}},"time":0.6810050141803363,"velocity":2.036126512050906,"position":0.6956517440081403,"holonomicRotation":-143.41745206111634,"angularVelocity":-0.5397353540245956,"angularAcceleration":0.25692234429644606,"curveRadius":-3.8042563156859828},{"acceleration":3.0082630846100304,"curvature":-0.2605004905028716,"pose":{"rotation":{"radians":0.39846635849571},"translation":{"x":1.8824471779424747,"y":1.905218658495034}},"time":0.6855722084320633,"velocity":2.0498658339186195,"position":0.7050138794616251,"holonomicRotation":-143.4934206099103,"angularVelocity":-0.5385033888089358,"angularAcceleration":0.26974224168240124,"curveRadius":-3.8387643649714223},{"acceleration":3.008145356988194,"curvature":-0.25815404901539574,"pose":{"rotation":{"radians":0.3960260181329658},"translation":{"x":1.8910953129011985,"y":1.90883458817998}},"time":0.6901147356797399,"velocity":2.06353041616771,"position":0.7143875226034763,"holonomicRotation":-143.56938915870424,"angularVelocity":-0.5372208529937618,"angularAcceleration":0.2823397076660379,"curveRadius":-3.8736560740147916},{"acceleration":3.008030833273362,"curvature":-0.25582408481316193,"pose":{"rotation":{"radians":0.3936046902748451},"translation":{"x":1.899762790960108,"y":1.9124339746736703}},"time":0.694633072255613,"velocity":2.077121711903043,"position":0.7237726576069079,"holonomicRotation":-143.6453577074982,"angularVelocity":-0.5358892188443892,"angularAcceleration":0.2947177854087214,"curveRadius":-3.9089360985316843},{"acceleration":3.0079193970020115,"curvature":-0.2535105381475729,"pose":{"rotation":{"radians":0.39120227834043453},"translation":{"x":1.9084494992349188,"y":1.9160169033456431}},"time":0.699127679114093,"velocity":2.0906411270545635,"position":0.7331692675551877,"holonomicRotation":-143.72132625629214,"angularVelocity":-0.53450991600699,"angularAcceleration":0.3068795293623583,"curveRadius":-3.9446091957640146},{"acceleration":3.0078109373548214,"curvature":-0.25121334627641934,"pose":{"rotation":{"radians":0.3888186859028706},"translation":{"x":1.917155324841346,"y":1.9195834595654369}},"time":0.7035990024880425,"velocity":2.104090022403179,"position":0.742577334453253,"holonomicRotation":-143.7972948050861,"angularVelocity":-0.5330843328064858,"angularAcceleration":0.31882802501153434,"curveRadius":-3.980680225881244},{"acceleration":3.0077053487961076,"curvature":-0.2489324438135702,"pose":{"rotation":{"radians":0.386453816708904},"translation":{"x":1.9258801548951041,"y":1.92313372870259}},"time":0.7080474745096486,"velocity":2.1174697154965334,"position":0.7519968392392374,"holonomicRotation":-143.87326335388005,"angularVelocity":-0.531613817616599,"angularAcceleration":0.33056635688492747,"curveRadius":-4.017154151063239},{"acceleration":3.0076025307100736,"curvature":-0.24666776241749405,"pose":{"rotation":{"radians":0.384107574697782},"translation":{"x":1.9346238765119077,"y":1.9266677961266407}},"time":0.7124735137981886,"velocity":2.1307814824617686,"position":0.7614277617959068,"holonomicRotation":-143.949231902674,"angularVelocity":-0.5300996801354483,"angularAcceleration":0.3420976142419553,"curveRadius":-4.054036045081011},{"acceleration":3.007502387191149,"curvature":-0.24441923100483498,"pose":{"rotation":{"radians":0.3817798640198564},"translation":{"x":1.943386376807472,"y":1.9301857472071278}},"time":0.7168775260168245,"velocity":2.144026559722535,"position":0.7708700809620048,"holonomicRotation":-144.02520045146795,"angularVelocity":-0.5285431925178772,"angularAcceleration":0.3534249089920073,"curveRadius":-4.0913310948933415},{"acceleration":3.0074048267290796,"curvature":-0.24218677617104545,"pose":{"rotation":{"radians":0.3794705890542729},"translation":{"x":1.9521675428975116,"y":1.9336876673135892}},"time":0.721259904400397,"velocity":2.1572061456258442,"position":0.7803237745435052,"holonomicRotation":-144.1011690002619,"angularVelocity":-0.5269455906043949,"angularAcceleration":0.3645513403112145,"curveRadius":-4.129044598594209},{"acceleration":3.007309761959814,"curvature":-0.23997032200932836,"pose":{"rotation":{"radians":0.3771796544263961},"translation":{"x":1.9609672618977416,"y":1.9371736418155632}},"time":0.7256210302560483,"velocity":2.1703214019846797,"position":0.789788819324774,"holonomicRotation":-144.17713754905586,"angularVelocity":-0.5253080749568607,"angularAcceleration":0.37548002551044907,"curveRadius":-4.167181973282209},{"acceleration":3.007217109422458,"curvature":-0.23776979012586594,"pose":{"rotation":{"radians":0.37490696502462795},"translation":{"x":1.9697854209238772,"y":1.9406437560825889}},"time":0.7299612734383654,"velocity":2.183373455541598,"position":0.7992651910796404,"holonomicRotation":-144.2531060978498,"angularVelocity":-0.5236318119287676,"angularAcceleration":0.38621408010557806,"curveRadius":-4.205748760053325},{"acceleration":3.007126789386476,"curvature":-0.2355851001344227,"pose":{"rotation":{"radians":0.37265242601627024},"translation":{"x":1.9786219070916327,"y":1.9440980954842038}},"time":0.73428099280061,"velocity":2.196363399358435,"position":0.8087528645823745,"holonomicRotation":-144.32907464664376,"angularVelocity":-0.5219179347767153,"angularAcceleration":0.3967565965122607,"curveRadius":-4.244750620601257},{"acceleration":3.007038725579207,"curvature":-0.2334161694032607,"pose":{"rotation":{"radians":0.3704159428637701},"translation":{"x":1.9874766075167227,"y":1.9475367453899473}},"time":0.7385805366234955,"velocity":2.209292294136177,"position":0.8182518136185764,"holonomicRotation":-144.4050431954377,"angularVelocity":-0.5201675444254835,"angularAcceleration":0.4071107129818884,"curveRadius":-4.284193346830027},{"acceleration":3.006952845003159,"curvature":-0.23126291313870428,"pose":{"rotation":{"radians":0.3681974213391701},"translation":{"x":1.9963494093148628,"y":1.9509597911693568}},"time":0.7428602430228587,"velocity":2.22216116946952,"position":0.8277620109959714,"holonomicRotation":-144.48101174423167,"angularVelocity":-0.5183817107010275,"angularAcceleration":0.41727949485549065,"curveRadius":-4.324082864943551},{"acceleration":3.0068690778698524,"curvature":-0.2291252446087691,"pose":{"rotation":{"radians":0.3659967675395759},"translation":{"x":2.0052401996017677,"y":1.9543673181919714}},"time":0.7471204403374844,"velocity":2.234971025040492,"position":0.8372834285551151,"holonomicRotation":-144.55698029302562,"angularVelocity":-0.5165614728780656,"angularAcceleration":0.427266083829675,"curveRadius":-4.364425236981189},{"acceleration":3.006787357272144,"curvature":-0.2270030755126701,"pose":{"rotation":{"radians":0.3638138879006716},"translation":{"x":2.014148865493152,"y":1.9577594118273292}},"time":0.7513614474982534,"velocity":2.247722831753593,"position":0.8468160371800061,"holonomicRotation":-144.63294884181957,"angularVelocity":-0.5147078408866597,"angularAcceleration":0.4370735349265144,"curveRadius":-4.405226659337421},{"acceleration":3.006707619128195,"curvature":-0.22489631551021666,"pose":{"rotation":{"radians":0.361648689210738},"translation":{"x":2.0230752941047307,"y":1.9611361574449684}},"time":0.7555835743797018,"velocity":2.26041753281697,"position":0.8563598068086099,"holonomicRotation":-144.70891739061352,"angularVelocity":-0.5128217959169467,"angularAcceleration":0.44670494816252354,"curveRadius":-4.446493477366781},{"acceleration":3.006629801972493,"curvature":-0.22280487258722523,"pose":{"rotation":{"radians":0.3595010786239081},"translation":{"x":2.0320193725522184,"y":1.9644976404144279}},"time":0.7597871221350043,"velocity":2.273056044772077,"position":0.8659147064432884,"holonomicRotation":-144.78488593940747,"angularVelocity":-0.5109042912908045,"angularAcceleration":0.4561633976260501,"curveRadius":-4.488232184457783},{"acceleration":3.0065538469355233,"curvature":-0.22072865300106642,"pose":{"rotation":{"radians":0.35737096367257815},"translation":{"x":2.0409809879513308,"y":1.9678439461052455}},"time":0.7639723835153305,"velocity":2.2856392584755274,"position":0.8754807041611433,"holonomicRotation":-144.86085448820143,"angularVelocity":-0.5089562533281916,"angularAcceleration":0.46545192416658154,"curveRadius":-4.53044942921465},{"acceleration":3.006479697454762,"curvature":-0.21866756194290038,"pose":{"rotation":{"radians":0.35525825228034913},"translation":{"x":2.0499600274177814,"y":1.9711751598869607}},"time":0.7681396431744525,"velocity":2.2981680400347,"position":0.8850577671242634,"holonomicRotation":-144.93682303699538,"angularVelocity":-0.506978581861188,"angularAcceleration":0.47457361162376677,"curveRadius":-4.57315200807482},{"acceleration":3.0064072992737443,"curvature":-0.21662150247977008,"pose":{"rotation":{"radians":0.35316285277292003},"translation":{"x":2.0589563780672866,"y":1.9744913671291102}},"time":0.7722891779594339,"velocity":2.3106432317008583,"position":0.8946458615898879,"holonomicRotation":-145.01279158578933,"angularVelocity":-0.5049721513392507,"angularAcceleration":0.4835314380781591,"curveRadius":-4.616346893325552},{"acceleration":3.0063366002624,"curvature":-0.2145903770107498,"pose":{"rotation":{"radians":0.3510846738908726},"translation":{"x":2.0679699270155596,"y":1.9777926532012338}},"time":0.7764212571881633,"velocity":2.3230656527213718,"position":0.9042449529204728,"holonomicRotation":-145.08876013458328,"angularVelocity":-0.5029378109689364,"angularAcceleration":0.49232850042416904,"curveRadius":-4.660041209349782},{"acceleration":3.0062675503917067,"curvature":-0.21257408605649006,"pose":{"rotation":{"radians":0.3490236247992464},"translation":{"x":2.077000561378317,"y":1.9810791034728692}},"time":0.780536142914461,"velocity":2.3354361001539106,"position":0.9138550055936765,"holonomicRotation":-145.16472868337723,"angularVelocity":-0.5008763860571609,"angularAcceleration":0.5009677179128507,"curveRadius":-4.704242264667468},{"acceleration":3.0062001015118995,"curvature":-0.2105725292185357,"pose":{"rotation":{"radians":0.3469796150993192},"translation":{"x":2.0860481682712724,"y":1.9843508033135548}},"time":0.784634090181423,"velocity":2.347755349643842,"position":0.9234759832122449,"holonomicRotation":-145.2406972321712,"angularVelocity":-0.4987886780306378,"angularAcceleration":0.5094521453104982,"curveRadius":-4.748957538341496},{"acceleration":3.006134207330466,"curvature":-0.20858560483354346,"pose":{"rotation":{"radians":0.3449525548381711},"translation":{"x":2.095112634810141,"y":1.98760783809283}},"time":0.7887153472636453,"velocity":2.3600241561676203,"position":0.9331078485138197,"holonomicRotation":-145.31666578096514,"angularVelocity":-0.4966754655024858,"angularAcceleration":0.5177847132828325,"curveRadius":-4.794194694298415},{"acceleration":3.0060698233577696,"curvature":-0.20661321021082638,"pose":{"rotation":{"radians":0.34294235451854815},"translation":{"x":2.104193848110638,"y":1.9908502931802317}},"time":0.7927801558989086,"velocity":2.3722432547438093,"position":0.9427505633806473,"holonomicRotation":-145.3926343297591,"angularVelocity":-0.4945375047139861,"angularAcceleration":0.5259683739973252,"curveRadius":-4.839961583190196},{"acceleration":3.0060069067879125,"curvature":-0.20465524142481842,"pose":{"rotation":{"radians":0.34094892510874697},"translation":{"x":2.1132916952884777,"y":1.9940782539452988}},"time":0.7968287515098865,"velocity":2.3844133611132,"position":0.9524040888492074,"holonomicRotation":-145.46860287855304,"angularVelocity":-0.492375530022293,"angularAcceleration":0.5340060849324701,"curveRadius":-4.886266254594594},{"acceleration":3.005945416338737,"curvature":-0.20271159385497983,"pose":{"rotation":{"radians":0.33897217805119295},"translation":{"x":2.1224060634593758,"y":1.9972918057575701}},"time":0.8008613634163946,"velocity":2.396535172389441,"position":0.9620683851197503,"holonomicRotation":-145.54457142734697,"angularVelocity":-0.49019025469915245,"angularAcceleration":0.5419007268251718,"curveRadius":-4.9331169519361655},{"acceleration":3.0058853123247284,"curvature":-0.20078216190554588,"pose":{"rotation":{"radians":0.33701202527138774},"translation":{"x":2.131536839739046,"y":2.0004910339865836}},"time":0.8048782150386664,"velocity":2.4086093676826157,"position":0.9717434115657454,"holonomicRotation":-145.62053997614095,"angularVelocity":-0.48798237130217886,"angularAcceleration":0.5496552037749559,"curveRadius":-4.98052212661417},{"acceleration":3.005826556487958,"curvature":-0.19886683894268223,"pose":{"rotation":{"radians":0.33506837918629806},"translation":{"x":2.140683911243204,"y":2.0036760240018783}},"time":0.8088795240921223,"velocity":2.420636608696209,"position":0.9814291267432482,"holonomicRotation":-145.69650852493487,"angularVelocity":-0.48575255225811315,"angularAcceleration":0.5572723861806831,"curveRadius":-5.028490447762494},{"acceleration":3.0057691119554892,"curvature":-0.19696551776735471,"pose":{"rotation":{"radians":0.3331411527121535},"translation":{"x":2.149847165087565,"y":2.006846861172992}},"time":0.812865502774054,"velocity":2.4326175402992725,"position":0.9911254884001743,"holonomicRotation":-145.77247707372885,"angularVelocity":-0.4835014504419187,"angularAcceleration":0.564755106794366,"curveRadius":-5.077030798767261},{"acceleration":3.005712943200509,"curvature":-0.19507809032765674,"pose":{"rotation":{"radians":0.33123025927248184},"translation":{"x":2.1590264883878425,"y":2.010003630869463}},"time":0.8168363579426384,"velocity":2.4445527910750613,"position":1.0008324534854922,"holonomicRotation":-145.84844562252277,"angularVelocity":-0.4812296995341878,"angularAcceleration":0.5721062117057192,"curveRadius":-5.126152292758155},{"acceleration":3.0056580159156514,"curvature":-0.19320444796529188,"pose":{"rotation":{"radians":0.329335612805163},"translation":{"x":2.1682217682597527,"y":2.0131464184608303}},"time":0.8207922912886584,"velocity":2.456442973846954,"position":1.0105499781583298,"holonomicRotation":-145.92441417131673,"angularVelocity":-0.4789379146706411,"angularAcceleration":0.5793284828351442,"curveRadius":-5.1758642750276875},{"acceleration":3.0056042970627868,"curvature":-0.19134448143366078,"pose":{"rotation":{"radians":0.32745712776960323},"translation":{"x":2.17743289181901,"y":2.0162753093166317}},"time":0.8247334995002902,"velocity":2.468288686183454,"position":1.020278017796994,"holonomicRotation":-146.00038272011068,"angularVelocity":-0.4766266928034245,"angularAcceleration":0.5864247061079984,"curveRadius":-5.226176331334125},{"acceleration":3.005551754690953,"curvature":-0.18949808059811774,"pose":{"rotation":{"radians":0.32559471915345295},"translation":{"x":2.186659746181329,"y":2.0193903888064053}},"time":0.828660174421299,"velocity":2.480090510882393,"position":1.0300165270079078,"holonomicRotation":-146.07635126890463,"angularVelocity":-0.47429661319450106,"angularAcceleration":0.5933976343335309,"curveRadius":-5.2770983053953575},{"acceleration":3.0055003580345834,"curvature":-0.18766513515858074,"pose":{"rotation":{"radians":0.32374830247920494},"translation":{"x":2.1959022184624244,"y":2.0224917422996906}},"time":0.8325725032029594,"velocity":2.491849016436422,"position":1.039765459634464,"holonomicRotation":-146.15231981769858,"angularVelocity":-0.4719482378125696,"angularAcceleration":0.600250007857164,"curveRadius":-5.328640288751452},{"acceleration":3.0054500772895287,"curvature":-0.18584553435619008,"pose":{"rotation":{"radians":0.32191779380982943},"translation":{"x":2.205160195778012,"y":2.0255794551660253}},"time":0.8364706684500032,"velocity":2.5035647574794373,"position":1.049524768765794,"holonomicRotation":-146.22828836649254,"angularVelocity":-0.46958211193424765,"angularAcceleration":0.6069844986988032,"curveRadius":-5.380812638109496},{"acceleration":3.0054008837754838,"curvature":-0.18403916658581485,"pose":{"rotation":{"radians":0.32010310975530043},"translation":{"x":2.2144335652438056,"y":2.028653612774948}},"time":0.8403548483608785,"velocity":2.515238275216325,"position":1.059294406745454,"holonomicRotation":-146.3042569152865,"angularVelocity":-0.4671987642611696,"angularAcceleration":0.6136038308639986,"curveRadius":-5.43362599685385},{"acceleration":3.0053527496862364,"curvature":-0.18224592029184322,"pose":{"rotation":{"radians":0.3183041674777316},"translation":{"x":2.223722213975521,"y":2.031714300495997}},"time":0.8442252168625894,"velocity":2.526870097835241,"position":1.0690743251800308,"holonomicRotation":-146.38022546408044,"angularVelocity":-0.4647987076097724,"angularAcceleration":0.6201106303795649,"curveRadius":-5.487091279731418},{"acceleration":3.0053056481460443,"curvature":-0.18046568326192214,"pose":{"rotation":{"radians":0.3165208846968057},"translation":{"x":2.233026029088872,"y":2.0347616036987106}},"time":0.8480819437403686,"velocity":2.5384607409043873,"position":1.078864474947664,"holonomicRotation":-146.4561940128744,"angularVelocity":-0.4623824391611454,"angularAcceleration":0.6265075348084647,"curveRadius":-5.541219704073222},{"acceleration":3.005259553314636,"curvature":-0.17869834312612273,"pose":{"rotation":{"radians":0.31475317969484884},"translation":{"x":2.2423448976995743,"y":2.037795607752627}},"time":0.8519251947624229,"velocity":2.5500107077542022,"position":1.0886648062064896,"holonomicRotation":-146.53216256166834,"angularVelocity":-0.4599504408671213,"angularAcceleration":0.6327971501388366,"curveRadius":-5.596022786256134},{"acceleration":3.005214439961067,"curvature":-0.17694378729438653,"pose":{"rotation":{"radians":0.31300097132175564},"translation":{"x":2.251678706923343,"y":2.040816398027285}},"time":0.8557551317999792,"velocity":2.561520489843608,"position":1.098475268403001,"holonomicRotation":-146.6081311104623,"angularVelocity":-0.45750317979409977,"angularAcceleration":0.6389820639409243,"curveRadius":-5.651512354803794},{"acceleration":3.0051702838889693,"curvature":-0.17520190272283118,"pose":{"rotation":{"radians":0.3112641789992896},"translation":{"x":2.2610273438758925,"y":2.043824059892223}},"time":0.8595719129428434,"velocity":2.5729905671142514,"position":1.1082958102803302,"holonomicRotation":-146.68409965925625,"angularVelocity":-0.4550411085825861,"angularAcceleration":0.6450648123004632,"curveRadius":-5.70770056979345},{"acceleration":3.0051270615630097,"curvature":-0.17347257642563704,"pose":{"rotation":{"radians":0.3095427227254719},"translation":{"x":2.2703906956729374,"y":2.046818678716979}},"time":0.8633756926106775,"velocity":2.5844214083302828,"position":1.118126379886452,"holonomicRotation":-146.7600682080502,"angularVelocity":-0.45256466571259707,"angularAcceleration":0.6510479276522266,"curveRadius":-5.764599918931121},{"acceleration":3.0050847502725535,"curvature":-0.17175569516021785,"pose":{"rotation":{"radians":0.30783652307892506},"translation":{"x":2.2797686494301925,"y":2.049800339871092}},"time":0.867166621660185,"velocity":2.595813471406323,"position":1.1279669245823092,"holonomicRotation":-146.83603675684415,"angularVelocity":-0.45007427579487236,"angularAcceleration":0.6569339297047109,"curveRadius":-5.822223240208576},{"acceleration":3.005043327958312,"curvature":-0.17005114535353827,"pose":{"rotation":{"radians":0.3061455012223293},"translation":{"x":2.289161092263373,"y":2.0527691287241}},"time":0.8709448474883877,"velocity":2.6071672037228835,"position":1.1378173910498581,"holonomicRotation":-146.9120053056381,"angularVelocity":-0.4475703500762283,"angularAcceleration":0.6627252664341486,"curveRadius":-5.88058373803357},{"acceleration":3.005002773329804,"curvature":-0.16835881388254545,"pose":{"rotation":{"radians":0.3044695789063674},"translation":{"x":2.2985679112881945,"y":2.0557251306455413}},"time":0.8747105141321664,"velocity":2.618483042430874,"position":1.14767772530004,"holonomicRotation":-146.98797385443206,"angularVelocity":-0.44505328657563337,"angularAcceleration":0.6684244089299428,"curveRadius":-5.939694970158463},{"acceleration":3.0049630656834596,"curvature":-0.16667858689772333,"pose":{"rotation":{"radians":0.3028086784730757},"translation":{"x":2.3079889936203704,"y":2.0586684310049543}},"time":0.8784637623642265,"velocity":2.6297614147445563,"position":1.15754787268067,"holonomicRotation":-147.063942403226,"angularVelocity":-0.4425234704979912,"angularAcceleration":0.674033775872476,"curveRadius":-5.999570902371618},{"acceleration":3.004924185080492,"curvature":-0.1650103510332912,"pose":{"rotation":{"radians":0.30116272285901236},"translation":{"x":2.3174242263756164,"y":2.061599115171878}},"time":0.8822047297856503,"velocity":2.641002738224791,"position":1.16742777788426,"holonomicRotation":-147.13991095201996,"angularVelocity":-0.439981274532692,"angularAcceleration":0.6795557616301376,"curveRadius":-6.0602258812130385},{"acceleration":3.0048861120679327,"curvature":-0.1633539924757645,"pose":{"rotation":{"radians":0.2995316355982074},"translation":{"x":2.3268734966696476,"y":2.06451726851585}},"time":0.8859335509151745,"velocity":2.6522074210512834,"position":1.1773173849557568,"holonomicRotation":-147.2158795008139,"angularVelocity":-0.4374270591555924,"angularAcceleration":0.6849927331927513,"curveRadius":-6.121674682351959},{"acceleration":3.0048488277941416,"curvature":-0.16170939802251516,"pose":{"rotation":{"radians":0.2979153408253188},"translation":{"x":2.336336691618178,"y":2.0674229764064087}},"time":0.889650357275339,"velocity":2.6633758622857617,"position":1.1872166373002093,"holonomicRotation":-147.29184804960786,"angularVelocity":-0.4348611728099374,"angularAcceleration":0.6903470606258185,"curveRadius":-6.1839324877133475},{"acceleration":3.0048123141195653,"curvature":-0.16007645396103062,"pose":{"rotation":{"radians":0.29631376327793957},"translation":{"x":2.3458136983369235,"y":2.0703163242130933}},"time":0.893355277475639,"velocity":2.6745084521264535,"position":1.1971254776903657,"holonomicRotation":-147.36781659840182,"angularVelocity":-0.43228395236408423,"angularAcceleration":0.6956210408106747,"curveRadius":-6.24701494351844},{"acceleration":3.004776553296603,"curvature":-0.15845504686958378,"pose":{"rotation":{"radians":0.29472682829911845},"translation":{"x":2.3553044039415982,"y":2.0731973973054414}},"time":0.8970484372928021,"velocity":2.6856055721526424,"position":1.2070438482741892,"holonomicRotation":-147.44378514719577,"angularVelocity":-0.4296957232790744,"angularAcceleration":0.7008169733087711,"curveRadius":-6.310938147795625},{"acceleration":1.5094462259050723,"curvature":-0.15684506354928204,"pose":{"rotation":{"radians":0.2931544618398636},"translation":{"x":2.3648086955479166,"y":2.0760662810529915}},"time":0.900737475012348,"velocity":2.6911739762156324,"position":1.216971690582309,"holonomicRotation":-147.51975369598972,"angularVelocity":-0.42622672327904765,"angularAcceleration":0.9403536270845709,"curveRadius":-6.3757186702008735},{"acceleration":-1.492253147613358,"curvature":-0.1552463907702274,"pose":{"rotation":{"radians":0.2915965904610345},"translation":{"x":2.374326460271595,"y":2.0789230608252827}},"time":0.9044376019414669,"velocity":2.6856524501590857,"position":1.2269089455353968,"holonomicRotation":-147.59572224478367,"angularVelocity":-0.42103187503356443,"angularAcceleration":1.4039648760698666,"curveRadius":-6.441373580658961},{"acceleration":-2.9923797173768936,"curvature":-0.15365891546332805,"pose":{"rotation":{"radians":0.2900531413353322},"translation":{"x":2.383857585228347,"y":2.0817678219918525}},"time":0.9081566221942255,"velocity":2.674523729386217,"position":1.2368555534514676,"holonomicRotation":-147.67169079357762,"angularVelocity":-0.4150149826577019,"angularAcceleration":1.6178702902732063,"curveRadius":-6.507920461267724},{"acceleration":-2.992332293116288,"curvature":-0.15208252482748008,"pose":{"rotation":{"radians":0.28852404224922923},"translation":{"x":2.393401957533888,"y":2.0846006499222396}},"time":0.9118947510311025,"velocity":2.663338005751801,"position":1.2468114540531188,"holonomicRotation":-147.74765934237158,"angularVelocity":-0.40905467757512726,"angularAcceleration":1.5944621875457432,"curveRadius":-6.57537742179375},{"acceleration":-2.992283942940502,"curvature":-0.15051710616160868,"pose":{"rotation":{"radians":0.28700922160455766},"translation":{"x":2.4029594643039327,"y":2.087421629985983}},"time":0.9156522083714451,"velocity":2.6520946264860097,"position":1.2567765864746918,"holonomicRotation":-147.82362789116553,"angularVelocity":-0.40315045720078463,"angularAcceleration":1.5713339738953038,"curveRadius":-6.643763127669424},{"acceleration":-2.992234639832672,"curvature":-0.14896254706298503,"pose":{"rotation":{"radians":0.28550860841976267},"translation":{"x":2.412529992654196,"y":2.09023084755262}},"time":0.9194292189434199,"velocity":2.6407929246175326,"position":1.2667508892693684,"holonomicRotation":-147.89959643995948,"angularVelocity":-0.39730182275090026,"angularAcceleration":1.5484824144472737,"curveRadius":-6.713096813369976},{"acceleration":-2.992184355871604,"curvature":-0.1474187351614666,"pose":{"rotation":{"radians":0.2840221323316916},"translation":{"x":2.4221134297003926,"y":2.0930283879916898}},"time":0.9232260124399524,"velocity":2.629432218514733,"position":1.2767343004161982,"holonomicRotation":-147.97556498875343,"angularVelocity":-0.39150827913833575,"angularAcceleration":1.5259043237025087,"curveRadius":-6.783398317077593},{"acceleration":-2.992133062178092,"curvature":-0.1458855586973756,"pose":{"rotation":{"radians":0.2825497235964942},"translation":{"x":2.4317096625582377,"y":2.0958143366727304}},"time":0.9270428236809543,"velocity":2.6180118114084383,"position":1.2867267573270575,"holonomicRotation":-148.05153353754739,"angularVelocity":-0.3857693352451185,"angularAcceleration":1.5035964659627299,"curveRadius":-6.854688078306612},{"acceleration":-2.992080728930227,"curvature":-0.1443629058782181,"pose":{"rotation":{"radians":0.2810913130907897},"translation":{"x":2.4413185783434463,"y":2.0985887789652806}},"time":0.9308798927821543,"velocity":2.606530990895164,"position":1.2967281968535418,"holonomicRotation":-148.12750208634134,"angularVelocity":-0.3800845038856271,"angularAcceleration":1.4815556377948629,"curveRadius":-6.92698719187311},{"acceleration":-2.992027325247793,"curvature":-0.1428506650745003,"pose":{"rotation":{"radians":0.2796468323126131},"translation":{"x":2.450940064171732,"y":2.1013518002388785}},"time":0.9347374653308685,"velocity":2.5949890284202852,"position":1.3067385552937905,"holonomicRotation":-148.2034706351353,"angularVelocity":-0.3744533018978659,"angularAcceleration":1.4597786345296708,"curveRadius":-7.00031742574299},{"acceleration":-2.9919728191360515,"curvature":-0.14134872541416107,"pose":{"rotation":{"radians":0.2782162133821684},"translation":{"x":2.4605740071588116,"y":2.104103485863062}},"time":0.9386157925690654,"velocity":2.5833851787398854,"position":1.3167577683992513,"holonomicRotation":-148.27943918392924,"angularVelocity":-0.368875250225112,"angularAcceleration":1.438262253328421,"curveRadius":-7.0747012190589915},{"acceleration":-2.9919171774740807,"curvature":-0.13985697593074498,"pose":{"rotation":{"radians":0.27679938904291745},"translation":{"x":2.4702202944203986,"y":2.106843921207371}},"time":0.9425151315840989,"velocity":2.5717186793600115,"position":1.3267857713813704,"holonomicRotation":-148.3554077327232,"angularVelocity":-0.3633498738602855,"angularAcceleration":1.41700332890365,"curveRadius":-7.150161751639651},{"acceleration":-2.991860365934178,"curvature":-0.13837530615541926,"pose":{"rotation":{"radians":0.27539629266140775},"translation":{"x":2.479878813072208,"y":2.109573191641342}},"time":0.946435745507517,"velocity":2.5599887499524074,"position":1.3368224989182274,"holonomicRotation":-148.43137628151715,"angularVelocity":-0.35787670219935186,"angularAcceleration":1.395998628745898,"curveRadius":-7.226722944893274},{"acceleration":-2.99180234902596,"curvature":-0.13690360593835305,"pose":{"rotation":{"radians":0.274006858228641},"translation":{"x":2.489549450229955,"y":2.1122913825345146}},"time":0.9503779037223631,"velocity":2.548194591744999,"position":1.3468678851611013,"holonomicRotation":-148.5073448303111,"angularVelocity":-0.35245526867342436,"angularAcceleration":1.3752450384945116,"curveRadius":-7.304409501458235},{"acceleration":-2.991743089796993,"curvature":-0.13544176546193154,"pose":{"rotation":{"radians":0.27263102035977127},"translation":{"x":2.499232093009354,"y":2.1149985792564268}},"time":0.9543418820794266,"velocity":2.536335386887149,"position":1.3569218637409763,"holonomicRotation":-148.58331337910505,"angularVelocity":-0.34708511120352126,"angularAcceleration":1.3547393517761943,"curveRadius":-7.38324693708359},{"acceleration":-2.991682550027684,"curvature":-0.133989675152465,"pose":{"rotation":{"radians":0.2712687142947918},"translation":{"x":2.508926628526121,"y":2.1176948671766174}},"time":0.9583279631229209,"velocity":2.524410297786331,"position":1.3669843677749842,"holonomicRotation":-148.659281927899,"angularVelocity":-0.34176577197367164,"angularAcceleration":1.3344784443184723,"curveRadius":-7.463261619689083},{"acceleration":-2.9916206900292828,"curvature":-0.13254722630343496,"pose":{"rotation":{"radians":0.2699198758984269},"translation":{"x":2.51863294389597,"y":2.1203803316646246}},"time":0.962336436326099,"velocity":2.5124184664162756,"position":1.3770553298727837,"holonomicRotation":-148.73525047669295,"angularVelocity":-0.33649679765739343,"angularAcceleration":1.3144591591882735,"curveRadius":-7.544480770278367},{"acceleration":-2.9915574685314867,"curvature":-0.13111430987134076,"pose":{"rotation":{"radians":0.26858444166032003},"translation":{"x":2.5283509262346158,"y":2.123055058089986}},"time":0.9663675983373531,"velocity":2.500359013594648,"position":1.3871346821428832,"holonomicRotation":-148.8112190254869,"angularVelocity":-0.331277739366134,"angularAcceleration":1.2946783772740917,"curveRadius":-7.626932567324462},{"acceleration":-2.9914928427832455,"curvature":-0.1296908176042822,"pose":{"rotation":{"radians":0.267262348695271},"translation":{"x":2.5380804626577733,"y":2.1257191318222413}},"time":0.9704217532373749,"velocity":2.488231038227698,"position":1.3972223561989003,"holonomicRotation":-148.88718757428086,"angularVelocity":-0.3261081526613413,"angularAcceleration":1.2751330011502313,"curveRadius":-7.710646123392019},{"acceleration":-2.9914267682434836,"curvature":-0.12827664175782477,"pose":{"rotation":{"radians":0.26595353474257566},"translation":{"x":2.547821440281157,"y":2.128372638230928}},"time":0.9744992128079942,"velocity":2.476033616521717,"position":1.407318283165762,"holonomicRotation":-148.9631561230748,"angularVelocity":-0.3209875977989237,"angularAcceleration":1.2558198980841906,"curveRadius":-7.795651541049178},{"acceleration":-2.991359198675729,"curvature":-0.1268716745838351,"pose":{"rotation":{"radians":0.2646579381664198},"translation":{"x":2.5575737462204833,"y":2.1310156626855847}},"time":0.9786002968133566,"velocity":2.4637658011577344,"position":1.4174223936858488,"holonomicRotation":-149.03912467186876,"angularVelocity":-0.3159156394899016,"angularAcceleration":1.236736019645126,"curveRadius":-7.881979987102742},{"acceleration":-2.991290085960478,"curvature":-0.12547580939453548,"pose":{"rotation":{"radians":0.263375497955205},"translation":{"x":2.567337267591465,"y":2.1336482905557497}},"time":0.9827253332941378,"velocity":2.451426620428548,"position":1.4275346179250747,"holonomicRotation":-149.11509322066271,"angularVelocity":-0.3108918471848144,"angularAcceleration":1.2178782729542734,"curveRadius":-7.969663673223935},{"acceleration":-2.9912193800550972,"curvature":-0.12408893931117966,"pose":{"rotation":{"radians":0.26210615372151924},"translation":{"x":2.5771118915098183,"y":2.1362706072109616}},"time":0.9868746588755528,"velocity":2.4390150773352612,"position":1.4376548855789189,"holonomicRotation":-149.19106176945667,"angularVelocity":-0.30591579493573257,"angularAcceleration":1.1992436244024214,"curveRadius":-8.05873598042679},{"acceleration":-2.991147028820014,"curvature":-0.12271095822904035,"pose":{"rotation":{"radians":0.2608498457014514},"translation":{"x":2.586897505091258,"y":2.138882698020759}},"time":0.9910486190899537,"velocity":2.426530148641543,"position":1.4477831258783929,"holonomicRotation":-149.26703031825062,"angularVelocity":-0.30098706157604155,"angularAcceleration":1.1808290224439757,"curveRadius":-8.14923144951323},{"acceleration":-2.991072977965146,"curvature":-0.12134176018814805,"pose":{"rotation":{"radians":0.25960651475426344},"translation":{"x":2.5966939954514987,"y":2.1414846483546803}},"time":0.9952475687148775,"velocity":2.4139707838825966,"position":1.4579192675959538,"holonomicRotation":-149.34299886704457,"angularVelocity":-0.29610523065289984,"angularAcceleration":1.1626314576780017,"curveRadius":-8.241185874091796},{"acceleration":-2.990997170954587,"curvature":-0.1199812401484755,"pose":{"rotation":{"radians":0.2583761023618045},"translation":{"x":2.6065012497062545,"y":2.1440765435822633}},"time":0.9994718721274636,"velocity":2.401335904326298,"position":1.4680632390513648,"holonomicRotation":-149.41896741583852,"angularVelocity":-0.2912698905085681,"angularAcceleration":1.1446479270227432,"curveRadius":-8.334636304496525},{"acceleration":-2.9909195487527853,"curvature":-0.1186292930200318,"pose":{"rotation":{"radians":0.2571585506278642},"translation":{"x":2.616319154971242,"y":2.146658469073046}},"time":1.003721903676219,"velocity":2.388624401884309,"position":1.4782149681175003,"holonomicRotation":-149.49493596463248,"angularVelocity":-0.2864806343136133,"angularAcceleration":1.1268754455145682,"curveRadius":-8.429621171485355},{"acceleration":-2.990840049912417,"curvature":-0.11728581455525564,"pose":{"rotation":{"radians":0.25595380227781384},"translation":{"x":2.6261475983621745,"y":2.1492305101965687}},"time":1.0079980480711868,"velocity":2.375835137968631,"position":1.4883743822260922,"holonomicRotation":-149.57090451342643,"angularVelocity":-0.2817370600179308,"angularAcceleration":1.1093110656564555,"curveRadius":-8.526180286950904},{"acceleration":-2.9907586101271897,"curvature":-0.11595070058421228,"pose":{"rotation":{"radians":0.2547618006570227},"translation":{"x":2.6359864669947672,"y":2.151792752322368}},"time":1.0123007007936464,"velocity":2.3629669422925477,"position":1.4985414083734294,"holonomicRotation":-149.64687306222038,"angularVelocity":-0.2770387706562839,"angularAcceleration":1.0919517945573505,"curveRadius":-8.624354962596568},{"acceleration":-2.990675162471691,"curvature":-0.11462384769931194,"pose":{"rotation":{"radians":0.2535824897311696},"translation":{"x":2.6458356479847356,"y":2.1543452808199826}},"time":1.0166302685265607,"velocity":2.350018611609482,"position":1.5087159731260018,"holonomicRotation":-149.72284161101433,"angularVelocity":-0.272385373922607,"angularAcceleration":1.074794764914024,"curveRadius":-8.72418802955611},{"acceleration":-2.990589636840466,"curvature":-0.11330515316706428,"pose":{"rotation":{"radians":0.2524158140846904},"translation":{"x":2.655695028447794,"y":2.1568881810589517}},"time":1.0209871696070654,"velocity":2.3369889083893858,"position":1.518898002626091,"holonomicRotation":-149.79881015980828,"angularVelocity":-0.26777648262422044,"angularAcceleration":1.057837029858082,"curveRadius":-8.825723915006202},{"acceleration":-2.9905019600885354,"curvature":-0.11199451401541628,"pose":{"rotation":{"radians":0.251261718919908},"translation":{"x":2.6655644954996576,"y":2.159421538408813}},"time":1.0253718345024072,"velocity":2.3238765594255346,"position":1.529087422597312,"holonomicRotation":-149.87477870860224,"angularVelocity":-0.26321171453911074,"angularAcceleration":1.0410757022638588,"curveRadius":-8.929008789326483},{"acceleration":-2.9904120555573805,"curvature":-0.11069182831269184,"pose":{"rotation":{"radians":0.25012015005647514},"translation":{"x":2.675443936256041,"y":2.1619454382391052}},"time":1.029784706310831,"velocity":2.310680254369995,"position":1.5392841583501027,"holonomicRotation":-149.9507472573962,"angularVelocity":-0.2586906923635794,"angularAcceleration":1.0245079331108478,"curveRadius":-9.034090548898638},{"acceleration":-2.990319843291179,"curvature":-0.10939699473150238,"pose":{"rotation":{"radians":0.24899105393006815},"translation":{"x":2.685333237832659,"y":2.164459965919366}},"time":1.0342262412890404,"velocity":2.2973986441899834,"position":1.5494881347871634,"holonomicRotation":-150.02671580619014,"angularVelocity":-0.2542130439018132,"angularAcceleration":1.0081308565020721,"curveRadius":-9.141018932506709},{"acceleration":-2.9902252392713278,"curvature":-0.1081099117254858,"pose":{"rotation":{"radians":0.24787437759156905},"translation":{"x":2.6952322873452266,"y":2.1669652068191354}},"time":1.0386969094079779,"velocity":2.284030339544331,"position":1.5596992764088502,"holonomicRotation":-150.1026843549841,"angularVelocity":-0.24977840197283416,"angularAcceleration":0.99194165413312,"curveRadius":-9.249845680562704},{"acceleration":-2.9901281557678927,"curvature":-0.10683047872471226,"pose":{"rotation":{"radians":0.24677006870564},"translation":{"x":2.705140971909459,"y":2.16946124630795}},"time":1.0431971949388061,"velocity":2.2705739090696064,"position":1.5699175073185123,"holonomicRotation":-150.17865290377804,"angularVelocity":-0.24538640456571345,"angularAcceleration":0.975937499306266,"curveRadius":-9.360624532787737},{"acceleration":-2.99002850057168,"curvature":-0.1055585956825843,"pose":{"rotation":{"radians":0.24567807555017618},"translation":{"x":2.7150591786410705,"y":2.171948169755349}},"time":1.0477275970711288,"velocity":2.257027877574911,"position":1.5801427512277895,"holonomicRotation":-150.254621452572,"angularVelocity":-0.2410366946617974,"angularAcceleration":0.9601156314320385,"curveRadius":-9.473411364878418},{"acceleration":-2.9899261771810695,"curvature":-0.10429416309147485,"pose":{"rotation":{"radians":0.24459834701486827},"translation":{"x":2.7249867946557758,"y":2.174426062530871}},"time":1.0522886305656456,"velocity":2.2433907241346556,"position":1.5903749314618558,"holonomicRotation":-150.33059000136595,"angularVelocity":-0.2367289204532162,"angularAcceleration":0.9444732676837332,"curveRadius":-9.58826429359153},{"acceleration":-2.989821084205278,"curvature":-0.10303708137237878,"pose":{"rotation":{"radians":0.24353083259968766},"translation":{"x":2.7349237070692904,"y":2.176895010004054}},"time":1.0568808264436202,"velocity":2.2296608800758864,"position":1.6006139709646217,"holonomicRotation":-150.4065585501599,"angularVelocity":-0.23246273537691953,"angularAcceleration":0.9290076446343196,"curveRadius":-9.70524384697945},{"acceleration":-2.9897131151674547,"curvature":-0.10178725187300632,"pose":{"rotation":{"radians":0.2424754824144988},"translation":{"x":2.744869802997329,"y":2.1793550975444367}},"time":1.0615047327157328,"velocity":2.2158367268508465,"position":1.6108597923038845,"holonomicRotation":-150.48252709895385,"angularVelocity":-0.22823779788830365,"angularAcceleration":0.9137160746741624,"curveRadius":-9.82441299473964},{"acceleration":-2.989602158309039,"curvature":-0.10054457639248407,"pose":{"rotation":{"radians":0.241432247177086},"translation":{"x":2.7548249695556066,"y":2.181806410521557}},"time":1.0661609151531075,"velocity":2.2019165937865903,"position":1.6211123176764377,"holonomicRotation":-150.5584956477478,"angularVelocity":-0.22405377182793187,"angularAcceleration":0.8985958167762008,"curveRadius":-9.945837317931673},{"acceleration":-2.989488095943985,"curvature":-0.09930895732245341,"pose":{"rotation":{"radians":0.24040107821234447},"translation":{"x":2.7647890938598376,"y":2.184249034304954}},"time":1.0708499581035387,"velocity":2.1878987557049063,"position":1.631371468913133,"holonomicRotation":-150.63446419654176,"angularVelocity":-0.2199103261885712,"angularAcceleration":0.8836442069654499,"curveRadius":-10.069585130705057},{"acceleration":-2.9893708044197265,"curvature":-0.09808029714367371,"pose":{"rotation":{"radians":0.23938192745079379},"translation":{"x":2.774762063025737,"y":2.1866830542641655}},"time":1.0755724653562002,"velocity":2.1737814304001395,"position":1.6416371674838985,"holonomicRotation":-150.7104327453357,"angularVelocity":-0.21580713528312734,"angularAcceleration":0.8688585714995692,"curveRadius":-10.195727675408058},{"acceleration":-2.9892501533459725,"curvature":-0.09685849921081774,"pose":{"rotation":{"radians":0.2383747474273008},"translation":{"x":2.7847437641690203,"y":2.18910855576873}},"time":1.080329061058408,"velocity":2.15956277596791,"position":1.6519093345027154,"holonomicRotation":-150.78640129412966,"angularVelocity":-0.2117438787209728,"angularAcceleration":0.854236268234565,"curveRadius":-10.324339197363013},{"acceleration":-2.9891260056041395,"curvature":-0.09564346711966643,"pose":{"rotation":{"radians":0.2373794912798881},"translation":{"x":2.7947340844054014,"y":2.191525624188186}},"time":1.085120390688321,"velocity":2.145240887969716,"position":1.6621878907325454,"holonomicRotation":-150.8623698429236,"angularVelocity":-0.2077202414125666,"angularAcceleration":0.8397746803488763,"curveRadius":-10.455497172105106},{"acceleration":-2.9889982163967095,"curvature":-0.09443510497735481,"pose":{"rotation":{"radians":0.23639611274834538},"translation":{"x":2.8047329108505954,"y":2.193934344892072}},"time":1.089947122087813,"velocity":2.130813796425608,"position":1.6724727565902238,"holonomicRotation":-150.93833839171754,"angularVelocity":-0.20373591363426918,"angularAcceleration":0.8254712037045779,"curveRadius":-10.589282452111387},{"acceleration":-2.988866633057042,"curvature":-0.09323331728116613,"pose":{"rotation":{"radians":0.2354245661727301},"translation":{"x":2.8147401306203177,"y":2.1963348032499264}},"time":1.0948099465601306,"velocity":2.1162794626178845,"position":1.6827638521513053,"holonomicRotation":-151.01430694051152,"angularVelocity":-0.1997905910743717,"angularAcceleration":0.8113232509947267,"curveRadius":-10.72577946555601},{"acceleration":-2.9887310943425818,"curvature":-0.0920380092030093,"pose":{"rotation":{"radians":0.23446480649210288},"translation":{"x":2.824755630830283,"y":2.198727084631287}},"time":1.0997095800373755,"velocity":2.101635775693561,"position":1.693061097154869,"holonomicRotation":-151.09027548930544,"angularVelocity":-0.1958839748084405,"angularAcceleration":0.7973282663028785,"curveRadius":-10.865076381588052},{"acceleration":-2.988591429889294,"curvature":-0.09084908647454751,"pose":{"rotation":{"radians":0.23351678924339092},"translation":{"x":2.8347792985962053,"y":2.2011112744056938}},"time":1.104646764323324,"velocity":2.086880549048791,"position":1.7033644110082842,"holonomicRotation":-151.16624403809942,"angularVelocity":-0.19201577129905367,"angularAcceleration":0.7834837197379829,"curveRadius":-11.00726533205331},{"acceleration":-2.9884474595214177,"curvature":-0.08966645469988563,"pose":{"rotation":{"radians":0.2325804705593253},"translation":{"x":2.8448110210338005,"y":2.203487457942683}},"time":1.109622268417613,"velocity":2.072011516478375,"position":1.7136737127919361,"holonomicRotation":-151.24221258689334,"angularVelocity":-0.18818569260959322,"angularAcceleration":0.7697870641603443,"curveRadius":-11.152442720602798},{"acceleration":-2.9882989924836383,"curvature":-0.08849002090475543,"pose":{"rotation":{"radians":0.23165580716802125},"translation":{"x":2.854850685258783,"y":2.205855720611794}},"time":1.1146368899279002,"velocity":2.0570263280714967,"position":1.7239889212639108,"holonomicRotation":-151.3181811356873,"angularVelocity":-0.18439345609775823,"angularAcceleration":0.7562358403431572,"curveRadius":-11.300709275188568},{"acceleration":-2.988145826765577,"curvature":-0.0873196915835784,"pose":{"rotation":{"radians":0.23074275639069342},"translation":{"x":2.864898178386868,"y":2.208216147782566}},"time":1.1196914565772567,"velocity":2.0419225458321137,"position":1.7343099548646428,"holonomicRotation":-151.39414968448125,"angularVelocity":-0.18063878481928644,"angularAcceleration":0.7428275337807332,"curveRadius":-11.45217054555038},{"acceleration":-2.9879877482304966,"curvature":-0.08615537411526783,"pose":{"rotation":{"radians":0.22984127614049665},"translation":{"x":2.87495338753377,"y":2.210568824824536}},"time":1.1247868278147564,"velocity":2.0266976390017786,"position":1.744636731721521,"holonomicRotation":-151.4701182332752,"angularVelocity":-0.17692140732794154,"angularAcceleration":0.7295596960603443,"curveRadius":-11.606937005021805},{"acceleration":-2.9878245294979866,"curvature":-0.08499697665397435,"pose":{"rotation":{"radians":0.22895132492145587},"translation":{"x":2.885016199815204,"y":2.2129138371072434}},"time":1.1299238965380405,"velocity":2.0113489790606334,"position":1.7549691696534628,"holonomicRotation":-151.54608678206915,"angularVelocity":-0.17324105768860354,"angularAcceleration":0.7164299014838088,"curveRadius":-11.765124353434768},{"acceleration":-2.9876559292241,"curvature":-0.08384440726344758,"pose":{"rotation":{"radians":0.22807286182657371},"translation":{"x":2.8950865023468846,"y":2.215251270000226}},"time":1.1351035909375171,"velocity":1.9958738343764681,"position":1.7653071861754446,"holonomicRotation":-151.6220553308631,"angularVelocity":-0.16959747566785324,"angularAcceleration":0.7034357125622032,"curveRadius":-11.92685395053124},{"acceleration":-2.987481690721248,"curvature":-0.08269757450296113,"pose":{"rotation":{"radians":0.2272058465366542},"translation":{"x":2.905164182244527,"y":2.2175812088730225}},"time":1.140326876472868,"velocity":1.9802693644741982,"position":1.7756506985030012,"holonomicRotation":-151.69802387965706,"angularVelocity":-0.16599040662272704,"angularAcceleration":0.6905747389672195,"curveRadius":-12.092253080097208},{"acceleration":-2.98730154086489,"curvature":-0.08155638805695935,"pose":{"rotation":{"radians":0.22635023931884168},"translation":{"x":2.9152491266238463,"y":2.2199037390951712}},"time":1.1455947579936492,"velocity":1.964532613890075,"position":1.7859996235566846,"holonomicRotation":-151.773992428451,"angularVelocity":-0.16241960158694854,"angularAcceleration":0.6778445987617788,"curveRadius":-12.261455219198716},{"acceleration":-2.9871151887925063,"curvature":-0.08042075708221146,"pose":{"rotation":{"radians":0.22550600102508866},"translation":{"x":2.925341222600557,"y":2.2222189460362105}},"time":1.1509082820170433,"velocity":1.9486605055737805,"position":1.7963538779664903,"holonomicRotation":-151.84996097724496,"angularVelocity":-0.15888481731446896,"angularAcceleration":0.6652429267124412,"curveRadius":-12.43460067128855},{"acceleration":-2.9869223242292935,"curvature":-0.07929059173235263,"pose":{"rotation":{"radians":0.2246730930909533},"translation":{"x":2.935440357290374,"y":2.2245269150656792}},"time":1.1562685391772327,"velocity":1.9326498337984008,"position":1.806713378076247,"holonomicRotation":-151.9259295260389,"angularVelocity":-0.1553858162480295,"angularAcceleration":0.6527673881817705,"curveRadius":-12.611836765899351},{"acceleration":-2.986722616077214,"curvature":-0.07816580256967064,"pose":{"rotation":{"radians":0.22385147753377455},"translation":{"x":2.9455464178090116,"y":2.2268277315531146}},"time":1.161676666862472,"velocity":1.9164972565302631,"position":1.8170780399479736,"holonomicRotation":-152.00189807483287,"angularVelocity":-0.1519223666669739,"angularAcceleration":0.6404156452349583,"curveRadius":-12.793318396605489},{"acceleration":-2.9865157104947717,"curvature":-0.07704630041518801,"pose":{"rotation":{"radians":0.22304111695190132},"translation":{"x":2.9556592912721857,"y":2.2291214808680566}},"time":1.1671338520577454,"velocity":1.9001992872094997,"position":1.8274477793662023,"holonomicRotation":-152.07786662362682,"angularVelocity":-0.14849424252178606,"angularAcceleration":0.6281854147367089,"curveRadius":-12.979208535791962},{"acceleration":-2.9863012289468926,"curvature":-0.07593199667758774,"pose":{"rotation":{"radians":0.22224197452240535},"translation":{"x":2.965778864795611,"y":2.231408248380042}},"time":1.1726413344129405,"velocity":1.8837522858837774,"position":1.8378225118422655,"holonomicRotation":-152.15383517242077,"angularVelocity":-0.14510122374557613,"angularAcceleration":0.6160743797952237,"curveRadius":-13.169678709307039},{"acceleration":-2.986078765985141,"curvature":-0.0748228030456995,"pose":{"rotation":{"radians":0.22145401400072728},"translation":{"x":2.9759050254950012,"y":2.2336881194586105}},"time":1.1782004095588035,"velocity":1.8671524496322003,"position":1.848202152618553,"holonomicRotation":-152.22980372121472,"angularVelocity":-0.14174309592926862,"angularAcceleration":0.6040803062010442,"curveRadius":-13.364909617048566},{"acceleration":-2.98584788685999,"curvature":-0.07371863149211477,"pose":{"rotation":{"radians":0.2206771997181538},"translation":{"x":2.986037660486073,"y":2.2359611794733}},"time":1.1838124326955792,"velocity":1.850395802208249,"position":1.8585866166727385,"holonomicRotation":-152.30577227000867,"angularVelocity":-0.13841965074644627,"angularAcceleration":0.5922009054174597,"curveRadius":-13.565091751695958},{"acceleration":-2.9856081247687722,"curvature":-0.0726193946177759,"pose":{"rotation":{"radians":0.21991149658135933},"translation":{"x":2.996176656884539,"y":2.2382275137936483}},"time":1.189478822482248,"velocity":1.8334781828230642,"position":1.868975818721967,"holonomicRotation":-152.38174081880263,"angularVelocity":-0.13513068560795855,"angularAcceleration":0.5804339733609014,"curveRadius":-13.770426003458011},{"acceleration":-2.9853589778542124,"curvature":-0.07152500533488972,"pose":{"rotation":{"radians":0.21915687007052753},"translation":{"x":3.0063219018061162,"y":2.2404872077891946}},"time":1.1952010652577278,"velocity":1.8163952339798237,"position":1.8793696732270242,"holonomicRotation":-152.45770936759658,"angularVelocity":-0.1318760039447135,"angularAcceleration":0.568777276838288,"curveRadius":-13.981124437780398},{"acceleration":-2.9850999058650407,"curvature":-0.07043537722358895,"pose":{"rotation":{"radians":0.21841328623814116},"translation":{"x":3.016473282366519,"y":2.2427403468294775}},"time":1.2009807196293292,"velocity":1.7991423882592241,"position":1.8897680943964599,"holonomicRotation":-152.53367791639053,"angularVelocity":-0.1286554151127128,"angularAcceleration":0.5572286204215324,"curveRadius":-14.1974110087551},{"acceleration":-2.984830326421967,"curvature":-0.06935042349828702,"pose":{"rotation":{"radians":0.2176807117074966},"translation":{"x":3.026630685681461,"y":2.2449870162840346}},"time":1.206819421468295,"velocity":1.7817148539433432,"position":1.9001709961906916,"holonomicRotation":-152.60964646518448,"angularVelocity":-0.12546873446346835,"angularAcceleration":0.545785816288384,"curveRadius":-14.419522615095499},{"acceleration":-2.9845496107377705,"curvature":-0.0682700585873789,"pose":{"rotation":{"radians":0.21695911367155807},"translation":{"x":3.036793998866658,"y":2.2472273015224045}},"time":1.2127188893574508,"velocity":1.7641075993512034,"position":1.9105782923260797,"holonomicRotation":-152.68561501397843,"angularVelocity":-0.12231578330393898,"angularAcceleration":0.5344467024432902,"curveRadius":-14.6477097089363},{"acceleration":-2.9842570790498564,"curvature":-0.06719419692695046,"pose":{"rotation":{"radians":0.21624845989153618},"translation":{"x":3.0469631090378253,"y":2.2494612879141256}},"time":1.218680930541994,"velocity":1.7463153357406438,"position":1.9209898962789647,"holonomicRotation":-152.7615835627724,"angularVelocity":-0.11919638895891708,"angularAcceleration":0.5232091239337748,"curveRadius":-14.882237540351001},{"acceleration":-2.9839519951655378,"curvature":-0.06612275313116783,"pose":{"rotation":{"radians":0.21554871869556802},"translation":{"x":3.057137903310677,"y":2.251689060828737}},"time":1.2247074474414146,"velocity":1.7283324986147186,"position":1.9314057212896842,"holonomicRotation":-152.83755211156634,"angularVelocity":-0.11611038476228722,"angularAcceleration":0.5120709438193923,"curveRadius":-15.123387225215774},{"acceleration":-2.983633560642792,"curvature":-0.06505564255536415,"pose":{"rotation":{"radians":0.21485985897719662},"translation":{"x":3.067318268800928,"y":2.253910705635776}},"time":1.230800444788595,"velocity":1.7101532272447637,"position":1.9418256803665586,"holonomicRotation":-152.9135206603603,"angularVelocity":-0.11305761009237646,"angularAcceleration":0.5010300343103665,"curveRadius":-15.371456813280606},{"acceleration":-2.9833009079050714,"curvature":-0.06399278095475576,"pose":{"rotation":{"radians":0.2141818501946795},"translation":{"x":3.077504092624294,"y":2.2561263077047817}},"time":1.2369620374715276,"velocity":1.6917713421996297,"position":1.9522496862898508,"holonomicRotation":-152.98948920915424,"angularVelocity":-0.1100379102297976,"angularAcceleration":0.49008430416754495,"curveRadius":-15.626762661041736},{"acceleration":-2.9829530927733425,"curvature":-0.0629340837225442,"pose":{"rotation":{"radians":0.21351466236901206},"translation":{"x":3.0876952618964886,"y":2.258335952405292}},"time":1.2431944591640551,"velocity":1.6731803206364368,"position":1.9626776516156956,"holonomicRotation":-153.0654577579482,"angularVelocity":-0.10705113655376818,"angularAcceleration":0.4792316411468829,"curveRadius":-15.889641047427862},{"acceleration":-2.9825890856335717,"curvature":-0.06187946722741488,"pose":{"rotation":{"radians":0.21285826608330538},"translation":{"x":3.097891663733227,"y":2.2605397251068466}},"time":1.249500071844884,"velocity":1.6543732690763637,"position":1.973109488680008,"holonomicRotation":-153.14142630674215,"angularVelocity":-0.10409714629354481,"angularAcceleration":0.4684699821802273,"curveRadius":-16.160449415714478},{"acceleration":-2.9822077616358524,"curvature":-0.06082884827474712,"pose":{"rotation":{"radians":0.21221263248086464},"translation":{"x":3.108093185250225,"y":2.262737711178982}},"time":1.2558813763192118,"velocity":1.635342893343662,"position":1.983545109602362,"holonomicRotation":-153.2173948555361,"angularVelocity":-0.10117580269647942,"angularAcceleration":0.45779724330943444,"curveRadius":-16.439568204271698},{"acceleration":-2.981807889458505,"curvature":-0.05978214331094924,"pose":{"rotation":{"radians":0.2115777332649147},"translation":{"x":3.118299713563197,"y":2.2649299959912375}},"time":1.262341023875132,"velocity":1.6160814652982978,"position":1.993984426289844,"holonomicRotation":-153.29336340433005,"angularVelocity":-0.0982869747077868,"angularAcceleration":0.44721139407134347,"curveRadius":-16.727402943695523},{"acceleration":-2.981388118289579,"curvature":-0.058739270243848334,"pose":{"rotation":{"radians":0.21095354069653593},"translation":{"x":3.128511135787857,"y":2.267116664913152}},"time":1.2688818292280681,"velocity":1.5965807859350092,"position":2.0044273504408827,"holonomicRotation":-153.369331953124,"angularVelocity":-0.09543053717361609,"angularAcceleration":0.43671037128302287,"curveRadius":-17.024385829933397},{"acceleration":-2.9809469630449192,"curvature":-0.05770014580979059,"pose":{"rotation":{"radians":0.2103400275938725},"translation":{"x":3.138727339039921,"y":2.269297803314263}},"time":1.2755067849315658,"velocity":1.5768321443503608,"position":2.014873793549055,"holonomicRotation":-153.44530050191796,"angularVelocity":-0.0926063705361139,"angularAcceleration":0.42629215407601556,"curveRadius":-17.330978734378164},{"acceleration":-2.9804827872381368,"curvature":-0.05666468845996548,"pose":{"rotation":{"radians":0.20973716733103487},"translation":{"x":3.1489482104351034,"y":2.2714734965641092}},"time":1.2822190774627016,"velocity":1.5568262719984034,"position":2.025323666906866,"holonomicRotation":-153.5212690507119,"angularVelocity":-0.08981436074801276,"angularAcceleration":0.41595472413486906,"curveRadius":-17.647674895565977},{"acceleration":-2.979993783150472,"curvature":-0.055632815876063536,"pose":{"rotation":{"radians":0.2091449338369502},"translation":{"x":3.1591736370891192,"y":2.273643830032229}},"time":1.289022105226257,"velocity":1.5365532915564084,"position":2.0357768816095065,"holonomicRotation":-153.59723759950586,"angularVelocity":-0.08705439910995616,"angularAcceleration":0.40569607151128373,"curveRadius":-17.975002419934274},{"acceleration":-2.979477948886014,"curvature":-0.05460444666339392,"pose":{"rotation":{"radians":0.20856330159422543},"translation":{"x":3.1694035061176824,"y":2.2758088890881614}},"time":1.2959194987650124,"velocity":1.5160026596028975,"position":2.0462333485585877,"holonomicRotation":-153.6732061482998,"angularVelocity":-0.08432638205383976,"angularAcceleration":0.39551419544035676,"curveRadius":-18.313526848178583},{"acceleration":-2.978933061453334,"curvature":-0.05357949974079319,"pose":{"rotation":{"radians":0.20799224563785312},"translation":{"x":3.179637704636509,"y":2.277968759101444}},"time":1.3029151435158082,"velocity":1.4951631021685696,"position":2.0566929784658567,"holonomicRotation":-153.74917469709376,"angularVelocity":-0.0816302108976226,"angularAcceleration":0.3854071000261245,"curveRadius":-18.66385473619198},{"acceleration":-2.978356645523316,"curvature":-0.05255789389336179,"pose":{"rotation":{"radians":0.20743174155463961},"translation":{"x":3.1898761197613137,"y":2.280123525441615}},"time":1.3100132055145852,"velocity":1.4740225420441755,"position":2.0671556818568813,"holonomicRotation":-153.82514324588772,"angularVelocity":-0.07896579141039907,"angularAcceleration":0.3753728112944898,"curveRadius":-19.026637597559876},{"acceleration":-2.9777459364166696,"curvature":-0.051539548448846326,"pose":{"rotation":{"radians":0.20688176548193749},"translation":{"x":3.2001186386078113,"y":2.2822732734782134}},"time":1.3172181605313629,"velocity":1.452568016520901,"position":2.0776213690747243,"holonomicRotation":-153.90111179468167,"angularVelocity":-0.07633303350561398,"angularAcceleration":0.36540934657529217,"curveRadius":-19.402575887767295},{"acceleration":-2.9770978366896155,"curvature":-0.05052438283598914,"pose":{"rotation":{"radians":0.20634229410639904},"translation":{"x":3.210365148291716,"y":2.2844180885807774}},"time":1.3245348272116184,"velocity":1.4307855839753332,"position":2.0880899502835866,"holonomicRotation":-153.97708034347562,"angularVelocity":-0.07373185073391991,"angularAcceleration":0.35551472895622094,"curveRadius":-19.79242385297753},{"acceleration":-2.9764088643282025,"curvature":-0.049512316579253805,"pose":{"rotation":{"radians":0.20581330466349224},"translation":{"x":3.220615535928743,"y":2.286558056118846}},"time":1.3319684049186833,"velocity":1.4086602173943528,"position":2.0985613354724384,"holonomicRotation":-154.05304889226957,"angularVelocity":-0.07116215956201685,"angularAcceleration":0.34568699933826275,"curveRadius":-20.196994790161177},{"acceleration":-2.975675091291263,"curvature":-0.04850327028899039,"pose":{"rotation":{"radians":0.20529477493606185},"translation":{"x":3.230869688634608,"y":2.2886932614619564}},"time":1.33952451711872,"velocity":1.3861756825337015,"position":2.1090354344586255,"holonomicRotation":-154.12901744106352,"angularVelocity":-0.06862387874916205,"angularAcceleration":0.3359241823913716,"curveRadius":-20.617166513553354},{"acceleration":-2.974892069617503,"curvature":-0.04749716397945958,"pose":{"rotation":{"radians":0.2047866832539702},"translation":{"x":3.241127493525025,"y":2.290823789979648}},"time":1.347209261333909,"velocity":1.3633143979108966,"position":2.1195121568914552,"holonomicRotation":-154.20498598985748,"angularVelocity":-0.06611692827555608,"angularAcceleration":0.326224322294414,"curveRadius":-21.053888616012017},{"acceleration":-2.9740547424844057,"curvature":-0.046493918028994705,"pose":{"rotation":{"radians":0.20428900849257836},"translation":{"x":3.2513888377157087,"y":2.2929497270414583}},"time":1.3550292669216082,"velocity":1.3400572732065454,"position":2.1299914122557673,"holonomicRotation":-154.28095453865143,"angularVelocity":-0.06364122836110046,"angularAcceleration":0.3165854405973694,"curveRadius":-21.508189509354242},{"acceleration":-2.9731573362445345,"curvature":-0.045493453468899575,"pose":{"rotation":{"radians":0.2038017300725623},"translation":{"x":3.2616536083223737,"y":2.2950711580169267}},"time":1.3629917622321779,"velocity":1.3163835218591124,"position":2.1404731098754817,"holonomicRotation":-154.35692308744538,"angularVelocity":-0.061196697895599,"angularAcceleration":0.30700557678903856,"curveRadius":-21.981184626566638},{"acceleration":-2.972193228755324,"curvature":-0.0444956909576803,"pose":{"rotation":{"radians":0.20332482795832663},"translation":{"x":3.2719216924607366,"y":2.297188168275591}},"time":1.371104653075936,"velocity":1.2922704426276632,"position":2.150957158917135,"holonomicRotation":-154.43289163623933,"angularVelocity":-0.058783252902088565,"angularAcceleration":0.29748273950551896,"curveRadius":-22.474086332339386},{"acceleration":-2.971154787534513,"curvature":-0.04350055210812622,"pose":{"rotation":{"radians":0.20285828265799166},"translation":{"x":3.28219297724651,"y":2.2993008431869897}},"time":1.3793766149176143,"velocity":1.2676931635994582,"position":2.161443468393386,"holonomicRotation":-154.50886018503329,"angularVelocity":-0.056400804218447766,"angularAcceleration":0.2880149508955479,"curveRadius":-22.988213977477145},{"acceleration":-2.970033169238169,"curvature":-0.042507957318657814,"pose":{"rotation":{"radians":0.2024020752219613},"translation":{"x":3.2924673497954116,"y":2.301409268120661}},"time":1.3878172018527386,"velocity":1.2426243404343007,"position":2.1719319471665233,"holonomicRotation":-154.58482873382724,"angularVelocity":-0.05404925505025289,"angularAcceleration":0.2786001952552901,"curveRadius":-23.52500715345065},{"acceleration":-2.9688180697272544,"curvature":-0.04151782938090851,"pose":{"rotation":{"radians":0.20195618724273423},"translation":{"x":3.302744697223153,"y":2.303513528446143}},"time":1.3964369762575175,"velocity":1.2170337984244206,"position":2.182422503951933,"holonomicRotation":-154.6607972826212,"angularVelocity":-0.05172849755555796,"angularAcceleration":0.2692364539619826,"curveRadius":-24.086037611104935},{"acceleration":-2.967497409116599,"curvature":-0.04053008930576914,"pose":{"rotation":{"radians":0.20152060085380974},"translation":{"x":3.313024906645451,"y":2.3056137095329756}},"time":1.4052476641175675,"velocity":1.1908881050271871,"position":2.192915047321574,"holonomicRotation":-154.73676583141514,"angularVelocity":-0.04943840887833006,"angularAcceleration":0.25992166713926707,"curveRadius":-24.67302730215445},{"acceleration":-2.9660569320251247,"curvature":-0.039544659128312995,"pose":{"rotation":{"radians":0.20109529872891674},"translation":{"x":3.32330786517802,"y":2.3077098967506955}},"time":1.4142623425392364,"velocity":1.1641500556046187,"position":2.2034094857074176,"holonomicRotation":-154.8127343802091,"angularVelocity":-0.04717884598863632,"angularAcceleration":0.25065374315098576,"curveRadius":-25.28786496187104},{"acceleration":-2.9644796944155885,"curvature":-0.038561460777848784,"pose":{"rotation":{"radians":0.200680264082004},"translation":{"x":3.3335934599365755,"y":2.3098021754688416}},"time":1.4234956679885893,"velocity":1.1367780497980815,"position":2.213905727404884,"holonomicRotation":-154.88870292900305,"angularVelocity":-0.04494963912940117,"angularAcceleration":0.24143055191360066,"curveRadius":-25.932627546476123},{"acceleration":-2.96274539805167,"curvature":-0.03758041732774122,"pose":{"rotation":{"radians":0.20027548066606427},"translation":{"x":3.343881578036831,"y":2.311890631056953}},"time":1.4329641566213132,"velocity":1.1087253286749743,"position":2.224403680576256,"holonomicRotation":-154.964671477797,"angularVelocity":-0.04275058371415077,"angularAcceleration":0.23224988702529425,"curveRadius":-26.60960338143497},{"acceleration":-2.9608295168274066,"curvature":-0.03660145018546279,"pose":{"rotation":{"radians":0.19988093277251817},"translation":{"x":3.3541721065945023,"y":2.313975348884567}},"time":1.4426865320152382,"velocity":1.0799390326349645,"position":2.2349032532540853,"holonomicRotation":-155.04064002659095,"angularVelocity":-0.040581429697995705,"angularAcceleration":0.22310946947290664,"curveRadius":-27.321321831045257},{"acceleration":-2.9587021347750033,"curvature":-0.03562448255498282,"pose":{"rotation":{"radians":0.1994966052311291},"translation":{"x":3.364464932725305,"y":2.316056414321223}},"time":1.452684161238642,"velocity":1.0503590257089905,"position":2.2454043533445796,"holonomicRotation":-155.1166085753849,"angularVelocity":-0.038441867846966585,"angularAcceleration":0.21400692136296998,"curveRadius":-28.070583157428324},{"acceleration":-2.956326378386701,"curvature":-0.0346494365627023,"pose":{"rotation":{"radians":0.19912248340922822},"translation":{"x":3.374759943544952,"y":2.318133912736459}},"time":1.4629816083340572,"velocity":1.0199164112307733,"position":2.255906888630974,"holonomicRotation":-155.19257712417885,"angularVelocity":-0.03633151192080033,"angularAcceleration":0.20493972016674666,"curveRadius":-28.86049815529844},{"acceleration":-2.9536562673661515,"curvature":-0.03367623558058404,"pose":{"rotation":{"radians":0.19875855321095104},"translation":{"x":3.3850570261691595,"y":2.3202079294998126}},"time":1.4736073463368438,"velocity":0.9885316335834521,"position":2.2664107667768985,"holonomicRotation":-155.2685456729728,"angularVelocity":-0.034249874990494394,"angularAcceleration":0.19590516251765627,"curveRadius":-29.694530364211726},{"acceleration":-2.9506337155766653,"curvature":-0.03270480293363732,"pose":{"rotation":{"radians":0.1984048010774937},"translation":{"x":3.3953560677136423,"y":2.322278549980823}},"time":1.4845946871335205,"velocity":0.9561120153842467,"position":2.2769158953297226,"holonomicRotation":-155.34451422176676,"angularVelocity":-0.03219633758555465,"angularAcceleration":0.18690031036088928,"curveRadius":-30.5765487114887},{"acceleration":-2.947184261903483,"curvature":-0.0317350603735765,"pose":{"rotation":{"radians":0.19806121398613907},"translation":{"x":3.405656955294115,"y":2.324345859549029}},"time":1.4959830166150199,"velocity":0.9225485099670003,"position":2.287422181723893,"holonomicRotation":-155.4204827705607,"angularVelocity":-0.030170104571771526,"angularAcceleration":0.1779218819647599,"curveRadius":-31.510890107920766},{"acceleration":-2.943210855058444,"curvature":-0.030766932099435953,"pose":{"rotation":{"radians":0.19772777944991882},"translation":{"x":3.4159595760262924,"y":2.3264099435739682}},"time":1.5078194673750656,"velocity":0.8877113396046691,"position":2.297929533284258,"holonomicRotation":-155.49645131935466,"angularVelocity":-0.02817014517103175,"angularAcceleration":0.1689661403814311,"curveRadius":-32.50242815137012},{"acceleration":-2.938584570687804,"curvature":-0.029800341128205083,"pose":{"rotation":{"radians":0.19740448551763912},"translation":{"x":3.4262638170258897,"y":2.3284708874251794}},"time":1.5201612347635345,"velocity":0.8514440123818964,"position":2.30843785722938,"holonomicRotation":-155.57241986814861,"angularVelocity":-0.026195108212925634,"angularAcceleration":0.16002869734454866,"curveRadius":-33.55666284818235},{"acceleration":-2.9331303327093714,"curvature":-0.02883521116168255,"pose":{"rotation":{"radians":0.1970913207732936},"translation":{"x":3.4365695654086212,"y":2.330528776472201}},"time":1.5330788673473668,"velocity":0.813554912423463,"position":2.318947060674838,"holonomicRotation":-155.64838841694257,"angularVelocity":-0.02424319954241956,"angularAcceleration":0.15110421029849422,"curveRadius":-34.67982233224782},{"acceleration":-2.926604185765042,"curvature":-0.027871464550638585,"pose":{"rotation":{"radians":0.1967882743358107},"translation":{"x":3.4468767082902025,"y":2.332583696084571}},"time":1.5466610852246885,"velocity":0.7738051367317205,"position":2.329457050636519,"holonomicRotation":-155.72435696573652,"angularVelocity":-0.022311999426022314,"angularAcceleration":0.14218591792889573,"curveRadius":-35.878990075427815},{"acceleration":-2.9186556313459144,"curvature":-0.026909025598709255,"pose":{"rotation":{"radians":0.1964953358590562},"translation":{"x":3.457185132786348,"y":2.3346357316318285}},"time":1.5610220945956894,"velocity":0.7318902958592371,"position":2.3399677340338982,"holonomicRotation":-155.80032551453047,"angularVelocity":-0.02039818157531586,"angularAcceleration":0.1332648563387899,"curveRadius":-37.162252357735575},{"acceleration":-2.908762123984014,"curvature":-0.025947818151589,"pose":{"rotation":{"radians":0.196212495531225},"translation":{"x":3.4674947260127724,"y":2.3366849684835107}},"time":1.5763131885921624,"velocity":0.6874121408080172,"position":2.3504790176933104,"holonomicRotation":-155.87629406332442,"angularVelocity":-0.018497062924108132,"angularAcceleration":0.12432849158119323,"curveRadius":-38.53888578060509},{"acceleration":-2.896108224802671,"curvature":-0.024987765501941962,"pose":{"rotation":{"radians":0.19593974407531212},"translation":{"x":3.477805375085191,"y":2.338731492009157}},"time":1.5927421735284397,"velocity":0.6398320224089052,"position":2.360990808351214,"holonomicRotation":-155.95226261211837,"angularVelocity":-0.016601844664828207,"angularAcceleration":0.11535820786438478,"curveRadius":-40.019584781291606},{"acceleration":-2.8793455320647463,"curvature":-0.024028790769838403,"pose":{"rotation":{"radians":0.1956770727483339},"translation":{"x":3.488116967119319,"y":2.3407753875783057}},"time":1.6106082388699678,"velocity":0.5883894469921994,"position":2.3715030126574423,"holonomicRotation":-156.02823116091233,"angularVelocity":-0.014702248198301255,"angularAcceleration":0.10632427623062055,"curveRadius":-41.61674258095532},{"acceleration":-2.8560676722522893,"curvature":-0.02307081841441656,"pose":{"rotation":{"radians":0.19542447334177693},"translation":{"x":3.49842938923087,"y":2.342816740560495}},"time":1.63037059923049,"velocity":0.531946808439112,"position":2.3820155371784457,"holonomicRotation":-156.10419970970628,"angularVelocity":-0.012781843967463246,"angularAcceleration":0.09717484125399632,"curveRadius":-43.34479956615311},{"acceleration":-2.821501269195091,"curvature":-0.02211377181770357,"pose":{"rotation":{"radians":0.19518193818118323},"translation":{"x":3.5087425285355596,"y":2.3448556363252635}},"time":1.6528023147587245,"velocity":0.46865569460597506,"position":2.392528288400534,"holonomicRotation":-156.18016825850023,"angularVelocity":-0.010812153902737268,"angularAcceleration":0.08780826692665358,"curveRadius":-45.22068909110441},{"acceleration":-2.7645437337359025,"curvature":-0.02115757473087249,"pose":{"rotation":{"radians":0.19494946012647896},"translation":{"x":3.5190562721491028,"y":2.3468921602421493}},"time":1.6794107841968988,"velocity":0.39509541715636703,"position":2.403041172733102,"holonomicRotation":-156.25613680729418,"angularVelocity":-0.008736994634150149,"angularAcceleration":0.07798867474917429,"curveRadius":-47.264396449978285},{"acceleration":-2.65098567135312,"curvature":-0.02020215076737322,"pose":{"rotation":{"radians":0.19472703257177848},"translation":{"x":3.529370507187214,"y":2.3489263976806907}},"time":1.7140877616351533,"velocity":0.303167246841719,"position":2.41355409651185,"holonomicRotation":-156.3321053560881,"angularVelocity":-0.006414271690678052,"angularAcceleration":0.0669817012629753,"curveRadius":-49.49968008431138},{"acceleration":-2.1213230821893267,"curvature":-0.02020215076737322,"pose":{"rotation":{"radians":0.19451464944570063},"translation":{"x":3.539685120765609,"y":2.350958434010427}},"time":1.7978050218632664,"velocity":0.12557589034217215,"position":2.4240669660020027,"holonomicRotation":-156.4080739048821,"angularVelocity":-0.0025369096587627296,"angularAcceleration":0.04631496565165023,"curveRadius":-49.49968008431138}] \ No newline at end of file diff --git a/src/main/deploy/pathplanner/generatedJSON/Blue4(1).wpilib.json b/src/main/deploy/pathplanner/generatedJSON/Blue4(1).wpilib.json new file mode 100644 index 0000000..b0b8c35 --- /dev/null +++ b/src/main/deploy/pathplanner/generatedJSON/Blue4(1).wpilib.json @@ -0,0 +1 @@ +[{"acceleration":0.0,"curvature":-0.00015685628868693162,"pose":{"rotation":{"radians":-1.5640918852954089},"translation":{"x":7.65,"y":1.9}},"time":0.0,"velocity":0,"position":0.0,"holonomicRotation":-90.0,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-6375.262403383093},{"acceleration":1.5,"curvature":-0.00015685628868693162,"pose":{"rotation":{"radians":-1.5640918852954089},"translation":{"x":7.65004351575605,"y":1.8935095109642994}},"time":0.06578061979371165,"velocity":0.09867092969056748,"position":0.006490634910667274,"holonomicRotation":-90.0,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-6375.262403383093},{"acceleration":5.146150844274086,"curvature":-0.00031964843965437504,"pose":{"rotation":{"radians":-1.5640928988386005},"translation":{"x":7.650086678142813,"y":1.8870707544760343}},"time":0.09284228945708287,"velocity":0.23793436387619168,"position":0.012929536067449138,"holonomicRotation":-90.0,"angularVelocity":-0.00003745309155734863,"angularAcceleration":-0.0013839904197796974,"curveRadius":-3128.43698245881},{"acceleration":3.466758909353448,"curvature":-0.0004891088501413281,"pose":{"rotation":{"radians":-1.564094948995331},"translation":{"x":7.650129483320291,"y":1.8806833311752045}},"time":0.11348157793418512,"velocity":0.3094858010869019,"position":0.019317102795648793,"holonomicRotation":-90.0,"angularVelocity":-0.00009933272326120416,"angularAcceleration":-0.0029981475268639392,"curveRadius":-2044.5346668968466},{"acceleration":3.290060426204831,"curvature":-0.0006652082718853021,"pose":{"rotation":{"radians":-1.5640980605714994},"translation":{"x":7.6501719274484845,"y":1.87434684170181}},"time":0.13077648723581722,"velocity":0.3663870977550035,"position":0.025653734420609794,"holonomicRotation":-90.0,"angularVelocity":-0.00017991283527495587,"angularAcceleration":-0.004659180953677938,"curveRadius":-1503.2885823350437},{"acceleration":3.212878427648186,"curvature":-0.0008481837280786304,"pose":{"rotation":{"radians":-1.5641022587760123},"translation":{"x":7.650214006687391,"y":1.8680608866958508}},"time":0.14592196605889224,"velocity":0.41504767994206365,"position":0.031939830267738736,"holonomicRotation":-90.0,"angularVelocity":-0.0002771919304737468,"angularAcceleration":-0.006422979183106485,"curveRadius":-1178.9898425253632},{"acceleration":3.169199770849868,"curvature":-0.0010382373216403808,"pose":{"rotation":{"radians":-1.5641075692196713},"translation":{"x":7.6502557171970125,"y":1.8618250667973273}},"time":0.15953221129817,"velocity":0.4581812660355932,"position":0.038175789662525925,"holonomicRotation":-90.0,"angularVelocity":-0.0003901798656580527,"angularAcceleration":-0.00830168253384843,"curveRadius":-963.1709235996573},{"acceleration":3.141017315714086,"curvature":-0.001235611463539469,"pose":{"rotation":{"radians":-1.5641140179167827},"translation":{"x":7.650297055137349,"y":1.855638982646239}},"time":0.17197288920170156,"velocity":0.4972576507498075,"position":0.04436201193057107,"holonomicRotation":-90.0,"angularVelocity":-0.0005183557649688665,"angularAcceleration":-0.010302967435112857,"curveRadius":-809.3158970340495},{"acceleration":3.121302540970637,"curvature":-0.0014405032606532807,"pose":{"rotation":{"radians":-1.5641216312842765},"translation":{"x":7.650338016668399,"y":1.8495022348825856}},"time":0.18348278102246302,"velocity":0.5331835053362474,"position":0.050498896397605665,"holonomicRotation":-90.0,"angularVelocity":-0.0006614629930788859,"angularAcceleration":-0.012433412089232987,"curveRadius":-694.201830231534},{"acceleration":3.106728454736761,"curvature":-0.0016530534162184848,"pose":{"rotation":{"radians":-1.564130436139509},"translation":{"x":7.650378597950163,"y":1.8434144241463681}},"time":0.1942281174109753,"velocity":0.5665663476501568,"position":0.05658684238951739,"holonomicRotation":-90.0,"angularVelocity":-0.0008194117814573494,"angularAcceleration":-0.01469928745528385,"curveRadius":-604.9411290577615},{"acceleration":3.0955122017855756,"curvature":-0.0018735110861447671,"pose":{"rotation":{"radians":-1.5641404597006616},"translation":{"x":7.650418795142643,"y":1.8373751510775855}},"time":0.2043302053578622,"velocity":0.5978374841532562,"position":0.0626262492323792,"holonomicRotation":-90.0,"angularVelocity":-0.0009922266768365353,"angularAcceleration":-0.01710684922639592,"curveRadius":-533.7571831815302},{"acceleration":3.08661106676409,"curvature":-0.002102125492073058,"pose":{"rotation":{"radians":-1.564151729584216},"translation":{"x":7.650458604405837,"y":1.8313840163162387}},"time":0.21388083325763788,"velocity":0.6273165579232497,"position":0.06861751625247223,"holonomicRotation":-90.0,"angularVelocity":-0.0011800149343732104,"angularAcceleration":-0.019662399112113437,"curveRadius":-475.7089925272861},{"acceleration":3.0793740317138947,"curvature":-0.0023390617119532155,"pose":{"rotation":{"radians":-1.564164273802671},"translation":{"x":7.650498021899745,"y":1.8254406205023268}},"time":0.2229514786918407,"velocity":0.6552484679242181,"position":0.07456104277631743,"holonomicRotation":-90.0,"angularVelocity":-0.001382946621173162,"angularAcceleration":-0.022372353574173887,"curveRadius":-427.5218541219922},{"acceleration":3.0733734410884055,"curvature":-0.0025845786636601578,"pose":{"rotation":{"radians":-1.5641781207612837},"translation":{"x":7.650537043784367,"y":1.8195445642758505}},"time":0.23159911935742353,"velocity":0.6818258970738964,"position":0.08045722813070115,"holonomicRotation":-90.0,"angularVelocity":-0.0016012412111118305,"angularAcceleration":-0.025243254013487162,"curveRadius":-386.9102589370785},{"acceleration":3.0683166846072725,"curvature":-0.002838874634879944,"pose":{"rotation":{"radians":-1.564193299255308},"translation":{"x":7.650575666219705,"y":1.8136954482768095}},"time":0.23987006433026414,"velocity":0.7072037755315319,"position":0.08630647164270758,"holonomicRotation":-90.0,"angularVelocity":-0.001835158385670295,"angularAcceleration":-0.028281795529601608,"curveRadius":-352.25225788890464},{"acceleration":3.0639967464171445,"curvature":-0.0031021886305964592,"pose":{"rotation":{"radians":-1.5642098384667067},"translation":{"x":7.650613885365757,"y":1.807892873145204}},"time":0.24780257281385362,"velocity":0.7315089557161765,"position":0.09210917263974783,"holonomicRotation":-90.0,"angularVelocity":-0.0020849913281371503,"angularAcceleration":-0.03149482197008697,"curveRadius":-322.35306071885435},{"acceleration":3.0602630159537236,"curvature":-0.003374734726743153,"pose":{"rotation":{"radians":-1.5642277679578145},"translation":{"x":7.650651697382522,"y":1.8021364395210338}},"time":0.25542869905264887,"velocity":0.7548469077997558,"position":0.097865730449593,"holonomicRotation":-90.0,"angularVelocity":-0.002351061409996491,"angularAcceleration":-0.03488928369763962,"curveRadius":-296.31958686277767},{"acceleration":3.057003288272658,"curvature":-0.0036567716834032256,"pose":{"rotation":{"radians":-1.564247117667727},"translation":{"x":7.650689098430003,"y":1.7964257480442987}},"time":0.2627756259630468,"velocity":0.7773064875235413,"position":0.10357654440040662,"holonomicRotation":-90.0,"angularVelocity":-0.002633714769258118,"angularAcceleration":-0.038472324920177624,"curveRadius":-273.46525475972186},{"acceleration":3.0541322473759225,"curvature":-0.003948513914746858,"pose":{"rotation":{"radians":-1.5642679179060677},"translation":{"x":7.650726084668198,"y":1.790760399354999}},"time":0.2698666507997091,"velocity":0.7989634151441352,"position":0.10924201382077821,"holonomicRotation":-90.0,"angularVelocity":-0.0029333190645547164,"angularAcceleration":-0.042251198126901576,"curveRadius":-253.25983942090542},{"acceleration":3.051583861286022,"curvature":-0.004250198917518585,"pose":{"rotation":{"radians":-1.5642901993470035},"translation":{"x":7.650762652257107,"y":1.7851399940931347}},"time":0.2767219278623206,"velocity":0.8198828679930446,"position":0.11486253803975903,"holonomicRotation":-90.0,"angularVelocity":-0.003250261183078766,"angularAcceleration":-0.046233305470999166,"curveRadius":-235.28310542788316},{"acceleration":3.0493062211591595,"curvature":-0.004562073660936934,"pose":{"rotation":{"radians":-1.564313993020349},"translation":{"x":7.650798797356732,"y":1.7795641328987057}},"time":0.28335903772057847,"velocity":0.8401214483743471,"position":0.1204385163868983,"holonomicRotation":-90.0,"angularVelocity":-0.0035849449313799706,"angularAcceleration":-0.05042612755381643,"curveRadius":-219.19856502155324},{"acceleration":3.047257954259982,"curvature":-0.004884359147523765,"pose":{"rotation":{"radians":-1.5643393303065007},"translation":{"x":7.65083451612707,"y":1.7740324164117123}},"time":0.2897934300983832,"velocity":0.8597287017284424,"position":0.12597034819227976,"holonomicRotation":-90.0,"angularVelocity":-0.003937790029597646,"angularAcceleration":-0.054837361090194804,"curveRadius":-204.73514944268018},{"acceleration":3.0454056777367726,"curvature":-0.005217321467493481,"pose":{"rotation":{"radians":-1.5643662429247591},"translation":{"x":7.6508698047281225,"y":1.768544445272154}},"time":0.29603877312109106,"velocity":0.8787483048292106,"position":0.13145843278656122,"holonomicRotation":-90.0,"angularVelocity":-0.004309229798991928,"angularAcceleration":-0.059474678659561075,"curveRadius":-191.6692322354487},{"acceleration":3.0437221570029234,"curvature":-0.005561185115409814,"pose":{"rotation":{"radians":-1.564394762926244},"translation":{"x":7.65090465931989,"y":1.7630998201200312}},"time":0.30210723206726076,"velocity":0.8972190077825299,"position":0.1369031695010126,"holonomicRotation":-90.0,"angularVelocity":-0.004699710707098209,"angularAcceleration":-0.06434597507704094,"curveRadius":-179.81778690104045},{"acceleration":3.0421849511885024,"curvature":-0.005916201511867652,"pose":{"rotation":{"radians":-1.5644249226821607},"translation":{"x":7.650939076062373,"y":1.7576981415953437}},"time":0.30800969429284564,"velocity":0.9151753895401629,"position":0.14230495766755835,"holonomicRotation":-90.0,"angularVelocity":-0.005109690628084217,"angularAcceleration":-0.06945913507229301,"curveRadius":-169.02737305246313},{"acceleration":3.0407754016964597,"curvature":-0.006282608178490673,"pose":{"rotation":{"radians":-1.5644567548736141},"translation":{"x":7.650973051115569,"y":1.7523390103380914}},"time":0.31375595252660726,"velocity":0.932648470229181,"position":0.14766419661881797,"holonomicRotation":-90.0,"angularVelocity":-0.005539638171217385,"angularAcceleration":-0.07482217569113939,"curveRadius":-159.16956327527},{"acceleration":3.0394778665325495,"curvature":-0.006660652476783018,"pose":{"rotation":{"radians":-1.564490292478574},"translation":{"x":7.651006580639479,"y":1.7470220269882746}},"time":0.31935485559499405,"velocity":0.9496662121824038,"position":0.15298128568814928,"holonomicRotation":-90.0,"angularVelocity":-0.005990031359749114,"angularAcceleration":-0.08044311234370072,"curveRadius":-150.13544145797906},{"acceleration":3.0382791334364407,"curvature":-0.007050597005667517,"pose":{"rotation":{"radians":-1.5645255687592226},"translation":{"x":7.651039660794105,"y":1.741746792185893}},"time":0.3248144333920457,"velocity":0.9662539334805587,"position":0.15825662420969355,"holonomicRotation":-90.0,"angularVelocity":-0.006461356896066003,"angularAcceleration":-0.0863300339032482,"curveRadius":-141.8319610660154},{"acceleration":3.037167964923761,"curvature":-0.0074526517096937745,"pose":{"rotation":{"radians":-1.5645626172488631},"translation":{"x":7.651072287739445,"y":1.7365129065709468}},"time":0.33014200128471916,"velocity":0.9824346520151429,"position":0.16349061151841926,"holonomicRotation":-90.0,"angularVelocity":-0.006954109339749443,"angularAcceleration":-0.09249106789630565,"curveRadius":-134.18042851771608},{"acceleration":3.036134741874148,"curvature":-0.007867077593703838,"pose":{"rotation":{"radians":-1.5646014717361743},"translation":{"x":7.6511044576354985,"y":1.7313199707834361}},"time":0.335344247950441,"velocity":0.9982293738527399,"position":0.16868364695017027,"holonomicRotation":-90.0,"angularVelocity":-0.007468789891707633,"angularAcceleration":-0.09893428455622377,"curveRadius":-127.11200418314392},{"acceleration":3.0351711816324003,"curvature":-0.00829411743931077,"pose":{"rotation":{"radians":-1.5646421662487509},"translation":{"x":7.651136166642267,"y":1.7261675854633607}},"time":0.3404273097561484,"velocity":1.0136573365598793,"position":0.17383612984171287,"holonomicRotation":-90.0,"angularVelocity":-0.008005905521531775,"angularAcceleration":-0.10566773538363335,"curveRadius":-120.56737890645283},{"acceleration":3.034270113076867,"curvature":-0.008734004447784731,"pose":{"rotation":{"radians":-1.5646847350378286},"translation":{"x":7.65116741091975,"y":1.7210553512507205}},"time":0.34539683412058525,"velocity":1.0287362158150974,"position":0.1789484595307846,"holonomicRotation":-90.0,"angularVelocity":-0.008565968482284803,"angularAcceleration":-0.11269950998952226,"curveRadius":-114.49501840517578},{"acceleration":3.033425295612634,"curvature":-0.009186981077193047,"pose":{"rotation":{"radians":-1.5647292125581505},"translation":{"x":7.651198186627948,"y":1.7159828687855156}},"time":0.35025803379427245,"velocity":1.043482301872284,"position":0.1840210353561445,"holonomicRotation":-90.0,"angularVelocity":-0.009149494632494263,"angularAcceleration":-0.12003747827269522,"curveRadius":-108.84968539692866},{"acceleration":3.0326312724565505,"curvature":-0.009653280652343707,"pose":{"rotation":{"radians":-1.5647756334508678},"translation":{"x":7.65122848992686,"y":1.7109497387077464}},"time":0.3550157336021644,"velocity":1.0579106510946577,"position":0.18905425665762438,"holonomicRotation":-90.0,"angularVelocity":-0.009757003298176659,"angularAcceleration":-0.12768957483922788,"curveRadius":-103.59172555054757},{"acceleration":3.0318832508118536,"curvature":-0.010133128399046532,"pose":{"rotation":{"radians":-1.5648240325212939},"translation":{"x":7.651258316976486,"y":1.7059555616574122}},"time":0.3596744108923904,"velocity":1.0720352167418314,"position":0.19404852277618206,"holonomicRotation":-90.0,"angularVelocity":-0.010389015467465044,"angularAcceleration":-0.13566343618914278,"curveRadius":-98.68620633427423},{"acceleration":3.0311770034034287,"curvature":-0.01062675852859125,"pose":{"rotation":{"radians":-1.564874444718809},"translation":{"x":7.651287663936827,"y":1.7009999382745133}},"time":0.3642382306988602,"velocity":1.0858689623868798,"position":0.19900423305395412,"holonomicRotation":-90.0,"angularVelocity":-0.011046053449272744,"angularAcceleration":-0.14396667915684666,"curveRadius":-94.10207235908335},{"acceleration":3.0305087870013354,"curvature":-0.011134391752309914,"pose":{"rotation":{"radians":-1.564926905113273},"translation":{"x":7.651316526967883,"y":1.6960824691990501}},"time":0.3687110764399958,"velocity":1.0994239607082927,"position":0.20392178683431064,"holonomicRotation":-90.0,"angularVelocity":-0.011728639327214957,"angularAcceleration":-0.15260662170050895,"curveRadius":-89.81182108960216},{"acceleration":3.029875274670122,"curvature":-0.011656241725718474,"pose":{"rotation":{"radians":-1.5649814488719986},"translation":{"x":7.651344902229653,"y":1.691202755071022}},"time":0.37309657682867475,"velocity":1.1127114799030073,"position":0.20880158346191283,"holonomicRotation":-90.0,"angularVelocity":-0.012437294240448229,"angularAcceleration":-0.1615904344832901,"curveRadius":-85.79094561788195},{"acceleration":3.0292734990857015,"curvature":-0.01219252562615672,"pose":{"rotation":{"radians":-1.5650381112332905},"translation":{"x":7.6513727858821365,"y":1.6863603965304292}},"time":0.3773981295508924,"velocity":1.1257420595693413,"position":0.21364402228276824,"holonomicRotation":-90.0,"angularVelocity":-0.013172536744512617,"angularAcceleration":-0.17092490817718828,"curveRadius":-82.01746140723233},{"acceleration":3.0287008048620976,"curvature":-0.012743448508550826,"pose":{"rotation":{"radians":-1.5650969274810578},"translation":{"x":7.651400174085335,"y":1.6815549942172718}},"time":0.38161892217611554,"velocity":1.1385255775905105,"position":0.21844950264429017,"holonomicRotation":-90.0,"angularVelocity":-0.013934882139384668,"angularAcceleration":-0.18061664302489894,"curveRadius":-78.47169463815091},{"acceleration":3.0281548082662257,"curvature":-0.013309204125814593,"pose":{"rotation":{"radians":-1.565157932916863},"translation":{"x":7.6514270629992485,"y":1.6767861487715496}},"time":0.38576195068578845,"velocity":1.1510713092928606,"position":0.223218423895357,"holonomicRotation":-90.0,"angularVelocity":-0.014724840937685094,"angularAcceleration":-0.19067182290830853,"curveRadius":-75.13597286109659},{"acceleration":3.0276333630604837,"curvature":-0.013889985097631917,"pose":{"rotation":{"radians":-1.56522116283025},"translation":{"x":7.651453448783877,"y":1.6720534608332633}},"time":0.3898300359441891,"velocity":1.163387979944969,"position":0.22795118538637163,"holonomicRotation":-90.0,"angularVelocity":-0.015542917458858387,"angularAcceleration":-0.20109620846415582,"curveRadius":-71.99431770236302},{"acceleration":3.027134531341736,"curvature":-0.014485982479744346,"pose":{"rotation":{"radians":-1.5652866524692177},"translation":{"x":7.651479327599219,"y":1.6673565310424117}},"time":0.39382583838487617,"velocity":1.1754838114935924,"position":0.2326481864693259,"holonomicRotation":-90.0,"angularVelocity":-0.01638960883074492,"angularAcceleration":-0.21189520364298656,"curveRadius":-69.032252482584},{"acceleration":3.0266565586029377,"curvature":-0.015097353214366884,"pose":{"rotation":{"radians":-1.5653544370072527},"translation":{"x":7.651504695605275,"y":1.662694960038996}},"time":0.39775187114402405,"velocity":1.1873665642933573,"position":0.23730982649785848,"holonomicRotation":-90.0,"angularVelocity":-0.01726540306549373,"angularAcceleration":-0.22307359323687748,"curveRadius":-66.2367757977858},{"acceleration":3.0261978522590303,"curvature":-0.015724267647577776,"pose":{"rotation":{"radians":-1.5654245515102847},"translation":{"x":7.6515295489620465,"y":1.6580683484630152}},"time":0.40161051183729707,"velocity":1.1990435744719794,"position":0.2419365048273236,"holonomicRotation":-90.0,"angularVelocity":-0.018170777899635462,"angularAcceleration":-0.2346356932689073,"curveRadius":-63.59596659206215},{"acceleration":3.025756963219143,"curvature":-0.0163668766534976,"pose":{"rotation":{"radians":-1.5654970309039653},"translation":{"x":7.651553883829532,"y":1.6534762969544698}},"time":0.40540401314807883,"velocity":1.2105217874780583,"position":0.2465286208148515,"holonomicRotation":-90.0,"angularVelocity":-0.01910619971966366,"angularAcceleration":-0.24658534250919367,"curveRadius":-61.09901242435894},{"acceleration":3.0253325698136755,"curvature":-0.017025321274896227,"pose":{"rotation":{"radians":-1.565571909934568},"translation":{"x":7.651577696367732,"y":1.64891840615336}},"time":0.4091345123708631,"velocity":1.2218077882784122,"position":0.2510865738194159,"holonomicRotation":-90.0,"angularVelocity":-0.02007212068168523,"angularAcceleration":-0.2589253888922268,"curveRadius":-58.7360428536815},{"acceleration":3.0249234639195226,"curvature":-0.01769972847006092,"pose":{"rotation":{"radians":-1.5656492231336108},"translation":{"x":7.651600982736647,"y":1.6443942766996855}},"time":0.4128040400334441,"velocity":1.2329078286064552,"position":0.25561076320189996,"holonomicRotation":-90.0,"angularVelocity":-0.021068978395008636,"angularAcceleration":-0.2716583181777284,"curveRadius":-56.49804185931437},{"acceleration":3.024528538860642,"curvature":-0.01839020298795172,"pose":{"rotation":{"radians":-1.5657290047787766},"translation":{"x":7.651623739096276,"y":1.6399035092334462}},"time":0.4164145277045969,"velocity":1.2438278516070613,"position":0.2601015883251637,"holonomicRotation":-90.0,"angularVelocity":-0.022097193629356065,"angularAcceleration":-0.2847856932354874,"curveRadius":-54.37677880201468},{"acceleration":3.024146778785616,"curvature":-0.01909685309767985,"pose":{"rotation":{"radians":-1.5658112888521805},"translation":{"x":7.6516459616066195,"y":1.6354457043946422}},"time":0.41996781507960906,"velocity":1.254573514176304,"position":0.264559448554111,"holonomicRotation":-90.0,"angularVelocity":-0.023157168199362223,"angularAcceleration":-0.2983081462704757,"curveRadius":-52.36464850439122},{"acceleration":3.023777249433436,"curvature":-0.019819752622961165,"pose":{"rotation":{"radians":-1.565896109000965},"translation":{"x":7.6516676464276765,"y":1.6310204628232738}},"time":0.42346565642387796,"velocity":1.2651502072552319,"position":0.2689847432557587,"holonomicRotation":-90.0,"angularVelocity":-0.02424928418311825,"angularAcceleration":-0.31222570616172307,"curveRadius":-50.454716515558374},{"acceleration":3.0234190899339324,"curvature":-0.020558974713331755,"pose":{"rotation":{"radians":-1.5659834984906915},"translation":{"x":7.65168878971945,"y":1.6266273851593405}},"time":0.42690972644444547,"velocity":1.2755630743024848,"position":0.27337787179930684,"holonomicRotation":-90.0,"angularVelocity":-0.025373900415653957,"angularAcceleration":-0.3265369826454323,"curveRadius":-48.64055790445308},{"acceleration":3.0230715056682973,"curvature":-0.02131456309030052,"pose":{"rotation":{"radians":-1.5660734901653068},"translation":{"x":7.651709387641937,"y":1.6222660720428423}},"time":0.4303016256505095,"velocity":1.285817028142436,"position":0.2777392335562068,"holonomicRotation":-90.0,"angularVelocity":-0.02653135283455139,"angularAcceleration":-0.3412402163449146,"curveRadius":-46.91627952979545},{"acceleration":3.0227337618816126,"curvature":-0.022086552602207533,"pose":{"rotation":{"radians":-1.5661661163962517},"translation":{"x":7.651729436355137,"y":1.61793612411378}},"time":0.43364288525639183,"velocity":1.2959167663603477,"position":0.28206922790023226,"holonomicRotation":-90.0,"angularVelocity":-0.027721949764630452,"angularAcceleration":-0.356331764219398,"curveRadius":-45.276418552529144},{"acceleration":3.022405178104371,"curvature":-0.022874937839684566,"pose":{"rotation":{"radians":-1.5662614090378133},"translation":{"x":7.6517489320190535,"y":1.6136371420121527}},"time":0.43693497167393347,"velocity":1.3058667853954926,"position":0.2863682542075515,"holonomicRotation":-90.0,"angularVelocity":-0.028945972090479277,"angularAcceleration":-0.3718074711911305,"curveRadius":-43.71596578790045},{"acceleration":3.022085123112929,"curvature":-0.023679727961092543,"pose":{"rotation":{"radians":-1.566359399378511},"translation":{"x":7.651767870793684,"y":1.609368726377961}},"time":0.4401792906356805,"velocity":1.3156713934644215,"position":0.2906367118567963,"holonomicRotation":-90.0,"angularVelocity":-0.030203670432243056,"angularAcceleration":-0.38766174244671625,"curveRadius":-42.230214875908636},{"acceleration":3.021773010553203,"curvature":-0.024500876877284878,"pose":{"rotation":{"radians":-1.5664601180890418},"translation":{"x":7.651786248839029,"y":1.6051304778512046}},"time":0.44337719098538464,"velocity":1.3253347224315961,"position":0.2948750002291353,"holonomicRotation":-90.0,"angularVelocity":-0.0314952623649372,"angularAcceleration":-0.403887485991752,"curveRadius":-40.81486572944312},{"acceleration":3.0214682949433036,"curvature":-0.025338330057467315,"pose":{"rotation":{"radians":-1.5665635951726227},"translation":{"x":7.651804062315088,"y":1.6009219970718833}},"time":0.44652996816812834,"velocity":1.3348607387302769,"position":0.29908351870834454,"holonomicRotation":-90.0,"angularVelocity":-0.03282093138303433,"angularAcceleration":-0.4204765961111993,"curveRadius":-39.46589999151486},{"acceleration":3.0211704681493465,"curvature":-0.0261920164236136,"pose":{"rotation":{"radians":-1.566669859910295},"translation":{"x":7.651821307381861,"y":1.5967428846799976}},"time":0.44963886744874065,"velocity":1.3442532534253135,"position":0.30326266668087926,"holonomicRotation":-90.0,"angularVelocity":-0.03418082352653797,"angularAcceleration":-0.4374191701816101,"curveRadius":-38.17957288307298},{"acceleration":3.020879056248592,"curvature":-0.02706181904273919,"pose":{"rotation":{"radians":-1.566778940808967},"translation":{"x":7.65183798019935,"y":1.5925927413155472}},"time":0.4527050868839789,"velocity":1.3535159314990872,"position":0.3074128435359464,"holonomicRotation":-90.0,"angularVelocity":-0.03557504639697184,"angularAcceleration":-0.45470420492769736,"curveRadius":-36.952430966325025},{"acceleration":3.0205936166791627,"curvature":-0.02794761228144935,"pose":{"rotation":{"radians":-1.5668908655446856},"translation":{"x":7.6518540769275525,"y":1.588471167618532}},"time":0.45572978007117015,"velocity":1.36265230043273,"position":0.3115344486655757,"holonomicRotation":-90.0,"angularVelocity":-0.03700366575777325,"angularAcceleration":-0.4723187683468959,"curveRadius":-35.78123203976767},{"acceleration":3.020313735701602,"curvature":-0.02884924675054469,"pose":{"rotation":{"radians":-1.5670056609066432},"translation":{"x":7.651869593726469,"y":1.5843777642289523}},"time":0.45871405869356907,"velocity":1.371665758147122,"position":0.3156278814646908,"holonomicRotation":-90.0,"angularVelocity":-0.03846670384459527,"angularAcceleration":-0.49024848948116956,"curveRadius":-34.66295008139578},{"acceleration":3.020039026095217,"curvature":-0.02976652120004775,"pose":{"rotation":{"radians":-1.567123352739464},"translation":{"x":7.651884526756101,"y":1.5803121317868078}},"time":0.4616589948805512,"velocity":1.380559580361168,"position":0.3196935413311812,"holonomicRotation":-90.0,"angularVelocity":-0.03996413686007223,"angularAcceleration":-0.5084772369928657,"curveRadius":-33.59478903427908},{"acceleration":3.019769125174925,"curvature":-0.03069923242275096,"pose":{"rotation":{"radians":-1.5672439658855533},"translation":{"x":7.651898872176446,"y":1.576273870932099}},"time":0.46456562339887075,"velocity":1.3893369274191425,"position":0.3237318276659722,"holonomicRotation":-90.0,"angularVelocity":-0.0414958930352356,"angularAcceleration":-0.5269872518999873,"curveRadius":-32.57410433685332},{"acceleration":3.019503692781222,"curvature":-0.03164712587834828,"pose":{"rotation":{"radians":-1.5673675241236555},"translation":{"x":7.651912626147507,"y":1.5722625823048249}},"time":0.46743494368956173,"velocity":1.398000850632656,"position":0.3277431398730957,"holonomicRotation":-90.0,"angularVelocity":-0.043061849352666326,"angularAcceleration":-0.5457586322834735,"curveRadius":-31.598446059335856},{"acceleration":3.0192424097767314,"curvature":-0.032609927431860045,"pose":{"rotation":{"radians":-1.567494050111808},"translation":{"x":7.651925784829281,"y":1.5682778665449866}},"time":0.47026792176358195,"velocity":1.4065542981797055,"position":0.33172787735975773,"holonomicRotation":-90.0,"angularVelocity":-0.04466183106489307,"angularAcceleration":-0.5647702419229255,"curveRadius":-30.66550829006125},{"acceleration":3.018984976430521,"curvature":-0.03358732940095602,"pose":{"rotation":{"radians":-1.5676235653220107},"translation":{"x":7.6519383443817715,"y":1.5643193242925837}},"time":0.4730654919680145,"velocity":1.415000120597397,"position":0.3356864395364095,"holonomicRotation":-90.0,"angularVelocity":-0.04629560680820836,"angularAcceleration":-0.5839981212005637,"curveRadius":-29.7731322446713},{"acceleration":3.0187311110220816,"curvature":-0.03457899070745353,"pose":{"rotation":{"radians":-1.5677560899830683},"translation":{"x":7.651950300964975,"y":1.560386556187616}},"time":0.4758285586334734,"velocity":1.4233410759022458,"position":0.33961922581681336,"holonomicRotation":-90.0,"angularVelocity":-0.047962889464159754,"angularAcceleration":-0.6034174552478608,"curveRadius":-28.91929404360692},{"acceleration":3.0184805486624504,"curvature":-0.03558453037267589,"pose":{"rotation":{"radians":-1.5678916430132475},"translation":{"x":7.651961650738893,"y":1.5564791628700836}},"time":0.47855799761234746,"velocity":1.4315798343687383,"position":0.3435266356181095,"holonomicRotation":-90.0,"angularVelocity":-0.04966333053363244,"angularAcceleration":-0.623000214562095,"curveRadius":-28.102099129229053},{"acceleration":3.018233040138848,"curvature":-0.03660354421735549,"pose":{"rotation":{"radians":-1.5680302419611793},"translation":{"x":7.651972389863526,"y":1.5525967449799865}},"time":0.4812546577165987,"velocity":1.4397189829934136,"position":0.347409068360881,"holonomicRotation":-90.0,"angularVelocity":-0.05139652109414556,"angularAcceleration":-0.6427174703184779,"curveRadius":-27.319758820673222},{"acceleration":3.0179883508770233,"curvature":-0.037635578489118984,"pose":{"rotation":{"radians":-1.5681719029416916},"translation":{"x":7.651982514498872,"y":1.5487389031573249}},"time":0.4839193620630179,"velocity":1.447761029669438,"position":0.35126692346921745,"holonomicRotation":-90.0,"angularVelocity":-0.05316198800915135,"angularAcceleration":-0.6625376347579456,"curveRadius":-26.570602609153866},{"acceleration":3.0177462599636296,"curvature":-0.038680154655294494,"pose":{"rotation":{"radians":-1.5683166405697468},"translation":{"x":7.651992020804935,"y":1.5449052380420984}},"time":0.4865529093331151,"velocity":1.4557084070942115,"position":0.355100600370778,"holonomicRotation":-90.0,"angularVelocity":-0.0549591912393814,"angularAcceleration":-0.6824267977402577,"curveRadius":-25.853050715843537},{"acceleration":3.0175065593870656,"curvature":-0.0397367514644396,"pose":{"rotation":{"radians":-1.5684644679016042},"translation":{"x":7.652000904941711,"y":1.5410953502743077}},"time":0.489156074954167,"velocity":1.4635634764309065,"position":0.35891049849685014,"holonomicRotation":-90.0,"angularVelocity":-0.05678752464379492,"angularAcceleration":-0.7023500117041034,"curveRadius":-25.165620317375453},{"acceleration":3.017269053223947,"curvature":-0.040804811594159815,"pose":{"rotation":{"radians":-1.568615396366571},"translation":{"x":7.652009163069201,"y":1.537308840493952}},"time":0.49172961220736616,"velocity":1.4713285307423032,"position":0.3626970172824102,"holonomicRotation":-90.0,"angularVelocity":-0.05864631055142644,"angularAcceleration":-0.722268894814279,"curveRadius":-24.506913791096267},{"acceleration":3.0170335568290434,"curvature":-0.041883738544649315,"pose":{"rotation":{"radians":-1.5687694357053292},"translation":{"x":7.652016791347407,"y":1.5335453093410318}},"time":0.49427425326848473,"velocity":1.479005798213783,"position":0.36646055616617745,"holonomicRotation":-90.0,"angularVelocity":-0.060534800413275594,"angularAcceleration":-0.7421439081152827,"curveRadius":-23.87561461195662},{"acceleration":3.0167998963534606,"curvature":-0.04297289989013605,"pose":{"rotation":{"radians":-1.5689265939081762},"translation":{"x":7.652023785936326,"y":1.5298043574555467}},"time":0.4967907101860037,"velocity":1.486597445181732,"position":0.370201514590671,"holonomicRotation":-90.0,"angularVelocity":-0.062452173034599184,"angularAcceleration":-0.7619334183610762,"curveRadius":-23.27047982697437},{"acceleration":3.016567908050338,"curvature":-0.04407162265285752,"pose":{"rotation":{"radians":-1.569086877148501},"translation":{"x":7.652030142995961,"y":1.526085585477497}},"time":0.49927967580122096,"velocity":1.4941055789808373,"position":0.3739202920022586,"holonomicRotation":-90.0,"angularVelocity":-0.0643975309842502,"angularAcceleration":-0.7815929387522689,"curveRadius":-22.690337677756503},{"acceleration":3.016337437732864,"curvature":-0.04517919194869084,"pose":{"rotation":{"radians":-1.569250289726373},"translation":{"x":7.652035858686308,"y":1.5223885940468829}},"time":0.5017418246144845,"velocity":1.5015322506235536,"position":0.3776172878512083,"holonomicRotation":-90.0,"angularVelocity":-0.06636990298543455,"angularAcceleration":-0.8010774940000561,"curveRadius":-22.134083343847344},{"acceleration":3.016108340314846,"curvature":-0.046294860344784014,"pose":{"rotation":{"radians":-1.569416834000303},"translation":{"x":7.652040929167371,"y":1.5187129838037041}},"time":0.5041778136013348,"velocity":1.508879457323708,"position":0.3812929015917336,"holonomicRotation":-90.0,"angularVelocity":-0.06836823763533104,"angularAcceleration":-0.8203381298863105,"curveRadius":-21.60066997831799},{"acceleration":3.015880479343262,"curvature":-0.04741783566896704,"pose":{"rotation":{"radians":-1.5695865103326163},"translation":{"x":7.652045350599149,"y":1.5150583553879604}},"time":0.5065882829820406,"velocity":1.5161491448750333,"position":0.38494753268203813,"holonomicRotation":-90.0,"angularVelocity":-0.07039140744599327,"angularAcceleration":-0.8393260776744922,"curveRadius":-21.08911100416288},{"acceleration":3.015653726559192,"curvature":-0.04854729035922857,"pose":{"rotation":{"radians":-1.569759317028094},"translation":{"x":7.652049119141641,"y":1.5114243094396522}},"time":0.508973856947718,"velocity":1.523343209894611,"position":0.38858158058435416,"holonomicRotation":-90.0,"angularVelocity":-0.07243820479425798,"angularAcceleration":-0.857989472434366,"curveRadius":-20.598471976508687},{"acceleration":3.0154279615370023,"curvature":-0.04968235404557698,"pose":{"rotation":{"radians":-1.5699352502755959},"translation":{"x":7.652052230954847,"y":1.5078104465987794}},"time":0.511335144345977,"velocity":1.5304635019405461,"position":0.39219544476498175,"holonomicRotation":-90.0,"angularVelocity":-0.07450734189819319,"angularAcceleration":-0.8762749953524411,"curveRadius":-20.127870734197348},{"acceleration":3.0152030712896387,"curvature":-0.050822121269766554,"pose":{"rotation":{"radians":-1.5701143040909376},"translation":{"x":7.652054682198768,"y":1.504216367505342}},"time":0.5136727393287943,"velocity":1.537511825512168,"position":0.3957895246943212,"holonomicRotation":-90.0,"angularVelocity":-0.07659745022462014,"angularAcceleration":-0.894127657609852,"curveRadius":-19.676471092025974},{"acceleration":3.0149789500162822,"curvature":-0.051965644209382884,"pose":{"rotation":{"radians":-1.5702964702664204},"translation":{"x":7.652056469033403,"y":1.5006416727993397}},"time":0.5159872219651077,"velocity":1.5444899419408311,"position":0.39936421984690396,"holonomicRotation":-90.0,"angularVelocity":-0.07870708236247381,"angularAcceleration":-0.911491883652228,"curveRadius":-19.243483174590196},{"acceleration":3.014755498791589,"curvature":-0.05311194327893897,"pose":{"rotation":{"radians":-1.570481738312175},"translation":{"x":7.652057587618753,"y":1.497085963120773}},"time":0.5182791588204294,"velocity":1.5513995711782953,"position":0.40291992970141777,"holonomicRotation":-90.0,"angularVelocity":-0.08083470769467545,"angularAcceleration":-0.9283088786942175,"curveRadius":-18.828156875151286},{"acceleration":3.0145326251440543,"curvature":-0.054259999921807966,"pose":{"rotation":{"radians":-1.5706700954102057},"translation":{"x":7.652058034114817,"y":1.4935488391096412}},"time":0.520549103505603,"velocity":1.5582423934890235,"position":0.4064570537407304,"holonomicRotation":-90.0,"angularVelocity":-0.08297871717361793,"angularAcceleration":-0.9445205836716275,"curveRadius":-18.429782555124625},{"acceleration":3.01431024304753,"curvature":-0.05540875694141852,"pose":{"rotation":{"radians":-1.5708615263635899},"translation":{"x":7.652057804681596,"y":1.4900299014059453}},"time":0.5227975971966626,"velocity":1.5650200510534122,"position":0.4099759914519058,"holonomicRotation":-90.0,"angularVelocity":-0.08513742072984373,"angularAcceleration":-0.960066539127578,"curveRadius":-18.04768876257701},{"acceleration":3.014088272396385,"curvature":-0.05655712462720251,"pose":{"rotation":{"radians":-1.5710560135521714},"translation":{"x":7.652056895479089,"y":1.4865287506496845}},"time":0.5250251691276147,"velocity":1.571734149486414,"position":0.41347714232622046,"holonomicRotation":-90.0,"angularVelocity":-0.08730904976809643,"angularAcceleration":-0.9748861565716481,"curveRadius":-17.6812383336586},{"acceleration":3.013866639097659,"curvature":-0.05770397957337466,"pose":{"rotation":{"radians":-1.571253536887692},"translation":{"x":7.652055302667296,"y":1.483044987480859}},"time":0.5272323370578168,"velocity":1.5783862592781366,"position":0.4169609058591709,"holonomicRotation":-90.0,"angularVelocity":-0.08949175675210587,"angularAcceleration":-0.9889174965538435,"curveRadius":-17.32982729082714},{"acceleration":3.0136452746096096,"curvature":-0.058848167872874196,"pose":{"rotation":{"radians":-1.5714540737751443},"translation":{"x":7.652053022406219,"y":1.479578212539469}},"time":0.5294196077155173,"velocity":1.584977917160008,"position":0.42042768155047827,"holonomicRotation":-90.0,"angularVelocity":-0.09168361800412758,"angularAcceleration":-1.002098777444404,"curveRadius":-16.99288246594582},{"acceleration":3.0134241158441464,"curvature":-0.05998849977043034,"pose":{"rotation":{"radians":-1.5716575990757367},"translation":{"x":7.652050050855855,"y":1.476128026465514}},"time":0.5315874772189993,"velocity":1.5915106274018038,"position":0.4238778689040902,"holonomicRotation":-90.0,"angularVelocity":-0.09388263466293037,"angularAcceleration":-1.014367633877748,"curveRadius":-16.669861787290806},{"acceleration":3.013203104981586,"curvature":-0.06112376429819957,"pose":{"rotation":{"radians":-1.5718640850713825},"translation":{"x":7.652046384176206,"y":1.4726940298989948}},"time":0.533736431476669,"velocity":1.5979858630434776,"position":0.42731186742817345,"holonomicRotation":-90.0,"angularVelocity":-0.09608673377244824,"angularAcceleration":-1.0256612497224427,"curveRadius":-16.360248938880478},{"acceleration":3.0129821894601907,"curvature":-0.06225271546779371,"pose":{"rotation":{"radians":-1.5720735014373393},"translation":{"x":7.652042018527271,"y":1.4692758234799106}},"time":0.5358669465673397,"velocity":1.6044050670660444,"position":0.4307300766351061,"holonomicRotation":-90.0,"angularVelocity":-0.09829377265326374,"angularAcceleration":-1.0359179761175845,"curveRadius":-16.06355630409966},{"acceleration":3.0127613213645312,"curvature":-0.0633740854940133,"pose":{"rotation":{"radians":-1.5722858152129122},"translation":{"x":7.652036950069051,"y":1.4658730078482618}},"time":0.5379794891018681,"velocity":1.610769653503809,"position":0.4341328960414605,"holonomicRotation":-90.0,"angularVelocity":-0.10050153883427185,"angularAcceleration":-1.0450753747786439,"curveRadius":-15.77932039894234},{"acceleration":3.0125404578955,"curvature":-0.06448658241776323,"pose":{"rotation":{"radians":-1.572500990780707},"translation":{"x":7.652031174961546,"y":1.4624851836440484}},"time":0.5400745165672258,"velocity":1.6170810085036014,"position":0.4375207251679839,"holonomicRotation":-90.0,"angularVelocity":-0.10270775507856267,"angularAcceleration":-1.0530727070511754,"curveRadius":-15.50710182657383},{"acceleration":3.0123195607777227,"curvature":-0.06558889480643354,"pose":{"rotation":{"radians":-1.572718989848184},"translation":{"x":7.6520246893647546,"y":1.4591119515072706}},"time":0.5421524776540099,"velocity":1.6233404913318559,"position":0.4408939635395724,"holonomicRotation":-90.0,"angularVelocity":-0.10491008174472996,"angularAcceleration":-1.059849811516791,"curveRadius":-15.246483462653364},{"acceleration":3.0120985961507185,"curvature":-0.06667969227412897,"pose":{"rotation":{"radians":-1.5729397714319067},"translation":{"x":7.652017489438678,"y":1.4557529120779278}},"time":0.5442138125683322,"velocity":1.6295494353334827,"position":0.4442530106852396,"holonomicRotation":-90.0,"angularVelocity":-0.10710611952901346,"angularAcceleration":-1.0653473964978724,"curveRadius":-14.99706981083339},{"acceleration":3.011877534792009,"curvature":-0.06775762744819597,"pose":{"rotation":{"radians":-1.573163291849637},"translation":{"x":7.652009571343315,"y":1.4524076659960206}},"time":0.5462589533289616,"velocity":1.6357091488459097,"position":0.4475982661380787,"holonomicRotation":-90.0,"angularVelocity":-0.10929341492443037,"angularAcceleration":-1.0695084844643314,"curveRadius":-14.758486057743818},{"acceleration":3.01165635157231,"curvature":-0.06882134208398606,"pose":{"rotation":{"radians":-1.5733895047138873},"translation":{"x":7.652000931238668,"y":1.4490758139015485}},"time":0.548288324050538,"velocity":1.64182091606924,"position":0.4509301294352213,"holonomicRotation":-90.0,"angularVelocity":-0.11146946284637788,"angularAcceleration":-1.0722771836666607,"curveRadius":-14.530376329767746},{"acceleration":3.0114350255530935,"curvature":-0.06986946356466871,"pose":{"rotation":{"radians":-1.5736183609326124},"translation":{"x":7.651991565284734,"y":1.4457569564345119}},"time":0.5503023412136204,"velocity":1.6478859978962117,"position":0.45424900011778757,"holonomicRotation":-90.0,"angularVelocity":-0.11363171224165843,"angularAcceleration":-1.073600282517557,"curveRadius":-14.312404145974806},{"acceleration":3.0112135399410596,"curvature":-0.07090061653222228,"pose":{"rotation":{"radians":-1.573849808712657},"translation":{"x":7.651981469641516,"y":1.4424506942349105}},"time":0.5523014139222853,"velocity":1.65390563270387,"position":0.45755527773083293,"holonomicRotation":-90.0,"angularVelocity":-0.1157775697908711,"angularAcceleration":-1.0734264641359006,"curveRadius":-14.104249707695121},{"acceleration":3.0109918817209746,"curvature":-0.07191341807731597,"pose":{"rotation":{"radians":-1.5740837935706438},"translation":{"x":7.6519706404690115,"y":1.4391566279427446}},"time":0.5542859441499411,"velocity":1.6598810371083716,"position":0.4608493618232873,"holonomicRotation":-90.0,"angularVelocity":-0.11790440615422164,"angularAcceleration":-1.0717077188906063,"curveRadius":-13.905610757159035},{"acceleration":3.010770041782619,"curvature":-0.07290648527984163,"pose":{"rotation":{"radians":-1.5743202583457778},"translation":{"x":7.651959073927221,"y":1.435874358198014}},"time":0.556256326973989,"velocity":1.6658134066858579,"position":0.4641316519478897,"holonomicRotation":-90.0,"angularVelocity":-0.12000955968966599,"angularAcceleration":-1.0683982370084142,"curveRadius":-13.716200913562572},{"acceleration":3.0105480148882515,"curvature":-0.07387843863662351,"pose":{"rotation":{"radians":-1.5745591432216521},"translation":{"x":7.651946766176145,"y":1.4326034856407186}},"time":0.5582129507999115,"velocity":1.671703916660872,"position":0.4674025476611164,"holonomicRotation":-90.0,"angularVelocity":-0.1220903439431842,"angularAcceleration":-1.0634564630925538,"curveRadius":-13.535748974319462},{"acceleration":3.01032579905976,"curvature":-0.07482790146976435,"pose":{"rotation":{"radians":-1.5748003857498762},"translation":{"x":7.651933713375785,"y":1.4293436109108588}},"time":0.5601561975753444,"velocity":1.6775537225628974,"position":0.4706624485231022,"holonomicRotation":-90.0,"angularVelocity":-0.12414405173545945,"angularAcceleration":-1.0568435353856414,"curveRadius":-13.363998994466911},{"acceleration":3.0101033961694412,"curvature":-0.07575351148724685,"pose":{"rotation":{"radians":-1.5750439208828944},"translation":{"x":7.6519199116861385,"y":1.4260943346484343}},"time":0.5620864429946452,"velocity":1.683363960854975,"position":0.4739117540975585,"holonomicRotation":-90.0,"angularVelocity":-0.1261679631942012,"angularAcceleration":-1.0485254561437733,"curveRadius":-13.200708196455693},{"acceleration":3.0098808113752793,"curvature":-0.07665391081921907,"pose":{"rotation":{"radians":-1.5752896810076429},"translation":{"x":7.651905357267206,"y":1.422855257493445}},"time":0.5640040566944431,"velocity":1.6891357495336272,"position":0.4771508639516826,"holonomicRotation":-90.0,"angularVelocity":-0.12815934970344978,"angularAcceleration":-1.038471152692755,"curveRadius":-13.045648803991286},{"acceleration":3.009658053106687,"curvature":-0.07752776429748295,"pose":{"rotation":{"radians":-1.575537595987929},"translation":{"x":7.651890046278989,"y":1.419625980085891}},"time":0.5659094024406282,"velocity":1.6948701887025857,"position":0.48038017765606295,"holonomicRotation":-90.0,"angularVelocity":-0.13011548207587673,"angularAcceleration":-1.0266548086317537,"curveRadius":-12.898604894149726},{"acceleration":3.0094351330918987,"curvature":-0.07837375621868359,"pose":{"rotation":{"radians":-1.5757875932134553},"translation":{"x":7.651873974881486,"y":1.4164061030657724}},"time":0.5678028383072059,"velocity":1.700568361121721,"position":0.48360009478457816,"holonomicRotation":-90.0,"angularVelocity":-0.13203363786393957,"angularAcceleration":-1.0130555895351072,"curveRadius":-12.759373140286074},{"acceleration":3.009212066123397,"curvature":-0.07919059119886207,"pose":{"rotation":{"radians":-1.5760395976485535},"translation":{"x":7.651857139234697,"y":1.4131952270730892}},"time":0.569684716847422,"velocity":1.7062313327319178,"position":0.4868110149142906,"holonomicRotation":-90.0,"angularVelocity":-0.133911105160526,"angularAcceleration":-0.9976559360578648,"curveRadius":-12.62776277915159},{"acceleration":3.0089888700044534,"curvature":-0.079977003018728,"pose":{"rotation":{"radians":-1.5762935318941125},"translation":{"x":7.651839535498623,"y":1.4099929527478414}},"time":0.5715553852575354,"velocity":1.711860153157418,"position":0.49001333762533406,"holonomicRotation":-90.0,"angularVelocity":-0.13574519363566884,"angularAcceleration":-0.9804455269716323,"curveRadius":-12.503594311552694},{"acceleration":3.0087655654704153,"curvature":-0.08073175678462587,"pose":{"rotation":{"radians":-1.5765493162488928},"translation":{"x":7.651821159833263,"y":1.406798880730029}},"time":0.5734151855335988,"velocity":1.7174558561866902,"position":0.4932074625007969,"holonomicRotation":-90.0,"angularVelocity":-0.13753323841942655,"angularAcceleration":-0.9614176354153259,"curveRadius":-12.386699358813344},{"acceleration":3.0085421760787043,"curvature":-0.08145364978295543,"pose":{"rotation":{"radians":-1.5768068687787018},"translation":{"x":7.651802008398618,"y":1.4036126116596517}},"time":0.5752644546215817,"velocity":1.7230194602328053,"position":0.4963937891265984,"holonomicRotation":-90.0,"angularVelocity":-0.139272608557956,"angularAcceleration":-0.9405716830678744,"curveRadius":-12.276920710915213},{"acceleration":3.0083187279861883,"curvature":-0.08214152290760071,"pose":{"rotation":{"radians":-1.5770661053914319},"translation":{"x":7.651782077354687,"y":1.40043374617671}},"time":0.577103524561155,"velocity":1.7285519687741,"position":0.49957271709136103,"holonomicRotation":-90.0,"angularVelocity":-0.14096071451759784,"angularAcceleration":-0.9179128663445645,"curveRadius":-12.174110785903972},{"acceleration":3.008095250194223,"curvature":-0.08279424829274151,"pose":{"rotation":{"radians":-1.577326939915638},"translation":{"x":7.65176136286147,"y":1.3972618849212035}},"time":0.5789327226234374,"velocity":1.7340543707769163,"position":0.5027446459862785,"holonomicRotation":-90.0,"angularVelocity":-0.1425950144953942,"angularAcceleration":-0.8934516231430433,"curveRadius":-12.078133694314475},{"acceleration":3.0078717739080303,"curvature":-0.08341075258679777,"pose":{"rotation":{"radians":-1.5775892841850263},"translation":{"x":7.651739861078968,"y":1.3940966285331322}},"time":0.5807523714429855,"velocity":1.73952764109966,"position":0.5059099754049768,"holonomicRotation":-90.0,"angularVelocity":-0.14417302205239044,"angularAcceleration":-0.8672044517843471,"curveRadius":-11.988861975072021},{"acceleration":3.0076483329318857,"curvature":-0.08399000851211874,"pose":{"rotation":{"radians":-1.5778530481284534},"translation":{"x":7.651717568167181,"y":1.3909375776524966}},"time":0.582562789144296,"velocity":1.744972740880917,"position":0.509069104943372,"holonomicRotation":-90.0,"angularVelocity":-0.14569231356728019,"angularAcceleration":-0.8391939129792915,"curveRadius":-11.906178100407171},{"acceleration":3.0074249633431296,"curvature":-0.08453103831045278,"pose":{"rotation":{"radians":-1.5781181398646993},"translation":{"x":7.651694480286108,"y":1.387784332919296}},"time":0.5843642894630741,"velocity":1.7503906179110806,"position":0.5122224341995248,"holonomicRotation":-90.0,"angularVelocity":-0.14715053529699532,"angularAcceleration":-0.809448499406464,"curveRadius":-11.829974172650662},{"acceleration":3.007201703217731,"curvature":-0.08503291846932806,"pose":{"rotation":{"radians":-1.5783844657981971},"translation":{"x":7.65167059359575,"y":1.384636494973531}},"time":0.5861571818625038,"velocity":1.7557822069883318,"position":0.5153703627734881,"holonomicRotation":-90.0,"angularVelocity":-0.148545408292523,"angularAcceleration":-0.7780015108387833,"curveRadius":-11.760151456646835},{"acceleration":1.6575700915070826,"curvature":-0.08549478833845872,"pose":{"rotation":{"radians":-1.578651930727025},"translation":{"x":7.651645904256106,"y":1.3814936644552012}},"time":0.5879442110710208,"velocity":1.7587443331570192,"position":0.5185132902671535,"holonomicRotation":-90.0,"angularVelocity":-0.14967014951582938,"angularAcceleration":-0.6293916282654122,"curveRadius":-11.696619401421021},{"acceleration":-1.3473368117363131,"curvature":-0.08591584036306892,"pose":{"rotation":{"radians":-1.5789204379463673},"translation":{"x":7.651620408427176,"y":1.378355442004307}},"time":0.5897310699234678,"velocity":1.7563368324477404,"position":0.5216516162840915,"holonomicRotation":-90.0,"angularVelocity":-0.1502677276241121,"angularAcceleration":-0.33442938565873925,"curveRadius":-11.639297197980408},{"acceleration":-2.997422741669673,"curvature":-0.0862953378109981,"pose":{"rotation":{"radians":-1.5791898893612473},"translation":{"x":7.651594102268961,"y":1.375221428260848}},"time":0.5915210041912473,"velocity":1.7509716427674042,"position":0.5247857404293911,"holonomicRotation":-90.0,"angularVelocity":-0.1505370447006754,"angularAcceleration":-0.15046199260566892,"curveRadius":-11.588111540743661},{"acceleration":-2.997211974618747,"curvature":-0.08663260232949883,"pose":{"rotation":{"radians":-1.5794601856018495},"translation":{"x":7.6515669819414605,"y":1.3720912238648242}},"time":0.593314271575705,"velocity":1.7455968402890143,"position":0.5279160623094938,"holonomicRotation":-90.0,"angularVelocity":-0.15072835369946735,"angularAcceleration":-0.10668180353361928,"curveRadius":-11.54299851453839},{"acceleration":-2.996999714334606,"curvature":-0.0869270302657307,"pose":{"rotation":{"radians":-1.5797312261422407},"translation":{"x":7.651539043604674,"y":1.3689644294562358}},"time":0.5951111330252042,"velocity":1.7402116470381663,"position":0.5310429815320262,"holonomicRotation":-90.0,"angularVelocity":-0.1508410904283788,"angularAcceleration":-0.06274091357619928,"curveRadius":-11.503901570582363},{"acceleration":-2.9967860132304773,"curvature":-0.08717808277241326,"pose":{"rotation":{"radians":-1.5800029094202461},"translation":{"x":7.651510283418602,"y":1.3658406456750827}},"time":0.596911852801114,"velocity":1.7348152751999724,"position":0.5341668977056292,"holonomicRotation":-90.0,"angularVelocity":-0.15087482330122967,"angularAcceleration":-0.018732994051692695,"curveRadius":-11.470773022281252},{"acceleration":-2.996570923377233,"curvature":-0.08738529810373122,"pose":{"rotation":{"radians":-1.580275132963843},"translation":{"x":7.651480697543245,"y":1.3627194731613652}},"time":0.5987166985465389,"velocity":1.7294069269180512,"position":0.5372882104397855,"holonomicRotation":-90.0,"angularVelocity":-0.15082925745142692,"angularAcceleration":0.025246395664704227,"curveRadius":-11.443572565409621},{"acceleration":-2.9963544976416645,"curvature":-0.08754828294382284,"pose":{"rotation":{"radians":-1.580547793516371},"translation":{"x":7.651450282138603,"y":1.3596005125550827}},"time":0.600525941357916,"velocity":1.7239857940828553,"position":0.5404073193446463,"holonomicRotation":-90.0,"angularVelocity":-0.1507042342871119,"angularAcceleration":0.06910247951729687,"curveRadius":-11.422268562841724},{"acceleration":-2.996136788470358,"curvature":-0.08766672198524361,"pose":{"rotation":{"radians":-1.580820787168225},"translation":{"x":7.651419033364674,"y":1.356483364496236}},"time":0.6023398558596061,"velocity":1.7185510581132017,"position":0.5435246240308527,"holonomicRotation":-90.0,"angularVelocity":-0.15049973502036526,"angularAcceleration":0.1127391983228031,"curveRadius":-11.406836908631346},{"acceleration":-2.995917848303332,"curvature":-0.08774037569131486,"pose":{"rotation":{"radians":-1.5810940094841124},"translation":{"x":7.65138694738146,"y":1.3533676296248243}},"time":0.604158720281619,"velocity":1.7131018897276495,"position":0.5466405241093613,"holonomicRotation":-90.0,"angularVelocity":-0.1502158778745496,"angularAcceleration":0.15606283919806035,"curveRadius":-11.397261433187444},{"acceleration":-2.9956977295394536,"curvature":-0.08776908061788026,"pose":{"rotation":{"radians":-1.5813673556381165},"translation":{"x":7.651354020348961,"y":1.350252908580848}},"time":0.6059828165406126,"velocity":1.707637448706121,"position":0.5497554191912635,"holonomicRotation":-90.0,"angularVelocity":-0.14985292177228993,"angularAcceleration":0.19897859034035972,"curveRadius":-11.393533952505372},{"acceleration":-2.9954764840526003,"curvature":-0.08775275098604564,"pose":{"rotation":{"radians":-1.5816407205481982},"translation":{"x":7.651320248427176,"y":1.347138802004307}},"time":0.6078124303243202,"velocity":1.7021568836421264,"position":0.5528697088876079,"holonomicRotation":-90.0,"angularVelocity":-0.1494112651073915,"angularAcceleration":0.241393385222227,"curveRadius":-11.395654139196377},{"acceleration":-2.9952541634965417,"curvature":-0.08769137889070983,"pose":{"rotation":{"radians":-1.5819139990069466},"translation":{"x":7.651285627776105,"y":1.3440249105352013}},"time":0.6096478511795621,"velocity":1.6966593316836946,"position":0.555983792809221,"holonomicRotation":-90.0,"angularVelocity":-0.1488914425092186,"angularAcceleration":0.28321711431375796,"curveRadius":-11.403629554580327},{"acceleration":-2.9950308187132038,"curvature":-0.08758503707322117,"pose":{"rotation":{"radians":-1.5821870858204727},"translation":{"x":7.65125015455575,"y":1.340910834813531}},"time":0.6114893726040095,"velocity":1.6911439182641541,"position":0.5590980705665283,"holonomicRotation":-90.0,"angularVelocity":-0.14829412783403473,"angularAcceleration":0.3243593407354012,"curveRadius":-11.417475329307665},{"acceleration":-2.9948065000048465,"curvature":-0.08743387246485756,"pose":{"rotation":{"radians":-1.5824598759408364},"translation":{"x":7.651213824926109,"y":1.3377961754792962}},"time":0.6133372921418758,"velocity":1.685609756820666,"position":0.5622129417693753,"holonomicRotation":-90.0,"angularVelocity":-0.14762012889295067,"angularAcceleration":0.36473392226929524,"curveRadius":-11.437215026726989},{"acceleration":-2.9945812567724746,"curvature":-0.08723810751863305,"pose":{"rotation":{"radians":-1.5827322646030169},"translation":{"x":7.651176635047181,"y":1.3346805331724967}},"time":0.615191911483723,"velocity":1.6800559485011228,"position":0.5653288060268509,"holonomicRotation":-90.0,"angularVelocity":-0.1468703879197096,"angularAcceleration":0.40425598737385265,"curveRadius":-11.462880482436091},{"acceleration":-2.994355137608174,"curvature":-0.08699805069663781,"pose":{"rotation":{"radians":-1.5830041474541385},"translation":{"x":7.6511385810789685,"y":1.3315635085331323}},"time":0.6170535365705752,"velocity":1.6744815818580068,"position":0.5684460629471096,"holonomicRotation":-90.0,"angularVelocity":-0.1460459751224142,"angularAcceleration":0.44284577121239604,"curveRadius":-11.494510417101182},{"acceleration":-2.994128189761771,"curvature":-0.08671407800863583,"pose":{"rotation":{"radians":-1.5832754206942212},"translation":{"x":7.651099659181471,"y":1.3284447022012036}},"time":0.6189224777025478,"velocity":1.6688857325297621,"position":0.5715651121371969,"holonomicRotation":-90.0,"angularVelocity":-0.1451480923833932,"angularAcceleration":0.48042323198980824,"curveRadius":-11.532152828753023},{"acceleration":-2.9939004595430343,"curvature":-0.08638663941913151,"pose":{"rotation":{"radians":-1.5835459812010253},"translation":{"x":7.651059865514687,"y":1.32532371481671}},"time":0.6207990496522111,"velocity":1.6632674629072997,"position":0.5746863532028763,"holonomicRotation":-90.0,"angularVelocity":-0.14417806194567745,"angularAcceleration":0.516916198118498,"curveRadius":-11.575864123480839},{"acceleration":-2.993671991719282,"curvature":-0.08601626393483194,"pose":{"rotation":{"radians":-1.5838157266626176},"translation":{"x":7.651019196238618,"y":1.3222001470196518}},"time":0.6226835717829139,"velocity":1.6576258217868396,"position":0.577810185748458,"holonomicRotation":-90.0,"angularVelocity":-0.14313732760024078,"angularAcceleration":0.5522537138094278,"curveRadius":-11.625708374844375},{"acceleration":-2.9934428298585805,"curvature":-0.08560354485070047,"pose":{"rotation":{"radians":-1.584084555707002},"translation":{"x":7.650977647513263,"y":1.3190735994500289}},"time":0.6245763681723153,"velocity":1.6519598440066037,"position":0.5809370093766298,"holonomicRotation":-90.0,"angularVelocity":-0.1420274499094033,"angularAcceleration":0.5863692983842086,"curveRadius":-11.681759227892737},{"acceleration":-2.993213015447922,"curvature":-0.085149152654037,"pose":{"rotation":{"radians":-1.584352368023695},"translation":{"x":7.650935215498622,"y":1.3159436727478415}},"time":0.6264777677413775,"velocity":1.6462685500689196,"position":0.5840672236882916,"holonomicRotation":-90.0,"angularVelocity":-0.1408500985540491,"angularAcceleration":0.6192024940527845,"curveRadius":-11.74409807767581},{"acceleration":-2.9929825886695602,"curvature":-0.08465381880959416,"pose":{"rotation":{"radians":-1.584619064490255},"translation":{"x":7.650891896354697,"y":1.3128099675530893}},"time":0.6283881043890945,"velocity":1.6405509457438052,"position":0.5872012282823927,"holonomicRotation":-90.0,"angularVelocity":-0.13960705139514515,"angularAcceleration":0.6506953423049691,"curveRadius":-11.812816173706578},{"acceleration":-2.992751587695135,"curvature":-0.08411833930219012,"pose":{"rotation":{"radians":-1.5848845472909812},"translation":{"x":7.650847686241486,"y":1.3096720845057725}},"time":0.6303077171332416,"velocity":1.6348060216559992,"position":0.590339422755772,"holonomicRotation":-90.0,"angularVelocity":-0.13830018660571247,"angularAcceleration":0.6807960581723128,"curveRadius":-11.888014056097322},{"acceleration":-2.992520048553784,"curvature":-0.08354357953444298,"pose":{"rotation":{"radians":-1.585148720032274},"translation":{"x":7.650802581318988,"y":1.3065296242458908}},"time":0.6322369502574532,"velocity":1.629032752853462,"position":0.5934822067030024,"holonomicRotation":-90.0,"angularVelocity":-0.13693147706077752,"angularAcceleration":0.7094578295167511,"curveRadius":-11.969800738400542},{"acceleration":-2.992288005291093,"curvature":-0.08293045520405007,"pose":{"rotation":{"radians":-1.585411487856132},"translation":{"x":7.650756577747206,"y":1.3033821874134448}},"time":0.6341761534649492,"velocity":1.6232300983558499,"position":0.5966299797162381,"holonomicRotation":-90.0,"angularVelocity":-0.13550298537167677,"angularAcceleration":0.7366384727391829,"curveRadius":-12.05829628620154},{"acceleration":-2.9920554894901885,"curvature":-0.08227994643262679,"pose":{"rotation":{"radians":-1.5856727575508778},"translation":{"x":7.650709671686138,"y":1.3002293746484341}},"time":0.636125682039256,"velocity":1.617397000683177,"position":0.5997831413850682,"holonomicRotation":-90.0,"angularVelocity":-0.13401685832617588,"angularAcceleration":0.762300724947962,"curveRadius":-12.153629691760058},{"acceleration":-2.9918225305242885,"curvature":-0.08159307983252262,"pose":{"rotation":{"radians":-1.5859324376532715},"translation":{"x":7.650661859295784,"y":1.2970707865908586}},"time":0.6380858970122827,"velocity":1.6115323853622048,"position":0.6029420912963726,"holonomicRotation":-90.0,"angularVelocity":-0.13247531825184702,"angularAcceleration":0.7864137839681112,"curveRadius":-12.255941337826602},{"acceleration":-2.991589155055511,"curvature":-0.08087093996973242,"pose":{"rotation":{"radians":-1.5861904385510757},"translation":{"x":7.650613136736146,"y":1.2939060238807187}},"time":0.6400571653401388,"velocity":1.605635160410886,"position":0.6061072290341827,"holonomicRotation":-90.0,"angularVelocity":-0.13088065899417137,"angularAcceleration":0.8089508846367787,"curveRadius":-12.365381190997287},{"acceleration":-2.9913553870685297,"curvature":-0.08011464857243006,"pose":{"rotation":{"radians":-1.5864466725790534},"translation":{"x":7.650563500167221,"y":1.2907346871580139}},"time":0.6420398600871069,"velocity":1.5997042157986305,"position":0.6092789541795494,"holonomicRotation":-90.0,"angularVelocity":-0.12923523823802185,"angularAcceleration":0.8298911159499741,"curveRadius":-12.482111796270566},{"acceleration":-2.9911212476993967,"curvature":-0.07932538274732635,"pose":{"rotation":{"radians":-1.5867010541088469},"translation":{"x":7.650512945749011,"y":1.2875563770627445}},"time":0.6440343606182011,"velocity":1.593738422881527,"position":0.6124576663104118,"holonomicRotation":-90.0,"angularVelocity":-0.1275414700711859,"angularAcceleration":0.8492192107398179,"curveRadius":-12.606305388847364},{"acceleration":-2.99088675515021,"curvature":-0.07850434864259706,"pose":{"rotation":{"radians":-1.5869534996355714},"translation":{"x":7.650461469641516,"y":1.2843706942349105}},"time":0.6460410528007808,"velocity":1.5877366338109857,"position":0.6156437650014758,"holonomicRotation":-90.0,"angularVelocity":-0.12580181899149287,"angularAcceleration":0.8669247305566217,"curveRadius":-12.738147851562358},{"acceleration":-2.9906519244163023,"curvature":-0.07765279562236496,"pose":{"rotation":{"radians":-1.587203927862138},"translation":{"x":7.650409068004734,"y":1.2811772393145118}},"time":0.6480603292157098,"velocity":1.58169768091475,"position":0.6188376498240947,"holonomicRotation":-90.0,"angularVelocity":-0.12401879441320839,"angularAcceleration":0.883001735226641,"curveRadius":-12.87783642540215},{"acceleration":-2.9904167673557027,"curvature":-0.07677200335444062,"pose":{"rotation":{"radians":-1.5874522597693943},"translation":{"x":7.650355736998668,"y":1.2779756129415483}},"time":0.6500925893785887,"velocity":1.5756203760480478,"position":0.6220397203461575,"holonomicRotation":-90.0,"angularVelocity":-0.12219493930569386,"angularAcceleration":0.8974515865777808,"curveRadius":-13.025581674392482},{"acceleration":-2.9901812923148996,"curvature":-0.0758632810677462,"pose":{"rotation":{"radians":-1.587698418692944},"translation":{"x":7.650301472783315,"y":1.2747654157560204}},"time":0.6521382399716216,"velocity":1.569503509914148,"position":0.6252503761319805,"holonomicRotation":-90.0,"angularVelocity":-0.12033282926615047,"angularAcceleration":0.9102776622192631,"curveRadius":-13.18160756989928},{"acceleration":-2.989945504064058,"curvature":-0.07492796270930376,"pose":{"rotation":{"radians":-1.587942330383914},"translation":{"x":7.650246271518678,"y":1.2715462483979276}},"time":0.6541976950867155,"velocity":1.5633458513519511,"position":0.6284700167422083,"holonomicRotation":-90.0,"angularVelocity":-0.11843506041107103,"angularAcceleration":0.9214907580021876,"curveRadius":-13.346152275348475},{"acceleration":-2.989709403762669,"curvature":-0.07396740483163587,"pose":{"rotation":{"radians":-1.588183923071492},"translation":{"x":7.650190129364754,"y":1.2683177115072704}},"time":0.656271376480451,"velocity":1.5571461465886927,"position":0.631699041733716,"holonomicRotation":-90.0,"angularVelocity":-0.11650424617200698,"angularAcceleration":0.9311045780210122,"curveRadius":-13.51946850475819},{"acceleration":-2.9894729886006064,"curvature":-0.07298298032638396,"pose":{"rotation":{"radians":-1.5884231275143161},"translation":{"x":7.650133042481546,"y":1.2650794057240484}},"time":0.6583597138416073,"velocity":1.5509031184564304,"position":0.6349378506595225,"holonomicRotation":-90.0,"angularVelocity":-0.11454300788434628,"angularAcceleration":0.9391386296775142,"curveRadius":-13.701824665530841},{"acceleration":-2.9892362519747264,"curvature":-0.07197607767606651,"pose":{"rotation":{"radians":-1.5886598770532032},"translation":{"x":7.650075007029051,"y":1.2618309316882619}},"time":0.6604631450719721,"velocity":1.544615465569088,"position":0.638186843068705,"holonomicRotation":-90.0,"angularVelocity":-0.11255397156293977,"angularAcceleration":0.9456150943720304,"curveRadius":-13.893505068455822},{"acceleration":-2.98899918274633,"curvature":-0.07094809746147339,"pose":{"rotation":{"radians":-1.5888941076494572},"translation":{"x":7.650016019167271,"y":1.2585718900399105}},"time":0.6625821165812152,"velocity":1.5382818614596976,"position":0.6414464185063236,"holonomicRotation":-90.0,"angularVelocity":-0.11053975725119716,"angularAcceleration":0.9505622435018338,"curveRadius":-14.094810654267725},{"acceleration":-2.988761765793549,"curvature":-0.06990044604535059,"pose":{"rotation":{"radians":-1.5891257579252756},"translation":{"x":7.649956075056206,"y":1.2553018814189945}},"time":0.6647170835966637,"velocity":1.5319009536726949,"position":0.6447169765133488,"holonomicRotation":-90.0,"angularVelocity":-0.10850297645921063,"angularAcceleration":0.9540104260386876,"curveRadius":-14.306060355483451},{"acceleration":-2.9885239813715057,"curvature":-0.06883452917484968,"pose":{"rotation":{"radians":-1.589354769195281},"translation":{"x":7.649895170855855,"y":1.2520205064655139}},"time":0.666868510488874,"velocity":1.525471362811157,"position":0.6479989166265974,"holonomicRotation":-90.0,"angularVelocity":-0.10644622451945558,"angularAcceleration":0.9559943436618704,"curveRadius":-14.527592648449081},{"acceleration":-2.98828580495456,"curvature":-0.06775175974373031,"pose":{"rotation":{"radians":-1.5895810854909183},"translation":{"x":7.649833302726218,"y":1.2487273658194686}},"time":0.6690368711139614,"velocity":1.5189916815351858,"position":0.6512926383786736,"holonomicRotation":-90.0,"angularVelocity":-0.10437207400783428,"angularAcceleration":0.956552377692105,"curveRadius":-14.759764230220444},{"acceleration":-2.988047207292239,"curvature":-0.06665354296781921,"pose":{"rotation":{"radians":-1.5898046535842587},"translation":{"x":7.649770466827296,"y":1.2454220601208588}},"time":0.6712226491737178,"velocity":1.51246047350797,"position":0.6545985412979161,"holonomicRotation":-90.0,"angularVelocity":-0.10228307139535045,"angularAcceleration":0.9557249434174734,"curveRadius":-15.002953413636346},{"acceleration":-2.9878081541634707,"curvature":-0.06554127993120595,"pose":{"rotation":{"radians":-1.590025423000471},"translation":{"x":7.649706659319088,"y":1.2421041900096843}},"time":0.673426338594626,"velocity":1.5058762722869368,"position":0.6579170249083515,"holonomicRotation":-90.0,"angularVelocity":-0.10018172893038609,"angularAcceleration":0.953556542508762,"curveRadius":-15.257559831752284},{"acceleration":-2.9875686058857056,"curvature":-0.06441635686670999,"pose":{"rotation":{"radians":-1.5902433460298626},"translation":{"x":7.649641876361596,"y":1.238773356125945}},"time":0.6756484439269599,"velocity":1.4992375801570847,"position":0.6612484887296539,"holonomicRotation":-90.0,"angularVelocity":-0.09807052177982581,"angularAcceleration":0.9500931930813749,"curveRadius":-15.524007389446053},{"acceleration":-2.9873285175837,"curvature":-0.06328015748393476,"pose":{"rotation":{"radians":-1.590458377732845},"translation":{"x":7.649576114114817,"y":1.2354291591096414}},"time":0.6778894807652521,"velocity":1.4925428669010987,"position":0.6645933322771096,"holonomicRotation":-90.0,"angularVelocity":-0.09595188231987216,"angularAcceleration":0.9453835937690946,"curveRadius":-15.802741961473073},{"acceleration":-2.987087838517806,"curvature":-0.06213404213887893,"pose":{"rotation":{"radians":-1.5906704759382402},"translation":{"x":7.6495093687387525,"y":1.2320711996007727}},"time":0.6801499761915092,"velocity":1.4857905685043011,"position":0.6679519550615894,"holonomicRotation":-90.0,"angularVelocity":-0.09382819488665974,"angularAcceleration":0.9394787569771098,"curveRadius":-16.094237000786936},{"acceleration":-2.9868465122723213,"curvature":-0.06097935437689598,"pose":{"rotation":{"radians":-1.5908796012401556},"translation":{"x":7.649441636393402,"y":1.2286990782393397}},"time":0.6824304692426583,"velocity":1.4789790857882152,"position":0.6713247565895243,"holonomicRotation":-90.0,"angularVelocity":-0.09170179308813993,"angularAcceleration":0.932430729156736,"curveRadius":-16.398992908637332},{"acceleration":-2.9866044761805592,"curvature":-0.05981741891213621,"pose":{"rotation":{"radians":-1.591085716986596},"translation":{"x":7.649372913238768,"y":1.2253123956653416}},"time":0.6847315114038335,"velocity":1.4721067829697692,"position":0.6747121363628897,"holonomicRotation":-90.0,"angularVelocity":-0.08957495430465769,"angularAcceleration":0.9242937045516799,"curveRadius":-16.71753843924403},{"acceleration":-2.9863616613045134,"curvature":-0.05864953516147047,"pose":{"rotation":{"radians":-1.5912887892674599},"translation":{"x":7.649303195434847,"y":1.2219107525187791}},"time":0.687053667129228,"velocity":1.4651719861398722,"position":0.6781144938791921,"holonomicRotation":-90.0,"angularVelocity":-0.08744989780106749,"angularAcceleration":0.9151223065495181,"curveRadius":-17.050433515744984},{"acceleration":-2.9861179919000813,"curvature":-0.057476981141426166,"pose":{"rotation":{"radians":-1.591488786892012},"translation":{"x":7.649232479141641,"y":1.2184937494396522}},"time":0.6893975143923888,"velocity":1.4581729816570819,"position":0.6815322286314641,"holonomicRotation":-90.0,"angularVelocity":-0.08532877875430724,"angularAcceleration":0.9049732378464715,"curveRadius":-17.398269361771618},{"acceleration":-2.9858733855516615,"curvature":-0.056301004011251245,"pose":{"rotation":{"radians":-1.5916856813694658},"translation":{"x":7.649160760519149,"y":1.2150609870679603}},"time":0.6917636452679761,"velocity":1.451108014448934,"position":0.6849657401082638,"holonomicRotation":-90.0,"angularVelocity":-0.0832136884249398,"angularAcceleration":0.8939025102922529,"curveRadius":-17.761672594686928},{"acceleration":-2.98562775236765,"curvature":-0.055122819459737314,"pose":{"rotation":{"radians":-1.5918794468799673},"translation":{"x":7.649088035727371,"y":1.2116120660437035}},"time":0.6941526665471786,"velocity":1.44397528621675,"position":0.6884154277936781,"holonomicRotation":-90.0,"angularVelocity":-0.08110664906518793,"angularAcceleration":0.8819675982355645,"curveRadius":-18.141307171894894},{"acceleration":-2.9853809950348142,"curvature":-0.05394361728140373,"pose":{"rotation":{"radians":-1.5920700602427722},"translation":{"x":7.649014300926308,"y":1.2081465870068826}},"time":0.6965652003891648,"velocity":1.436772953535006,"position":0.6918816911673319,"holonomicRotation":-90.0,"angularVelocity":-0.07900961200526427,"angularAcceleration":0.8692259662551124,"curveRadius":-18.53787436581001},{"acceleration":-2.985133008337203,"curvature":-0.05276455338153593,"pose":{"rotation":{"radians":-1.5922575008835356},"translation":{"x":7.6489395522759605,"y":1.2046641505974969}},"time":0.6990018850111492,"velocity":1.4294991258390126,"position":0.695364929704404,"holonomicRotation":-90.0,"angularVelocity":-0.0769244567278956,"angularAcceleration":0.8557345741651741,"curveRadius":-18.9521172058273},{"acceleration":-2.9848836786148016,"curvature":-0.0515867461808539,"pose":{"rotation":{"radians":-1.59244175079583},"translation":{"x":7.648863785936325,"y":1.2011643574555464}},"time":0.7014633754198707,"velocity":1.422151863292953,"position":0.698865542875645,"holonomicRotation":-90.0,"angularVelocity":-0.07485298810897224,"angularAcceleration":0.8415505547305013,"curveRadius":-19.384824088229543},{"acceleration":-2.984632883657643,"curvature":-0.0504112807664606,"pose":{"rotation":{"radians":-1.5926227944960578},"translation":{"x":7.648786998067406,"y":1.1976468082210314}},"time":0.7039503441875349,"velocity":1.414729174528353,"position":0.7023839301474003,"holonomicRotation":-90.0,"angularVelocity":-0.07279693359314177,"angularAcceleration":0.8267311365399918,"curveRadius":-19.836829868153547},{"acceleration":-2.9843804919791403,"curvature":-0.04923920698229567,"pose":{"rotation":{"radians":-1.592800618984457},"translation":{"x":7.648709184829202,"y":1.1941111035339516}},"time":0.7064634822755365,"velocity":1.4072290142448713,"position":0.70592049098164,"holonomicRotation":-90.0,"angularVelocity":-0.07075794571264782,"angularAcceleration":0.8113314147872119,"curveRadius":-20.309019200076833},{"acceleration":-2.9841263625540484,"curvature":-0.04807153271481904,"pose":{"rotation":{"radians":-1.5929752136943547},"translation":{"x":7.648630342381711,"y":1.1905568440343073}},"time":0.709003499909574,"velocity":1.3996492806617877,"position":0.7094756248359889,"holonomicRotation":-90.0,"angularVelocity":-0.06873759754972136,"angularAcceleration":0.7954071404279816,"curveRadius":-20.80233234776243},{"acceleration":-2.983870344068185,"curvature":-0.04690922975561617,"pose":{"rotation":{"radians":-1.5931465704413164},"translation":{"x":7.6485504668849345,"y":1.1869836303620982}},"time":0.7115711275101066,"velocity":1.3919878128099474,"position":0.7130497311637648,"holonomicRotation":-90.0,"angularVelocity":-0.06673738314938021,"angularAcceleration":0.7790126574142666,"curveRadius":-21.317766358768143},{"acceleration":-2.983612274586198,"curvature":-0.04575323028472149,"pose":{"rotation":{"radians":-1.5933146833724026},"translation":{"x":7.648469554498873,"y":1.1833910631573246}},"time":0.7141671166824588,"velocity":1.3842423876506247,"position":0.7166432094140167,"holonomicRotation":-90.0,"angularVelocity":-0.06475871813204974,"angularAcceleration":0.7622007974469561,"curveRadius":-21.85638027691201},{"acceleration":-2.9833519807341187,"curvature":-0.04460442975709628,"pose":{"rotation":{"radians":-1.5934795489118665},"translation":{"x":7.648387601383526,"y":1.1797787430599862}},"time":0.7167922412712919,"velocity":1.3764107170088555,"position":0.7202564590315701,"holonomicRotation":-90.0,"angularVelocity":-0.06280293901677826,"angularAcceleration":0.7450233499739625,"curveRadius":-22.419297936230343},{"acceleration":-2.9830892771341855,"curvature":-0.04346367678270848,"pose":{"rotation":{"radians":-1.5936411657024063},"translation":{"x":7.648304603698892,"y":1.1761462707100834}},"time":0.7194472984846045,"velocity":1.368490444305645,"position":0.7238898794570732,"holonomicRotation":-90.0,"angularVelocity":-0.060871302407148026,"angularAcceleration":0.727531067859819,"curveRadius":-23.0077175706828},{"acceleration":-2.982823965627233,"curvature":-0.04233178912354648,"pose":{"rotation":{"radians":-1.5937995345470686},"translation":{"x":7.648220557604975,"y":1.1724932467476155}},"time":0.7221331100929274,"velocity":1.3604791410731798,"position":0.7275438701270486,"holonomicRotation":-90.0,"angularVelocity":-0.0589649862899892,"angularAcceleration":0.7097728341226583,"curveRadius":-23.622908946311547},{"acceleration":-2.9825558344392773,"curvature":-0.04120953362601409,"pose":{"rotation":{"radians":-1.5939546583517403},"translation":{"x":7.648135459261771,"y":1.1688192718125832}},"time":0.7248505237099305,"velocity":1.3523743032352022,"position":0.7312188304739451,"holonomicRotation":-90.0,"angularVelocity":-0.05708509139025625,"angularAcceleration":0.6917956427281566,"curveRadius":-24.266229486487955},{"acceleration":-2.982284657379353,"curvature":-0.040097642362608536,"pose":{"rotation":{"radians":-1.5941065420586273},"translation":{"x":7.648049304829281,"y":1.1651239465449863}},"time":0.7276004141612892,"velocity":1.3441733471326414,"position":0.7349151599261959,"holonomicRotation":-90.0,"angularVelocity":-0.05523263910821279,"angularAcceleration":0.673645846920268,"curveRadius":-24.939122129846474},{"acceleration":-2.9820101927416753,"curvature":-0.038996805722760944,"pose":{"rotation":{"radians":-1.5942551925875712},"translation":{"x":7.647962090467507,"y":1.1614068715848247}},"time":0.7303836849493368,"velocity":1.3358736052735232,"position":0.7386332579082776,"holonomicRotation":-90.0,"angularVelocity":-0.053408575831794765,"angularAcceleration":0.6553668023432049,"curveRadius":-25.643125929576797},{"acceleration":-2.981732182355507,"curvature":-0.037907673753438655,"pose":{"rotation":{"radians":-1.5944006187711857},"translation":{"x":7.647873812336446,"y":1.1576676475720984}},"time":0.7332012698218189,"velocity":1.3274723217827253,"position":0.7423735238407713,"holonomicRotation":-90.0,"angularVelocity":-0.05161377214747465,"angularAcceleration":0.6370007526123006,"curveRadius":-26.379883041736072},{"acceleration":-2.9814503503345575,"curvature":-0.03683085582430425,"pose":{"rotation":{"radians":-1.5945428312877592},"translation":{"x":7.6477844665961,"y":1.1539058751468076}},"time":0.736054134453926,"velocity":1.3189666475258726,"position":0.7461363571404267,"holonomicRotation":-90.0,"angularVelocity":-0.04984902367011356,"angularAcceleration":0.6185882279516588,"curveRadius":-27.15114752614876},{"acceleration":-2.9811644018702674,"curvature":-0.03576692202813053,"pose":{"rotation":{"radians":-1.5946818425996634},"translation":{"x":7.64769404940647,"y":1.1501211549489518}},"time":0.7389432782537644,"velocity":1.3103536348779101,"position":0.7499221572202299,"holonomicRotation":-90.0,"angularVelocity":-0.048115054678817555,"angularAcceleration":0.6001670776625908,"curveRadius":-27.95879386024619},{"acceleration":-2.980874021616788,"curvature":-0.03471640644489967,"pose":{"rotation":{"radians":-1.5948176668853389},"translation":{"x":7.647602556927552,"y":1.1463130876185317}},"time":0.7418697363025138,"velocity":1.3016302321050415,"position":0.7537313234894694,"holonomicRotation":-90.0,"angularVelocity":-0.04641251759393241,"angularAcceleration":0.5817739590057238,"curveRadius":-28.804824646443617},{"acceleration":-2.9805788723977242,"curvature":-0.03367979610910361,"pose":{"rotation":{"radians":-1.594950319971888},"translation":{"x":7.647509985319349,"y":1.1424812737955468}},"time":0.7448345814417735,"velocity":1.292793277323033,"position":0.7575642553538081,"holonomicRotation":-90.0,"angularVelocity":-0.04474199505145433,"angularAcceleration":0.5634434393747889,"curveRadius":-29.69139114621009},{"acceleration":-2.9802785932314158,"curvature":-0.032657552168952726,"pose":{"rotation":{"radians":-1.5950798192712776},"translation":{"x":7.647416330741861,"y":1.1386253141199973}},"time":0.7478389265219796,"velocity":1.2838394919938148,"position":0.761421352215354,"holonomicRotation":-90.0,"angularVelocity":-0.04310400301312061,"angularAcceleration":0.5452076890652514,"curveRadius":-30.620788564511336},{"acceleration":-2.97997279747532,"curvature":-0.03165008427455536,"pose":{"rotation":{"radians":-1.595206183712948},"translation":{"x":7.647321589355087,"y":1.134744809231883}},"time":0.7508839268273751,"velocity":1.274765473915432,"position":0.7653030134727342,"holonomicRotation":-90.0,"angularVelocity":-0.041498991460380975,"angularAcceleration":0.5270973371975197,"curveRadius":-31.595492489855264},{"acceleration":-2.9796610707668423,"curvature":-0.03065778504501439,"pose":{"rotation":{"radians":-1.5953294336763815},"translation":{"x":7.647225757319028,"y":1.130839359771204}},"time":0.7539707826947964,"velocity":1.2655676896562085,"position":0.7692096385211683,"holonomicRotation":-90.0,"angularVelocity":-0.03992734637666811,"angularAcceleration":0.5091410649586915,"curveRadius":-32.61814245653149},{"acceleration":-2.979342968509102,"curvature":-0.029680987149809976,"pose":{"rotation":{"radians":-1.595449590926421},"translation":{"x":7.647128830793683,"y":1.1269085663779606}},"time":0.7571007423455877,"velocity":1.2562424663789065,"position":0.7731416267525447,"holonomicRotation":-90.0,"angularVelocity":-0.038389392658521974,"angularAcceleration":0.4913653496323377,"curveRadius":-33.69160179722669},{"acceleration":-2.9790180133423334,"curvature":-0.02872001149846278,"pose":{"rotation":{"radians":-1.5955666785473746},"translation":{"x":7.647030805939053,"y":1.1229520296921525}},"time":0.7602751049522738,"velocity":1.2467859829927082,"position":0.7770993775554972,"holonomicRotation":-90.0,"angularVelocity":-0.036885395734849544,"angularAcceleration":0.47379493461288114,"curveRadius":-34.81892756392261},{"acceleration":-2.978685692146752,"curvature":-0.02777512732802341,"pose":{"rotation":{"radians":-1.5956807208776267},"translation":{"x":7.646931678915137,"y":1.1189693503537796}},"time":0.7634952239642767,"velocity":1.2371942605646453,"position":0.7810832903154823,"holonomicRotation":-90.0,"angularVelocity":-0.03541556378104339,"angularAcceleration":0.45645268026659636,"curveRadius":-36.00343531066592},{"acceleration":-2.9783454526976496,"curvature":-0.026846592218145386,"pose":{"rotation":{"radians":-1.5957917434439866},"translation":{"x":7.646831445881936,"y":1.1149601290028421}},"time":0.7667625107199927,"velocity":1.2274631519130994,"position":0.7850937644148573,"holonomicRotation":-90.0,"angularVelocity":-0.033980049705045055,"angularAcceleration":0.4393596838376566,"curveRadius":-37.24867543241143},{"acceleration":-2.9779967001601046,"curvature":-0.025934604907596383,"pose":{"rotation":{"radians":-1.595899772901217},"translation":{"x":7.646730102999449,"y":1.1109239662793402}},"time":0.7700784383760353,"velocity":1.217588330295435,"position":0.7891311992329587,"holonomicRotation":-90.0,"angularVelocity":-0.03257895480125084,"angularAcceleration":0.42253482256797953,"curveRadius":-38.558520693218455},{"acceleration":-2.977638792704398,"curvature":-0.025039355982222105,"pose":{"rotation":{"radians":-1.596004836964151},"translation":{"x":7.646627646427676,"y":1.1068604628232732}},"time":0.7734445461884507,"velocity":1.2075652770927614,"position":0.7931959941461822,"holonomicRotation":-90.0,"angularVelocity":-0.0312123285375995,"angularAcceleration":0.4059959870003942,"curveRadius":-39.93712940181042},{"acceleration":-2.977271037121269,"curvature":-0.024160995973067517,"pose":{"rotation":{"radians":-1.5961069643500725},"translation":{"x":7.64652407232662,"y":1.1027692192746417}},"time":0.7768624441853311,"velocity":1.1973892683788145,"position":0.7972885485280603,"holonomicRotation":-90.0,"angularVelocity":-0.02988017372508691,"angularAcceleration":0.3897585047091737,"curveRadius":-41.38902225366492},{"acceleration":-2.9768926834199285,"curvature":-0.023299655174802442,"pose":{"rotation":{"radians":-1.5962061847162632},"translation":{"x":7.646419376856276,"y":1.0986498362734456}},"time":0.7803338182756023,"velocity":1.1870553602480727,"position":0.801409261749343,"holonomicRotation":-90.0,"angularVelocity":-0.028582447068661535,"angularAcceleration":0.37383659112463674,"curveRadius":-42.91909011088955},{"acceleration":-2.976502919020916,"curvature":-0.022455418181532117,"pose":{"rotation":{"radians":-1.5963025285976613},"translation":{"x":7.646313556176646,"y":1.094501914459685}},"time":0.7838604358449502,"velocity":1.1765583727586382,"position":0.805558533178077,"holonomicRotation":-90.0,"angularVelocity":-0.027319061254474024,"angularAcceleration":0.35824293089457876,"curveRadius":-44.532682131140376},{"acceleration":-2.9761008620890164,"curvature":-0.021628369786517186,"pose":{"rotation":{"radians":-1.5963960273510462},"translation":{"x":7.646206606447732,"y":1.0903250544733596}},"time":0.7874441518970701,"velocity":1.1658928723264421,"position":0.8097367621796854,"holonomicRotation":-90.0,"angularVelocity":-0.026089888826328535,"angularAcceleration":0.34298823072726814,"curveRadius":-46.23556975724475},{"acceleration":-2.9756855539811653,"curvature":-0.020818548066409873,"pose":{"rotation":{"radians":-1.5964867130971703},"translation":{"x":7.646098523829532,"y":1.0861188569544695}},"time":0.7910869158068327,"velocity":1.1550531523835976,"position":0.8139443481170459,"holonomicRotation":-90.0,"angularVelocity":-0.024894763528592472,"angularAcceleration":0.3280820078768027,"curveRadius":-48.03408944802789},{"acceleration":-2.975255950617235,"curvature":-0.02002597806471046,"pose":{"rotation":{"radians":-1.5965746186620438},"translation":{"x":7.645989304482046,"y":1.0818829225430147}},"time":0.7947907787618221,"velocity":1.1440332120864944,"position":0.8181816903505706,"holonomicRotation":-90.0,"angularVelocity":-0.023733482027206987,"angularAcceleration":0.3135325241505282,"curveRadius":-49.93513908627455},{"acceleration":-2.974810912810504,"curvature":-0.019250653935271873,"pose":{"rotation":{"radians":-1.5966597775238291},"translation":{"x":7.6458789445652755,"y":1.0776168518789953}},"time":0.7985579019802741,"velocity":1.1328267328263417,"position":0.8224491882382838,"holonomicRotation":-90.0,"angularVelocity":-0.022605807362040452,"angularAcceleration":0.2993463711627502,"curveRadius":-51.94628729820742},{"acceleration":-2.9743491949754386,"curvature":-0.01849256106880203,"pose":{"rotation":{"radians":-1.5967422237597537},"translation":{"x":7.645767440239219,"y":1.0733202456024113}},"time":0.8023905658071016,"velocity":1.121427052258406,"position":0.8267472411359004,"holonomicRotation":-90.0,"angularVelocity":-0.021511470781098375,"angularAcceleration":0.2855289768129575,"curveRadius":-54.07579816984112},{"acceleration":-2.973869432375749,"curvature":-0.017751657771666946,"pose":{"rotation":{"radians":-1.5968219919911313},"translation":{"x":7.645654787663877,"y":1.0689927043532628}},"time":0.8062911798058521,"velocity":1.1098271355200249,"position":0.831076248396903,"holonomicRotation":-90.0,"angularVelocity":-0.02045017307611464,"angularAcceleration":0.27208478083801607,"curveRadius":-56.332766937185966},{"acceleration":-2.9733701264073007,"curvature":-0.017027878978646386,"pose":{"rotation":{"radians":-1.5968991173356324},"translation":{"x":7.645540982999249,"y":1.0646338287715493}},"time":0.8102622939836466,"velocity":1.0980195432552182,"position":0.8354366093726192,"holonomicRotation":-90.0,"angularVelocity":-0.019421588261644963,"angularAcceleration":0.25901668106680825,"curveRadius":-58.72722029878404},{"acceleration":-2.972849627613221,"curvature":-0.016321130365172767,"pose":{"rotation":{"radians":-1.596973635355428},"translation":{"x":7.645426022405335,"y":1.0602432194972713}},"time":0.8143066113090565,"velocity":1.0859963960004237,"position":0.8398287234122964,"holonomicRotation":-90.0,"angularVelocity":-0.01842536423327779,"angularAcceleration":0.24632687007719106,"curveRadius":-61.270266067715134},{"acceleration":-2.9723061160068744,"curvature":-0.015631332270066963,"pose":{"rotation":{"radians":-1.5970455820107219},"translation":{"x":7.645309902042136,"y":1.0558204771704287}},"time":0.8184270017103328,"velocity":1.0737493344103741,"position":0.8442529898631778,"holonomicRotation":-90.0,"angularVelocity":-0.017461125836905685,"angularAcceleration":0.23401627090321953,"curveRadius":-63.97407352890439},{"acceleration":-2.97173757822396,"curvature":-0.014958365665293849,"pose":{"rotation":{"radians":-1.597114993612946},"translation":{"x":7.645192618069653,"y":1.0513652024310214}},"time":0.8226265177744381,"velocity":1.0612694747123173,"position":0.8487098080705767,"holonomicRotation":-90.0,"angularVelocity":-0.016528476416000283,"angularAcceleration":0.22208497518965983,"curveRadius":-66.85222318907361},{"acceleration":-2.9711417809813656,"curvature":-0.01430210081065519,"pose":{"rotation":{"radians":-1.597181906780671},"translation":{"x":7.645074166647882,"y":1.0468769959190494}},"time":0.8269084124072958,"velocity":1.0485473586668737,"position":0.8531995773779496,"holonomicRotation":-90.0,"angularVelocity":-0.01562700006941387,"angularAcceleration":0.21053211811164088,"curveRadius":-69.91979802400716},{"acceleration":-2.970516239817345,"curvature":-0.01366238636857524,"pose":{"rotation":{"radians":-1.597246358393459},"translation":{"x":7.6449545439368265,"y":1.0423554582745127}},"time":0.8312761587642411,"velocity":1.0355728971821647,"position":0.8577226971269682,"holonomicRotation":-90.0,"angularVelocity":-0.014756262731610528,"angularAcceleration":0.19935620492677206,"curveRadius":-73.19365541440791},{"acceleration":-2.969858182515012,"curvature":-0.013039075739580729,"pose":{"rotation":{"radians":-1.5973083855536077},"translation":{"x":7.644833746096486,"y":1.0378001901374114}},"time":0.8357334728189965,"velocity":1.0223353065646104,"position":0.8622795666575913,"holonomicRotation":-90.0,"angularVelocity":-0.013915815530746918,"angularAcceleration":0.18855462965795855,"curveRadius":-76.69255244560416},{"acceleration":-2.9691645058272984,"curvature":-0.012431988846163596,"pose":{"rotation":{"radians":-1.5973680255442346},"translation":{"x":7.64471176928686,"y":1.0332107921477456}},"time":0.8402843390124086,"velocity":1.0088230361923616,"position":0.8668705853081345,"holonomicRotation":-90.0,"angularVelocity":-0.013105195383090908,"angularAcceleration":0.17812436428683948,"curveRadius":-80.43765260524597},{"acceleration":-2.9684317241585076,"curvature":-0.01184095561590441,"pose":{"rotation":{"radians":-1.5974253157900948},"translation":{"x":7.644588609667947,"y":1.028586864945515}},"time":0.8449330395122846,"velocity":0.9950236861524182,"position":0.8714961524153397,"holonomicRotation":-90.0,"angularVelocity":-0.012323927054826853,"angularAcceleration":0.1680616611642109,"curveRadius":-84.45264321883198},{"acceleration":-2.967655908342286,"curvature":-0.011265776200774343,"pose":{"rotation":{"radians":-1.5974802938197517},"translation":{"x":7.64446426339975,"y":1.02392800917072}},"time":0.8496841877277169,"velocity":0.9809239130794806,"position":0.8761566673144422,"holonomicRotation":-90.0,"angularVelocity":-0.01157152485334816,"angularAcceleration":0.1583621826477225,"curveRadius":-88.76441198354942},{"acceleration":-2.966832612343593,"curvature":-0.010706248600109306,"pose":{"rotation":{"radians":-1.5975329972330439},"translation":{"x":7.644338726642267,"y":1.01923382546336}},"time":0.854542766861552,"velocity":0.9665093220555667,"position":0.8808525293392384,"holonomicRotation":-90.0,"angularVelocity":-0.01084749508867639,"angularAcceleration":0.14902088547444742,"curveRadius":-93.40339808565537},{"acceleration":-2.9659567847344595,"curvature":-0.010162169152715592,"pose":{"rotation":{"radians":-1.5975834636624047},"translation":{"x":7.644211995555497,"y":1.0145039144634356}},"time":0.8595141744614548,"velocity":0.9517643419549543,"position":0.8855841378221498,"holonomicRotation":-90.0,"angularVelocity":-0.010151336084730156,"angularAcceleration":0.1400325742672624,"curveRadius":-98.40418762688815},{"acceleration":-2.9650226615239736,"curvature":-0.00963332647021008,"pose":{"rotation":{"radians":-1.5976317307425374},"translation":{"x":7.644084066299444,"y":1.0097378768109462}},"time":0.864604274154584,"velocity":0.9366720810154102,"position":0.890351892094289,"holonomicRotation":-90.0,"angularVelocity":-0.00948254121581899,"angularAcceleration":0.13139131043227678,"curveRadius":-103.80630232893917},{"acceleration":-2.9640236352088314,"curvature":-0.009119473762035651,"pose":{"rotation":{"radians":-1.5976778360799875},"translation":{"x":7.643954935034104,"y":1.0049353131458925}},"time":0.8698194560383176,"velocity":0.9212141586501109,"position":0.89515619148552,"holonomicRotation":-90.0,"angularVelocity":-0.008840600093716984,"angularAcceleration":0.12309084062902016,"curveRadius":-109.65545009439006},{"acceleration":-2.962952093866381,"curvature":-0.008620393608203849,"pose":{"rotation":{"radians":-1.5977218172205712},"translation":{"x":7.643824597919479,"y":1.000095824108274}},"time":0.8751667075706031,"velocity":0.9053705085260952,"position":0.8999974353245223,"holonomicRotation":-90.0,"angularVelocity":-0.008224999388589348,"angularAcceleration":0.11512469563303171,"curveRadius":-116.00398374481657},{"acceleration":-2.9617992219796716,"curvature":-0.00813585278373972,"pose":{"rotation":{"radians":-1.597763711622214},"translation":{"x":7.6436930511155685,"y":0.9952190103380907}},"time":0.8806536972869892,"velocity":0.8891191466530926,"position":0.9048760229388497,"holonomicRotation":-90.0,"angularVelocity":-0.007635225106731411,"angularAcceleration":0.10748594627335759,"curveRadius":-122.91274517633795},{"acceleration":-2.960554751793087,"curvature":-0.0076655998332974574,"pose":{"rotation":{"radians":-1.597803556628894},"translation":{"x":7.643560290782371,"y":0.9903044724753428}},"time":0.8862888743075515,"velocity":0.8724358965476714,"position":0.9097923536549889,"holonomicRotation":-90.0,"angularVelocity":-0.00707076397679611,"angularAcceleration":0.10016741761183734,"curveRadius":-130.45293541886298},{"acceleration":-2.959206650419585,"curvature":-0.00720939320090073,"pose":{"rotation":{"radians":-1.5978413894421433},"translation":{"x":7.64342631307989,"y":0.9853518111600305}},"time":0.892081587442747,"velocity":0.8552940613140281,"position":0.9147468267984173,"holonomicRotation":-90.0,"angularVelocity":-0.006531104228077747,"angularAcceleration":0.09316182868429795,"curveRadius":-138.70792896620782},{"acceleration":-2.9577407223147776,"curvature":-0.006766970930152382,"pose":{"rotation":{"radians":-1.5978772470998788},"translation":{"x":7.643291114168123,"y":0.9803606270321532}},"time":0.8980422288447348,"velocity":0.8376640295082532,"position":0.9197398416936602,"holonomicRotation":-90.0,"angularVelocity":-0.00601573812569013,"angularAcceleration":0.08646151775138616,"curveRadius":-147.7766064494504},{"acceleration":-2.956140099229062,"curvature":-0.006338097446372521,"pose":{"rotation":{"radians":-1.5979111664505652},"translation":{"x":7.64315469020707,"y":0.9753305207317116}},"time":0.9041824086994942,"velocity":0.8195127976231207,"position":0.9247717976643431,"holonomicRotation":-90.0,"angularVelocity":-0.005524162400573061,"angularAcceleration":0.08005884790753182,"curveRadius":-157.7760532180409},{"acceleration":-2.954384578536469,"curvature":-0.005922507454045476,"pose":{"rotation":{"radians":-1.5979431841333103},"translation":{"x":7.6430170373567305,"y":0.9702610928987051}},"time":0.9105151695923503,"velocity":0.8008033865017076,"position":0.9298430940332479,"holonomicRotation":-90.0,"angularVelocity":-0.005055880568804728,"angularAcceleration":0.07394592022202988,"curveRadius":-168.84740251646824},{"acceleration":-2.952449754717108,"curvature":-0.00551992680123421,"pose":{"rotation":{"radians":-1.5979733365546158},"translation":{"x":7.642878151777108,"y":0.965151944173134}},"time":0.917055252172451,"velocity":0.7814941212922598,"position":0.9349541301223625,"holonomicRotation":-90.0,"angularVelocity":-0.004610403758095596,"angularAcceleration":0.06811486021056895,"curveRadius":-181.1618226126492},{"acceleration":-2.9503058641619435,"curvature":-0.005130118988157686,"pose":{"rotation":{"radians":-1.5980016598736837},"translation":{"x":7.642738029628197,"y":0.9600026751949982}},"time":0.9238194280008523,"velocity":0.7615377336795051,"position":0.9401053052529329,"holonomicRotation":-90.0,"angularVelocity":-0.004187253523031831,"angularAcceleration":0.06255754519080521,"curveRadius":-194.92725262482014},{"acceleration":-2.94791622664725,"curvature":-0.004752812626600708,"pose":{"rotation":{"radians":-1.598028189977911},"translation":{"x":7.642596667070002,"y":0.9548128866042978}},"time":0.930826921636084,"velocity":0.740880229484078,"position":0.9452970187455116,"holonomicRotation":-90.0,"angularVelocity":-0.0037859619442073174,"angularAcceleration":0.05726606397570274,"curveRadius":-210.40173020984773},{"acceleration":-2.945235108675458,"curvature":-0.004387734784955471,"pose":{"rotation":{"radians":-1.5980529624713524},"translation":{"x":7.642454060262522,"y":0.9495821790410328}},"time":0.9380999531240131,"velocity":0.7194594417993273,"position":0.950529669920006,"holonomicRotation":-90.0,"angularVelocity":-0.0034060753734636347,"angularAcceleration":0.052232218624953974,"curveRadius":-227.90803205079052},{"acceleration":-2.9422047418456567,"curvature":-0.0040346447863295306,"pose":{"rotation":{"radians":-1.5980760126559561},"translation":{"x":7.642310205365756,"y":0.944310153145203}},"time":0.9456644458172923,"velocity":0.6972031555275044,"position":0.955803658095725,"holonomicRotation":-90.0,"angularVelocity":-0.0030471553795232667,"angularAcceleration":0.04744799268023049,"curveRadius":-247.85329389795874},{"acceleration":-2.9387510785656388,"curvature":-0.00369327021319609,"pose":{"rotation":{"radians":-1.5980973755166863},"translation":{"x":7.642165098539704,"y":0.9389964095568086}},"time":0.9535509657365101,"velocity":0.6740266366087736,"position":0.9611193825914235,"holonomicRotation":-90.0,"angularVelocity":-0.002708781686852982,"angularAcceleration":0.04290532403852004,"curveRadius":-270.7627501575678},{"acceleration":-2.9347776129111387,"curvature":-0.0033633478924839665,"pose":{"rotation":{"radians":-1.5981170857084877},"translation":{"x":7.642018735944367,"y":0.9336405489158498}},"time":0.9617959925423275,"velocity":0.6498293165212085,"position":0.9664772427253469,"holonomicRotation":-90.0,"angularVelocity":-0.0023905552117128195,"angularAcceleration":0.03859617229086909,"curveRadius":-297.32279620395144},{"acceleration":-2.9301561514490864,"curvature":-0.003044612319058155,"pose":{"rotation":{"radians":-1.5981351775432557},"translation":{"x":7.641871113739745,"y":0.9282421718623259}},"time":0.9704436777592059,"velocity":0.6244902484871768,"position":0.9718776378152741,"holonomicRotation":-90.0,"angularVelocity":-0.002092101448463281,"angularAcceleration":0.03451256096452504,"curveRadius":-328.4490421786601},{"acceleration":-2.9247126170086934,"curvature":-0.0027368091501536406,"pose":{"rotation":{"radians":-1.5981516849779496},"translation":{"x":7.641722228085835,"y":0.9228008790362376}},"time":0.9795483404613329,"velocity":0.5978617266086577,"position":0.9773209671785572,"holonomicRotation":-90.0,"angularVelocity":-0.0018130748204410797,"angularAcceleration":0.030646563980565433,"curveRadius":-365.3890151397153},{"acceleration":-2.918204451867169,"curvature":-0.002439682252446406,"pose":{"rotation":{"radians":-1.598166641601999},"translation":{"x":7.641572075142642,"y":0.9173162710775848}},"time":0.9891781184776135,"velocity":0.569760065531055,"position":0.9828076301321628,"holonomicRotation":-90.0,"angularVelocity":-0.0015531639487642074,"angularAcceleration":0.0269903284621362,"curveRadius":-409.88944318353094},{"acceleration":-2.910283169838673,"curvature":-0.0021529713388179278,"pose":{"rotation":{"radians":-1.5981800806311828},"translation":{"x":7.641420651070163,"y":0.9117879486263671}},"time":0.9994205062004096,"velocity":0.5399518169224393,"position":0.9883380259927106,"holonomicRotation":-90.0,"angularVelocity":-0.0013120992435976895,"angularAcceleration":0.023535987085315076,"curveRadius":-464.47436710840856},{"acceleration":-2.900429226265874,"curvature":-0.0018764288399979268,"pose":{"rotation":{"radians":-1.5981920348942138},"translation":{"x":7.6412679520283975,"y":0.9062155123225847}},"time":1.0103911295607697,"velocity":0.5081323002976956,"position":0.99391255407651,"holonomicRotation":-90.0,"angularVelocity":-0.0010896612378669484,"angularAcceleration":0.020275785470356255,"curveRadius":-532.9272172138992},{"acceleration":-2.887831857591094,"curvature":-0.001609778529598094,"pose":{"rotation":{"radians":-1.5982025368260517},"translation":{"x":7.641113974177348,"y":0.9005985628062378}},"time":1.0222484269347438,"velocity":0.47389041919620195,"position":0.9995316136995966,"holonomicRotation":-90.0,"angularVelocity":-0.0008856935528147583,"angularAcceleration":0.017201869753210704,"curveRadius":-621.2034647086922},{"acceleration":-2.8711503654296293,"curvature":-0.0013528014377730305,"pose":{"rotation":{"radians":-1.598211618462562},"translation":{"x":7.640958713677011,"y":0.8949367007173262}},"time":1.0352199773273183,"velocity":0.4366471475463729,"position":1.0051956041777683,"holonomicRotation":-90.0,"angularVelocity":-0.0007001195875217096,"angularAcceleration":0.014306228606202695,"curveRadius":-739.2067838471482},{"acceleration":-2.8479920416937206,"curvature":-0.0011052547757918192,"pose":{"rotation":{"radians":-1.5982193114287115},"translation":{"x":7.64080216668739,"y":0.88922952669585}},"time":1.0496542803402682,"velocity":0.3955383674380959,"position":1.0109049248266173,"holonomicRotation":-90.0,"angularVelocity":-0.0005329641578495326,"angularAcceleration":0.011580429586535044,"curveRadius":-904.7687663539718},{"acceleration":-2.8136103661233767,"curvature":-0.0008668392826019655,"pose":{"rotation":{"radians":-1.598225646938051},"translation":{"x":7.640644329368484,"y":0.8834766413818089}},"time":1.0661366826399126,"velocity":0.3491633094692007,"position":1.016659974961564,"holonomicRotation":-90.0,"angularVelocity":-0.00038438021498292955,"angularAcceleration":0.009014701872057143,"curveRadius":-1153.6163854945867},{"acceleration":-2.756964297225786,"curvature":-0.0006374317165796447,"pose":{"rotation":{"radians":-1.5982306557839472},"translation":{"x":7.640485197880291,"y":0.8776776454152034}},"time":1.085805979137862,"velocity":0.29493576127280585,"position":1.0224611538978872,"holonomicRotation":-90.0,"angularVelocity":-0.00025465302720881054,"angularAcceleration":0.006595415742888576,"curveRadius":-1568.7954866222187},{"acceleration":-2.6440291814165526,"curvature":-0.00041668548431578645,"pose":{"rotation":{"radians":-1.5982343683355769},"translation":{"x":7.640324768382812,"y":0.8718321394360331}},"time":1.111595482785304,"velocity":0.2267475610547205,"position":1.0283088609507565,"holonomicRotation":-90.0,"angularVelocity":-0.00014395591634597688,"angularAcceleration":0.004292331964822956,"curveRadius":-2399.8916152359816},{"acceleration":-2.117094153765788,"curvature":-0.00041668548431578645,"pose":{"rotation":{"radians":-1.598236814534424},"translation":{"x":7.640163037036049,"y":0.8659397240842983}},"time":1.1742832513131567,"velocity":0.09403165279178075,"position":1.034203495435259,"holonomicRotation":-90.0,"angularVelocity":-0.00003902194805279061,"angularAcceleration":0.0016739145571366663,"curveRadius":-2399.8916152359816}] \ No newline at end of file diff --git a/src/main/deploy/pathplanner/generatedJSON/Blue4(2).wpilib.json b/src/main/deploy/pathplanner/generatedJSON/Blue4(2).wpilib.json new file mode 100644 index 0000000..8bdb09c --- /dev/null +++ b/src/main/deploy/pathplanner/generatedJSON/Blue4(2).wpilib.json @@ -0,0 +1 @@ +[{"acceleration":0.0,"curvature":-0.12698893541348918,"pose":{"rotation":{"radians":1.9639199914577683},"translation":{"x":7.64,"y":0.86}},"time":0.0,"velocity":0,"position":0.0,"holonomicRotation":-90.0,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-7.874701813539077},{"acceleration":1.5,"curvature":-0.12698893541348918,"pose":{"rotation":{"radians":1.9639199914577683},"translation":{"x":7.635350144931455,"y":0.8712122759559763}},"time":0.08995634445036114,"velocity":0.1349345166755417,"position":0.01213821586030803,"holonomicRotation":-90.36764,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-7.874701813539077},{"acceleration":5.134604903600637,"curvature":-0.1267160002088196,"pose":{"rotation":{"radians":1.9623818707034337},"translation":{"x":7.630737367957878,"y":0.8823836734712213}},"time":0.127081292073105,"velocity":0.3255564547851992,"position":0.02422448219245473,"holonomicRotation":-90.73528,"angularVelocity":-0.041430920521818376,"angularAcceleration":-1.115985965632354,"curveRadius":-7.891663233940986},{"acceleration":3.4612334450421676,"curvature":-0.12642658693551465,"pose":{"rotation":{"radians":1.9608536330403796},"translation":{"x":7.6261613886315684,"y":0.8935141417383029}},"time":0.15547537314228574,"velocity":0.4238349978230862,"position":0.03625888748059948,"holonomicRotation":-91.10292,"angularVelocity":-0.0538224026102703,"angularAcceleration":-0.43641074554449244,"curveRadius":-7.9097286752671865},{"acceleration":3.285076857646677,"curvature":-0.12612032655830466,"pose":{"rotation":{"radians":1.9593354368798952},"translation":{"x":7.621621926504822,"y":0.9046036299497903}},"time":0.179334918136847,"velocity":0.502215436918699,"position":0.048241519294724415,"holonomicRotation":-91.47056,"angularVelocity":-0.06363055795198531,"angularAcceleration":-0.41107889291060545,"curveRadius":-7.928936019188835},{"acceleration":3.2081318042713804,"curvature":-0.12579684032640406,"pose":{"rotation":{"radians":1.9578274426791265},"translation":{"x":7.617118701129937,"y":0.9156520872982515}},"time":0.2002872342299885,"velocity":0.5694332285502534,"position":0.06017246429324742,"holonomicRotation":-91.8382,"angularVelocity":-0.07197267328657621,"angularAcceleration":-0.39814764618416487,"curveRadius":-7.949325256543074},{"acceleration":3.1645910068879797,"curvature":-0.12545574040983223,"pose":{"rotation":{"radians":1.9563298129814117},"translation":{"x":7.61265143205921,"y":0.9266594629762553}},"time":0.21916783253291283,"velocity":0.6291826001443521,"position":0.07205180822576239,"holonomicRotation":-92.20584,"angularVelocity":-0.07932109320300296,"angularAcceleration":-0.3892048227777076,"curveRadius":-7.970938569516647},{"acceleration":3.136501760676607,"curvature":-0.12509662905863012,"pose":{"rotation":{"radians":1.954842712458335},"translation":{"x":7.608219838844938,"y":0.9376257061763702}},"time":0.23647358687727543,"velocity":0.6834621291152823,"position":0.0838796359359065,"holonomicRotation":-92.57348,"angularVelocity":-0.08593098535234871,"angularAcceleration":-0.3819476468819137,"curveRadius":-7.993820517188527},{"acceleration":3.11685644851012,"curvature":-0.12471909837927146,"pose":{"rotation":{"radians":1.953366307950989},"translation":{"x":7.603823641039421,"y":0.9485507660911645}},"time":0.2525285876415453,"velocity":0.7335032617782317,"position":0.09565603136435044,"holonomicRotation":-92.94112,"angularVelocity":-0.09195916767762408,"angularAcceleration":-0.37547069687414725,"curveRadius":-8.018018194446809},{"acceleration":3.1023378780355415,"curvature":-0.12432273024315504,"pose":{"rotation":{"radians":1.951900768515706},"translation":{"x":7.599462558194953,"y":0.9594345919132069}},"time":0.2675581899972785,"velocity":0.780130166458235,"position":0.10738107755192966,"holonomicRotation":-93.30875999999999,"angularVelocity":-0.0975101935896603,"angularAcceleration":-0.3693395061725455,"curveRadius":-8.043581395326202},{"acceleration":3.09116841542289,"curvature":-0.12390709577607993,"pose":{"rotation":{"radians":1.9504462654664383},"translation":{"x":7.595136309863834,"y":0.9702771328350659}},"time":0.2817266484175711,"velocity":0.823927257622276,"position":0.11905485664289661,"holonomicRotation":-93.6764,"angularVelocity":-0.1026578196527326,"angularAcceleration":-0.36331588874197246,"curveRadius":-8.070562817541628},{"acceleration":3.082308390837794,"curvature":-0.12347175510015368,"pose":{"rotation":{"radians":1.9490029724226983},"translation":{"x":7.5908446155983595,"y":0.9810783380493099}},"time":0.2951580931052806,"velocity":0.8653271122842766,"position":0.13067744988831823,"holonomicRotation":-94.04404,"angularVelocity":-0.10745627721347946,"angularAcceleration":-0.3572555054437086,"curveRadius":-8.099018266880984},{"acceleration":3.075108687760456,"curvature":-0.12301625713949192,"pose":{"rotation":{"radians":1.9475710653554195},"translation":{"x":7.586587194950829,"y":0.9918381567485074}},"time":0.30794906250829385,"velocity":0.9046607334203609,"position":0.1422489376496056,"holonomicRotation":-94.41168,"angularVelocity":-0.11194671976476446,"angularAcceleration":-0.3510635050246583,"curveRadius":-8.129006874807361},{"acceleration":3.069142903049428,"curvature":-0.12254013897604833,"pose":{"rotation":{"radians":1.9461507226364865},"translation":{"x":7.582363767473538,"y":1.002556538125227}},"time":0.3201764090853554,"velocity":0.942188207390475,"position":0.15376939940218928,"holonomicRotation":-94.77932,"angularVelocity":-0.1161611564685298,"angularAcceleration":-0.344673039011719,"curveRadius":-8.16059136505027},{"acceleration":3.0641192881230683,"curvature":-0.12204292576312101,"pose":{"rotation":{"radians":1.944742125087783},"translation":{"x":7.578174052718785,"y":1.0132334313720373}},"time":0.3319025095208275,"velocity":0.9781183779092735,"position":0.1652389137393345,"holonomicRotation":-95.14696,"angularVelocity":-0.12012497730638529,"angularAcceleration":-0.33803401733322214,"curveRadius":-8.193838305228343},{"acceleration":3.059831442121889,"curvature":-0.12152412987714938,"pose":{"rotation":{"radians":1.9433454560322376},"translation":{"x":7.574017770238868,"y":1.0238687856815065}},"time":0.3431788244983494,"velocity":1.012622001028765,"position":0.17665755837610336,"holonomicRotation":-95.5146,"angularVelocity":-0.12385864161558713,"angularAcceleration":-0.3311067770494609,"curveRadius":-8.228818433103907},{"acceleration":3.056129207454674,"curvature":-0.12098325141331974,"pose":{"rotation":{"radians":1.941960901347135},"translation":{"x":7.5698946395860816,"y":1.0344625502462035}},"time":0.3540484054979581,"velocity":1.0458408449944634,"position":0.18802541015346985,"holonomicRotation":-95.88224,"angularVelocity":-0.12737884607993777,"angularAcceleration":-0.3238583404896084,"curveRadius":-8.265606919288865},{"acceleration":3.052900722194567,"curvature":-0.12041977707662298,"pose":{"rotation":{"radians":1.9405886495164393},"translation":{"x":7.565804380312725,"y":1.0450146742586965}},"time":0.3645477061077007,"velocity":1.0778941674084845,"position":0.19934254504257978,"holonomicRotation":-96.24988,"angularVelocity":-0.1306993562430649,"angularAcceleration":-0.3162601287980949,"curveRadius":-8.304283766973768},{"acceleration":3.050060936620296,"curvature":-0.11983317962403801,"pose":{"rotation":{"radians":1.9392288916874236},"translation":{"x":7.5617467119710975,"y":1.055525106911554}},"time":0.3747079201628673,"velocity":1.1088834394058487,"position":0.21060903814917256,"holonomicRotation":-96.61752,"angularVelocity":-0.1338316123688553,"angularAcceleration":-0.30828643065818234,"curveRadius":-8.344934208850821},{"acceleration":3.047544030181119,"curvature":-0.11922291834797172,"pose":{"rotation":{"radians":1.9378818217271414},"translation":{"x":7.557721354113493,"y":1.0659937973973448}},"time":0.3845559896106676,"velocity":1.1388958646603016,"position":0.2218249637181598,"holonomicRotation":-96.98516000000001,"angularVelocity":-0.13678518083390506,"angularAcceleration":-0.29991344808291154,"curveRadius":-8.387649068288493},{"acceleration":3.045298265422573,"curvature":-0.1185884375246022,"pose":{"rotation":{"radians":1.936547636279756},"translation":{"x":7.553728026292212,"y":1.0764206949086372}},"time":0.3941153766249682,"velocity":1.1680070493534542,"position":0.23299039513836076,"holonomicRotation":-97.3528,"angularVelocity":-0.13956809630047282,"angularAcceleration":-0.29111861068126915,"curveRadius":-8.432525302414422},{"acceleration":3.0432824112472026,"curvature":-0.11792916660625358,"pose":{"rotation":{"radians":1.9352265348280069},"translation":{"x":7.54976644805955,"y":1.0868057486379998}},"time":0.40340666408923687,"velocity":1.1962830610713047,"position":0.2441054049474095,"holonomicRotation":-97.72044,"angularVelocity":-0.14218712496300062,"angularAcceleration":-0.28188005942123284,"curveRadius":-8.479666470796307},{"acceleration":3.041463203976636,"curvature":-0.11724451984949269,"pose":{"rotation":{"radians":1.9339187197530203},"translation":{"x":7.545836338967805,"y":1.097148907778001}},"time":0.41244802891744115,"velocity":1.2237820395100165,"position":0.2551700648368235,"holonomicRotation":-98.08808,"angularVelocity":-0.14464797072526825,"angularAcceleration":-0.2721763593247658,"curveRadius":-8.529183293886183},{"acceleration":3.0398135109800206,"curvature":-0.1165338955693169,"pose":{"rotation":{"radians":1.9326243963986083},"translation":{"x":7.541937418569274,"y":1.1074501215212094}},"time":0.42125561967151537,"velocity":1.250555472883434,"position":0.2661844456572485,"holonomicRotation":-98.45572,"angularVelocity":-0.14695543770733355,"angularAcceleration":-0.2619861715302687,"curveRadius":-8.581194296428357},{"acceleration":3.0383109800038914,"curvature":-0.11579667524219099,"pose":{"rotation":{"radians":1.9313437731354333},"translation":{"x":7.538069406416255,"y":1.1177093390601933}},"time":0.42984386112779427,"velocity":1.2766492211989708,"position":0.2771486174238757,"holonomicRotation":-98.82336000000001,"angularVelocity":-0.14911356063920966,"angularAcceleration":-0.2512881062861016,"curveRadius":-8.63582652877106},{"acceleration":3.0369370305874943,"curvature":-0.1150322240264295,"pose":{"rotation":{"radians":1.9300770614276888},"translation":{"x":7.534232022061046,"y":1.1279265095875217}},"time":0.4382257023665912,"velocity":1.3021043452415786,"position":0.28806264932203823,"holonomicRotation":-99.191,"angularVelocity":-0.15112570993128482,"angularAcceleration":-0.24006053500053773,"curveRadius":-8.693216257126721},{"acceleration":3.0356760905842757,"curvature":-0.11423988899867388,"pose":{"rotation":{"radians":1.9288244759021396},"translation":{"x":7.530424985055943,"y":1.1381015822957627}},"time":0.4464128206887971,"velocity":1.3269577845830836,"position":0.2989266097129922,"holonomicRotation":-99.55864,"angularVelocity":-0.15299467727879298,"angularAcceleration":-0.22828146289750814,"curveRadius":-8.753509905910432},{"acceleration":3.0345150109422665,"curvature":-0.11341899973435231,"pose":{"rotation":{"radians":1.927586234417146},"translation":{"x":7.526648014953243,"y":1.1482345063774848}},"time":0.4544157906146309,"velocity":1.3512429169551456,"position":0.3097405661398801,"holonomicRotation":-99.92628,"angularVelocity":-0.15472274623906282,"angularAcceleration":-0.21592845859530088,"curveRadius":-8.816864919829833},{"acceleration":3.0334426120341735,"curvature":-0.1125688666145972,"pose":{"rotation":{"radians":1.9263625581355892},"translation":{"x":7.522900831305245,"y":1.1583252310252565}},"time":0.46224422501089757,"velocity":1.374990023438295,"position":0.320504585333888,"holonomicRotation":-100.29392,"angularVelocity":-0.15631175016811674,"angularAcceleration":-0.20297850740266868,"curveRadius":-8.883450904979854},{"acceleration":3.032449328252964,"curvature":-0.11168878139156056,"pose":{"rotation":{"radians":1.9251536715990567},"translation":{"x":7.519183153664246,"y":1.1683737054316468}},"time":0.4699068937712354,"velocity":1.3982266781732064,"position":0.33121873322059675,"holonomicRotation":-100.66156000000001,"angularVelocity":-0.15776312070146273,"angularAcceleration":-0.1894079698261677,"curveRadius":-8.953450718512022},{"acceleration":3.0315269268996636,"curvature":-0.11077801537806828,"pose":{"rotation":{"radians":1.923959802803456},"translation":{"x":7.5154947015825435,"y":1.1783798787892237}},"time":0.47741182426812556,"velocity":1.4209780770590394,"position":0.3418830749265295,"holonomicRotation":-101.0292,"angularVelocity":-0.15907792831599188,"angularAcceleration":-0.17519251045349074,"curveRadius":-9.027061882153731},{"acceleration":3.0306682838771875,"curvature":-0.10983581966887798,"pose":{"rotation":{"radians":1.9227811832777917},"translation":{"x":7.511835194612435,"y":1.1883437002905555}},"time":0.4847663868888504,"velocity":1.4432673167354588,"position":0.3524976747859059,"holonomicRotation":-101.39684,"angularVelocity":-0.1602569162091205,"angularAcceleration":-0.16030700313928747,"curveRadius":-9.104497995414427},{"acceleration":3.0298672031889904,"curvature":-0.10886142435433095,"pose":{"rotation":{"radians":1.9216180481641834},"translation":{"x":7.508204352306215,"y":1.1982651191282117}},"time":0.4919773682786665,"velocity":1.4651156327512689,"position":0.36306259634760396,"holonomicRotation":-101.76448,"angularVelocity":-0.16130052911396922,"angularAcceleration":-0.14472550245693172,"curveRadius":-9.185990408733945},{"acceleration":3.0291182706245126,"curvature":-0.1078540373393007,"pose":{"rotation":{"radians":1.9204706362997765},"translation":{"x":7.5046018942161865,"y":1.2081440844947597}},"time":0.49905103438581405,"velocity":1.4865426039967269,"position":0.37357790238232647,"holonomicRotation":-102.13212,"angularVelocity":-0.16220893763241312,"angularAcceleration":-0.12842117576429032,"curveRadius":-9.271790140354923},{"acceleration":3.028416734257972,"curvature":-0.10681284407317258,"pose":{"rotation":{"radians":1.9193391903034127},"translation":{"x":7.501027539894643,"y":1.2179805455827681}},"time":0.5059931849936309,"velocity":1.5075663290691785,"position":0.38404365488999825,"holonomicRotation":-102.49976000000001,"angularVelocity":-0.16298205848340858,"angularAcceleration":-0.11136618818452684,"curveRadius":-9.3621699588389},{"acceleration":3.0277584062463645,"curvature":-0.10573700671440062,"pose":{"rotation":{"radians":1.9182239566608914},"translation":{"x":7.497481008893882,"y":1.2277744515848066}},"time":0.5128092011052948,"velocity":1.5282035791483797,"position":0.3944599151073761,"holonomicRotation":-102.8674,"angularVelocity":-0.16361957252607706,"angularAcceleration":-0.0935317687376849,"curveRadius":-9.457426790045563},{"acceleration":3.0271395815939433,"curvature":-0.10462566311090316,"pose":{"rotation":{"radians":1.917125185815042},"translation":{"x":7.493962020766202,"y":1.2375257516934426}},"time":0.5195040862950508,"velocity":1.5484699311005172,"position":0.4048267435158835,"holonomicRotation":-103.23504,"angularVelocity":-0.16412093930014923,"angularAcceleration":-0.07488803166323471,"curveRadius":-9.557884464158668},{"acceleration":3.026556970527646,"curvature":-0.10347792655038932,"pose":{"rotation":{"radians":1.9160431322586553},"translation":{"x":7.4904702950639,"y":1.2472343951012448}},"time":0.5260825029401686,"velocity":1.5683798838528333,"position":0.41514419984968876,"holonomicRotation":-103.60268,"angularVelocity":-0.16448540959924624,"angularAcceleration":-0.05540395489657847,"curveRadius":-9.66389676848659},{"acceleration":3.0260076419944846,"curvature":-0.10229288415377032,"pose":{"rotation":{"radians":1.9149780546277595},"translation":{"x":7.487005551339274,"y":1.2569003310007818}},"time":0.5325488040884212,"velocity":1.5879469605428835,"position":0.4254123431040115,"holonomicRotation":-103.97032,"angularVelocity":-0.16471203652239683,"angularAcceleration":-0.035047381486683724,"curveRadius":-9.775851060145731},{"acceleration":3.0254889760964887,"curvature":-0.10106959689860463,"pose":{"rotation":{"radians":1.9139302157998344},"translation":{"x":7.4835675091446205,"y":1.266523508584622}},"time":0.5389070615877272,"velocity":1.6071837985142166,"position":0.43563123154367756,"holonomicRotation":-104.33796000000001,"angularVelocity":-0.16479968419641977,"angularAcceleration":-0.013784857570256003,"curveRadius":-9.894172240572239},{"acceleration":3.0249986239106783,"curvature":-0.09980709799591933,"pose":{"rotation":{"radians":1.912899882993202},"translation":{"x":7.480155888032236,"y":1.2761038770453341}},"time":0.5451610910008907,"velocity":1.6261022288829332,"position":0.44580092271192223,"holonomicRotation":-104.7056,"angularVelocity":-0.16474703564132315,"angularAcceleration":0.008418341459317176,"curveRadius":-10.019327483511098},{"acceleration":3.02453447337218,"curvature":-0.09850439230970404,"pose":{"rotation":{"radians":1.9118873278692226},"translation":{"x":7.4767704075544215,"y":1.2856413855754867}},"time":0.5513144737440068,"velocity":1.6447133471173412,"position":0.4559214734394467,"holonomicRotation":-105.07324,"angularVelocity":-0.16455259915568152,"angularAcceleration":0.03159830840347959,"curveRadius":-10.151831573722488},{"acceleration":3.0240946202251706,"curvature":-0.09716045534495561,"pose":{"rotation":{"radians":1.9108928266395566},"translation":{"x":7.473410787263471,"y":1.2951359833676481}},"time":0.5573705768180581,"velocity":1.663027575843109,"position":0.46599293985374235,"holonomicRotation":-105.44088,"angularVelocity":-0.1642147132414379,"angularAcceleration":0.05579262937108032,"curveRadius":-10.29225312345058},{"acceleration":3.023677343065534,"curvature":-0.0957742322984009,"pose":{"rotation":{"radians":1.9099166601723943},"translation":{"x":7.470076746711682,"y":1.304587619614387}},"time":0.5633325704464315,"velocity":1.6810547208967226,"position":0.47601537738867555,"holonomicRotation":-105.80852,"angularVelocity":-0.16373155155965816,"angularAcceleration":0.08104028818151848,"curveRadius":-10.44122177752707},{"acceleration":3.023281082013047,"curvature":-0.09434463674157978,"pose":{"rotation":{"radians":1.9089591141054973},"translation":{"x":7.466768005451355,"y":1.3139962435082713}},"time":0.5692034438841422,"velocity":1.6988040214958464,"position":0.48598884079435173,"holonomicRotation":-106.17616000000001,"angularVelocity":-0.1631011257620104,"angularAcceleration":0.1073819431361421,"curveRadius":-10.599436645658075},{"acceleration":3.022904420172437,"curvature":-0.09287055040136313,"pose":{"rotation":{"radians":1.9080204789604542},"translation":{"x":7.463484283034785,"y":1.3233618042418704}},"time":0.5749860196255576,"velocity":1.716284195264553,"position":0.49591338414726316,"holonomicRotation":-106.5438,"angularVelocity":-0.16232128847366598,"angularAcceleration":0.13485984848571278,"curveRadius":-10.767676035925833},{"acceleration":3.022546067682666,"curvature":-0.09135082079248769,"pose":{"rotation":{"radians":1.907101050260509},"translation":{"x":7.460225299014269,"y":1.3326842510077521}},"time":0.5806829662048637,"velocity":1.7335034787456327,"position":0.5057890608607183,"holonomicRotation":-106.91144,"angularVelocity":-0.16138973521096345,"angularAcceleration":0.16351799156522823,"curveRadius":-10.94680914002511},{"acceleration":3.0222048478384034,"curvature":-0.08978426080777253,"pose":{"rotation":{"radians":1.9062011286510985},"translation":{"x":7.456990772942105,"y":1.3419635329984856}},"time":0.5862968097562721,"velocity":1.7504696639417054,"position":0.5156159236955734,"holonomicRotation":-107.27908000000001,"angularVelocity":-0.1603040058330055,"angularAcceleration":0.193402143828103,"curveRadius":-11.13780957823992},{"acceleration":3.0218796849479435,"curvature":-0.08816964819312259,"pose":{"rotation":{"radians":1.905321020025674},"translation":{"x":7.453780424370591,"y":1.3511995994066386}},"time":0.591829944478009,"velocity":1.7671901313514022,"position":0.5253940247712646,"holonomicRotation":-107.64672,"angularVelocity":-0.1590614849782933,"angularAcceleration":0.22456002197650293,"curveRadius":-11.341771465500777},{"acceleration":3.0215695937933122,"curvature":-0.08650572225057337,"pose":{"rotation":{"radians":1.9044610356527123},"translation":{"x":7.450593972852023,"y":1.3603923994247804}},"time":0.5972846421247603,"velocity":1.783671879904162,"position":0.5351234155771544,"holonomicRotation":-108.01436000000001,"angularVelocity":-0.15765940271207088,"angularAcceleration":0.257041243533906,"curveRadius":-11.559928915492891},{"acceleration":3.021273670278536,"curvature":-0.08479118526039595,"pose":{"rotation":{"radians":1.9036214923075216},"translation":{"x":7.447431137938702,"y":1.3695418822454786}},"time":0.6026630606368097,"velocity":1.7999215541423557,"position":0.5448041469841904,"holonomicRotation":-108.382,"angularVelocity":-0.15609483406874985,"angularAcceleration":0.2908975268131082,"curveRadius":-11.793678752443121},{"acceleration":3.020991083364434,"curvature":-0.0830246987352215,"pose":{"rotation":{"radians":1.9028027124087954},"translation":{"x":7.444291639182921,"y":1.3786479970613026}},"time":0.6079672520001413,"velocity":1.815945468955439,"position":0.554436269256905,"holonomicRotation":-108.74964,"angularVelocity":-0.1543646981491954,"angularAcceleration":0.32618278660062205,"curveRadius":-12.04460859519832},{"acceleration":3.0207210677797507,"curvature":-0.08120488369107497,"pose":{"rotation":{"radians":1.9020050241555855},"translation":{"x":7.44117519613698,"y":1.3877106930648204}},"time":0.6131991694198191,"velocity":1.8317496321299436,"position":0.564019832065734,"holonomicRotation":-109.11728000000001,"angularVelocity":-0.15246575762257455,"angularAcceleration":0.36295307710300234,"curveRadius":-12.314530291112375},{"acceleration":3.020462917728735,"curvature":-0.0793303183337162,"pose":{"rotation":{"radians":1.901228761673243},"translation":{"x":7.438081528353174,"y":1.396729919448601}},"time":0.6183606738787636,"velocity":1.8473397649478769,"position":0.5735548844996979,"holonomicRotation":-109.48492000000002,"angularVelocity":-0.15039461624356723,"angularAcceleration":0.4012669940482567,"curveRadius":-12.605521079511282},{"acceleration":3.02021598120488,"curvature":-0.07739953665766482,"pose":{"rotation":{"radians":1.9004742651580182},"translation":{"x":7.435010355383803,"y":1.405705625405212}},"time":0.6234535401452266,"velocity":1.8627213210359876,"position":0.5830414750794235,"holonomicRotation":-109.85256000000001,"angularVelocity":-0.14814771795467857,"angularAcceleration":0.4411854094195834,"curveRadius":-12.919973984120366},{"acceleration":3.0199796550105416,"curvature":-0.0754110280213925,"pose":{"rotation":{"radians":1.8997418810307414},"translation":{"x":7.431961396781164,"y":1.4146377601272229}},"time":0.6284794622847227,"velocity":1.877899503644933,"position":0.5924796517705414,"holonomicRotation":-110.2202,"angularVelocity":-0.1457213436558036,"angularAcceleration":0.4827719633392898,"curveRadius":-13.260659962311099},{"acceleration":3.019753380280234,"curvature":-0.07336323340403929,"pose":{"rotation":{"radians":1.8990319620910356},"translation":{"x":7.428934372097553,"y":1.4235262728072016}},"time":0.6334400587256059,"velocity":1.8928792815154962,"position":0.6018694619974487,"holonomicRotation":-110.58784,"angularVelocity":-0.14311160929255862,"angularAcceleration":0.5260928588620173,"curveRadius":-13.630805971877205},{"acceleration":3.019536638519583,"curvature":-0.0712545457162891,"pose":{"rotation":{"radians":1.8983448676781896},"translation":{"x":7.425929000885268,"y":1.4323711126377168}},"time":0.6383368769218236,"velocity":1.9076654034711449,"position":0.6112109526574612,"holonomicRotation":-110.95548000000001,"angularVelocity":-0.14031446243538392,"angularAcceleration":0.5712172159740829,"curveRadius":-14.034192344466742},{"acceleration":3.0193289480196177,"curvature":-0.06908330696418012,"pose":{"rotation":{"radians":1.8976809638357213},"translation":{"x":7.422945002696608,"y":1.4411722288113369}},"time":0.6431713976514388,"velocity":1.922262411859873,"position":0.6205041701353579,"holonomicRotation":-111.32312000000002,"angularVelocity":-0.13732567913120203,"angularAcceleration":0.6182170832101862,"curveRadius":-14.475276936561574},{"acceleration":3.0191298607082717,"curvature":-0.0668478069993928,"pose":{"rotation":{"radians":1.8970406234812602},"translation":{"x":7.419982097083868,"y":1.4499295705206308}},"time":0.6479450389852187,"velocity":1.9366746549549991,"position":0.6297491603183349,"holonomicRotation":-111.69076000000001,"angularVelocity":-0.13414086012909474,"angularAcceleration":0.6671676356517287,"curveRadius":-14.959353864953016},{"acceleration":3.0189389592021647,"curvature":-0.06454628139140065,"pose":{"rotation":{"radians":1.896424226580126},"translation":{"x":7.417040003599347,"y":1.4586430869581664}},"time":0.6526591599558285,"velocity":1.9509062984115648,"position":0.6389459686113715,"holonomicRotation":-112.0584,"angularVelocity":-0.1307554271468776,"angularAcceleration":0.7181472438496304,"curveRadius":-15.492759279750356},{"acceleration":3.018755854363974,"curvature":-0.06217691015612584,"pose":{"rotation":{"radians":1.8958321603250714},"translation":{"x":7.414118441795342,"y":1.4673127273165127}},"time":0.6573150639548893,"velocity":1.9649613358660862,"position":0.6480946399530303,"holonomicRotation":-112.42604000000001,"angularVelocity":-0.127164618337091,"angularAcceleration":0.7712377253721189,"curveRadius":-16.08314079115553},{"acceleration":3.018580182830294,"curvature":-0.059737814599165245,"pose":{"rotation":{"radians":1.89526481932117},"translation":{"x":7.4112171312241495,"y":1.4759384407882379}},"time":0.6619140018822666,"velocity":1.978843598755734,"position":0.6571952188316958,"holonomicRotation":-112.79368000000001,"angularVelocity":-0.12336348366955818,"angularAcceleration":0.8265244557672329,"curveRadius":-16.73981558766252},{"acceleration":3.0184116050384717,"curvature":-0.057227055773322315,"pose":{"rotation":{"radians":1.894722605774501},"translation":{"x":7.408335791438068,"y":1.4845201765659108}},"time":0.6664571750694206,"velocity":1.9925567654275393,"position":0.6662477493022686,"holonomicRotation":-113.16132,"angularVelocity":-0.11934688032632872,"angularAcceleration":0.8840964624871767,"curveRadius":-17.474252108321334},{"acceleration":3.018249803235594,"curvature":-0.05464263285195127,"pose":{"rotation":{"radians":1.8942059296884364},"translation":{"x":7.405474141989395,"y":1.4930578838420996}},"time":0.6709457379964118,"velocity":2.006104369598741,"position":0.6752522750033245,"holonomicRotation":-113.52896000000001,"angularVelocity":-0.1151094669872419,"angularAcceleration":0.9440467713186939,"curveRadius":-18.300728713226533},{"acceleration":3.018094479833421,"curvature":-0.051982480275459514,"pose":{"rotation":{"radians":1.893715209063948},"translation":{"x":7.402631902430428,"y":1.5015515118093732}},"time":0.6753808008201785,"velocity":2.019489808224866,"position":0.6842088391747584,"holonomicRotation":-113.8966,"angularVelocity":-0.11064569860402453,"angularAcceleration":1.0064724132647778,"curveRadius":-19.23725060252832},{"acceleration":3.0179453558050513,"curvature":-0.04924446548084328,"pose":{"rotation":{"radians":1.8932508701061843},"translation":{"x":7.399808792313463,"y":1.5100010096602996}},"time":0.6797634317299498,"velocity":2.032716348825218,"position":0.6931174846759173,"holonomicRotation":-114.26424,"angularVelocity":-0.10594982039860713,"angularAcceleration":1.0714747150958293,"curveRadius":-20.306850531030996},{"acceleration":3.017802169223082,"curvature":-0.046426386270113584,"pose":{"rotation":{"radians":1.892813347437158},"translation":{"x":7.397004531190799,"y":1.518406326587448}},"time":0.684094659144112,"velocity":2.045787136311075,"position":0.7019782540042483,"holonomicRotation":-114.63188000000001,"angularVelocity":-0.10101586159980659,"angularAcceleration":1.1391594869083708,"curveRadius":-21.539475292819372},{"acceleration":3.0176646741311184,"curvature":-0.04352596998810766,"pose":{"rotation":{"radians":1.892403084314598},"translation":{"x":7.394218838614732,"y":1.526767411783386}},"time":0.6883754737614575,"velocity":2.0587051993583425,"position":0.7107911893144665,"holonomicRotation":-114.99952,"angularVelocity":-0.09583762887036504,"angularAcceleration":1.209637228498494,"curveRadius":-22.97478953997404},{"acceleration":3.0175326391511432,"curvature":-0.04054086750875463,"pose":{"rotation":{"radians":1.8920205328564266},"translation":{"x":7.391451434137561,"y":1.5350842144406827}},"time":0.6926068304785266,"velocity":2.07147345635999,"position":0.7195563324382657,"holonomicRotation":-115.36716000000001,"angularVelocity":-0.09040869956159918,"angularAcceleration":1.2830233118531034,"curveRadius":-24.66646772627779},{"acceleration":3.0174058465425735,"curvature":-0.03746865477378843,"pose":{"rotation":{"radians":1.891666154273003},"translation":{"x":7.388702037311582,"y":1.5433566837519066}},"time":0.6967896501836525,"velocity":2.0840947209932703,"position":0.7282737249045852,"holonomicRotation":-115.7348,"angularVelocity":-0.08472241416219436,"angularAcceleration":1.3594383215792114,"curveRadius":-26.688975252443807},{"acceleration":3.0172840912265984,"curvature":-0.03430682653198047,"pose":{"rotation":{"radians":1.8913404191047392},"translation":{"x":7.385970367689092,"y":1.5515847689096263}},"time":0.7009248214373389,"velocity":2.096571707431516,"position":0.7369434079604483,"holonomicRotation":-116.10244,"angularVelocity":-0.07877186899419537,"angularAcceleration":1.4390081578106722,"curveRadius":-29.14871764859423},{"acceleration":3.0171671797710435,"curvature":-0.031052794534172763,"pose":{"rotation":{"radians":1.8910438074669242},"translation":{"x":7.383256144822392,"y":1.5597684191064098}},"time":0.7050132020477304,"velocity":2.1089070352276016,"position":0.7455654225923911,"holonomicRotation":-116.47008000000001,"angularVelocity":-0.07254990816192859,"angularAcceleration":1.521864382306359,"curveRadius":-32.20322083732358},{"acceleration":3.0170549297178098,"curvature":-0.027703885055644265,"pose":{"rotation":{"radians":1.8907768093033936},"translation":{"x":7.380559088263774,"y":1.5679075835348264}},"time":0.7090556205491477,"velocity":2.121103233895285,"position":0.7541398095485055,"holonomicRotation":-116.83772,"angularVelocity":-0.0660491147655755,"angularAcceleration":1.6081445783196096,"curveRadius":-36.09602039538727},{"acceleration":3.0169471687021563,"curvature":-0.024257335984350672,"pose":{"rotation":{"radians":1.8905399246432348},"translation":{"x":7.37787891756554,"y":1.5760022113874437}},"time":0.7130528775909487,"velocity":2.1331627472101213,"position":0.7626666093610986,"holonomicRotation":-117.20536000000001,"angularVelocity":-0.05926180320194764,"angularAcceleration":1.6979922713626145,"curveRadius":-41.224642336864115},{"acceleration":3.016843733775321,"curvature":-0.020710292991709497,"pose":{"rotation":{"radians":1.890333663870659},"translation":{"x":7.3752153522799855,"y":1.5840522518568307}},"time":0.7170057472433597,"velocity":2.145087937251428,"position":0.7711458623700128,"holonomicRotation":-117.57300000000001,"angularVelocity":-0.05218000862995766,"angularAcceleration":1.7915578287967229,"curveRadius":-48.28516913789237},{"acceleration":3.0167444708381144,"curvature":-0.017059803413158343,"pose":{"rotation":{"radians":1.8901585479976333},"translation":{"x":7.372568111959407,"y":1.592057654135556}},"time":0.7209149782263286,"velocity":2.1568810882045284,"position":0.7795776087466014,"holonomicRotation":-117.94064,"angularVelocity":-0.04479547864748229,"angularAcceleration":1.8889981212794207,"curveRadius":-58.61732259052254},{"acceleration":3.0166492339298596,"curvature":-0.013302819235945765,"pose":{"rotation":{"radians":1.890015108946807},"translation":{"x":7.369936916156105,"y":1.600018367416188}},"time":0.7247812950669545,"velocity":2.168544409939933,"position":0.7879618885183975,"holonomicRotation":-118.30828000000001,"angularVelocity":-0.03709966273823072,"angularAcceleration":1.9904773008736514,"curveRadius":-75.17203551093017},{"acceleration":2.462051711652185,"curvature":-0.009436188649531264,"pose":{"rotation":{"radians":1.8899038898432727},"translation":{"x":7.367321484422373,"y":1.6079343408912952}},"time":0.7286091063461142,"velocity":2.1779686792516695,"position":0.7962987415944935,"holonomicRotation":-118.67592000000002,"angularVelocity":-0.029055534722859603,"angularAcceleration":2.10149545751302,"curveRadius":-105.97499023609224},{"acceleration":-0.5485378988068667,"curvature":-0.005456651859990139,"pose":{"rotation":{"radians":1.8898254453118648},"translation":{"x":7.36472153631051,"y":1.6158055237534463}},"time":0.7324188156832185,"velocity":2.1758789092968294,"position":0.8045882077916501,"holonomicRotation":-119.04356000000001,"angularVelocity":-0.020590686707756073,"angularAcceleration":2.221914394534214,"curveRadius":-183.26256203594545},{"acceleration":-3.000694398920046,"curvature":-0.0013608268262992153,"pose":{"rotation":{"radians":1.8897803417862884},"translation":{"x":7.362136791372815,"y":1.6236318651952093}},"time":0.7362267621976969,"velocity":2.164452425519447,"position":0.8128303268611611,"holonomicRotation":-119.41120000000001,"angularVelocity":-0.011844579592942411,"angularAcceleration":2.296804086286327,"curveRadius":-734.84735946859},{"acceleration":-3.00069852153666,"curvature":0.0028547471338387707,"pose":{"rotation":{"radians":1.8897691578253981},"translation":{"x":7.359566969161583,"y":1.631413314409153}},"time":0.7400329362491075,"velocity":2.153031244670668,"position":0.8210251385165028,"holonomicRotation":-119.77884,"angularVelocity":-0.002938373479304527,"angularAcceleration":2.3399366380360838,"curveRadius":350.2937223919033},{"acceleration":-3.000702727653132,"curvature":0.007193682227653756,"pose":{"rotation":{"radians":1.8897924844379528},"translation":{"x":7.357011789229114,"y":1.6391498205878459}},"time":0.7438373279996613,"velocity":2.14161539596772,"position":0.8291726824617814,"holonomicRotation":-120.14648000000001,"angularVelocity":0.0061314959352617125,"angularAcceleration":2.384052434464969,"curveRadius":139.01086652894222},{"acceleration":-3.0007070139659366,"curvature":0.011659714328564153,"pose":{"rotation":{"radians":1.8898509254191818},"translation":{"x":7.354470971127703,"y":1.6468413329238567}},"time":0.7476399274229498,"velocity":2.1302049092069555,"position":0.8372729984210182,"holonomicRotation":-120.51412000000002,"angularVelocity":0.015368692497838609,"angularAcceleration":2.429179499161776,"curveRadius":85.76539457319157},{"acceleration":-3.0007113769581437,"curvature":0.016256691480769272,"pose":{"rotation":{"radians":1.8899450976935281},"translation":{"x":7.351944234409648,"y":1.6544878006097536}},"time":0.7514407243133682,"velocity":2.11879981473637,"position":0.8453261261682872,"holonomicRotation":-120.88176000000001,"angularVelocity":0.024776981528212387,"angularAcceleration":2.4753464343468847,"curveRadius":61.51313145008271},{"acceleration":-3.0007158127657543,"curvature":0.020988600661656944,"pose":{"rotation":{"radians":1.8900756316704546},"translation":{"x":7.3494312986272465,"y":1.6620891728381055}},"time":0.7552397082962774,"velocity":2.1074001434264105,"position":0.8533321055587447,"holonomicRotation":-121.24940000000001,"angularVelocity":0.0343602335555137,"angularAcceleration":2.5225828985892527,"curveRadius":47.64491049786142},{"acceleration":-3.0007203172844004,"curvature":0.025859567802419086,"pose":{"rotation":{"radians":1.890243171608446},"translation":{"x":7.346931883332797,"y":1.6696453988014806}},"time":0.7590368688389445,"velocity":2.0960059266380386,"position":0.8612909765605711,"holonomicRotation":-121.61704000000002,"angularVelocity":0.044122426773606394,"angularAcceleration":2.5709192720189264,"curveRadius":38.6704065450952},{"acceleration":-3.0007248859895594,"curvature":0.030873859194485497,"pose":{"rotation":{"radians":1.8904483759900266},"translation":{"x":7.344445708078595,"y":1.677156427692447}},"time":0.7628321952623056,"velocity":2.084617196189005,"position":0.8692027792878602,"holonomicRotation":-121.98468000000001,"angularVelocity":0.054067650233581725,"angularAcceleration":2.620386852303449,"curveRadius":32.38986074596771},{"acceleration":-3.0007295140628387,"curvature":0.03603589187657699,"pose":{"rotation":{"radians":1.8906919179069828},"translation":{"x":7.341972492416939,"y":1.6846222087035743}},"time":0.7666256767535985,"velocity":2.0732339843170315,"position":0.8770675540344862,"holonomicRotation":-122.35232000000002,"angularVelocity":0.06420010681881255,"angularAcceleration":2.671017799477259,"curveRadius":27.750111012237525},{"acceleration":-3.000734196292773,"curvature":0.04135023251562134,"pose":{"rotation":{"radians":1.8909744854570854},"translation":{"x":7.339511955900128,"y":1.69204269102743}},"time":0.7704173023799121,"velocity":2.061856323640612,"position":0.8848853413089788,"holonomicRotation":-122.71996000000001,"angularVelocity":0.07452411655348716,"angularAcceleration":2.722845225812026,"curveRadius":24.183660868707783},{"acceleration":-3.0007389270566525,"curvature":0.046821611869777735,"pose":{"rotation":{"radians":1.8912967821519526},"translation":{"x":7.337063818080456,"y":1.6994178238565834}},"time":0.7742070611027086,"velocity":2.050484247116964,"position":0.8926561818704472,"holonomicRotation":-123.08760000000001,"angularVelocity":0.08504411980862117,"angularAcceleration":2.77590317078844,"curveRadius":21.357658569748573},{"acceleration":-3.0007437003697497,"curvature":0.05245492262572976,"pose":{"rotation":{"radians":1.8916595273352934},"translation":{"x":7.334627798510223,"y":1.706747556383602}},"time":0.7779949417933664,"velocity":2.039117787996721,"position":0.9003801167655766,"holonomicRotation":-123.45524,"angularVelocity":0.09576468029614692,"angularAcceleration":2.8302265469887997,"curveRadius":19.063987704930636},{"acceleration":-3.0007485096874786,"curvature":0.05825523011187883,"pose":{"rotation":{"radians":1.8920634566140646},"translation":{"x":7.332203616741725,"y":1.7140318378010555}},"time":0.7817809332498077,"velocity":2.027756979776115,"position":0.9080571873667482,"holonomicRotation":-123.82288000000001,"angularVelocity":0.10669048871834366,"angularAcceleration":2.8858513147482308,"curveRadius":17.165840699272938},{"acceleration":-3.0007533481634048,"curvature":0.06422777651792935,"pose":{"rotation":{"radians":1.8925093223016354},"translation":{"x":7.32979099232726,"y":1.7212706173015115}},"time":0.7855650242142682,"velocity":2.016401856144755,"position":0.915687435411307,"holonomicRotation":-124.19052000000002,"angularVelocity":0.11782636616250892,"angularAcceleration":2.9428144166594645,"curveRadius":15.56958771133619},{"acceleration":-3.0007582083143265,"curvature":0.07037798970647652,"pose":{"rotation":{"radians":1.8929978938718721},"translation":{"x":7.327389644819126,"y":1.728463844077539}},"time":0.7893472033922737,"velocity":2.0050524509310397,"position":0.9232709030420273,"holonomicRotation":-124.55816000000002,"angularVelocity":0.12917726718975395,"angularAcceleration":3.0011536981785287,"curveRadius":14.208987840810337},{"acceleration":-3.0007630821923246,"curvature":0.07671148754422581,"pose":{"rotation":{"radians":1.8935299584273007},"translation":{"x":7.324999293769619,"y":1.7356114673217062}},"time":0.7931274594728908,"velocity":1.993708798043091,"position":0.9308076328488094,"holonomicRotation":-124.92580000000001,"angularVelocity":0.14074828373576387,"angularAcceleration":3.0609081234838427,"curveRadius":13.035857236160082},{"acceleration":-3.000767961288414,"curvature":0.08323408737457239,"pose":{"rotation":{"radians":1.8941063211785532},"translation":{"x":7.322619658731039,"y":1.742713436226582}},"time":0.7969057811503245,"velocity":1.9823709314060063,"position":0.9382976679116553,"holonomicRotation":-125.29344,"angularVelocity":0.15254464824815273,"angularAcceleration":3.122117574806652,"curveRadius":12.014308458742052},{"acceleration":-3.000772836503269,"curvature":0.08995181127129794,"pose":{"rotation":{"radians":1.8947278059390875},"translation":{"x":7.32025045925568,"y":1.7497696999847343}},"time":0.8006821571469384,"velocity":1.9710388848949445,"position":0.945741051844965,"holonomicRotation":-125.66108000000001,"angularVelocity":0.16457173784909884,"angularAcceleration":3.184823124532732,"curveRadius":11.117063523979118},{"acceleration":-3.000777698129917,"curvature":0.09687089554357245,"pose":{"rotation":{"radians":1.8953952556297105},"translation":{"x":7.317891414895842,"y":1.7567802077887325}},"time":0.8044565762377744,"velocity":1.9597126922637678,"position":0.9531378288431992,"holonomicRotation":-126.02872000000002,"angularVelocity":0.17683507701713228,"angularAcceleration":3.249066643873116,"curveRadius":10.323018016801557},{"acceleration":-3.0007825357712603,"curvature":0.10399779710780847,"pose":{"rotation":{"radians":1.8961095328003923},"translation":{"x":7.315542245203821,"y":1.763744908831144}},"time":0.8082290272766597,"velocity":1.9483923870692288,"position":0.9604880437279546,"holonomicRotation":-126.39636000000002,"angularVelocity":0.1893403422123438,"angularAcceleration":3.3148913176900616,"curveRadius":9.615588289464998},{"acceleration":-3.000787338405718,"curvature":0.1113392028693276,"pose":{"rotation":{"radians":1.89687152016335},"translation":{"x":7.313202669731914,"y":1.7706637523045383}},"time":0.8119994992239891,"velocity":1.9370780025898688,"position":0.9677917419965085,"holonomicRotation":-126.76400000000001,"angularVelocity":0.20209336486307575,"angularAcceleration":3.3823412105651376,"curveRadius":8.98156241673153},{"acceleration":-3.0007920941661874,"curvature":0.1189020372098145,"pose":{"rotation":{"radians":1.897682121140756},"translation":{"x":7.31087240803242,"y":1.7775366874014833}},"time":0.8157679811762738,"velocity":1.9257695717404448,"position":0.9750489698718715,"holonomicRotation":-127.13164,"angularVelocity":0.21510013519225998,"angularAcceleration":3.4514614887033064,"curveRadius":8.410284831666932},{"acceleration":-3.0007967904967328,"curvature":0.1266934708852212,"pose":{"rotation":{"radians":1.8985422604274358},"translation":{"x":7.308551179657636,"y":1.7843636633145479}},"time":0.8195344623975616,"velocity":1.9144671269801383,"position":0.9822597743544149,"holonomicRotation":-127.49928000000001,"angularVelocity":0.22836680608372933,"angularAcceleration":3.52229842976185,"curveRadius":7.89306657251467},{"acceleration":-3.0008014140401844,"curvature":0.1347209312732251,"pose":{"rotation":{"radians":1.8994528845667564},"translation":{"x":7.306238704159858,"y":1.7911446292363005}},"time":0.8232989323528271,"velocity":1.9031707002152656,"position":0.989424203275117,"holonomicRotation":-127.86692000000002,"angularVelocity":0.24189969640928988,"angularAcceleration":3.5948992783516065,"curveRadius":7.422751539416827},{"acceleration":-3.0008059504477567,"curvature":0.14299210959018271,"pose":{"rotation":{"radians":1.9004149625415039},"translation":{"x":7.303934701091386,"y":1.797879534359309}},"time":0.8270613807434471,"velocity":1.8918803226964405,"position":0.9965423053504919,"holonomicRotation":-128.23456000000002,"angularVelocity":0.25570529476124326,"angularAcceleration":3.669312351598363,"curveRadius":6.99339287227815},{"acceleration":-3.00081038456859,"curvature":0.1515149723534107,"pose":{"rotation":{"radians":1.9014294863807881},"translation":{"x":7.301638890004515,"y":1.8045683278761426}},"time":0.8308217975448785,"velocity":1.880596024908399,"position":1.0036141302392625,"holonomicRotation":-128.6022,"angularVelocity":0.2697902633819946,"angularAcceleration":3.7455870890136573,"curveRadius":6.600007804294659},{"acceleration":-3.0008147002671266,"curvature":0.160297770651815,"pose":{"rotation":{"radians":1.9024974717793324},"translation":{"x":7.2993509904515435,"y":1.8112109589793701}},"time":0.8345801730466583,"velocity":1.8693178364535343,"position":1.0106397286008295,"holonomicRotation":-128.96984000000003,"angularVelocity":0.2841614410370891,"angularAcceleration":3.8237737682913577,"curveRadius":6.23838994100619},{"acceleration":-3.000818880269204,"curvature":0.16934904989369443,"pose":{"rotation":{"radians":1.9036199587340779},"translation":{"x":7.297070721984769,"y":1.8178073768615592}},"time":0.8383364978948605,"velocity":1.8580457859286248,"position":1.0176191521556106,"holonomicRotation":-129.33748000000003,"angularVelocity":0.2988258470996484,"angularAcceleration":3.9039238231958815,"curveRadius":5.9049637457531094},{"acceleration":-3.0008229064147796,"curvature":0.17867766103736157,"pose":{"rotation":{"radians":1.9047980121945576},"translation":{"x":7.294797804156488,"y":1.824357530715279}},"time":0.8420907631371489,"velocity":1.846779900792809,"position":1.0245524537473139,"holonomicRotation":-129.70512000000002,"angularVelocity":0.3137906845819041,"angularAcceleration":3.9860895585347653,"curveRadius":5.596670530575725},{"acceleration":-3.0008267591307125,"curvature":0.18829277097899821,"pose":{"rotation":{"radians":1.9060327227292533},"translation":{"x":7.292531956518998,"y":1.8308613697330975}},"time":0.8458429602705672,"velocity":1.835520207229314,"position":1.031439687407211,"holonomicRotation":-130.07276000000002,"angularVelocity":0.32906334363378426,"angularAcceleration":4.07032426837521,"curveRadius":5.310878345465201},{"acceleration":-3.000830417900444,"curvature":0.198203874546766,"pose":{"rotation":{"radians":1.9073252072051767},"translation":{"x":7.290272898624599,"y":1.8373188431075838}},"time":0.8495930812922257,"velocity":1.8242667299967132,"position":1.0382809084204838,"holonomicRotation":-130.4404,"angularVelocity":0.34465140417037643,"angularAcceleration":4.156681996811479,"curveRadius":5.0453100489922615},{"acceleration":-3.0008338607493084,"curvature":0.20842080449868072,"pose":{"rotation":{"radians":1.9086766094869914},"translation":{"x":7.288020350025584,"y":1.8437299000313059}},"time":0.8533411187530477,"velocity":1.8130194922729215,"position":1.0450761733947234,"holonomicRotation":-130.80804,"angularVelocity":0.360562640032476,"angularAcceleration":4.245217938299276,"curveRadius":4.797985510157312},{"acceleration":-3.000837064326642,"curvature":0.2189537448720541,"pose":{"rotation":{"radians":1.9100881011441997},"translation":{"x":7.285774030274253,"y":1.8500944896968323}},"time":0.8570870658147439,"velocity":1.8017785154891781,"position":1.0518255403306473,"holonomicRotation":-131.17568,"angularVelocity":0.3768050199217719,"angularAcceleration":4.33598756783853,"curveRadius":4.567174681503398},{"acceleration":-3.000840003996673,"curvature":0.2298132420190694,"pose":{"rotation":{"radians":1.9115608821801175},"translation":{"x":7.283533658922905,"y":1.856412561296732}},"time":0.8608309163102043,"velocity":1.790543819153418,"position":1.0585290686951283,"holonomicRotation":-131.54332000000002,"angularVelocity":0.3933867118101279,"angularAcceleration":4.4290475563760925,"curveRadius":4.351359352552113},{"acceleration":-3.0008426534420156,"curvature":0.24101021706579542,"pose":{"rotation":{"radians":1.913096181771988},"translation":{"x":7.281298955523834,"y":1.8626840640235733}},"time":0.8645726648074964,"velocity":1.7793154206642912,"position":1.0651868194966077,"holonomicRotation":-131.91096000000002,"angularVelocity":0.4103160843069931,"angularAcceleration":4.524454946428602,"curveRadius":4.149201690179805},{"acceleration":-3.000844984839883,"curvature":0.2525559790017317,"pose":{"rotation":{"radians":1.9146952590245365},"translation":{"x":7.2790696396293395,"y":1.8689089470699245}},"time":0.8683123066776749,"velocity":1.7680933351130688,"position":1.07179885536298,"holonomicRotation":-132.2786,"angularVelocity":0.42760170841497164,"angularAcceleration":4.622267240566925,"curveRadius":3.959518218308121},{"acceleration":-3.0008469686001864,"curvature":0.2644622373950492,"pose":{"rotation":{"radians":1.9163594037411236},"translation":{"x":7.2768454307917185,"y":1.8750871596283543}},"time":0.8720498381666227,"velocity":1.756877575074412,"position":1.078365240622047,"holonomicRotation":-132.64624000000003,"angularVelocity":0.44525236014948505,"angularAcceleration":4.722542615816802,"curveRadius":3.7812581858566707},{"acceleration":-3.0008485734048707,"curvature":0.27674111520145195,"pose":{"rotation":{"radians":1.9180899372051432},"translation":{"x":7.2746260485632686,"y":1.881218650891431}},"time":0.8757852564711475,"velocity":1.7456681503842084,"position":1.084886041384618,"holonomicRotation":-133.01388000000003,"angularVelocity":0.4632770209225113,"angularAcceleration":4.825339307030988,"curveRadius":3.613485474581745},{"acceleration":-3.000849765970113,"curvature":0.2894051624872118,"pose":{"rotation":{"radians":1.9198882129764152},"translation":{"x":7.272411212496287,"y":1.8873033700517234}},"time":0.8795185598195798,"velocity":1.7344650679047697,"position":1.0913613256303658,"holonomicRotation":-133.38152000000002,"angularVelocity":0.48168487889608946,"angularAcceleration":4.930715844804784,"curveRadius":3.455363378475281},{"acceleration":-3.000850511018348,"curvature":0.3024673699028651,"pose":{"rotation":{"radians":1.9217556176997264},"translation":{"x":7.27020064214307,"y":1.8933412663017999}},"time":0.8832497475571289,"velocity":1.7232683312758401,"position":1.097791163296529,"holonomicRotation":-133.74916000000002,"angularVelocity":0.5004853292474071,"angularAcceleration":5.038730740380013,"curveRadius":3.3061417511619244},{"acceleration":-3.0008507712042087,"curvature":0.3159411824835179,"pose":{"rotation":{"radians":1.9236935719239656},"translation":{"x":7.267994057055916,"y":1.8993322888342292}},"time":0.8869788202362656,"velocity":1.7120779406507762,"position":1.1041756263695623,"holonomicRotation":-134.1168,"angularVelocity":0.51968797365674,"angularAcceleration":5.149442250553965,"curveRadius":3.1651460950399155},{"acceleration":-3.0008505068314464,"curvature":0.3298405134117903,"pose":{"rotation":{"radians":1.9257035309342707},"translation":{"x":7.265791176787124,"y":1.905276386841579}},"time":0.8907057797124222,"velocity":1.7008938924178116,"position":1.1105147889798457,"holonomicRotation":-134.48444,"angularVelocity":0.5393026200483102,"angularAcceleration":5.262908415574723,"curveRadius":3.0317682617463886},{"acceleration":-3.0008496759082117,"curvature":0.3441797580902883,"pose":{"rotation":{"radians":1.927786985592613},"translation":{"x":7.263591720888988,"y":1.911173509516419}},"time":0.8944306292453164,"velocity":1.6897161789042192,"position":1.1168087274995608,"holonomicRotation":-134.85208000000003,"angularVelocity":0.5593392806725064,"angularAcceleration":5.37918658116311,"curveRadius":2.9054584893329816},{"acceleration":-3.0008482339128975,"curvature":0.35897380832585285,"pose":{"rotation":{"radians":1.9299454631865884},"translation":{"x":7.26139540891381,"y":1.9170236060513166}},"time":0.8981533736062122,"velocity":1.6785447880635158,"position":1.1230575206438353,"holonomicRotation":-135.21972000000002,"angularVelocity":0.579808169652552,"angularAcceleration":5.498333217572893,"curveRadius":2.7857185588656255},{"acceleration":-3.0008461336495458,"curvature":0.3742380659048269,"pose":{"rotation":{"radians":1.932180528288095},"translation":{"x":7.259201960413882,"y":1.9228266256388413}},"time":0.9018740191914745,"velocity":1.6673797031443012,"position":1.1292612495752952,"holonomicRotation":-135.58736000000002,"angularVelocity":0.600719700462694,"angularAcceleration":5.62040386027999,"curveRadius":2.672095895916456},{"acceleration":-3.000843325160863,"curvature":0.3899884574051316,"pose":{"rotation":{"radians":1.9344937836138167},"translation":{"x":7.257011094941505,"y":1.9285825174715607}},"time":0.9055925741427611,"velocity":1.656220902339489,"position":1.135419998012114,"holonomicRotation":-135.955,"angularVelocity":0.6220844806720734,"angularAcceleration":5.7454523300744675,"curveRadius":2.564178454546336},{"acceleration":-3.0008397554761403,"curvature":0.40624144742133617,"pose":{"rotation":{"radians":1.9368868708951161},"translation":{"x":7.254822532048975,"y":1.934291230742044}},"time":0.9093090484742545,"velocity":1.6450683584153367,"position":1.1415338523397167,"holonomicRotation":-136.32264,"angularVelocity":0.6439133081104113,"angularAcceleration":5.873531065009635,"curveRadius":2.461590284171184},{"acceleration":-3.0008353685358524,"curvature":0.42301405246046503,"pose":{"rotation":{"radians":1.9393614717458607},"translation":{"x":7.2526359912885905,"y":1.9399527146428595}},"time":0.9130234542073248,"velocity":1.6339220383184472,"position":1.1476029017262366,"holonomicRotation":-136.69028000000003,"angularVelocity":0.6662171632766483,"angularAcceleration":6.004690055170985,"curveRadius":2.3639876599453165},{"acceleration":-3.00083010488381,"curvature":0.4403238543668703,"pose":{"rotation":{"radians":1.9419193085322386},"translation":{"x":7.250451192212648,"y":1.9455669183665754}},"time":0.9167358055130601,"velocity":1.6227819027602919,"position":1.1536272382418724,"holonomicRotation":-137.05792000000002,"angularVelocity":0.6890072021002442,"angularAcceleration":6.138976876565247,"curveRadius":2.2710557015764516},{"acceleration":-3.000823901710363,"curvature":0.4581890136464568,"pose":{"rotation":{"radians":1.9445621452408786},"translation":{"x":7.248267854373446,"y":1.9511337911057605}},"time":0.9204461188631251,"velocity":1.6116479057765818,"position":1.1596069569822796,"holonomicRotation":-137.42556000000002,"angularVelocity":0.7122947469096281,"angularAcceleration":6.276436142240097,"curveRadius":2.1825054076298955},{"acceleration":-3.000816692360453,"curvature":0.4766282811648586,"pose":{"rotation":{"radians":1.9472917883406524},"translation":{"x":7.24608569732328,"y":1.9566532820529834}},"time":0.924154413189423,"velocity":1.6005199942620414,"position":1.1655421561961279,"holonomicRotation":-137.7932,"angularVelocity":0.7360912752842135,"angularAcceleration":6.4171088594097405,"curveRadius":2.0980710535179403},{"acceleration":-3.000808406372006,"curvature":0.49566101124401946,"pose":{"rotation":{"radians":1.9501100876369737},"translation":{"x":7.2439044406144495,"y":1.9621253404008125}},"time":0.9278607100530805,"velocity":1.589398107477068,"position":1.1714329374169732,"holonomicRotation":-138.16084,"angularVelocity":0.7604084076363316,"angularAcceleration":6.561032007598446,"curveRadius":2.017507888082988},{"acceleration":-3.000798969070204,"curvature":0.5153071716186958,"pose":{"rotation":{"radians":1.9530189371165494},"translation":{"x":7.24172380379925,"y":1.9675499153418163}},"time":0.9315650338232989,"velocity":1.5782821765262942,"position":1.1772794055995917,"holonomicRotation":-138.52848,"angularVelocity":0.7852578932116835,"angularAcceleration":6.70823802582637,"curveRadius":1.9405901083401866},{"acceleration":-3.000788301534475,"curvature":0.535587355126432,"pose":{"rotation":{"radians":1.9560202757730871},"translation":{"x":7.23954350642998,"y":1.9729269560685636}},"time":0.9352674118666467,"velocity":1.567172123805958,"position":1.1830816692609176,"holonomicRotation":-138.89612000000002,"angularVelocity":0.8106515924083777,"angularAcceleration":6.858753725141546,"curveRadius":1.86710905406633},{"acceleration":-3.0007763201497575,"curvature":0.5565227872730252,"pose":{"rotation":{"radians":1.959116088419125},"translation":{"x":7.237363268058937,"y":1.9782564117736219}},"time":0.938967874747408,"velocity":1.5560678624197766,"position":1.1888398406257474,"holonomicRotation":-139.26376000000002,"angularVelocity":0.8366014592750199,"angularAcceleration":7.0126002348398755,"curveRadius":1.7968716158057492},{"acceleration":-3.0007629364615913,"curvature":0.5781353353720309,"pose":{"rotation":{"radians":1.962308406469537},"translation":{"x":7.235182808238418,"y":1.9835382316495611}},"time":0.9426664564396381,"velocity":1.544969295560257,"position":1.1945540357773643,"holonomicRotation":-139.6314,"angularVelocity":0.8631195187924084,"angularAcceleration":7.169791483339891,"curveRadius":1.7296988072118074},{"acceleration":-3.000748056867543,"curvature":0.6004475146367044,"pose":{"rotation":{"radians":1.9655993086997898},"translation":{"x":7.233001846520722,"y":1.9887723648889486}},"time":0.9463631945516114,"velocity":1.5338763158540047,"position":1.200224374813235,"holonomicRotation":-139.99904,"angularVelocity":0.8902178435615588,"angularAcceleration":7.330333918267469,"curveRadius":1.665424496935492},{"acceleration":-3.0007315824337506,"curvature":0.6234824926151638,"pose":{"rotation":{"radians":1.968990921968357},"translation":{"x":7.230820102458143,"y":1.9939587606843534}},"time":0.9500581305634029,"velocity":1.5227888046683502,"position":1.205850982005957,"holonomicRotation":-140.36668000000003,"angularVelocity":0.917908526086425,"angularAcceleration":7.494225187255793,"curveRadius":1.6038942742490712},{"acceleration":-3.0007134083951095,"curvature":0.6472640924227719,"pose":{"rotation":{"radians":1.9724854218988015},"translation":{"x":7.228637295602981,"y":1.9990973682283442}},"time":0.9537513100783709,"velocity":1.5117066313781757,"position":1.2114339859696042,"holonomicRotation":-140.73432000000003,"angularVelocity":0.946203648179504,"angularAcceleration":7.661453221648909,"curveRadius":1.5449644306034396},{"acceleration":-3.000693423974555,"curvature":0.6718167927478627,"pose":{"rotation":{"radians":1.976085033517589},"translation":{"x":7.226453145507533,"y":2.0041881367134895}},"time":0.9574427830893776,"velocity":1.5006296525892684,"position":1.2169735198316538,"holonomicRotation":-141.10196000000002,"angularVelocity":0.975115247505461,"angularAcceleration":7.831995314540456,"curveRadius":1.488501047897007},{"acceleration":-3.0006715121309853,"curvature":0.6971657260691185,"pose":{"rotation":{"radians":1.9797920318349291},"translation":{"x":7.224267371724096,"y":2.009231015332357}},"time":0.9611326042606189,"velocity":1.489557711315867,"position":1.2224697214106528,"holonomicRotation":-141.4696,"angularVelocity":1.004655278752454,"angularAcceleration":8.005816508732224,"curveRadius":1.4343791764382545},{"acceleration":-3.000647548940926,"curvature":0.723336673579645,"pose":{"rotation":{"radians":1.9836087423649496},"translation":{"x":7.222079693804968,"y":2.014225953277516}},"time":0.9648208332260018,"velocity":1.4784906361109578,"position":1.2279227333998046,"holonomicRotation":-141.83724,"angularVelocity":1.034835571718411,"angularAcceleration":8.182868593361231,"curveRadius":1.3824820951649042},{"acceleration":-3.000621403552423,"curvature":0.7503560567307656,"pose":{"rotation":{"radians":1.9875375415771057},"translation":{"x":7.219889831302446,"y":2.0191728997415344}},"time":0.9685075349050565,"velocity":1.4674282401442735,"position":1.2333327035566368,"holonomicRotation":-142.20488,"angularVelocity":1.0656677849680323,"angularAcceleration":8.363088726377981,"curveRadius":1.332700643954166},{"acceleration":-3.0005929375303424,"curvature":0.7782509254506629,"pose":{"rotation":{"radians":1.991580857264314},"translation":{"x":7.217697503768828,"y":2.0240718039169816}},"time":0.972192779837447,"velocity":1.456370320227073,"position":1.2386997848989376,"holonomicRotation":-142.57252000000003,"angularVelocity":1.0971633531521041,"angularAcceleration":8.546397529035179,"curveRadius":1.284932619156127},{"acceleration":-3.0005620046106536,"curvature":0.80704894154379,"pose":{"rotation":{"radians":1.9957411688252373},"translation":{"x":7.21550243075641,"y":2.0289226149964255}},"time":0.9758766445371934,"velocity":1.4453166557788877,"position":1.244024135907117,"holonomicRotation":-142.94016000000002,"angularVelocity":1.1293334310594187,"angularAcceleration":8.732698003140467,"curveRadius":1.239082227265074},{"acceleration":-3.000528450277846,"curvature":0.836778358094789,"pose":{"rotation":{"radians":2.0000210074410245},"translation":{"x":7.21330433181749,"y":2.0337252821724348}},"time":0.97955921186781,"velocity":1.4342670077333086,"position":1.249305920733177,"holonomicRotation":-143.30780000000001,"angularVelocity":1.1621888295713771,"angularAcceleration":8.921873128781746,"curveRadius":1.195059588152878},{"acceleration":-3.00049211116248,"curvature":0.8674679936581415,"pose":{"rotation":{"radians":2.0044229561425126},"translation":{"x":7.211102926504366,"y":2.038479754637578}},"time":0.9832405714396266,"velocity":1.4232211173797205,"position":1.2545453094164543,"holonomicRotation":-143.67544,"angularVelocity":1.1957399475965793,"angularAcceleration":9.113784559938045,"curveRadius":1.1527802838960854},{"acceleration":-3.0004528148551235,"curvature":0.8991471997401072,"pose":{"rotation":{"radians":2.008949649750133},"translation":{"x":7.208897934369335,"y":2.0431859815844233}},"time":0.9869208200306518,"velocity":1.4121787051354122,"position":1.2597424781063047,"holonomicRotation":-144.04308000000003,"angularVelocity":1.2299966960545607,"angularAcceleration":9.308270246070077,"curveRadius":1.1121649495088721},{"acceleration":-3.0004103790598364,"curvature":0.9318458230183916,"pose":{"rotation":{"radians":2.0136037746726436},"translation":{"x":7.206689074964695,"y":2.0478439122055394}},"time":0.9906000620324199,"velocity":1.4011394692462344,"position":1.2648976092918904,"holonomicRotation":-144.41072000000003,"angularVelocity":1.2649684147642253,"angularAcceleration":9.50514228008348,"curveRadius":1.0731388984079433},{"acceleration":-3.0003646114337874,"curvature":0.9655941601803909,"pose":{"rotation":{"radians":2.01838806855205},"translation":{"x":7.204476067842743,"y":2.052453495693495}},"time":0.9942784099223643,"velocity":1.3901030844087032,"position":1.2700108920392303,"holonomicRotation":-144.77836000000002,"angularVelocity":1.3006637823696572,"angularAcceleration":9.704184778991033,"curveRadius":1.0356317811752107},{"acceleration":-3.0003153088702743,"curvature":1.000422904245272,"pose":{"rotation":{"radians":2.0233053197365383},"translation":{"x":7.202258632555775,"y":2.057014681240858}},"time":0.9979559847643585,"velocity":1.3790692003107516,"position":1.2750825222356623,"holonomicRotation":-145.14600000000002,"angularVelocity":1.337090717594109,"angularAcceleration":9.905151299299783,"curveRadius":0.9995772745271252},{"acceleration":-3.000262256872613,"curvature":1.0363630835013706,"pose":{"rotation":{"radians":2.028358366563374},"translation":{"x":7.200036488656091,"y":2.0615274180401983}},"time":1.00163291673918,"velocity":1.3680374400856068,"position":1.280112702841866,"holonomicRotation":-145.51364,"angularVelocity":1.3742562716519457,"angularAcceleration":10.10776220836712,"curveRadius":0.964912795447598},{"acceleration":-3.000205229292144,"curvature":1.07344599001726,"pose":{"rotation":{"radians":2.033550096435718},"translation":{"x":7.197809355695987,"y":2.065991655284083}},"time":1.0053093457067641,"velocity":1.3570073986719398,"position":1.2851016441515695,"holonomicRotation":-145.88128,"angularVelocity":1.4121665121563463,"angularAcceleration":10.311702154091176,"curveRadius":0.931579240408659},{"acceleration":-3.00014398725061,"curvature":1.1117030982577012,"pose":{"rotation":{"radians":2.0388834446704847},"translation":{"x":7.19557695322776,"y":2.0704073421650806}},"time":1.0089854218022603,"velocity":1.3459786410773613,"position":1.2900495640590823,"holonomicRotation":-146.24892000000003,"angularVelocity":1.4508263964668553,"angularAcceleration":10.516616986757816,"curveRadius":0.8995207457523812},{"acceleration":-3.000078279032431,"curvature":1.1511659729759487,"pose":{"rotation":{"radians":2.0443613930959237},"translation":{"x":7.193339000803708,"y":2.0747744278757607}},"time":1.0126613060680156,"velocity":1.3349507005354315,"position":1.2949566883347396,"holonomicRotation":-146.61656000000002,"angularVelocity":1.4902396347109503,"angularAcceleration":10.722110761557333,"curveRadius":0.8686844672926177},{"acceleration":-3.0000078389707383,"curvature":1.1918661638021095,"pose":{"rotation":{"radians":2.0499869683799745},"translation":{"x":7.1910952179761285,"y":2.0790928616086912}},"time":1.016337171123786,"velocity":1.3239230765531216,"position":1.2998232509083694,"holonomicRotation":-146.98420000000002,"angularVelocity":1.5304085429413943,"angularAcceleration":10.927742890720651,"curveRadius":0.8390203786052224},{"acceleration":-2.9999323871026484,"curvature":1.2338350876702466,"pose":{"rotation":{"radians":2.0557632400588464},"translation":{"x":7.1888453242973185,"y":2.0833625925564405}},"time":1.020013201877623,"velocity":1.3128952328387011,"position":1.3046494941608502,"holonomicRotation":-147.35184000000004,"angularVelocity":1.5713338831137136,"angularAcceleration":11.13302442576245,"curveRadius":0.8104810845412258},{"acceleration":-2.999851628273743,"curvature":1.2771038965956416,"pose":{"rotation":{"radians":2.061693318245822},"translation":{"x":7.186589039319577,"y":2.0875835699115775}},"time":1.0236895962800638,"velocity":1.3018665951043622,"position":1.3094356692238167,"holonomicRotation":-147.71948000000003,"angularVelocity":1.6130146926125497,"angularAcceleration":11.337415123677198,"curveRadius":0.7830216497386675},{"acceleration":-2.999765251583911,"curvature":1.321703329517619,"pose":{"rotation":{"radians":2.0677803509910895},"translation":{"x":7.184326082595199,"y":2.09175574286667}},"time":1.0273665661244487,"velocity":1.2908365487340547,"position":1.3141820362875416,"holonomicRotation":-148.08712000000003,"angularVelocity":1.6554481007134145,"angularAcceleration":11.540319854857081,"curveRadius":0.7565994407874944},{"acceleration":-2.999672929306355,"curvature":1.3676635482706017,"pose":{"rotation":{"radians":2.0740275212613},"translation":{"x":7.182056173676482,"y":2.0958790606142874}},"time":1.0310443378963847,"velocity":1.279804436309611,"position":1.3188888649169996,"holonomicRotation":-148.45476000000002,"angularVelocity":1.6986291313345498,"angularAcceleration":11.741084901090476,"curveRadius":0.7311739800804745},{"acceleration":-2.99957431657141,"curvature":1.41501395595663,"pose":{"rotation":{"radians":2.0804380435148264},"translation":{"x":7.179779032115726,"y":2.0999534723469977}},"time":1.0347231536756196,"velocity":1.2687695549828204,"position":1.3235564343760833,"holonomicRotation":-148.82240000000002,"angularVelocity":1.74255049402329,"angularAcceleration":11.938994862600802,"curveRadius":0.7067068107635328},{"acceleration":-2.9994690501070673,"curvature":1.4637829953714203,"pose":{"rotation":{"radians":2.0870151598365716},"translation":{"x":7.1774943774652264,"y":2.1039789272573692}},"time":1.038403272093827,"velocity":1.2577311536866784,"position":1.3281850339599188,"holonomicRotation":-149.19004,"angularVelocity":1.787202359903673,"angularAcceleration":12.133268771860182,"curveRadius":0.6831613723906255},{"acceleration":-2.999356747733838,"curvature":1.5139979284498906,"pose":{"rotation":{"radians":2.093762135600808},"translation":{"x":7.17520192927728,"y":2.107955374537971}},"time":1.0420849693520753,"velocity":1.2466884301720382,"position":1.332774963335173,"holonomicRotation":-149.55768,"angularVelocity":1.8325721239356718,"angularAcceleration":12.323056690865757,"curveRadius":0.6605028852475722},{"acceleration":-2.9992370073576295,"curvature":1.5656845940015502,"pose":{"rotation":{"radians":2.100682254629673},"translation":{"x":7.172901407104186,"y":2.1118827633813706}},"time":1.0457685403020536,"velocity":1.2356405278596359,"position":1.3373265328882127,"holonomicRotation":-149.92532000000003,"angularVelocity":1.878644153414722,"angularAcceleration":12.50743642641708,"curveRadius":0.6386982434592505},{"acceleration":-2.999109405980778,"curvature":1.618867143085465,"pose":{"rotation":{"radians":2.107778813812079},"translation":{"x":7.170592530498242,"y":2.1157610429801377}},"time":1.0494542995954612,"velocity":1.224586532494596,"position":1.3418400640809365,"holonomicRotation":-150.29296000000002,"angularVelocity":1.9253995221823879,"angularAcceleration":12.685410263033889,"curveRadius":0.6177159158929244},{"acceleration":-2.9989734990981654,"curvature":1.6735677505386393,"pose":{"rotation":{"radians":2.115055117146915},"translation":{"x":7.168275019011743,"y":2.11959016252684}},"time":1.0531425829063155,"velocity":1.213525468588178,"position":1.3463158898140268,"holonomicRotation":-150.66060000000002,"angularVelocity":1.9728157306740917,"angularAcceleration":12.855901918424403,"curveRadius":0.5975258543779594},{"acceleration":-2.998828819387716,"curvature":1.7298063036159914,"pose":{"rotation":{"radians":2.122514469172561},"translation":{"x":7.1659485921969885,"y":2.123370071214047}},"time":1.0568337482313421,"velocity":1.2024562956343634,"position":1.3507543547973324,"holonomicRotation":-151.02824000000004,"angularVelocity":2.020866411772536,"angularAcceleration":13.017753708470664,"curveRadius":0.5780994079566004},{"acceleration":-2.998674876010883,"curvature":1.7876000629303959,"pose":{"rotation":{"radians":2.1301601677530337},"translation":{"x":7.163612969606275,"y":2.127100718234326}},"time":1.0605281772740547,"velocity":1.1913779040827763,"position":1.3551558159270218,"holonomicRotation":-151.39588000000003,"angularVelocity":2.0695210253271004,"angularAcceleration":13.169724737449785,"curveRadius":0.5594092441240517},{"acceleration":-2.9985111534893805,"curvature":1.8469633003966965,"pose":{"rotation":{"radians":2.137995496172608},"translation":{"x":7.1612678707919,"y":2.1307820527802463}},"time":1.0642262769186124,"velocity":1.180289111051855,"position":1.359520642669078,"holonomicRotation":-151.76352000000003,"angularVelocity":2.1187445371043725,"angularAcceleration":13.310488225949202,"curveRadius":0.5414292746289094},{"acceleration":-2.998337110658555,"curvature":1.9079069076543327,"pose":{"rotation":{"radians":2.146023714516414},"translation":{"x":7.158913015306162,"y":2.134414024044376}},"time":1.0679284808000966,"velocity":1.1691886557627766,"position":1.3638492174486303,"holonomicRotation":-152.13116000000002,"angularVelocity":2.1684970900596414,"angularAcceleration":13.438631298534226,"curveRadius":0.5241345874833303},{"acceleration":-2.998152179659442,"curvature":1.970437980950084,"pose":{"rotation":{"radians":2.1542480502883734},"translation":{"x":7.1565481227013565,"y":2.1379965812192836}},"time":1.071635250978462,"velocity":1.1580751946730141,"position":1.3681419360445488,"holonomicRotation":-152.49880000000002,"angularVelocity":2.2187336619791025,"angularAcceleration":13.552653523724983,"curveRadius":0.5075013827726925},{"acceleration":-2.997955764816024,"curvature":2.034559377035259,"pose":{"rotation":{"radians":2.1626716882431074},"translation":{"x":7.154172912529782,"y":2.141529673497538}},"time":1.075347079724087,"velocity":1.1469472962870577,"position":1.372399207988624,"holonomicRotation":-152.86644,"angularVelocity":2.2694037176856723,"angularAcceleration":13.650968075047189,"curveRadius":0.4915069136282426},{"acceleration":-2.9977472414972515,"curvature":2.1002692441559283,"pose":{"rotation":{"radians":2.1712977593928215},"translation":{"x":7.151787104343737,"y":2.1450132500717074}},"time":1.0790644914236296,"velocity":1.1358034356192441,"position":1.3766214569685757,"holonomicRotation":-153.23408000000003,"angularVelocity":2.320450853150164,"angularAcceleration":13.731902622131408,"curveRadius":0.47612943092059956},{"acceleration":-2.997525954802018,"curvature":2.1675605270620544,"pose":{"rotation":{"radians":2.1801293291631825},"translation":{"x":7.149390417695516,"y":2.1484472601343603}},"time":1.0827880446157454,"velocity":1.124641988281791,"position":1.3808091212340299,"holonomicRotation":-153.60172000000003,"angularVelocity":2.371812436857552,"angularAcceleration":13.793702159577123,"curveRadius":0.4613481319275618},{"acceleration":-2.9972912185772134,"curvature":2.2364204497639473,"pose":{"rotation":{"radians":2.1891693846688196},"translation":{"x":7.14698257213742,"y":2.151831652878066}},"time":1.0865183341672024,"velocity":1.1134612241664585,"position":1.3849626540044906,"holonomicRotation":-153.96936000000002,"angularVelocity":2.4234192496145788,"angularAcceleration":13.834532693814367,"curveRadius":0.44714311215744307},{"acceleration":-2.9970423138456206,"curvature":2.3068299724549317,"pose":{"rotation":{"radians":2.198420821094302},"translation":{"x":7.144563287221742,"y":2.1551663774953913}},"time":1.0902559936010354,"velocity":1.1022593006885169,"position":1.3890825238782392,"holonomicRotation":-154.33700000000005,"angularVelocity":2.4751951292670236,"angularAcceleration":13.852487250115393,"curveRadius":0.4334953212593291},{"acceleration":-2.99677848753046,"curvature":2.3787632341619487,"pose":{"rotation":{"radians":2.207886427148948},"translation":{"x":7.142132282500784,"y":2.158451383178906}},"time":1.0940016975896156,"velocity":1.0910342555548826,"position":1.3931692152409487,"holonomicRotation":-154.70464000000004,"angularVelocity":2.527056618329837,"angularAcceleration":13.845591969073721,"curveRadius":0.4203865208772261},{"acceleration":-2.9964989509824838,"curvature":2.4521869741687508,"pose":{"rotation":{"radians":2.217568869605404},"translation":{"x":7.139689277526841,"y":2.1616866191211783}},"time":1.0977561646269611,"velocity":1.0797839990159785,"position":1.3972232286727073,"holonomicRotation":-155.07228000000003,"angularVelocity":2.5789126286488413,"angularAcceleration":13.811816644864646,"curveRadius":0.40779924636007125},{"acceleration":-2.996202878357667,"curvature":2.5270599435803756,"pose":{"rotation":{"radians":2.227470676899904},"translation":{"x":7.13723399185221,"y":2.1648720345147767}},"time":1.1015201598962128,"velocity":1.0685063055561221,"position":1.401245081351986,"holonomicRotation":-155.43992000000003,"angularVelocity":2.630664117829387,"angularAcceleration":13.749084544103313,"curveRadius":0.3957167706054433},{"acceleration":-2.9958894049770923,"curvature":2.6033323100021044,"pose":{"rotation":{"radians":2.237594221809801},"translation":{"x":7.13476614502919,"y":2.16800757855227}},"time":1.1052944983500796,"velocity":1.0571988049713847,"position":1.4052353074549717,"holonomicRotation":-155.80756000000002,"angularVelocity":2.682203791110761,"angularAcceleration":13.655286591633153,"curveRadius":0.384123070327196},{"acceleration":-2.995557625220249,"curvature":2.6809450582363357,"pose":{"rotation":{"radians":2.2479417032248414},"translation":{"x":7.132285456610078,"y":2.171093200426226}},"time":1.109080048024194,"velocity":1.0458589727794414,"position":1.4091944585485465,"holonomicRotation":-156.17520000000002,"angularVelocity":2.7334158327908846,"angularAcceleration":13.528297364663386,"curveRadius":0.3730027950135807},{"acceleration":-2.995206590735083,"curvature":2.7598293979663606,"pose":{"rotation":{"radians":2.258515127030757},"translation":{"x":7.12979164614717,"y":2.174128849329214}},"time":1.112877733605767,"velocity":1.0344841198959747,"position":1.4131231039750416,"holonomicRotation":-156.54284,"angularVelocity":2.784175671946075,"angularAcceleration":13.365993067326844,"curveRadius":0.3623412377362425},{"acceleration":-2.9948353079093137,"curvature":2.8399061836880684,"pose":{"rotation":{"radians":2.2693162861509233},"translation":{"x":7.127284433192765,"y":2.177114474453803}},"time":1.1166885402827895,"velocity":1.0230713815080108,"position":1.417021831226763,"holonomicRotation":-156.91048,"angularVelocity":2.8343497940454947,"angularAcceleration":13.166273272781401,"curveRadius":0.35212430809997447},{"acceleration":-2.994442735133162,"curvature":2.9210853558353844,"pose":{"rotation":{"radians":2.2803467397972117},"translation":{"x":7.12476353729916,"y":2.180050024992559}},"time":1.1205135179023096,"velocity":1.011617705063192,"position":1.42089124630814,"holonomicRotation":-157.27812000000003,"angularVelocity":2.883795604449177,"angularAcceleration":12.927084893606947,"curveRadius":0.34233850715875974},{"acceleration":-2.9940277800688038,"curvature":3.0032654141156834,"pose":{"rotation":{"radians":2.2916077919954954},"translation":{"x":7.122228678018651,"y":2.1829354501380536}},"time":1.1243537854701564,"velocity":1.0001198372821614,"position":1.424731974083215,"holonomicRotation":-157.64576000000002,"angularVelocity":2.9323613522579426,"angularAcceleration":12.64644896501195,"curveRadius":0.33297090403661567},{"acceleration":-2.9935892959619235,"curvature":3.0863329328557914,"pose":{"rotation":{"radians":2.303100469473926},"translation":{"x":7.119679574903537,"y":2.185770699082853}},"time":1.1282105360289014,"velocity":0.9885743100923071,"position":1.4285446586060244,"holonomicRotation":-158.01340000000005,"angularVelocity":2.9798861252179245,"angularAcceleration":12.322490717534626,"curveRadius":0.32400911429691337},{"acceleration":-2.9931260777164312,"curvature":3.1701621307443215,"pose":{"rotation":{"radians":2.314825499013823},"translation":{"x":7.1171159475061145,"y":2.188555721019527}},"time":1.1320850419561077,"velocity":0.9769774253633191,"position":1.4323299634313413,"holonomicRotation":-158.38104000000004,"angularVelocity":3.026199923341271,"angularAcceleration":11.953472002233115,"curveRadius":0.315441279896057},{"acceleration":-2.992636857088478,"curvature":3.2546145087977463,"pose":{"rotation":{"radians":2.326783284385096},"translation":{"x":7.114537515378683,"y":2.1912904651406433}},"time":1.1359786607309654,"velocity":0.9653252383102282,"position":1.43608857190307,"holonomicRotation":-158.74868000000004,"angularVelocity":3.071123821491763,"angularAcceleration":11.53782656909795,"curveRadius":0.3072560505389622},{"acceleration":-2.9921202973947763,"curvature":3.3395385670346522,"pose":{"rotation":{"radians":2.3389738830102376},"translation":{"x":7.111943998073537,"y":2.1939748806387716}},"time":1.1398928412246332,"velocity":0.9536135394074582,"position":1.4398211874175162,"holonomicRotation":-159.11632000000003,"angularVelocity":3.1144702307067713,"angularAcceleration":11.074197851921406,"curveRadius":0.2994425666681105},{"acceleration":-2.9915749868519668,"curvature":3.4247696197179582,"pose":{"rotation":{"radians":2.3513969825102823},"translation":{"x":7.109335115142976,"y":2.196608916706479}},"time":1.1438291305780162,"velocity":0.941837834636866,"position":1.4435285336586106,"holonomicRotation":-159.48396000000002,"angularVelocity":3.1560432642910046,"angularAcceleration":10.561478044926773,"curveRadius":0.2919904434571437},{"acceleration":-2.9373864698847605,"curvature":3.5101297174776325,"pose":{"rotation":{"radians":2.364051877327777},"translation":{"x":7.106710586139297,"y":2.199192522536335}},"time":1.1477882664560137,"velocity":0.9302083224764006,"position":1.4472113548021388,"holonomicRotation":-159.85160000000002,"angularVelocity":3.1963779995081265,"angularAcceleration":10.187762294615224,"curveRadius":0.2848897563588039},{"acceleration":-2.8231849524500614,"curvature":3.595427695694556,"pose":{"rotation":{"radians":2.376937445618934},"translation":{"x":7.104070130614796,"y":2.2017256473209073}},"time":1.1517699763671267,"velocity":0.9189672189703251,"position":1.450870415685901,"holonomicRotation":-160.21924,"angularVelocity":3.236189621748491,"angularAcceleration":9.998624492771182,"curveRadius":0.2781310276931664},{"acceleration":-2.703100742963897,"curvature":3.680459363488766,"pose":{"rotation":{"radians":2.390052126644017},"translation":{"x":7.101413468121772,"y":2.2042082402527656}},"time":1.1557738400351578,"velocity":0.9081443721145441,"position":1.4545065019427372,"holonomicRotation":-160.58688,"angularVelocity":3.2755063889405807,"angularAcceleration":9.819706776235982,"curveRadius":0.2717052142784927},{"acceleration":-2.584531471861522,"curvature":3.7650078438505594,"pose":{"rotation":{"radians":2.4033938989029133},"translation":{"x":7.098740318212522,"y":2.2066402505244773}},"time":1.1597994126222926,"velocity":0.8977401530708313,"position":1.4581204200933093,"holonomicRotation":-160.95452000000003,"angularVelocity":3.314254548914384,"angularAcceleration":9.625502741557293,"curveRadius":0.2656036963198667},{"acceleration":-2.4673963033343824,"curvature":3.848844083615874,"pose":{"rotation":{"radians":2.4169602592700676},"translation":{"x":7.096050400439344,"y":2.209021627328611}},"time":1.1638462242301513,"velocity":0.8877550650693101,"position":1.4617129975955672,"holonomicRotation":-161.32216000000003,"angularVelocity":3.352357777369513,"angularAcceleration":9.415617070271857,"curveRadius":0.2598182670628034},{"acceleration":-2.351617219339541,"curvature":3.9317275398802787,"pose":{"rotation":{"radians":2.4307482034157193},"translation":{"x":7.093343434354534,"y":2.2113523198577356}},"time":1.1679137794766739,"velocity":0.8781897321109727,"position":1.4652850828478574,"holonomicRotation":-161.68980000000005,"angularVelocity":3.3897373999871774,"angularAcceleration":9.189702499952775,"curveRadius":0.2543411235536555},{"acceleration":-2.2371188551783825,"curvature":4.013407057016053,"pose":{"rotation":{"radians":2.4447542077988027},"translation":{"x":7.09061913951039,"y":2.2136322773044195}},"time":1.1720015571572304,"velocity":0.8690448875860223,"position":1.4688375451427333,"holonomicRotation":-162.05744000000004,"angularVelocity":3.426312651420033,"angularAcceleration":8.94746590716635,"curveRadius":0.2491648581351463},{"acceleration":-2.1238283542562324,"curvature":4.093621937888948,"pose":{"rotation":{"radians":2.4589742135394337},"translation":{"x":7.08787723545921,"y":2.2158614488612316}},"time":1.1761090099984621,"velocity":0.860321362778044,"position":1.4723712745686484,"holonomicRotation":-162.42508000000004,"angularVelocity":3.4620009748832103,"angularAcceleration":8.688675157734888,"curveRadius":0.24428245088888034},{"acceleration":-2.0116752206028443,"curvature":4.172103216794246,"pose":{"rotation":{"radians":2.4734036124746113},"translation":{"x":7.085117441753291,"y":2.2180397837207395}},"time":1.1802355645129479,"velocity":0.8520200753147863,"position":1.475887181856871,"holonomicRotation":-162.79272000000003,"angularVelocity":3.4967183602022085,"angularAcceleration":8.413165316761782,"curveRadius":0.23968726276345062},{"acceleration":-1.9005911989565554,"curvature":4.248575133381858,"pose":{"rotation":{"radians":2.4880372357106477},"translation":{"x":7.082339477944929,"y":2.2201672310755125}},"time":1.184380620962877,"velocity":0.8441420175068727,"position":1.4793861981711942,"holonomicRotation":-163.16036000000003,"angularVelocity":3.5303797216769532,"angularAcceleration":8.120845127530016,"curveRadius":0.23537302945234764},{"acceleration":-1.7905101501527916,"curvature":4.32275680539017,"pose":{"rotation":{"radians":2.5028693449778565},"translation":{"x":7.079543063586424,"y":2.2222437401181185}},"time":1.1885435534401811,"velocity":0.8366882446518591,"position":1.482869274838234,"holonomicRotation":-163.52800000000002,"angularVelocity":3.5628993139024523,"angularAcceleration":7.811703024921295,"curveRadius":0.23133385592108055},{"acceleration":-1.6813679268067532,"curvature":4.394364091286049,"pose":{"rotation":{"radians":2.5178936270861585},"translation":{"x":7.076727918230072,"y":2.224269260041127}},"time":1.192723710069862,"velocity":0.8296598633656851,"position":1.4863373830164621,"holonomicRotation":-163.89564000000001,"angularVelocity":3.5941911845176606,"angularAcceleration":7.485812946104223,"curveRadius":0.22756421161891963},{"acceleration":-1.5731022652662836,"curvature":4.463111632963981,"pose":{"rotation":{"radians":2.5331031917584386},"translation":{"x":7.073893761428171,"y":2.2262437400371056}},"time":1.1969204133426081,"velocity":0.8230580199406777,"position":1.4897915133024071,"holonomicRotation":-164.26328,"angularVelocity":3.6241696598024293,"angularAcceleration":7.143339268099409,"curveRadius":0.22405892620164947},{"acceleration":-1.4656526873225997,"curvature":4.528715059444202,"pose":{"rotation":{"radians":2.5484905731047434},"translation":{"x":7.071040312733017,"y":2.228167129298623}},"time":1.2011329605820034,"velocity":0.8168838887587847,"position":1.4932326752729044,"holonomicRotation":-164.63092000000003,"angularVelocity":3.65274986174727,"angularAcceleration":6.784541589839528,"curveRadius":0.22081318583172854},{"acceleration":-1.3589604018052241,"curvature":4.590893331001775,"pose":{"rotation":{"radians":2.56404773496331},"translation":{"x":7.068167291696909,"y":2.230039377018248}},"time":1.2053606245503827,"velocity":0.8111386608336184,"position":1.4966618969626702,"holonomicRotation":-164.99856000000003,"angularVelocity":3.6798482506949317,"angularAcceleration":6.409778343393168,"curveRadius":0.21782252993052897},{"acceleration":-1.252968205935219,"curvature":4.649371194542283,"pose":{"rotation":{"radians":2.5797660803037226},"translation":{"x":7.065274417872144,"y":2.2318604323885483}},"time":1.2096026541960652,"velocity":0.8058235325589437,"position":1.5000802242769737,"holonomicRotation":-165.36620000000005,"angularVelocity":3.7053831899573426,"angularAcceleration":6.019509856184184,"curveRadius":0.21508284844493838},{"acceleration":-1.1476204050505312,"curvature":4.703881721788187,"pose":{"rotation":{"radians":2.595636464836288},"translation":{"x":7.062361410811019,"y":2.2336302446020935}},"time":1.2138582755435858,"velocity":0.8009396946643603,"position":1.503488720339664,"holonomicRotation":-165.73384000000004,"angularVelocity":3.7292755244334685,"angularAcceleration":5.614299893021651,"curveRadius":0.21259037942387898},{"acceleration":-1.0428627261069876,"curvature":4.754168889764762,"pose":{"rotation":{"radians":2.611649214935282},"translation":{"x":7.059427990065831,"y":2.2353487628514515}},"time":1.2181266927268586,"velocity":0.7964883214844506,"position":1.5068884647773644,"holonomicRotation":-166.10148000000004,"angularVelocity":3.7514491699043275,"angularAcceleration":5.19481684165127,"curveRadius":0.2103417070758461},{"acceleration":-0.9386422350132517,"curvature":4.799990168229456,"pose":{"rotation":{"radians":2.6277941499113737},"translation":{"x":7.056473875188878,"y":2.2370159363291906}},"time":1.2224070891635697,"velocity":0.7924705606063533,"position":1.5102805529411822,"holonomicRotation":-166.46912000000003,"angularVelocity":3.7718317017610374,"angularAcceleration":4.761832731636234,"curveRadius":0.20833376006035947},{"acceleration":-0.834907277138482,"curvature":4.8411190688661465,"pose":{"rotation":{"radians":2.6440606086265914},"translation":{"x":7.053498785732459,"y":2.2386317142278798}},"time":1.226698628867915,"velocity":0.7888875228770668,"position":1.5136660950678718,"holonomicRotation":-166.83676000000003,"angularVelocity":3.7903549392185805,"angularAcceleration":4.316221853613034,"curveRadius":0.20656381009736519},{"acceleration":-0.7316073874942312,"curvature":4.8773476108075355,"pose":{"rotation":{"radians":2.660437480369346},"translation":{"x":7.050502441248869,"y":2.2401960457400873}},"time":1.231000457896305,"velocity":0.7857402729801595,"position":1.517046215382953,"holonomicRotation":-167.20440000000002,"angularVelocity":3.8069555146601477,"angularAcceleration":3.8589575113309356,"curveRadius":0.20502947089195298},{"acceleration":-0.628693232591384,"curvature":4.9084886608698355,"pose":{"rotation":{"radians":2.676913239842217},"translation":{"x":7.047484561290406,"y":2.2417088800583826}},"time":1.2353117059195768,"velocity":0.7830298205239055,"position":1.5204220511488495,"holonomicRotation":-167.57204000000002,"angularVelocity":3.821575419446024,"angularAcceleration":3.39110733294831,"curveRadius":0.20372869717963035},{"acceleration":-0.5261165488325613,"curvature":4.934378099188908,"pose":{"rotation":{"radians":2.6934759860578414},"translation":{"x":7.0444448654093685,"y":2.2431701663753327}},"time":1.239631487913451,"velocity":0.7807571117295794,"position":1.523794751661688,"holonomicRotation":-167.93968000000004,"angularVelocity":3.8341625200327734,"angularAcceleration":2.9138277358902442,"curveRadius":0.20265978404945814},{"acceleration":-0.4238300699364113,"curvature":4.954876769937344,"pose":{"rotation":{"radians":2.710113484859925},"translation":{"x":7.041383073158052,"y":2.2445798538835064}},"time":1.2439589059570133,"velocity":0.7789230218375323,"position":1.527165477200934,"holonomicRotation":-168.30732000000003,"angularVelocity":3.8446710335355445,"angularAcceleration":2.428356446496759,"curveRadius":0.20182136638943},{"acceleration":-0.32178747921847606,"curvature":4.969872176359048,"pose":{"rotation":{"radians":2.726813214731485},"translation":{"x":7.038298904088755,"y":2.2459378917754727}},"time":1.2482930511279533,"velocity":0.7775283481884085,"position":1.5305353979365037,"holonomicRotation":-168.67496000000003,"angularVelocity":3.8530619563761026,"angularAcceleration":1.9360041045275498,"curveRadius":0.2012124184514952},{"acceleration":-0.21994334706634908,"curvature":4.979279882901402,"pose":{"rotation":{"radians":2.7435624154925655},"translation":{"x":7.035192077753775,"y":2.2472442292438006}},"time":1.2526330054815604,"velocity":0.776573804101761,"position":1.5339056927985124,"holonomicRotation":-169.04260000000005,"angularVelocity":3.8593034387929843,"angularAcceleration":1.4381447149770485,"curveRadius":0.20083225356219683},{"acceleration":-0.11825306673271961,"curvature":4.9830445947290265,"pose":{"rotation":{"radians":2.7603481394306466},"translation":{"x":7.03206231370541,"y":2.2484988154810575}},"time":1.25697784409908,"velocity":0.7760600136107806,"position":1.5372775483151613,"holonomicRotation":-169.41024000000004,"angularVelocity":3.8633710974664406,"angularAcceleration":0.9362047780219904,"curveRadius":0.20068052392261987},{"acceleration":-0.016672816731877118,"curvature":4.981140892489423,"pose":{"rotation":{"radians":2.7771573043659914},"translation":{"x":7.0289093314959565,"y":2.249701599679813}},"time":1.2613266371906449,"velocity":0.7759875069805601,"position":1.540652157424659,"holonomicRotation":-169.77788000000004,"angularVelocity":3.8652482611666685,"angularAcceleration":0.43165164695211133,"curveRadius":0.20075722040061197},{"acceleration":0.08484050485495692,"curvature":4.973573600350237,"pose":{"rotation":{"radians":2.7939767481215507},"translation":{"x":7.025732850677712,"y":2.250852531032634}},"time":1.2656784522364355,"velocity":0.7763567171660803,"position":1.544030718267323,"holonomicRotation":-170.14552000000003,"angularVelocity":3.864926146580662,"angularAcceleration":-0.07401844577889118,"curveRadius":0.2010626725076674},{"acceleration":0.18632932224280702,"curvature":4.960377786051056,"pose":{"rotation":{"radians":2.8107932838241076},"translation":{"x":7.0225325908029745,"y":2.251951558732091}},"time":1.270032356149707,"velocity":0.7771679771313506,"position":1.5474144329642245,"holonomicRotation":-170.51316000000003,"angularVelocity":3.8624039568940822,"angularAcceleration":-0.5792938330337342,"curveRadius":0.20159754823757034},{"acceleration":0.28783544030495317,"curvature":4.941618382643841,"pose":{"rotation":{"radians":2.82759375547136},"translation":{"x":7.0193082714240385,"y":2.2529986319707507}},"time":1.2743874174445815,"velocity":0.7784215181167158,"position":1.550804506388872,"holonomicRotation":-170.88080000000002,"angularVelocity":3.857688907163092,"angularAcceleration":-1.0826597863362573,"curveRadius":0.2023628541435417},{"acceleration":0.3894000872693488,"curvature":4.917389450652851,"pose":{"rotation":{"radians":2.8443650931638507},"translation":{"x":7.016059612093207,"y":2.2539936999411827}},"time":1.2787427083917782,"velocity":0.7801174687916376,"position":1.5542021449384502,"holonomicRotation":-171.24844000000002,"angularVelocity":3.850796168574179,"angularAcceleration":-1.5826126595170071,"curveRadius":0.2033599351922871},{"acceleration":0.49106396166466626,"curvature":4.88781308441718,"pose":{"rotation":{"radians":2.8610943674435196},"translation":{"x":7.012786332362772,"y":2.2549367118359553}},"time":1.2830973071456342,"velocity":0.7822558553071661,"position":1.5576085553111674,"holonomicRotation":-171.61608000000004,"angularVelocity":3.8417487408811453,"angularAcceleration":-2.077671951984586,"curveRadius":0.20459047486658122},{"acceleration":0.5928672904929633,"curvature":4.853037995977697,"pose":{"rotation":{"radians":2.877768842158827},"translation":{"x":7.0094881517850345,"y":2.255827616847637}},"time":1.2874502998258153,"velocity":0.7848366022830008,"position":1.5610249432960435,"holonomicRotation":-171.98372000000003,"angularVelocity":3.830577246597508,"angularAcceleration":-2.566393997054104,"curveRadius":0.20605649509210966},{"acceleration":0.6948498580816391,"curvature":4.813237799066312,"pose":{"rotation":{"radians":2.8943760253405637},"translation":{"x":7.00616478991229,"y":2.2566663641687965}},"time":1.2918007825386961,"velocity":0.7878595345786327,"position":1.5644525125814062,"holonomicRotation":-172.35136000000003,"angularVelocity":3.8173196580155553,"angularAcceleration":-3.0473833495993228,"curveRadius":0.20776035628116762},{"acceleration":0.7970510686327286,"curvature":4.768609032008344,"pose":{"rotation":{"radians":2.9109037175851546},"translation":{"x":7.002815966296838,"y":2.257452902992002}},"time":1.2961478633233932,"velocity":0.7913243799635082,"position":1.5678924635880078,"holonomicRotation":-172.71900000000005,"angularVelocity":3.8020209568621643,"angularAcceleration":-3.519304542774254,"curveRadius":0.20970475735957758},{"acceleration":0.8995099822983971,"curvature":4.719368959063337,"pose":{"rotation":{"radians":2.927340057501765},"translation":{"x":6.999441400490973,"y":2.258187182509822}},"time":1.3004906640092957,"velocity":0.7952307725316099,"position":1.571345992332409,"holonomicRotation":-173.08664000000005,"angularVelocity":3.7847327347915507,"angularAcceleration":-3.9808923597931005,"curveRadius":0.21189273580306633},{"acceleration":1.002265362330172,"curvature":4.665753192907386,"pose":{"rotation":{"radians":2.9436735638300777},"translation":{"x":6.996040812046994,"y":2.2588691519148245}},"time":1.304828321972942,"velocity":0.7995782568622082,"position":1.5748142893258457,"holonomicRotation":-173.45428000000004,"angularVelocity":3.7655127410236076,"angularAcceleration":-4.4309611151974435,"curveRadius":0.21432766772150388},{"acceleration":1.1053557159681535,"curvature":4.608013184921065,"pose":{"rotation":{"radians":2.959893173894797},"translation":{"x":6.992613920517198,"y":2.2594987603995795}},"time":1.309159991783761,"velocity":0.8043662928472838,"position":1.5782985385134127,"holonomicRotation":-173.82192000000003,"angularVelocity":3.7444243843812393,"angularAcceleration":-4.8684127746063135,"curveRadius":0.21701326794643927},{"acceleration":1.208819346852398,"curvature":4.546413627081297,"pose":{"rotation":{"radians":2.9759882781293663},"translation":{"x":6.989160445453883,"y":2.260075957156654}},"time":1.3134848467294395,"velocity":0.8095942611779502,"position":1.581799916257861,"holonomicRotation":-174.18956000000003,"angularVelocity":3.721536198723179,"angularAcceleration":-5.29224354239456,"curveRadius":0.21995359024162944},{"acceleration":1.3126943888843483,"curvature":4.481229815140277,"pose":{"rotation":{"radians":2.9919487504599993},"translation":{"x":6.985680106409346,"y":2.2606006913786176}},"time":1.3178020802138017,"velocity":0.8152614693483761,"position":1.5853195903718422,"holonomicRotation":-174.55720000000002,"angularVelocity":3.696921278046408,"angularAcceleration":-5.70154956083129,"curveRadius":0.22315302746165824},{"acceleration":1.4170188533089954,"curvature":4.412745011651804,"pose":{"rotation":{"radians":3.0077649744223507},"translation":{"x":6.982172622935884,"y":2.261072912258038}},"time":1.3221109070214332,"velocity":0.821367158170433,"position":1.588858719201875,"holonomicRotation":-174.92484000000002,"angularVelocity":3.6706566934505123,"angularAcceleration":-6.095530353964983,"curveRadius":0.22661631192364642},{"acceleration":1.5218306718521282,"curvature":4.3412478555438145,"pose":{"rotation":{"radians":3.0234278649288107},"translation":{"x":6.978637714585795,"y":2.2614925689874843}},"time":1.3264105644450515,"velocity":0.827910508716152,"position":1.592418450766768,"holonomicRotation":-175.29248000000004,"angularVelocity":3.6428228957085786,"angularAcceleration":-6.473491955205775,"curveRadius":0.2303485157436912},{"acceleration":1.6271677345765982,"curvature":4.267029850798426,"pose":{"rotation":{"radians":3.0389288856887826},"translation":{"x":6.975075100911376,"y":2.2618596107595246}},"time":1.330700313273405,"velocity":0.8348906495990867,"position":1.595999921952689,"holonomicRotation":-175.66012000000003,"angularVelocity":3.613503116433383,"angularAcceleration":-6.834847551307315,"curveRadius":0.23435505139784404},{"acceleration":1.7330679372453186,"curvature":4.1903829714306475,"pose":{"rotation":{"radians":3.054260062324398},"translation":{"x":6.971484501464926,"y":2.262173986766727}},"time":1.334979438638818,"velocity":0.8423066645693372,"position":1.5996042577665042,"holonomicRotation":-176.02776000000006,"angularVelocity":3.582782771342162,"angularAcceleration":-7.179117802793197,"curveRadius":0.23864167232871983},{"acceleration":1.8395692150837948,"curvature":4.111597408528492,"pose":{"rotation":{"radians":3.0694139912942835},"translation":{"x":6.96786563579874,"y":2.262435646201661}},"time":1.339247250725349,"velocity":0.8501576002994821,"position":1.6032325706485184,"holonomicRotation":-176.39540000000005,"angularVelocity":3.5507488761538815,"angularAcceleration":-7.505929159669066,"curveRadius":0.24321447375313238},{"acceleration":1.9467095890250736,"curvature":4.030959484205676,"pose":{"rotation":{"radians":3.084383844775806},"translation":{"x":6.9642182234651155,"y":2.262644538256895}},"time":1.3435030853395538,"velocity":0.8584424743522593,"position":1.6068859598451704,"holonomicRotation":-176.76304000000005,"angularVelocity":3.5174894793978826,"angularAcceleration":-7.81501157140565,"curveRadius":0.24807989361298574},{"acceleration":2.054527201893198,"curvature":3.9487497500299162,"pose":{"rotation":{"radians":3.099163371705104},"translation":{"x":6.960541984016352,"y":2.2628006121249973}},"time":1.3477463043474116,"velocity":0.8671602832274935,"position":1.6105655108418206,"holonomicRotation":-177.13068000000004,"angularVelocity":3.4830931191456864,"angularAcceleration":-8.106194893192866,"curveRadius":0.25324471372044377},{"acceleration":2.1630603638232815,"curvature":3.8652412827704943,"pose":{"rotation":{"radians":3.1137468952062473},"translation":{"x":6.956836637004746,"y":2.2629038169985356}},"time":1.3519762959818256,"velocity":0.8763100104711984,"position":1.614272294855267,"holonomicRotation":-177.49832000000004,"angularVelocity":3.447648307976811,"angularAcceleration":-8.379404554965728,"curveRadius":0.25871606113117696},{"acceleration":2.2723475816262213,"curvature":3.7806981869652114,"pose":{"rotation":{"radians":3.1281293066705613},"translation":{"x":6.953101901982595,"y":2.2629541020700796}},"time":1.356192475026429,"velocity":0.885890634726906,"position":1.618007368385213,"holonomicRotation":-177.86596000000003,"angularVelocity":3.41124305020284,"angularAcceleration":-8.634656495570178,"curveRadius":0.26450140967288},{"acceleration":2.382427605332933,"curvature":3.6953743050106476,"pose":{"rotation":{"radians":-3.140879250406345},"translation":{"x":6.949337498502195,"y":2.2629514165321973}},"time":1.3603942828818942,"velocity":0.8959011377540713,"position":1.6217717728235483,"holonomicRotation":-178.23360000000002,"angularVelocity":-1491.9788749794395,"angularAcceleration":-355892.0753800251,"curveRadius":0.27060858182730657},{"acceleration":2.4933394687384354,"curvature":3.609512137259251,"pose":{"rotation":{"radians":-3.126912163460546},"translation":{"x":6.9455431461158454,"y":2.262895709577457}},"time":1.364581187521716,"velocity":0.906340512344383,"position":1.6255665341199415,"holonomicRotation":-178.60124000000002,"angularVelocity":3.3358980314377824,"angularAcceleration":357140.87175258435,"curveRadius":0.27704575077542554},{"acceleration":2.60512251761795,"curvature":3.523341965378941,"pose":{"rotation":{"radians":-3.1131582081492826},"translation":{"x":6.941718564375843,"y":2.262786930398428}},"time":1.3687526833452126,"velocity":0.9172077700463233,"position":1.6293926625019683,"holonomicRotation":-178.96888000000004,"angularVelocity":3.2971279112379643,"angularAcceleration":-9.294057057767876,"curveRadius":0.28382144277399096},{"acceleration":2.717816459999511,"curvature":3.4370811720604904,"pose":{"rotation":{"radians":-3.0996203359944543},"translation":{"x":6.937863472834485,"y":2.2626250281876774}},"time":1.3729082909354,"velocity":0.9285019487562335,"position":1.6332511522477235,"holonomicRotation":-179.33652000000004,"angularVelocity":3.257735929348842,"angularAcceleration":-9.479235234370561,"curveRadius":0.2909445398406205},{"acceleration":2.831461392340343,"curvature":3.3509337477479497,"pose":{"rotation":{"radians":-3.086300999766787},"translation":{"x":6.9339775910440675,"y":2.262409952137775}},"time":1.3770475567301153,"velocity":0.9402221200466047,"position":1.637142981508667,"holonomicRotation":-179.70416000000006,"angularVelocity":3.217801631553216,"angularAcceleration":-9.647676611299453,"curveRadius":0.2984242826860025},{"acceleration":2.946097850903864,"curvature":3.2650899695877404,"pose":{"rotation":{"radians":-3.0732021732281036},"translation":{"x":6.930060638556891,"y":2.2621416514412886}},"time":1.3811700526143846,"velocity":0.9523673963116107,"position":1.641069112180274,"holonomicRotation":-180.07180000000005,"angularVelocity":3.1774019687117314,"angularAcceleration":-9.799806713122907,"curveRadius":0.3062702741162942},{"acceleration":3.004711208306354,"curvature":3.17972624280447,"pose":{"rotation":{"radians":-3.0603253721264725},"translation":{"x":6.926112334925249,"y":2.2618200752907875}},"time":1.3852763596357098,"velocity":0.9647056630433336,"position":1.645030489817941,"holonomicRotation":-180.43944000000005,"angularVelocity":3.1358593097784286,"angularAcceleration":-10.116793195822959,"curveRadius":0.31449248257234097},{"acceleration":3.0053728581948413,"curvature":3.095005084098475,"pose":{"rotation":{"radians":-3.047671676159482},"translation":{"x":6.922132399701442,"y":2.261445172878839}},"time":1.389368010749551,"velocity":0.9770026002460744,"position":1.6490280435954636,"holonomicRotation":-180.80708000000004,"angularVelocity":3.0925647409638395,"angularAcceleration":-10.581197567928847,"curveRadius":0.32310124630741405},{"acceleration":3.0048535531561336,"curvature":2.9831440732684555,"pose":{"rotation":{"radians":-3.035241751655781},"translation":{"x":6.918120552437767,"y":2.261016893398013}},"time":1.393446465199769,"velocity":0.9892577585921972,"position":1.6530626863034066,"holonomicRotation":-181.17472000000004,"angularVelocity":3.0477046281679065,"angularAcceleration":-10.999292340640432,"curveRadius":0.33521679658748726},{"acceleration":2.253170335696713,"curvature":1.2165107278553988,"pose":{"rotation":{"radians":-3.0170164638976193},"translation":{"x":6.91,"y":2.26}},"time":1.4015690390523725,"velocity":1.0075593010463895,"position":1.6612466611370336,"holonomicRotation":178.09,"angularVelocity":2.2437823390574034,"angularAcceleration":-98.97383559680566,"curveRadius":0.8220231660126104},{"acceleration":2.6029257762428424,"curvature":0.012862789761680798,"pose":{"rotation":{"radians":-3.0050751306208374},"translation":{"x":6.898658508819916,"y":2.2584419968174596}},"time":1.4126158937377418,"velocity":1.0363134438533461,"position":1.672694665159776,"holonomicRotation":178.2503916267346,"angularVelocity":1.0809713368093221,"angularAcceleration":-105.26172701340397,"curveRadius":77.743632487804},{"acceleration":3.0600363574497416,"curvature":0.013340220637966372,"pose":{"rotation":{"radians":-3.0049284904407965},"translation":{"x":6.887411685084861,"y":2.2568953178970164}},"time":1.4232376218461456,"velocity":1.0688163180440076,"position":1.6840473414878647,"holonomicRotation":178.41078325346916,"angularVelocity":0.013805680068663955,"angularAcceleration":-100.4700596597205,"curveRadius":74.96127891273343},{"acceleration":3.056876959289774,"curvature":0.013831694216449314,"pose":{"rotation":{"radians":-3.00477767424503},"translation":{"x":6.87625881322879,"y":2.2553598454901804}},"time":1.4334713092724616,"velocity":1.1000994413460865,"position":1.6953054153084655,"holonomicRotation":178.57117488020376,"angularVelocity":0.01473722906357271,"angularAcceleration":0.09102769667493142,"curveRadius":72.29772321099696},{"acceleration":3.0540918379079094,"curvature":0.014337554563921821,"pose":{"rotation":{"radians":-3.0046226052605216},"translation":{"x":6.8651991776856605,"y":2.2538354618484635}},"time":1.4433488022011607,"velocity":1.1302662118786195,"position":1.706469611823844,"holonomicRotation":178.73156650693832,"angularVelocity":0.015699225059192846,"angularAcceleration":0.09739272936607739,"curveRadius":69.74690108704738},{"acceleration":3.0516181793345245,"curvature":0.014858153832301832,"pose":{"rotation":{"radians":-3.004463205771828},"translation":{"x":6.8542320628894275,"y":2.252322049223376}},"time":1.4528976974064192,"velocity":1.1594057940795466,"position":1.7175406562518791,"holonomicRotation":178.89195813367292,"angularVelocity":0.016692977068794457,"angularAcceleration":0.10406984140472739,"curveRadius":67.30311257284106},{"acceleration":3.049406459947267,"curvature":0.015393848018588337,"pose":{"rotation":{"radians":-3.004299397132594},"translation":{"x":6.843356753274047,"y":2.2508194898664295}},"time":1.4621421036859494,"velocity":1.1875957463067233,"position":1.7285192738265804,"holonomicRotation":179.0523497604075,"angularVelocity":0.01771975768705122,"angularAcceleration":0.11107047734697098,"curveRadius":64.96101551687939},{"acceleration":3.0474171055079378,"curvature":0.01594499775744835,"pose":{"rotation":{"radians":-3.0041310997777444},"translation":{"x":6.832572533273474,"y":2.249327666029135}},"time":1.4711032359947114,"velocity":1.2149040541891643,"position":1.7394061897986208,"holonomicRotation":179.21274138714207,"angularVelocity":0.01878081352342289,"angularAcceleration":0.11840644684312913,"curveRadius":62.71559364333383},{"acceleration":3.0456181101490953,"curvature":0.016511967026038615,"pose":{"rotation":{"radians":-3.0039582332379817},"translation":{"x":6.821878687321666,"y":2.2478464599630033}},"time":1.4797998851701348,"velocity":1.2413907264154471,"position":1.75020212943588,"holonomicRotation":179.37313301387667,"angularVelocity":0.019877373029050075,"angularAcceleration":0.12608988628931247,"curveRadius":60.56213644461898},{"acceleration":3.0439833080996124,"curvature":0.017095124590909432,"pose":{"rotation":{"radians":-3.003780716155549},"translation":{"x":6.811274499852579,"y":2.246375753919545}},"time":1.4882487937138267,"velocity":1.2671090629941053,"position":1.7609078180240003,"holonomicRotation":179.53352464061126,"angularVelocity":0.021010652620364986,"angularAcceleration":0.13413325347935554,"curveRadius":58.49621011430147},{"acceleration":3.042491098450903,"curvature":0.01769484535943654,"pose":{"rotation":{"radians":-3.003598466301934},"translation":{"x":6.800759255300166,"y":2.244915430150272}},"time":1.4964649596471398,"velocity":1.292106674709606,"position":1.7715239808669558,"holonomicRotation":179.69391626734583,"angularVelocity":0.022181861356507758,"angularAcceleration":0.14254930409742747,"curveRadius":56.51363319017121},{"acceleration":3.04112349014739,"curvature":0.018311505724758325,"pose":{"rotation":{"radians":-3.0034114005968444},"translation":{"x":6.790332238098387,"y":2.2434653709066947}},"time":1.5044618846040043,"velocity":1.3164263110448726,"position":1.7820513432876237,"holonomicRotation":179.85430789408042,"angularVelocity":0.02339220464100688,"angularAcceleration":0.15135108695251223,"curveRadius":54.61047360228472},{"acceleration":3.0398653771670356,"curvature":0.01894548762169199,"pose":{"rotation":{"radians":-3.0032194351301835},"translation":{"x":6.779992732681195,"y":2.2420254584403247}},"time":1.5122517781967686,"velocity":1.340106538869332,"position":1.7924906306283834,"holonomicRotation":180.01469952081501,"angularVelocity":0.024642886886054764,"angularAcceleration":0.16055190358563995,"curveRadius":52.78301725288038},{"acceleration":3.0387039816144115,"curvature":0.01959717330189182,"pose":{"rotation":{"radians":-3.003022485184635},"translation":{"x":6.769740023482546,"y":2.2405955750026725}},"time":1.5198457277340118,"velocity":1.363182303564332,"position":1.802842568251714,"holonomicRotation":180.17509114754958,"angularVelocity":0.025935113814280764,"angularAcceleration":0.1701653298969781,"curveRadius":51.02776735170601},{"acceleration":3.0376284210639604,"curvature":0.020266951254621905,"pose":{"rotation":{"radians":-3.0028204652615127},"translation":{"x":6.759573394936398,"y":2.239175602845249}},"time":1.5272538402206404,"velocity":1.3856853966001537,"position":1.8131078815408064,"holonomicRotation":180.33548277428417,"angularVelocity":0.02727009389870384,"angularAcceleration":0.1802051584438927,"curveRadius":49.341412402713935},{"acceleration":3.036629368879861,"curvature":0.0209552110030194,"pose":{"rotation":{"radians":-3.0026132891080315},"translation":{"x":6.749492131476704,"y":2.237765424219566}},"time":1.534485361988352,"velocity":1.407644847981681,"position":1.8232872959001931,"holonomicRotation":180.49587440101874,"angularVelocity":0.028649039598585235,"angularAcceleration":0.19068541092392266,"curveRadius":47.720827046595325},{"acceleration":3.035698785116612,"curvature":0.021662343180101316,"pose":{"rotation":{"radians":-3.0024008697469435},"translation":{"x":6.7394955175374225,"y":2.236364921377134}},"time":1.541548780125222,"velocity":1.4290872578385474,"position":1.8333815367563795,"holonomicRotation":180.65626602775333,"angularVelocity":0.03007316811377253,"angularAcceleration":0.20162030444631163,"curveRadius":46.1630577858532},{"acceleration":3.03482970137746,"curvature":0.022388741452662512,"pose":{"rotation":{"radians":-3.002183119508831},"translation":{"x":6.729582837552507,"y":2.234973976569464}},"time":1.548451908984264,"velocity":1.4500370783324046,"position":1.8433913295584972,"holonomicRotation":180.81665765448793,"angularVelocity":0.03154370178494243,"angularAcceleration":0.2130242244056753,"curveRadius":44.66530653875044},{"acceleration":3.034016047433545,"curvature":0.02313480060427866,"pose":{"rotation":{"radians":-3.0019599500664444},"translation":{"x":6.719753375955915,"y":2.233592472048067}},"time":1.555201964373769,"velocity":1.4705168547052274,"position":1.8533173997789578,"holonomicRotation":180.9770492812225,"angularVelocity":0.0330618683119874,"angularAcceleration":0.22491171396985368,"curveRadius":43.22492409184868},{"acceleration":3.033252510449968,"curvature":0.02390091529587267,"pose":{"rotation":{"radians":-3.0017312724717407},"translation":{"x":6.710006417181603,"y":2.2322202900644545}},"time":1.5618056275116035,"velocity":1.49054743249623,"position":1.8631604729141271,"holonomicRotation":181.13744090795709,"angularVelocity":0.034628900646616494,"angularAcceleration":0.2372974365774425,"curveRadius":41.8394018647765},{"acceleration":3.0325344199003186,"curvature":0.024687481912013864,"pose":{"rotation":{"radians":-3.0014969971954577},"translation":{"x":6.700341245663525,"y":2.230857312870137}},"time":1.56826910042166,"velocity":1.5101481365680698,"position":1.8729212744850072,"holonomicRotation":181.29783253469168,"angularVelocity":0.03624603669622204,"angularAcceleration":0.25019615183803673,"curveRadius":40.50635879203873},{"acceleration":3.031857652800114,"curvature":0.02549489361172703,"pose":{"rotation":{"radians":-3.0012570341694023},"translation":{"x":6.690757145835638,"y":2.2295034227166255}},"time":1.5745981541345349,"velocity":1.5293369265024324,"position":1.882600530037924,"holonomicRotation":181.45822416142624,"angularVelocity":0.03791451881144598,"angularAcceleration":0.26362268214438433,"curveRadius":39.22354080897299},{"acceleration":3.0312185553014883,"curvature":0.026323545816205576,"pose":{"rotation":{"radians":-3.0010112928319463},"translation":{"x":6.6812534021318974,"y":2.2281585018554315}},"time":1.5807981708052408,"velocity":1.5481305320778547,"position":1.8921989651452356,"holonomicRotation":181.61861578816084,"angularVelocity":0.039635593016548926,"angularAcceleration":0.2775918673307357,"curveRadius":37.988803141572575},{"acceleration":3.030613877238576,"curvature":0.02717383004454473,"pose":{"rotation":{"radians":-3.0007596821753113},"translation":{"x":6.6718292989862595,"y":2.2268224325380657}},"time":1.5868741806626818,"velocity":1.566544571870054,"position":1.9017173054060388,"holonomicRotation":181.7790074148954,"angularVelocity":0.04141050830042671,"angularAcceleration":0.2921185655589603,"curveRadius":36.80011240081906},{"acceleration":3.0300407175514135,"curvature":0.028046136301337215,"pose":{"rotation":{"radians":-3.000502110797379},"translation":{"x":6.66248412083268,"y":2.225495097016039}},"time":1.5928308945472067,"velocity":1.5845936574829682,"position":1.9111562764468977,"holonomicRotation":181.93939904163,"angularVelocity":0.04324051531191155,"angularAcceleration":0.3072175442636358,"curveRadius":35.6555351958523},{"acceleration":3.029496478118693,"curvature":0.028940850004017478,"pose":{"rotation":{"radians":-3.0002384869553023},"translation":{"x":6.653217152105115,"y":2.224176377540863}},"time":1.5986727326649655,"velocity":1.6022914854864578,"position":1.9205166039225727,"holonomicRotation":182.0997906683646,"angularVelocity":0.0451268653397241,"angularAcceleration":0.32290350909899196,"curveRadius":34.5532353010082},{"acceleration":3.0289788247649123,"curvature":0.029858356047317854,"pose":{"rotation":{"radians":-2.9999687186231365},"translation":{"x":6.64402767723752,"y":2.222866156364048}},"time":1.6044038500844602,"velocity":1.6196509187923487,"position":1.9297990135167642,"holonomicRotation":182.26018229509916,"angularVelocity":0.04707080878296272,"angularAcceleration":0.33919099905826183,"curveRadius":33.491462102443144},{"acceleration":3.0284856542878176,"curvature":0.030799029225159535,"pose":{"rotation":{"radians":-2.999692713552253},"translation":{"x":6.634914980663852,"y":2.221564315737106}},"time":1.6100281594164474,"velocity":1.636684058919549,"position":1.9390042309428601,"holonomicRotation":182.42057392183375,"angularVelocity":0.049073593679125824,"angularAcceleration":0.35609437140532746,"curveRadius":32.46855583302302},{"acceleration":3.0280150661123595,"curvature":0.03176324355932637,"pose":{"rotation":{"radians":-2.999410379335373},"translation":{"x":6.625878346818065,"y":2.2202707379115467}},"time":1.6155493510493624,"velocity":1.653402310366909,"position":1.9481329819447002,"holonomicRotation":182.58096554856834,"angularVelocity":0.051136463946784054,"angularAcceleration":0.3736277247397612,"curveRadius":31.482930832685017},{"acceleration":3.027565338078861,"curvature":0.0327513644881467,"pose":{"rotation":{"radians":-2.9991216234745313},"translation":{"x":6.616917060134115,"y":2.2189853051388826}},"time":1.620970911255585,"velocity":1.6698164381255765,"position":1.9571859922973383,"holonomicRotation":182.7413571753029,"angularVelocity":0.05326065742299396,"angularAcceleration":0.39180483023537155,"curveRadius":30.53307902215548},{"acceleration":3.0271349057046617,"curvature":0.03376374932652467,"pose":{"rotation":{"radians":-2.9988263534511566},"translation":{"x":6.60803040504596,"y":2.217707899670623}},"time":1.6262961384368435,"velocity":1.6859366192067713,"position":1.9661639878078172,"holonomicRotation":182.9017488020375,"angularVelocity":0.05544740408707312,"angularAcceleration":0.4106391313736156,"curveRadius":29.617563805759094},{"acceleration":3.0267223441483173,"curvature":0.03480074594344085,"pose":{"rotation":{"radians":-2.998524476802116},"translation":{"x":6.599217665987554,"y":2.2164384037582803}},"time":1.631528157737926,"velocity":1.7017724889303727,"position":1.975067694315952,"holonomicRotation":183.06214042877207,"angularVelocity":0.057697923434247025,"angularAcceleration":0.4301435483443866,"curveRadius":28.73501624434224},{"acceleration":3.0263263525702824,"curvature":0.035862695413265824,"pose":{"rotation":{"radians":-2.9982159011973573},"translation":{"x":6.5904781273928545,"y":2.215176699653365}},"time":1.6366699342251945,"velocity":1.7173331826128198,"position":1.9838978376951166,"holonomicRotation":183.22253205550666,"angularVelocity":0.06001342250543191,"angularAcceleration":0.4503305573313515,"curveRadius":27.884128297565},{"acceleration":3.0259457408711694,"curvature":0.03694992547474626,"pose":{"rotation":{"radians":-2.9979005345226484},"translation":{"x":6.581811073695816,"y":2.213922669607389}},"time":1.641724284798985,"velocity":1.732627373204451,"position":1.9926551438530378,"holonomicRotation":183.38292368224126,"angularVelocity":0.062395093119227654,"angularAcceleration":0.4712119943056483,"curveRadius":27.063654043996884},{"acceleration":3.0255794175042117,"curvature":0.038062751458510215,"pose":{"rotation":{"radians":-2.9975782849657837},"translation":{"x":6.573215789330395,"y":2.212676195871862}},"time":1.6466938889858942,"velocity":1.7476633053455062,"position":2.0013403387325903,"holonomicRotation":183.54331530897582,"angularVelocity":0.06484410925794157,"angularAcceleration":0.49279903320370294,"curveRadius":26.27240442903967},{"acceleration":3.02522637946745,"curvature":0.0392014776897363,"pose":{"rotation":{"radians":-2.9972490611074027},"translation":{"x":6.564691558730546,"y":2.2114371606982957}},"time":1.6515812987374308,"velocity":1.762448826253121,"position":2.009954148312604,"holonomicRotation":183.70370693571041,"angularVelocity":0.06736162407448272,"angularAcceleration":0.5151020570251277,"curveRadius":25.50924248097462},{"acceleration":3.024885703144275,"curvature":0.04036639153850581,"pose":{"rotation":{"radians":-2.9969127720149182},"translation":{"x":6.556237666330228,"y":2.210205446338201}},"time":1.656388947344932,"velocity":1.7769914137916931,"position":2.0184972986086613,"holonomicRotation":183.864098562445,"angularVelocity":0.06994876704587044,"angularAcceleration":0.5381306294621987,"curveRadius":24.773083792889743},{"acceleration":3.0245565362596296,"curvature":0.04155776424404432,"pose":{"rotation":{"radians":-2.9965693273417484},"translation":{"x":6.547853396563394,"y":2.2089809350430882}},"time":1.6611191575665611,"velocity":1.7912982020354036,"position":2.026970515673915,"holonomicRotation":184.02449018917957,"angularVelocity":0.07260664052506721,"angularAcceleration":0.5618933101627313,"curveRadius":24.06289217407336},{"acceleration":3.024238090986627,"curvature":0.0427758511009598,"pose":{"rotation":{"radians":-2.9962186374301236},"translation":{"x":6.539538033864,"y":2.2077635090644705}},"time":1.6657741490501046,"velocity":1.805376004593154,"position":2.03537452559989,"holonomicRotation":184.18488181591417,"angularVelocity":0.07533631648190305,"angularAcceleration":0.5863976263943619,"curveRadius":23.377676288422514},{"acceleration":3.0239296377013956,"curvature":0.04402088717183533,"pose":{"rotation":{"radians":-2.9958606134177175},"translation":{"x":6.531290862666003,"y":2.2065530506538567}},"time":1.6703560451249873,"velocity":1.8192313359308594,"position":2.043710054517295,"holonomicRotation":184.34527344264876,"angularVelocity":0.07813883304092856,"angularAcceleration":0.6116499617676874,"curveRadius":22.716489017963326},{"acceleration":3.0236304993649923,"curvature":0.045293087434986834,"pose":{"rotation":{"radians":-2.9954951673506063},"translation":{"x":6.52311116740336,"y":2.2053494420627584}},"time":1.6748668790280081,"velocity":1.832870430897603,"position":2.0519778285968324,"holonomicRotation":184.50566506938333,"angularVelocity":0.08101519031025736,"angularAcceleration":0.6376553274113086,"curveRadius":22.078424250397774},{"acceleration":3.02334004694427,"curvature":0.04659264522368338,"pose":{"rotation":{"radians":-2.995122212298424},"translation":{"x":6.514998232510024,"y":2.2041525655426875}},"time":1.6793085996196377,"velocity":1.8462992626396137,"position":2.0601785740500094,"holonomicRotation":184.66605669611792,"angularVelocity":0.0839663469343608,"angularAcceleration":0.6644174398688789,"curveRadius":21.462614865482948},{"acceleration":3.023057694636196,"curvature":0.04791972845909825,"pose":{"rotation":{"radians":-2.994741662474879},"translation":{"x":6.506951342419953,"y":2.202962303345154}},"time":1.6836830766410753,"velocity":1.8595235590592798,"position":2.068313017129936,"holonomicRotation":184.82644832285249,"angularVelocity":0.08699321580162883,"angularAcceleration":0.6919384539990869,"curveRadius":20.868231773340437},{"acceleration":3.022782896301559,"curvature":0.04927448078526469,"pose":{"rotation":{"radians":-2.994353433363473},"translation":{"x":6.498969781567102,"y":2.20177853772167}},"time":1.6879921055565217,"velocity":1.87254881796456,"position":2.07638188413213,"holonomicRotation":184.98683994958708,"angularVelocity":0.09009665960101478,"angularAcceleration":0.7202188382308532,"curveRadius":20.294480714224907},{"acceleration":3.022515141984915,"curvature":0.05065701882697322,"pose":{"rotation":{"radians":-2.993957441846635},"translation":{"x":6.491052834385427,"y":2.2006011509237453}},"time":1.6922374120200998,"velocity":1.8853803210330913,"position":2.084385901395315,"holonomicRotation":185.14723157632167,"angularVelocity":0.09327748661620858,"angularAcceleration":0.749257336892674,"curveRadius":19.74060106884009},{"acceleration":3.0222539546379115,"curvature":0.05206742890056143,"pose":{"rotation":{"radians":-2.9935536063400097},"translation":{"x":6.4831997853088845,"y":2.1994300252028913}},"time":1.6964206560024948,"velocity":1.8980231467020998,"position":2.092325795302203,"holonomicRotation":185.30762320305624,"angularVelocity":0.09653644595550098,"angularAcceleration":0.7790507445914205,"curveRadius":19.205864801002633},{"acceleration":3.021998887430832,"curvature":0.05350576802049533,"pose":{"rotation":{"radians":-2.9931418469313984},"translation":{"x":6.4754099187714305,"y":2.1982650428106196}},"time":1.7005434356085738,"velocity":1.910482182084793,"position":2.1002022922802794,"holonomicRotation":185.46801482979083,"angularVelocity":0.09987422272200375,"angularAcceleration":0.8095937899715172,"curveRadius":18.689573797295107},{"acceleration":3.0217495213315178,"curvature":0.05497205866066971,"pose":{"rotation":{"radians":-2.9927220855236047},"translation":{"x":6.4676825192070195,"y":2.1971060859984406}},"time":1.7046072906138907,"velocity":1.9227621340018701,"position":2.1080161188025768,"holonomicRotation":185.62840645652543,"angularVelocity":0.10329143319445662,"angularAcceleration":0.8408790343115065,"curveRadius":18.191059683116062},{"acceleration":3.021505462721553,"curvature":0.05646628968641748,"pose":{"rotation":{"radians":-2.9922942459827655},"translation":{"x":6.460016871049609,"y":2.195953037017866}},"time":1.7086137057450421,"velocity":1.9348675392065744,"position":2.1157680013884277,"holonomicRotation":185.78879808326,"angularVelocity":0.10678861945998351,"angularAcceleration":0.8728966297912895,"curveRadius":17.70968139669609},{"acceleration":3.0212663414237957,"curvature":0.05798841294296515,"pose":{"rotation":{"radians":-2.991858254290163},"translation":{"x":6.452412258733154,"y":2.194805778120406}},"time":1.712564113726269,"velocity":1.9468027738751472,"position":2.123458666604219,"holonomicRotation":185.94918970999458,"angularVelocity":0.11036624436629848,"angularAcceleration":0.9056342846907236,"curveRadius":17.244824426968815},{"acceleration":3.0210318088658026,"curvature":0.05953834036799484,"pose":{"rotation":{"radians":-2.991414038699559},"translation":{"x":6.44486796669161,"y":2.1936641915575725}},"time":1.716459898112395,"velocity":1.9585720624261167,"position":2.131088841064121,"holonomicRotation":186.10958133672915,"angularVelocity":0.11402468580804917,"angularAcceleration":0.9390769814621704,"curveRadius":16.795899815466733},{"acceleration":3.0208015364900502,"curvature":0.061115945321361116,"pose":{"rotation":{"radians":-2.990961529897655},"translation":{"x":6.437383279358932,"y":2.1925281595808754}},"time":1.72030239592619,"velocity":1.9701794857259882,"position":2.138659251430807,"holonomicRotation":186.26997296346374,"angularVelocity":0.1177642314536353,"angularAcceleration":0.9732069676554584,"curveRadius":16.362342016339262},{"acceleration":3.0205752141325846,"curvature":0.06272105617081246,"pose":{"rotation":{"radians":-2.9905006611704392},"translation":{"x":6.429957481169079,"y":2.191397564441827}},"time":1.7240929001164542,"velocity":1.9816289887321659,"position":2.146170624416145,"holonomicRotation":186.43036459019834,"angularVelocity":0.12158507261371149,"angularAcceleration":1.0080034128150905,"curveRadius":15.943609069283415},{"acceleration":3.02035254868321,"curvature":0.06435345676204153,"pose":{"rotation":{"radians":-2.990031368572067},"translation":{"x":6.422589856556005,"y":2.1902722883919377}},"time":1.7278326618515398,"velocity":1.9929243876201996,"position":2.153623686781886,"holonomicRotation":186.5907562169329,"angularVelocity":0.12548729882153453,"angularAcceleration":1.0434424661906208,"curveRadius":15.539180804190202},{"acceleration":3.020133263022433,"curvature":0.06601288471604431,"pose":{"rotation":{"radians":-2.9895535910990696},"translation":{"x":6.415279689953665,"y":2.1891522136827177}},"time":1.7315228926616006,"velocity":2.0040693764378945,"position":2.1610191653403166,"holonomicRotation":186.7511478436675,"angularVelocity":0.12947089154830524,"angularAcceleration":1.0794969019038296,"curveRadius":15.14855780506365},{"acceleration":3.0199170947251166,"curvature":0.06769902654316559,"pose":{"rotation":{"radians":-2.9890672708684325},"translation":{"x":6.408026265796017,"y":2.1880372225656797}},"time":1.735164766441616,"velocity":2.0150675333229944,"position":2.168357786954886,"holonomicRotation":186.9115394704021,"angularVelocity":0.13353571815304394,"angularAcceleration":1.1161360470657067,"curveRadius":14.771261140105016},{"acceleration":3.019703795074175,"curvature":0.06941151904576184,"pose":{"rotation":{"radians":-2.988572353298434},"translation":{"x":6.400828868517015,"y":2.186927197292334}},"time":1.738759421326123,"velocity":2.025922326319722,"position":2.175640278540823,"holonomicRotation":187.07193109713666,"angularVelocity":0.13768152601562078,"angularAcceleration":1.1533257004574726,"curveRadius":14.406830649257465},{"acceleration":3.0194931282631474,"curvature":0.07114994490019887,"pose":{"rotation":{"radians":-2.9880687872946146},"translation":{"x":6.393686782550616,"y":2.185822020114191}},"time":1.7423079614455588,"velocity":2.036637118825724,"position":2.182867367065708,"holonomicRotation":187.23232272387125,"angularVelocity":0.14190793590339504,"angularAcceleration":1.191027787631811,"curveRadius":14.054824658018884},{"acceleration":3.019284870280549,"curvature":0.07291383032566565,"pose":{"rotation":{"radians":-2.987556525438189},"translation":{"x":6.386599292330776,"y":2.1847215732827623}},"time":1.7458114585732492,"velocity":2.047215174696431,"position":2.190039779550021,"holonomicRotation":187.39271435060581,"angularVelocity":0.14621443596364517,"angularAcceleration":1.229200397001357,"curveRadius":13.714819198683632},{"acceleration":3.019078808499254,"curvature":0.07470264455169157,"pose":{"rotation":{"radians":-2.987035524178305},"translation":{"x":6.37956568229145,"y":2.183625739049559}},"time":1.7492709536712576,"velocity":2.0576596630349355,"position":2.19715824306766,"holonomicRotation":187.5531059773404,"angularVelocity":0.15060037523513645,"angularAcceleration":1.2677975101095351,"curveRadius":13.386406947186932},{"acceleration":3.01887474078089,"curvature":0.07651579742623879,"pose":{"rotation":{"radians":-2.9865057440266223},"translation":{"x":6.372585236866595,"y":2.1825343996660926}},"time":1.7526874583425858,"velocity":2.067973662688968,"position":2.2042234847464206,"holonomicRotation":187.713497604075,"angularVelocity":0.1550649575071828,"angularAcceleration":1.306768964642092,"curveRadius":13.06919660562905},{"acceleration":3.018672474774991,"curvature":0.07835263518899827,"pose":{"rotation":{"radians":-2.9859671497550626},"translation":{"x":6.365657240490165,"y":2.1814474373838726}},"time":1.7560619561965718,"velocity":2.078160166476983,"position":2.2112362317684364,"holonomicRotation":187.87388923080957,"angularVelocity":0.1596072348730252,"angularAcceleration":1.3460602324808018,"curveRadius":12.76281260467948},{"acceleration":3.018471827459703,"curvature":0.08021244143025796,"pose":{"rotation":{"radians":-2.9854197105969273},"translation":{"x":6.358780977596118,"y":2.1803647344544115}},"time":1.7593954041337445,"velocity":2.0882220851636424,"position":2.2181972113705837,"holonomicRotation":188.03428085754416,"angularVelocity":0.16422610115806371,"angularAcceleration":1.3856122465665497,"curveRadius":12.466893940255721},{"acceleration":3.0182726247071274,"curvature":0.0820944338658806,"pose":{"rotation":{"radians":-2.9848634004478805},"translation":{"x":6.351955732618409,"y":2.17928617312922}},"time":1.7626887335558614,"velocity":2.0981622512025604,"position":2.225107150844844,"holonomicRotation":188.19467248427875,"angularVelocity":0.1689202863554723,"angularAcceleration":1.4253615705383091,"curveRadius":12.181093807574348},{"acceleration":3.018074700539498,"curvature":0.08399776214496592,"pose":{"rotation":{"radians":-2.9842981980708614},"translation":{"x":6.3451807899909936,"y":2.1782116356598085}},"time":1.7659428515063786,"velocity":2.107983422261588,"position":2.2319667775386183,"holonomicRotation":188.35506411101332,"angularVelocity":0.17368834984276896,"angularAcceleration":1.4652399082641767,"curveRadius":11.905079069537225},{"acceleration":3.017877896769515,"curvature":0.08592150642552569,"pose":{"rotation":{"radians":-2.9837240873020816},"translation":{"x":6.3384554341478285,"y":2.1771410042976886}},"time":1.7691586417461744,"velocity":2.1176882845469147,"position":2.238776818854994,"holonomicRotation":188.5154557377479,"angularVelocity":0.17852867443749562,"angularAcceleration":1.5051742289739751,"curveRadius":11.638529648764614},{"acceleration":3.0176820630209726,"curvature":0.08786467645893598,"pose":{"rotation":{"radians":-2.9831410572567023},"translation":{"x":6.331778949522868,"y":2.176074161294371}},"time":1.7723369657689507,"velocity":2.1272794559409154,"position":2.2455380022529696,"holonomicRotation":188.67584736448248,"angularVelocity":0.1834394609238156,"angularAcceleration":1.54508679767344,"curveRadius":11.381137907761548},{"acceleration":3.01748705543289,"curvature":0.08982620834703287,"pose":{"rotation":{"radians":-2.9825491025370243},"translation":{"x":6.32515062055007,"y":2.1750109889013673}},"time":1.7754786637603814,"velocity":2.136759488962137,"position":2.2522510552476125,"holonomicRotation":188.83623899121707,"angularVelocity":0.18841872175256927,"angularAcceleration":1.5848948060364423,"curveRadius":11.132608382362294},{"acceleration":3.017292737502295,"curvature":0.09180496414692298,"pose":{"rotation":{"radians":-2.981948223439347},"translation":{"x":6.3185697316633895,"y":2.173951369370188}},"time":1.77858455550476,"velocity":2.1461308735659186,"position":2.2589167054101766,"holonomicRotation":188.99663061795167,"angularVelocity":0.19346427600537527,"angularAcceleration":1.624510661692647,"curveRadius":10.892657159580374},{"acceleration":3.0170989787214566,"curvature":0.09379973147924694,"pose":{"rotation":{"radians":-2.9813384261618614},"translation":{"x":6.312035567296782,"y":2.172895184952344}},"time":1.7816554412425964,"velocity":2.1553960397893155,"position":2.265535680368155,"holonomicRotation":189.15702224468623,"angularVelocity":0.19857374371580347,"angularAcceleration":1.6638416882380829,"curveRadius":10.661011329454057},{"acceleration":3.0169056549371263,"curvature":0.09580922005553653,"pose":{"rotation":{"radians":-2.980719723010549},"translation":{"x":6.305547411884203,"y":2.171842317899347}},"time":1.7846921024823514,"velocity":2.1645573602556607,"position":2.2721087078052697,"holonomicRotation":189.31741387142083,"angularVelocity":0.2037445412786432,"angularAcceleration":1.7027903854224204,"curveRadius":10.437408836230402},{"acceleration":3.0167126480125255,"curvature":0.09783206235176847,"pose":{"rotation":{"radians":-2.980092132604536},"translation":{"x":6.299104549859609,"y":2.1707926504627078}},"time":1.787695302769251,"velocity":2.1736171525456656,"position":2.2786365154614048,"holonomicRotation":189.47780549815542,"angularVelocity":0.20897387655106478,"angularAcceleration":1.7412542530821924,"curveRadius":10.221597868440758},{"acceleration":3.0165198453250337,"curvature":0.09986681275741051,"pose":{"rotation":{"radians":-2.979455680079481},"translation":{"x":6.292706265656958,"y":2.169746064893937}},"time":1.7906657884139028,"velocity":2.1825776814430107,"position":2.2851198311324685,"holonomicRotation":189.63819712488998,"angularVelocity":0.21425874459322747,"angularAcceleration":1.7791259323800839,"curveRadius":10.01333648675792},{"acceleration":3.0163271398055778,"curvature":0.10191194598350661,"pose":{"rotation":{"radians":-2.9788103972885907},"translation":{"x":6.286351843710202,"y":2.1687024434445457}},"time":1.7936042891832324,"velocity":2.1914411610638793,"position":2.2915593826701954,"holonomicRotation":189.79858875162458,"angularVelocity":0.21959592375314216,"angularAcceleration":1.8162932661515734,"curveRadius":9.81239235841733},{"acceleration":3.016134429833441,"curvature":0.10396585808406453,"pose":{"rotation":{"radians":-2.978156322999986},"translation":{"x":6.280040568453299,"y":2.167661668366045}},"time":1.7965115189560648,"velocity":2.2002097568771557,"position":2.297955897981865,"holonomicRotation":189.95898037835914,"angularVelocity":0.2249819724318918,"angularAcceleration":1.8526394883134387,"curveRadius":9.618542264051934},{"acceleration":3.0159416185845838,"curvature":0.10602686468831321,"pose":{"rotation":{"radians":-2.9774935030914538},"translation":{"x":6.273771724320206,"y":2.166623621909946}},"time":1.7993881763455217,"velocity":2.208885587620428,"position":2.304310105029958,"holonomicRotation":190.11937200509374,"angularVelocity":0.2304132257673767,"angularAcceleration":1.8880431696143518,"curveRadius":9.431571922264196},{"acceleration":3.0157486146775323,"curvature":0.10809320134465442,"pose":{"rotation":{"radians":-2.9768219907400386},"translation":{"x":6.267544595744876,"y":2.1655881863277604}},"time":1.8022349452902344,"velocity":2.217470727121752,"position":2.310622731831738,"holonomicRotation":190.27976363182833,"angularVelocity":0.23588579349313185,"angularAcceleration":1.9223786095880246,"curveRadius":9.251275635842322},{"acceleration":3.0155553310945544,"curvature":0.11016302572708017,"pose":{"rotation":{"radians":-2.9761418466068017},"translation":{"x":6.2613584671612665,"y":2.1645552438709985}},"time":1.805052495616232,"velocity":2.225967206027941,"position":2.3168945064587416,"holonomicRotation":190.4401552585629,"angularVelocity":0.2413955580353728,"angularAcceleration":1.9555159286428372,"curveRadius":9.077455828758895},{"acceleration":3.015361685737252,"curvature":0.11223441527035952,"pose":{"rotation":{"radians":-2.975453139016406},"translation":{"x":6.255212623003334,"y":2.1635246767911713}},"time":1.8078414835712435,"velocity":2.234377013449466,"position":2.323126157036207,"holonomicRotation":190.6005468852975,"angularVelocity":0.2469381730954775,"angularAcceleration":1.987321261156779,"curveRadius":8.909923017740303},{"acceleration":3.0151676011696176,"curvature":0.11430537003235033,"pose":{"rotation":{"radians":-2.974755944129693},"translation":{"x":6.249106347705033,"y":2.1624963673397897}},"time":1.8106025523330163,"velocity":2.2427020985245645,"position":2.3293184117424053,"holonomicRotation":190.76093851203208,"angularVelocity":0.25250906328934886,"angularAcceleration":2.0176571735557176,"curveRadius":8.748495365676899},{"acceleration":3.014973004437581,"curvature":0.11637381280351508,"pose":{"rotation":{"radians":-2.9740503461096246},"translation":{"x":6.243038925700321,"y":2.1614701977683652}},"time":1.8133363324931526,"velocity":2.2509443719074427,"position":2.3354719988078965,"holonomicRotation":190.92133013876665,"angularVelocity":0.25810342410025205,"angularAcceleration":2.046382841048981,"curveRadius":8.592998509796999},{"acceleration":3.014777826774435,"curvature":0.11843759188712212,"pose":{"rotation":{"radians":-2.9733364372786744},"translation":{"x":6.2370096414231515,"y":2.1604460503284084}},"time":1.8160434425178633,"velocity":2.2591057071845793,"position":2.341587646514697,"holonomicRotation":191.08172176550124,"angularVelocity":0.2637162229956036,"angularAcceleration":2.0733545530538184,"curveRadius":8.443265217288932},{"acceleration":3.0145820041455025,"curvature":0.1204944806205236,"pose":{"rotation":{"radians":-2.9726143182685347},"translation":{"x":6.231017779307483,"y":2.159423807271431}},"time":1.8187244891869312,"velocity":2.2671879422254255,"position":2.3476660831953513,"holonomicRotation":191.2421133922358,"angularVelocity":0.26934220074232895,"angularAcceleration":2.0984258915124903,"curveRadius":8.299135320142389},{"acceleration":3.0143854761676785,"curvature":0.12254218216999843,"pose":{"rotation":{"radians":-2.97188409815957},"translation":{"x":6.22506262378727,"y":2.158403350848943}},"time":1.8213800680121155,"velocity":2.2751928804668795,"position":2.3537080372319292,"holonomicRotation":191.4025050189704,"angularVelocity":0.2749758742010045,"angularAcceleration":2.1214484033568697,"curveRadius":8.160455300304147},{"acceleration":3.014188187067852,"curvature":0.12457832901117324,"pose":{"rotation":{"radians":-2.971145894610925},"translation":{"x":6.219143459296468,"y":2.1573845633124566}},"time":1.8240107636361145,"velocity":2.2831222921405083,"position":2.359714237054918,"holonomicRotation":191.562896645705,"angularVelocity":0.28061153936274,"angularAcceleration":2.142271842596759,"curveRadius":8.027078288313785},{"acceleration":3.0139900852573427,"curvature":0.1266004890023583,"pose":{"rotation":{"radians":-2.9703998339784894},"translation":{"x":6.2132595702690345,"y":2.156367326913482}},"time":1.8266171502131567,"velocity":2.2909779154420615,"position":2.3656854111420262,"holonomicRotation":191.72328827243956,"angularVelocity":0.2862432760385309,"angularAcceleration":2.1607449659987816,"curveRadius":7.898863644842415},{"acceleration":3.013791122878187,"curvature":0.1286061651128037,"pose":{"rotation":{"radians":-2.9696460514228376},"translation":{"x":6.207410241138923,"y":2.1553515239035304}},"time":1.8291997917722123,"velocity":2.2987614576463193,"position":2.3716222880168987,"holonomicRotation":191.88367989917415,"angularVelocity":0.2918649523813513,"angularAcceleration":2.176715666604647,"curveRadius":7.775676999021585},{"acceleration":3.013591256048829,"curvature":0.13059280177145197,"pose":{"rotation":{"radians":-2.9688846910029283},"translation":{"x":6.201594756340092,"y":2.154337036534113}},"time":1.8317592425637468,"velocity":2.306474596171975,"position":2.3775255962477253,"holonomicRotation":192.04407152590875,"angularVelocity":0.29747023167137654,"angularAcceleration":2.190032060223588,"curveRadius":7.657389890065161},{"acceleration":3.013390445461944,"curvature":0.13255778669095664,"pose":{"rotation":{"radians":-2.968115905757567},"translation":{"x":6.1958124003064965,"y":2.1533237470567403}},"time":1.8342960473908934,"velocity":2.3141189796001003,"position":2.3833960644457663,"holonomicRotation":192.2044631526433,"angularVelocity":0.3030525790295977,"angularAcceleration":2.2005427057233415,"curveRadius":7.543879729460072},{"acceleration":3.013188654839149,"curvature":0.13449845622251022,"pose":{"rotation":{"radians":-2.96733985777303},"translation":{"x":6.1900624574720915,"y":2.152311537722924}},"time":1.8368107419258544,"velocity":2.3216962286432308,"position":2.389234421263775,"holonomicRotation":192.3648547793779,"angularVelocity":0.3086052694463476,"angularAcceleration":2.208097381034787,"curveRadius":7.435029576440861},{"acceleration":3.0129858525186073,"curvature":0.13641209983433258,"pose":{"rotation":{"radians":-2.9665567182345867},"translation":{"x":6.184344212270833,"y":2.151300290784175}},"time":1.8393038530122945,"velocity":2.329207937075432,"position":2.395041395394322,"holonomicRotation":192.5252464061125,"angularVelocity":0.3141213974389948,"angularAcceleration":2.2125480178757773,"curveRadius":7.330728001507658},{"acceleration":3.012782010116144,"curvature":0.13829596449307355,"pose":{"rotation":{"radians":-2.9657666674640617},"translation":{"x":6.178656949136678,"y":2.150289888492004}},"time":1.8417758989544475,"velocity":2.3366556726181313,"position":2.4008177155680266,"holonomicRotation":192.68563803284707,"angularVelocity":0.3195938866074948,"angularAcceleration":2.213748974152889,"curveRadius":7.230868982081428},{"acceleration":3.0125771037525624,"curvature":0.14014726026216215,"pose":{"rotation":{"radians":-2.96496989494048},"translation":{"x":6.172999952503581,"y":2.1492802130979225}},"time":1.844227389793606,"velocity":2.344040977790239,"position":2.4065641105516913,"holonomicRotation":192.84602965958166,"angularVelocity":0.325015501120665,"angularAcceleration":2.2115581370197646,"curveRadius":7.135351758781305},{"acceleration":3.0123711125024513,"curvature":0.14196316634437559,"pose":{"rotation":{"radians":-2.964166599303149},"translation":{"x":6.167372506805498,"y":2.148271146853441}},"time":1.8466588275726274,"velocity":2.3513653707176108,"position":2.412281309146337,"holonomicRotation":193.00642128631623,"angularVelocity":0.3303788582466653,"angularAcceleration":2.2058377032204297,"curveRadius":7.044080698891927},{"acceleration":3.0121640197368333,"curvature":0.14374083651942632,"pose":{"rotation":{"radians":-2.963356988339181},"translation":{"x":6.161773896476387,"y":2.1472625720100713}},"time":1.8490707065890541,"velocity":2.3586303459108495,"position":2.4179700401851467,"holonomicRotation":193.16681291305082,"angularVelocity":0.3356764408389011,"angularAcceleration":2.1964545303289618,"curveRadius":6.956965217499982},{"acceleration":3.011955812273869,"curvature":0.14547740608391915,"pose":{"rotation":{"radians":-2.962541278949695},"translation":{"x":6.156203405950202,"y":2.146254370819323}},"time":1.8514635136374027,"velocity":2.365837375007773,"position":2.4236310325313117,"holonomicRotation":193.3272045397854,"angularVelocity":0.34090061296358626,"angularAcceleration":2.1832818188540406,"curveRadius":6.873919647860276},{"acceleration":3.011746481091741,"curvature":0.14716999819350257,"pose":{"rotation":{"radians":-2.961719697101433},"translation":{"x":6.150660319660899,"y":2.1452464255327084}},"time":1.8538377282411533,"velocity":2.3729879074859754,"position":2.4292650150757886,"holonomicRotation":193.48759616651998,"angularVelocity":0.34604363353014134,"angularAcceleration":2.166198690897796,"curveRadius":6.794863166915151},{"acceleration":3.011536020147811,"curvature":0.14881573092492326,"pose":{"rotation":{"radians":-2.960892477754896},"translation":{"x":6.1451439220424335,"y":2.144238618401739}},"time":1.8561938228749333,"velocity":2.3800833713424807,"position":2.4348727167349575,"holonomicRotation":193.64798779325457,"angularVelocity":0.3510976743790363,"angularAcceleration":2.1450924663355297,"curveRadius":6.7197197082914215},{"acceleration":3.0113244270941038,"curvature":0.1504117239994254,"pose":{"rotation":{"radians":-2.9600598647750966},"translation":{"x":6.139653497528764,"y":2.143230831677924}},"time":1.8585322631773649,"velocity":2.3871251737464942,"position":2.4404548664481953,"holonomicRotation":193.80837941998917,"angularVelocity":0.3560548366077735,"angularAcceleration":2.119858361824594,"curveRadius":6.648417911916362},{"acceleration":3.011111704039728,"curvature":0.1519551072986954,"pose":{"rotation":{"radians":-2.9592221108231658},"translation":{"x":6.134188330553842,"y":2.1422229476127757}},"time":1.8608535081550197,"velocity":2.394114701666654,"position":2.4460121931753687,"holonomicRotation":193.96877104672373,"angularVelocity":0.3609071683494807,"angularAcceleration":2.0904005343759753,"curveRadius":6.580891012990555},{"acceleration":3.0108978555463577,"curvature":0.15344302798111076,"pose":{"rotation":{"radians":-2.958379477223761},"translation":{"x":6.128747705551627,"y":2.141214848457805}},"time":1.8631580103778884,"velocity":2.4010533224675914,"position":2.4515454258942215,"holonomicRotation":194.12916267345832,"angularVelocity":0.3656466854503692,"angularAcceleration":2.0566337727323196,"curveRadius":6.517076814484544},{"acceleration":0.1618447159589695,"curvature":0.15487265885766813,"pose":{"rotation":{"radians":-2.9575322338155234},"translation":{"x":6.123330906956073,"y":2.1402064164645225}},"time":1.865452426601543,"velocity":2.4014246616096004,"position":2.457055293597703,"holonomicRotation":194.2895543001929,"angularVelocity":0.369263170083347,"angularAcceleration":1.5762112365197967,"curveRadius":6.456917621069741},{"acceleration":-2.846629111574702,"curvature":0.15624120642645398,"pose":{"rotation":{"radians":-2.9566806587786014},"translation":{"x":6.117937219201138,"y":2.13919753388444}},"time":1.867743639650435,"velocity":2.394902427843805,"position":2.4625425252912017,"holonomicRotation":194.44994592692748,"angularVelocity":0.37166994895296185,"angularAcceleration":1.0504387057235072,"curveRadius":6.400360205044378},{"acceleration":-3.001692552336336,"curvature":0.1575459190926992,"pose":{"rotation":{"radians":-2.9558250384403078},"translation":{"x":6.112565926720775,"y":2.1381880829690676}},"time":1.870032270281304,"velocity":2.388032662324077,"position":2.468007849989712,"holonomicRotation":194.61033755366208,"angularVelocity":0.37385689361713126,"angularAcceleration":0.9555690790256928,"curveRadius":6.347355778930746},{"acceleration":-3.001507776831697,"curvature":0.15878409638742733,"pose":{"rotation":{"radians":-2.9549656670615083},"translation":{"x":6.107216313948943,"y":2.137177945969917}},"time":1.8723186027260474,"velocity":2.3811702177107565,"position":2.473451996714921,"holonomicRotation":194.77072918039664,"angularVelocity":0.3758733253229222,"angularAcceleration":0.8819503525950126,"curveRadius":6.297859941590352},{"acceleration":-3.001320288058631,"curvature":0.15995309592168652,"pose":{"rotation":{"radians":-2.9541028465997248},"translation":{"x":6.101887665319594,"y":2.1361670051384984}},"time":1.8746029245290796,"velocity":2.3743142363388614,"position":2.4788756944922397,"holonomicRotation":194.93112080713124,"angularVelocity":0.3777140596558013,"angularAcceleration":0.8058121804185843,"curveRadius":6.251832727824179},{"acceleration":-3.0011301219402107,"curvature":0.16105034404470017,"pose":{"rotation":{"radians":-2.953236886452192},"translation":{"x":6.096579265266687,"y":2.1351551427263242}},"time":1.8768855265862388,"velocity":2.3674638505487184,"position":2.484279672347752,"holonomicRotation":195.09151243386583,"angularVelocity":0.37937412034511986,"angularAcceleration":0.7272667980439103,"curveRadius":6.209238520610959},{"acceleration":-3.000937317704844,"curvature":0.162073342856957,"pose":{"rotation":{"radians":-2.952368103176913},"translation":{"x":6.091290398224178,"y":2.1341422409849047}},"time":1.8791667031852965,"velocity":2.360618182564331,"position":2.489664659305128,"holonomicRotation":195.2519040606004,"angularVelocity":0.3808487583283935,"angularAcceleration":0.646437449815461,"curveRadius":6.170046118457506},{"acceleration":-3.000741915816699,"curvature":0.16301967983236093,"pose":{"rotation":{"radians":-2.9514968201939333},"translation":{"x":6.086020348626021,"y":2.1331281821657506}},"time":1.881446752048126,"velocity":2.3537763443715285,"position":2.495031384382467,"holonomicRotation":195.412295687335,"angularVelocity":0.3821334696742307,"angularAcceleration":0.56345781302377,"curveRadius":6.134228708020629},{"acceleration":-3.0005439593931595,"curvature":0.16388703538905025,"pose":{"rotation":{"radians":-2.9506233674650164},"translation":{"x":6.080768400906173,"y":2.1321128485203733}},"time":1.8837259743746173,"velocity":2.346937437587661,"position":2.5003805765890954,"holonomicRotation":195.57268731406958,"angularVelocity":0.3832240140704128,"angularAcceleration":0.4784721453044472,"curveRadius":6.101763923095608},{"acceleration":-3.000343493683944,"curvature":0.1646731928053321,"pose":{"rotation":{"radians":-2.949748081153687},"translation":{"x":6.075533839498589,"y":2.131096122300283}},"time":1.8860046748884267,"velocity":2.3401005533269985,"position":2.5057129649223273,"holonomicRotation":195.73307894080415,"angularVelocity":0.3841164321616961,"angularAcceleration":0.3916346557500988,"curveRadius":6.072633820746689},{"acceleration":-3.0001405652784863,"curvature":0.16537604521575008,"pose":{"rotation":{"radians":-2.948871303265983},"translation":{"x":6.0703159488372265,"y":2.1300778857569926}},"time":1.8882831618846343,"velocity":2.3332647720622166,"position":2.5110292783641803,"holonomicRotation":195.89347056753874,"angularVelocity":0.38480706238975854,"angularAcceleration":0.3031091374284529,"curveRadius":6.046824972113688},{"acceleration":-2.9999352239685657,"curvature":0.16599360381235087,"pose":{"rotation":{"radians":-2.9479933812707126},"translation":{"x":6.065114013356039,"y":2.1290580211420114}},"time":1.8905617472794165,"velocity":2.326429163475589,"position":2.516330245878071,"holonomicRotation":196.0538621942733,"angularVelocity":0.3852925579531699,"angularAcceleration":0.21306884724317324,"curveRadius":6.024328510455499},{"acceleration":-2.9997275201496167,"curvature":0.166524006997771,"pose":{"rotation":{"radians":-2.94711466770376},"translation":{"x":6.059927317488985,"y":2.128036410706851}},"time":1.892840746661808,"velocity":2.3195927863098253,"position":2.521616596405471,"holonomicRotation":196.2142538210079,"angularVelocity":0.3855699013093627,"angularAcceleration":0.1216952309577844,"curveRadius":6.00514014783097},{"acceleration":-2.99951750688857,"curvature":0.16696552539382434,"pose":{"rotation":{"radians":-2.946235519752575},"translation":{"x":6.054755145670019,"y":2.127012936703023}},"time":1.895120479347671,"velocity":2.312754688207553,"position":2.5268890588625608,"holonomicRotation":196.3746454477425,"angularVelocity":0.385636419847235,"angularAcceleration":0.029178218255504155,"curveRadius":5.989260343662463},{"acceleration":-2.9993052388523513,"curvature":0.16731657199299557,"pose":{"rotation":{"radians":-2.9453562988247213},"translation":{"x":6.049596782333097,"y":2.125987481382037}},"time":1.8974012684359574,"velocity":2.3059139055463387,"position":2.5321483621368586,"holonomicRotation":196.53503707447706,"angularVelocity":0.3854897992844416,"angularAcceleration":-0.06428501589490355,"curveRadius":5.976694287293092},{"acceleration":-2.99909077216946,"curvature":0.16757570699096372,"pose":{"rotation":{"radians":-2.944477370101345},"translation":{"x":6.044451511912176,"y":2.1249599269954054}},"time":1.8996834408673802,"velocity":2.299069463266759,"position":2.537395235083852,"holonomicRotation":196.69542870121165,"angularVelocity":0.3851280960519589,"angularAcceleration":-0.15849075534454163,"curveRadius":5.9674520725962},{"acceleration":-2.998874164663296,"curvature":0.1677416440404426,"pose":{"rotation":{"radians":-2.9435991020749914},"translation":{"x":6.039318618841209,"y":2.123930155794639}},"time":1.901967327485605,"velocity":2.292220374692344,"position":2.5426304065236343,"holonomicRotation":196.85582032794622,"angularVelocity":0.38454974924995927,"angularAcceleration":-0.2532292090967085,"curveRadius":5.961548819438657},{"acceleration":-2.9986554757966286,"curvature":0.16781325913733225,"pose":{"rotation":{"radians":-2.942721866073063},"translation":{"x":6.034197387554155,"y":2.122898050031248}},"time":1.9042532631010693,"velocity":2.2853656413417136,"position":2.5478546052375357,"holonomicRotation":197.0162119546808,"angularVelocity":0.3837535913057898,"angularAcceleration":-0.3482853754862964,"curveRadius":5.959004700466704},{"acceleration":-2.9984347660392343,"curvature":0.1677895914207041,"pose":{"rotation":{"radians":-2.941846035771572},"translation":{"x":6.029087102484969,"y":2.1218634919567445}},"time":1.9065415865575648,"velocity":2.2785042527338146,"position":2.553068559964791,"holonomicRotation":197.1766035814154,"angularVelocity":0.3827388558226956,"angularAcceleration":-0.44344058101306694,"curveRadius":5.959845253408292},{"acceleration":-2.998212097595919,"curvature":0.16766985233155984,"pose":{"rotation":{"radians":-2.9409719866941666},"translation":{"x":6.023987048067605,"y":2.120826363822639}},"time":1.9088326408016985,"velocity":2.2716351861828046,"position":2.5582729993992186,"holonomicRotation":197.33699520814997,"angularVelocity":0.3815051868122838,"angularAcceleration":-0.5384721961824716,"curveRadius":5.964101393866224},{"acceleration":-2.997987533398822,"curvature":0.16745342719266834,"pose":{"rotation":{"radians":-2.9401000957035777},"translation":{"x":6.018896508736021,"y":2.1197865478804423}},"time":1.9111267729553678,"velocity":2.2647574065861344,"position":2.5634686521859287,"holonomicRotation":197.49738683488457,"angularVelocity":0.380052643957054,"angularAcceleration":-0.6331557024326175,"curveRadius":5.971809695178238},{"acceleration":-2.9977611377973403,"curvature":0.16713988140544775,"pose":{"rotation":{"radians":-2.9392307404835614},"translation":{"x":6.013814768924173,"y":2.1187439263816654}},"time":1.913424334391394,"velocity":2.2578698662015135,"position":2.5686562469180787,"holonomicRotation":197.65777846161916,"angularVelocity":0.3783817078336531,"angularAcceleration":-0.727265045974564,"curveRadius":5.98301250181099},{"acceleration":-2.9975329756832276,"curvature":0.1667289612743818,"pose":{"rotation":{"radians":-2.9383642990146015},"translation":{"x":6.008741113066016,"y":2.1176983815778203}},"time":1.9157256808124519,"velocity":2.2509715044159218,"position":2.5738365121336697,"holonomicRotation":197.81817008835372,"angularVelocity":0.3764932828155251,"angularAcceleration":-0.8205739913158755,"curveRadius":5.997758232022596},{"acceleration":-2.9973031130797168,"curvature":0.1662205967703824,"pose":{"rotation":{"radians":-2.937501149041878},"translation":{"x":6.003674825595505,"y":2.116649795720417}},"time":1.918031172333452,"velocity":2.244061247502849,"position":2.5790101763123925,"holonomicRotation":197.97856171508832,"angularVelocity":0.37438869970294836,"angularAcceleration":-0.9128565832520383,"curveRadius":6.016101610929739},{"acceleration":-2.9970716164029536,"curvature":0.16561490602554257,"pose":{"rotation":{"radians":-2.936641667542125},"translation":{"x":5.998615190946598,"y":2.1155980510609664}},"time":1.9203411735675329,"velocity":2.2371380083703296,"position":2.584177967872537,"holonomicRotation":198.1389533418229,"angularVelocity":0.372069714540695,"angularAcceleration":-1.0038891443173086,"curveRadius":6.038103839794295},{"acceleration":-2.9968385528690797,"curvature":0.1649121930845763,"pose":{"rotation":{"radians":-2.935786230185663},"translation":{"x":5.9935614935532495,"y":2.114543029850981}},"time":1.9226560537158335,"velocity":2.230200686296631,"position":2.5893406151679716,"holonomicRotation":198.29934496855748,"angularVelocity":0.3695385081122892,"angularAcceleration":-1.0934503154575663,"curveRadius":6.063833008922169},{"acceleration":-2.9966039895310663,"curvature":0.16411294969447318,"pose":{"rotation":{"radians":-2.934935210797084},"translation":{"x":5.9885130178494155,"y":2.11348461434197}},"time":1.9249761866612145,"velocity":2.22324816665626,"position":2.594498846485189,"holonomicRotation":198.45973659529207,"angularVelocity":0.36679768298336124,"angularAcceleration":-1.181322447226345,"curveRadius":6.093364368026327},{"acceleration":-2.9963679944500234,"curvature":0.1632178560662699,"pose":{"rotation":{"radians":-2.934088980819828},"translation":{"x":5.983469048269053,"y":2.112422686785446}},"time":1.9273019510661176,"velocity":2.216279320630777,"position":2.5996533900404346,"holonomicRotation":198.62012822202664,"angularVelocity":0.3638502573485298,"angularAcceleration":-1.2672932944617235,"curveRadius":6.126780636022929},{"acceleration":-2.9961306351129364,"curvature":0.162227778071722,"pose":{"rotation":{"radians":-2.9332479087780094},"translation":{"x":5.978428869246116,"y":2.1113571294329185}},"time":1.9296337304747555,"velocity":2.2092930049102315,"position":2.604804973976932,"holonomicRotation":198.78051984876123,"angularVelocity":0.36069966082679267,"angularAcceleration":-1.3511554781151105,"curveRadius":6.1641724486782605},{"acceleration":-2.9958919789912017,"curvature":0.16114376732694968,"pose":{"rotation":{"radians":-2.932412359746744},"translation":{"x":5.973391765214561,"y":2.1102878245358996}},"time":1.9319719134198263,"velocity":2.20228806137968,"position":2.609954326362183,"holonomicRotation":198.94091147549582,"angularVelocity":0.35734972450581753,"angularAcceleration":-1.4327092446026146,"curveRadius":6.205638707521765},{"acceleration":-2.9956520937233977,"curvature":0.15996705702587655,"pose":{"rotation":{"radians":-2.9315826948246024},"translation":{"x":5.968357020608345,"y":2.1092146543459}},"time":1.9343168935339774,"velocity":2.1952633167909834,"position":2.6151021751853833,"holonomicRotation":199.1013031022304,"angularVelocity":0.3538046728563042,"angularAcceleration":-1.51176192417168,"curveRadius":6.251287099932321},{"acceleration":-2.9954110463777455,"curvature":0.15869905971994758,"pose":{"rotation":{"radians":-2.930759270615026},"translation":{"x":5.963323919861423,"y":2.108137501114431}},"time":1.9366690696662325,"velocity":2.1882175824214003,"position":2.620249248354936,"holonomicRotation":199.26169472896498,"angularVelocity":0.35006911186830225,"angularAcceleration":-1.588129790442386,"curveRadius":6.301234561595235},{"acceleration":-2.995168903351831,"curvature":0.15734136426677325,"pose":{"rotation":{"radians":-2.929942438714611},"translation":{"x":5.958291747407753,"y":2.107056247093003}},"time":1.9390288460036191,"velocity":2.1811496537167945,"position":2.625396273696076,"holonomicRotation":199.42208635569955,"angularVelocity":0.34614801728191447,"angularAcceleration":-1.6616382342109224,"curveRadius":6.355607787310741},{"acceleration":-2.9949257301957415,"curvature":0.15589573029462145,"pose":{"rotation":{"radians":-2.9291325452140287},"translation":{"x":5.9532597876812865,"y":2.105970774533128}},"time":1.9413966321982457,"velocity":2.1740583099189053,"position":2.630543978948615,"holonomicRotation":199.58247798243414,"angularVelocity":0.34204671959834443,"angularAcceleration":-1.7321233196128805,"curveRadius":6.414543862812264},{"acceleration":-2.9946815921888867,"curvature":0.15436408268869414,"pose":{"rotation":{"radians":-2.92832993020685},"translation":{"x":5.948227325115982,"y":2.104880965686316}},"time":1.9437728435000834,"velocity":2.1669423136741406,"position":2.635693091764798,"holonomicRotation":199.74286960916874,"angularVelocity":0.33777089039092356,"angularAcceleration":-1.7994313906822945,"curveRadius":6.478190927462697},{"acceleration":-2.994436552817617,"curvature":0.15274850811634733,"pose":{"rotation":{"radians":-2.927534927315631},"translation":{"x":5.943193644145795,"y":2.1037867028040784}},"time":1.946157900895733,"velocity":2.1598004106280393,"position":2.6408443397072934,"holonomicRotation":199.9032612359033,"angularVelocity":0.33332652399435286,"angularAcceleration":-1.8634211506512321,"curveRadius":6.546708785124814},{"acceleration":-2.9941906751048677,"curvature":0.1510512460419898,"pose":{"rotation":{"radians":-2.926747863228716},"translation":{"x":5.938158029204683,"y":2.1026878681379264}},"time":1.9485522312534607,"velocity":2.1526313289978107,"position":2.6459984502473084,"holonomicRotation":200.0636528626379,"angularVelocity":0.3287199213654778,"angularAcceleration":-1.9239628374620128,"curveRadius":6.620269783951443},{"acceleration":-2.993944019863291,"curvature":0.14927468337087332,"pose":{"rotation":{"radians":-2.9259690572554984},"translation":{"x":5.9331197647266,"y":2.101584343939371}},"time":1.9509562674748089,"velocity":2.1454337791293705,"position":2.6511561507628394,"holonomicRotation":200.2240444893725,"angularVelocity":0.3239576701471993,"angularAcceleration":-1.9809398776894331,"curveRadius":6.69905959549415},{"acceleration":-2.9936966473615705,"curvature":0.14742134683996935,"pose":{"rotation":{"radians":-2.9251988208970574},"translation":{"x":5.928078135145502,"y":2.1004760124599233}},"time":1.9533704486531056,"velocity":2.13820645302978,"position":2.6563181685370565,"holonomicRotation":200.38443611610705,"angularVelocity":0.31904662556618996,"angularAcceleration":-2.034248558127775,"curveRadius":6.783278144145111},{"acceleration":-2.9934486152348607,"curvature":0.14549389544478336,"pose":{"rotation":{"radians":-2.9244374574360887},"translation":{"x":5.923032424895345,"y":2.0993627559510943}},"time":1.9557952202392075,"velocity":2.1309480238831027,"position":2.661485230756828,"holonomicRotation":200.54482774284165,"angularVelocity":0.3139938892935695,"angularAcceleration":-2.083798862367642,"curveRadius":6.873140601143033},{"acceleration":-2.9931999796875997,"curvature":0.14349511153575809,"pose":{"rotation":{"radians":-2.9236852615453985},"translation":{"x":5.917981918410085,"y":2.098244456664395}},"time":1.9582310342148386,"velocity":2.123657145540721,"position":2.666658064511385,"holonomicRotation":200.70521936957624,"angularVelocity":0.30880678829150576,"angularAcceleration":-2.1295144267820394,"curveRadius":6.968878516469924},{"acceleration":-2.992950795222638,"curvature":0.14142789262678104,"pose":{"rotation":{"radians":-2.922942518917689},"translation":{"x":5.912925900123678,"y":2.097120996851336}},"time":1.9606783492739075,"velocity":2.1163324519885203,"position":2.671837396791133,"holonomicRotation":200.8656109963108,"angularVelocity":0.3034928522819301,"angularAcceleration":-2.1713330246892353,"curveRadius":7.070741007496552},{"acceleration":-2.992701113286822,"curvature":0.1392952404302116,"pose":{"rotation":{"radians":-2.9222095059158804},"translation":{"x":5.907863654470081,"y":2.0959922587634283}},"time":1.9631376310121964,"velocity":2.108972556792457,"position":2.677023954486605,"holonomicRotation":201.0260026230454,"angularVelocity":0.2980597913595872,"angularAcceleration":-2.2092063864643117,"curveRadius":7.1789961876049215},{"acceleration":-2.992450983597596,"curvature":0.13710025629168074,"pose":{"rotation":{"radians":-2.9214864892464227},"translation":{"x":5.902794465883248,"y":2.094858124652184}},"time":1.9656093521258549,"velocity":2.101576052514711,"position":2.6822184643875646,"holonomicRotation":201.18639424977997,"angularVelocity":0.2925154725030717,"angularAcceleration":-2.2431004962000904,"curveRadius":7.293932389684965},{"acceleration":-2.9922004533932824,"curvature":0.13484612570074236,"pose":{"rotation":{"radians":-2.92077372565416},"translation":{"x":5.897717618797135,"y":2.0937184767691135}},"time":1.968093992619146,"velocity":2.0941415101041656,"position":2.6874216531822515,"holonomicRotation":201.34678587651456,"angularVelocity":0.2868678966584228,"angularAcceleration":-2.272995171695013,"curveRadius":7.415860076093344},{"acceleration":-2.9919495665937785,"curvature":0.13253611313085678,"pose":{"rotation":{"radians":-2.9200714616428285},"translation":{"x":5.8926323976457,"y":2.092573197365727}},"time":1.9705920400219228,"velocity":2.086667478260097,"position":2.6926342474567777,"holonomicRotation":201.50717750324915,"angularVelocity":0.28112517422641475,"angularAcceleration":-2.2988844909927457,"curveRadius":7.545113376100526},{"acceleration":-2.9916983649291797,"curvature":0.13017354979801737,"pose":{"rotation":{"radians":-2.919379933218755},"translation":{"x":5.887538086862897,"y":2.091422168693537}},"time":1.973103989617344,"velocity":2.0791524827626913,"position":2.6978569736946723,"holonomicRotation":201.66756912998372,"angularVelocity":0.2752955016828972,"angularAcceleration":-2.3207760833036377,"curveRadius":7.682052164603647},{"acceleration":-2.991446886574336,"curvature":0.12776182319698912,"pose":{"rotation":{"radians":-2.9186993656578992},"translation":{"x":5.882433970882682,"y":2.0902652730040536}},"time":1.9756303446803636,"velocity":2.0715950257750397,"position":2.7030905582765654,"holonomicRotation":201.8279607567183,"angularVelocity":0.2693871383392156,"angularAcceleration":-2.3386908001045015,"curveRadius":7.8270642589230555},{"acceleration":-2.991195166810784,"curvature":0.12530436972396514,"pose":{"rotation":{"radians":-2.9180299733006927},"translation":{"x":5.877319334139011,"y":2.089102392548788}},"time":1.9781716167275745,"velocity":2.063993585109871,"position":2.7083357274800277,"holonomicRotation":201.9883523834529,"angularVelocity":0.26340838161786306,"angularAcceleration":-2.352663001158971,"curveRadius":7.980567654607057},{"acceleration":-2.990943237631868,"curvature":0.1228046613770466,"pose":{"rotation":{"radians":-2.917371959369508},"translation":{"x":5.872193461065841,"y":2.0879334095792514}},"time":1.980728325779005,"velocity":2.056346613461903,"position":2.713593207479544,"holonomicRotation":202.14874401018747,"angularVelocity":0.25736754474137113,"angularAcceleration":-2.362739269496512,"curveRadius":8.143013374139802},{"acceleration":-2.9906911271594354,"curvature":0.12026619777314575,"pose":{"rotation":{"radians":-2.916725515813365},"translation":{"x":5.867055636097127,"y":2.0867582063469547}},"time":1.9833010006325256,"velocity":2.0486525376044127,"position":2.7188637243466403,"holonomicRotation":202.30913563692206,"angularVelocity":0.25127293301694575,"angularAcceleration":-2.3689786200868173,"curveRadius":8.314888293768693},{"acceleration":-2.9904388599965173,"curvature":0.11769249562589788,"pose":{"rotation":{"radians":-2.9160908231766673},"translation":{"x":5.8619051436668235,"y":2.085576665103409}},"time":1.9858901791515473,"velocity":2.040909757545662,"position":2.7241480040501393,"holonomicRotation":202.46952726365663,"angularVelocity":0.2451328218717725,"angularAcceleration":-2.3714514468833006,"curveRadius":8.496718458402313},{"acceleration":-2.990186457136176,"curvature":0.11508707866917495,"pose":{"rotation":{"radians":-2.9154680504943675},"translation":{"x":5.856741268208888,"y":2.0843886681001247}},"time":1.988496408566752,"velocity":2.0331166456441268,"position":2.7294467724565594,"holonomicRotation":202.62991889039122,"angularVelocity":0.23895543449343756,"angularAcceleration":-2.370239297544607,"curveRadius":8.68907275746014},{"acceleration":-2.989933934957637,"curvature":0.11245346888382461,"pose":{"rotation":{"radians":-2.914857355212261},"translation":{"x":5.851563294157278,"y":2.083194097588614}},"time":1.9911202457926382,"velocity":2.0252715456826444,"position":2.7347607553306497,"holonomicRotation":202.79031051712582,"angularVelocity":0.23274892058149257,"angularAcceleration":-2.3654340485426655,"curveRadius":8.89256694280456},{"acceleration":-2.989681306452674,"curvature":0.10979517666165414,"pose":{"rotation":{"radians":-2.9142588831314975},"translation":{"x":5.846370505945946,"y":2.081992835820387}},"time":1.9937622577597194,"velocity":2.0173727718932377,"position":2.7400906783360552,"holonomicRotation":202.95070214386038,"angularVelocity":0.22652133609548059,"angularAcceleration":-2.3571371226195272,"curveRadius":9.107868217941936},{"acceleration":-2.989428579667603,"curvature":0.10711568978463298,"pose":{"rotation":{"radians":-2.9136727683785675},"translation":{"x":5.841162188008849,"y":2.080784765046955}},"time":1.996423021763263,"velocity":2.0094186079372935,"position":2.7454372670361056,"holonomicRotation":203.11109377059498,"angularVelocity":0.2202806232155222,"angularAcceleration":-2.3454590003649,"curveRadius":9.335700512320855},{"acceleration":-2.9891757583411915,"curvature":0.10441846878352025,"pose":{"rotation":{"radians":-2.913099133399764},"translation":{"x":5.835937624779945,"y":2.0795697675198292}},"time":1.9991031258295338,"velocity":2.0014073058325654,"position":2.7508012468947314,"holonomicRotation":203.27148539732957,"angularVelocity":0.21403459142602083,"angularAcceleration":-2.3305183810241012,"curveRadius":9.576849877708838},{"acceleration":-2.9889228415922178,"curvature":0.10170693456988876,"pose":{"rotation":{"radians":-2.9125380889784913},"translation":{"x":5.830696100693186,"y":2.078347725490521}},"time":2.0018031691005604,"velocity":1.9933370848265064,"position":2.756183343277505,"holonomicRotation":203.43187702406414,"angularVelocity":0.20779089998041322,"angularAcceleration":-2.312441253296452,"curveRadius":9.832171269628049},{"acceleration":-2.9886698235057096,"curvature":0.09898446204185535,"pose":{"rotation":{"radians":-2.911989734275953},"translation":{"x":5.825436900182532,"y":2.0771185212105405}},"time":2.004523762238513,"velocity":1.9852061302130708,"position":2.7615842814527842,"holonomicRotation":203.59226865079873,"angularVelocity":0.20155704095868351,"angularAcceleration":-2.291360268011655,"curveRadius":10.10259569403077},{"acceleration":-2.988416693397654,"curvature":0.09625437268447126,"pose":{"rotation":{"radians":-2.9114541568958487},"translation":{"x":5.820159307681936,"y":2.075882036931399}},"time":2.0072655278508775,"velocity":1.977012592087697,"position":2.767004786592982,"holonomicRotation":203.75266027753332,"angularVelocity":0.19534032292514752,"angularAcceleration":-2.267414109178607,"curveRadius":10.38913840598257},{"acceleration":-2.988163435361882,"curvature":0.09351992601910275,"pose":{"rotation":{"radians":-2.9109314329688942},"translation":{"x":5.814862607625355,"y":2.074638154904608}},"time":2.0100291009376687,"velocity":1.9687545840387974,"position":2.7724455837759283,"holonomicRotation":203.9130519042679,"angularVelocity":0.1891478569728918,"angularAcceleration":-2.240746221568478,"curveRadius":10.692908373299355},{"acceleration":-2.987910027658603,"curvature":0.09078431252241739,"pose":{"rotation":{"radians":-2.9104216272589234},"translation":{"x":5.809546084446745,"y":2.073386757381678}},"time":2.0128151293620413,"velocity":1.9604301817722727,"position":2.777907397986344,"holonomicRotation":204.07344353100248,"angularVelocity":0.18298654296236838,"angularAcceleration":-2.2115043610550886,"curveRadius":11.015118936469005},{"acceleration":-2.9876564438799753,"curvature":0.08805065054123777,"pose":{"rotation":{"radians":-2.9099247932907253},"translation":{"x":5.8042090225800615,"y":2.07212772661412}},"time":2.015624274345745,"velocity":1.952037421659917,"position":2.783390954117402,"holonomicRotation":204.23383515773705,"angularVelocity":0.1768630565813826,"angularAcceleration":-2.179839921580749,"curveRadius":11.357099508670393},{"acceleration":-2.987402650756524,"curvature":0.08532197511350706,"pose":{"rotation":{"radians":-2.909440973495301},"translation":{"x":5.798850706459261,"y":2.070860944853446}},"time":2.0184572109909786,"velocity":1.943574299216521,"position":2.7888969769723864,"holonomicRotation":204.39422678447164,"angularVelocity":0.17078383882621556,"angularAcceleration":-2.1459067097018965,"curveRadius":11.720310021769444},{"acceleration":-2.987148609948773,"curvature":0.0826012372959009,"pose":{"rotation":{"radians":-2.908970199374076},"translation":{"x":5.793470420518298,"y":2.069586294351166}},"time":2.0213146288303223,"velocity":1.9350387674896827,"position":2.794426191266433,"holonomicRotation":204.55461841120623,"angularVelocity":0.16475508577807538,"angularAcceleration":-2.109860505919194,"curveRadius":12.106356184686657},{"acceleration":-2.986894276575472,"curvature":0.07989129376862522,"pose":{"rotation":{"radians":-2.9085124916814618},"translation":{"x":5.7880674491911295,"y":2.068303657358791}},"time":2.0241972324065496,"velocity":1.9264287353662135,"position":2.7999793216283466,"holonomicRotation":204.7150100379408,"angularVelocity":0.15878273946126917,"angularAcceleration":-2.0718583595954487,"curveRadius":12.517008460222462},{"acceleration":-2.98663959918516,"curvature":0.07719490943786049,"pose":{"rotation":{"radians":-2.9080678606227197},"translation":{"x":5.782641076911712,"y":2.0670129161278323}},"time":2.0271057418842675,"velocity":1.9177420657854558,"position":2.805557092602502,"holonomicRotation":204.8754016646754,"angularVelocity":0.1528724806119272,"angularAcceleration":-2.032057620791825,"curveRadius":12.95422207606797},{"acceleration":-2.9863845201871246,"curvature":0.07451474603167944,"pose":{"rotation":{"radians":-2.907636306068298},"translation":{"x":5.777190588113999,"y":2.0657139529098014}},"time":2.030040893695479,"velocity":1.9089765738520545,"position":2.811160228650804,"holonomicRotation":205.03579329140996,"angularVelocity":0.147029721860846,"angularAcceleration":-1.9906155207248197,"curveRadius":13.420162494747775},{"acceleration":-2.9861289746336332,"curvature":0.07185336456755809,"pose":{"rotation":{"radians":-2.9072178177809502},"translation":{"x":5.771715267231949,"y":2.064406649956209}},"time":2.033003441221334,"velocity":1.9001300248463697,"position":2.8167894541547156,"holonomicRotation":205.19618491814455,"angularVelocity":0.1412596029921639,"angularAcceleration":-1.9476882035898573,"curveRadius":13.917232770078266},{"acceleration":-2.98587289059724,"curvature":0.06921321691158427,"pose":{"rotation":{"radians":-2.9068123756583937},"translation":{"x":5.766214398699517,"y":2.063090889518566}},"time":2.03599415551252,"velocity":1.8912001321207963,"position":2.8224454934173417,"holonomicRotation":205.35657654487915,"angularVelocity":0.1355669860379068,"angularAcceleration":-1.9034305520371213,"curveRadius":14.448107523703746},{"acceleration":-2.9856161888224295,"curvature":0.06659664878935818,"pose":{"rotation":{"radians":-2.9064199499862884},"translation":{"x":5.760687266950658,"y":2.0617665538483827}},"time":2.0390138260509385,"velocity":1.8821845548763834,"position":2.8281290706655686,"holonomicRotation":205.5169681716137,"angularVelocity":0.1299564529019095,"angularAcceleration":-1.8579951238440058,"curveRadius":15.015770585738467},{"acceleration":-2.9853587822360677,"curvature":0.06400589249441155,"pose":{"rotation":{"radians":-2.9060405017038358},"translation":{"x":5.755133156419329,"y":2.0604335251971717}},"time":2.0420632615555374,"velocity":1.8730808958118665,"position":2.8338409100522433,"holonomicRotation":205.6773597983483,"angularVelocity":0.12443230292307171,"angularAcceleration":-1.8115319935465803,"curveRadius":15.623561535171337},{"acceleration":-2.985100575712355,"curvature":0.06144306931966145,"pose":{"rotation":{"radians":-2.905673982677872},"translation":{"x":5.749551351539486,"y":2.059091685816443}},"time":2.0451432908354077,"velocity":1.8638866986353149,"position":2.8395817356584008,"holonomicRotation":205.8377514250829,"angularVelocity":0.11899855250047055,"angularAcceleration":-1.7641879114960939,"curveRadius":16.275228615247666},{"acceleration":-2.9848414659273157,"curvature":0.05891018399163823,"pose":{"rotation":{"radians":-2.9053203359879896},"translation":{"x":5.743941136745083,"y":2.057740917957708}},"time":2.0482547636935218,"velocity":1.8545994454283086,"position":2.8453522714955244,"holonomicRotation":205.99814305181746,"angularVelocity":0.1136589345333168,"angularAcceleration":-1.7161062334929649,"curveRadius":16.974993663946815},{"acceleration":-2.9845813405379875,"curvature":0.05640912827002364,"pose":{"rotation":{"radians":-2.904979496218021},"translation":{"x":5.738301796470079,"y":2.0563811038724777}},"time":2.051398551884772,"velocity":1.8452165538540997,"position":2.8511532415078302,"holonomicRotation":206.15853467855206,"angularVelocity":0.10841690000532217,"angularAcceleration":-1.66742611432422,"curveRadius":17.727627259423716},{"acceleration":-2.984320078050687,"curvature":0.05394167876488653,"pose":{"rotation":{"radians":-2.904651389755157},"translation":{"x":5.732632615148427,"y":2.055012125812263}},"time":2.054575550132309,"velocity":1.8357353741960434,"position":2.8569853695745926,"holonomicRotation":206.31892630528665,"angularVelocity":0.1032756197200738,"angularAcceleration":-1.6182823799900805,"curveRadius":18.538540566352424},{"acceleration":-2.984057547733314,"curvature":0.051509495676159846,"pose":{"rotation":{"radians":-2.904335935094988},"translation":{"x":5.726932877214084,"y":2.0536338660285747}},"time":2.0577866772065034,"velocity":1.8261531862135623,"position":2.8628493795124696,"holonomicRotation":206.47931793202122,"angularVelocity":0.09823798712413571,"angularAcceleration":-1.5688051203023927,"curveRadius":19.413896153963517},{"acceleration":-2.9837936085873147,"curvature":0.0491141239587484,"pose":{"rotation":{"radians":-2.9040330431513395},"translation":{"x":5.721201867101007,"y":2.0522462067729244}},"time":2.061032877071278,"velocity":1.8164671958048515,"position":2.8687459950778584,"holonomicRotation":206.6397095587558,"angularVelocity":0.0933066219783713,"angularAcceleration":-1.5191193861093852,"curveRadius":20.36074186806046},{"acceleration":-2.983528108685223,"curvature":0.0467569967012438,"pose":{"rotation":{"radians":-2.9037426175698493},"translation":{"x":5.715438869243149,"y":2.050849030296822}},"time":2.0643151201029584,"velocity":1.8066745314602963,"position":2.8746759399692587,"holonomicRotation":206.80010118549038,"angularVelocity":0.08848387480358805,"angularAcceleration":-1.469344935226789,"curveRadius":21.387173483137737},{"acceleration":-2.9832608857339133,"curvature":0.04443943171427635,"pose":{"rotation":{"radians":-2.9034645550454505},"translation":{"x":5.70964316807447,"y":2.0494422188517802}},"time":2.067634404387292,"velocity":1.7967722404862123,"position":2.8806399378296317,"holonomicRotation":206.96049281222497,"angularVelocity":0.0837718316900919,"angularAcceleration":-1.419596126712002,"curveRadius":22.5025379808974},{"acceleration":-2.982991765067713,"curvature":0.04216263698318793,"pose":{"rotation":{"radians":-2.9031987456398207},"translation":{"x":5.703814048028923,"y":2.0480256546893085}},"time":2.0709917571008036,"velocity":1.7867572849893796,"position":2.8866387122487773,"holonomicRotation":207.12088443895956,"angularVelocity":0.07917232066802854,"angularAcceleration":-1.369981474854511,"curveRadius":23.717681614618726},{"acceleration":-2.9827205598426447,"curvature":0.039927707623297316,"pose":{"rotation":{"radians":-2.9029450731033166},"translation":{"x":5.697950793540462,"y":2.046599220060919}},"time":2.0743882359832386,"velocity":1.7766265375956694,"position":2.8926729867656946,"holonomicRotation":207.28127606569413,"angularVelocity":0.0746869170351618,"angularAcceleration":-1.320604010248131,"curveRadius":25.04526454247307},{"acceleration":-2.9824470703971757,"curvature":0.03773563235774043,"pose":{"rotation":{"radians":-2.90270341519343},"translation":{"x":5.692052689043048,"y":2.045162797218122}},"time":2.0778249309085135,"velocity":1.7663767768839345,"position":2.898743484870935,"holonomicRotation":207.44166769242872,"angularVelocity":0.07031695135615722,"angularAcceleration":-1.271560546985432,"curveRadius":26.500152177650666},{"acceleration":-2.9821710824761998,"curvature":0.03558729606571058,"pose":{"rotation":{"radians":-2.9024736439961805},"translation":{"x":5.686119018970633,"y":2.043716268412429}},"time":2.0813029655623136,"velocity":1.7560046825155216,"position":2.9048509300089593,"holonomicRotation":207.60205931916332,"angularVelocity":0.066063515784295,"angularAcceleration":-1.2229422634460723,"curveRadius":28.099915153810457},{"acceleration":-2.9818923678838596,"curvature":0.03348347632161145,"pose":{"rotation":{"radians":-2.902255626243924},"translation":{"x":5.680149067757175,"y":2.0422595158953514}},"time":2.084823499235281,"velocity":1.7455068300252214,"position":2.910996045580458,"holonomicRotation":207.76245094589788,"angularVelocity":0.06192747251089617,"angularAcceleration":-1.1748341750449525,"curveRadius":29.86547724002492},{"acceleration":-2.9816106819072594,"curvature":0.031424852322229385,"pose":{"rotation":{"radians":-2.902049223632187},"translation":{"x":5.674142119836628,"y":2.040792421918399}},"time":2.088387728741666,"velocity":1.7348796852562152,"position":2.917179554944676,"holonomicRotation":207.92284257263248,"angularVelocity":0.05790946160101763,"angularAcceleration":-1.1273154275505373,"curveRadius":31.821947474757664},{"acceleration":-2.981325763622808,"curvature":0.029412006057310175,"pose":{"rotation":{"radians":-2.901854293134068},"translation":{"x":5.66809745964295,"y":2.039314868733084}},"time":2.091996890474298,"velocity":1.7241195983976387,"position":2.923402181421693,"holonomicRotation":208.08323419936704,"angularVelocity":0.054009909380505906,"angularAcceleration":-1.0804592615660564,"curveRadius":33.999721000038896},{"acceleration":-2.9810373338068414,"curvature":0.02744542214591239,"pose":{"rotation":{"radians":-2.901670687310108},"translation":{"x":5.662014371610095,"y":2.037826738590917}},"time":2.0956522626079073,"velocity":1.7132227975983918,"position":2.9296646482946986,"holonomicRotation":208.24362582610163,"angularVelocity":0.05022903749567362,"angularAcceleration":-1.0343329616344477,"curveRadius":36.43594894199636},{"acceleration":-2.9807450942874496,"curvature":0.02552549546122646,"pose":{"rotation":{"radians":-2.901498254616068},"translation":{"x":5.6558921401720195,"y":2.0363279137434085}},"time":2.0993551674640747,"velocity":1.7021853821137576,"position":2.935967678812225,"holonomicRotation":208.40401745283623,"angularVelocity":0.04656687134507839,"angularAcceleration":-0.988998176525021,"curveRadius":39.17651673085101},{"acceleration":-2.9804487260420744,"curvature":0.023652530319699865,"pose":{"rotation":{"radians":-2.901336839704291},"translation":{"x":5.64973004976268,"y":2.03481827644207}},"time":2.1031069740525385,"velocity":1.6910033149468142,"position":2.9423119961903565,"holonomicRotation":208.5644090795708,"angularVelocity":0.043023249725376016,"angularAcceleration":-0.9445107406651471,"curveRadius":42.278774680065155},{"acceleration":-2.980147887945336,"curvature":0.021826746921382867,"pose":{"rotation":{"radians":-2.901186283721591},"translation":{"x":5.643527384816032,"y":2.033297708938413}},"time":2.1069091008052103,"velocity":1.679672414935139,"position":2.9486983236149062,"holonomicRotation":208.7248007063054,"angularVelocity":0.039597833658274836,"angularAcceleration":-0.9009210607442587,"curveRadius":45.815347729181596},{"acceleration":-2.97984221497521,"curvature":0.020048285488190955,"pose":{"rotation":{"radians":-2.901046424600646},"translation":{"x":5.637283429766032,"y":2.0317660934839483}},"time":2.1107630185210704,"velocity":1.6681883482323783,"position":2.9551273842435504,"holonomicRotation":208.88519233303998,"angularVelocity":0.036290115995309555,"angularAcceleration":-0.8582740750672978,"curveRadius":49.87957701365686},{"acceleration":-2.9795313163164363,"curvature":0.01831720281397368,"pose":{"rotation":{"radians":-2.900917097345847},"translation":{"x":5.630997469046634,"y":2.030223312330186}},"time":2.1146702535421977,"velocity":1.656546619126721,"position":2.9615999012079324,"holonomicRotation":209.04558395977455,"angularVelocity":0.03309943069709923,"angularAcceleration":-0.8166095156696599,"curveRadius":54.59348843575221},{"acceleration":-2.979214772981511,"curvature":0.016633486882289675,"pose":{"rotation":{"radians":-2.9007981343133533},"translation":{"x":5.624668787091796,"y":2.028669247728638}},"time":2.11863239118352,"velocity":1.6447425601331074,"position":2.9681165976157207,"holonomicRotation":209.20597558650914,"angularVelocity":0.03002496209447915,"angularAcceleration":-0.7759620893922253,"curveRadius":60.119685492086404},{"acceleration":-2.978892136035478,"curvature":0.014997051754273263,"pose":{"rotation":{"radians":-2.9006893654832577},"translation":{"x":5.618296668335472,"y":2.027103781930815}},"time":2.1226510794415603,"velocity":1.6327713212840533,"position":2.9746781965526297,"holonomicRotation":209.36636721324373,"angularVelocity":0.027065754572520227,"angularAcceleration":-0.7363615518169228,"curveRadius":66.67977255696673},{"acceleration":-2.9785629233183855,"curvature":0.013407740576247825,"pose":{"rotation":{"radians":-2.9005906187257002},"translation":{"x":5.611880397211619,"y":2.025526797188229}},"time":2.12672803301047,"velocity":1.6206278585436087,"position":2.9812854210843933,"holonomicRotation":209.5267588399783,"angularVelocity":0.024220721646312584,"angularAcceleration":-0.697833045709317,"curveRadius":74.58378198124798},{"acceleration":-2.978226616917716,"curvature":0.011865338690294405,"pose":{"rotation":{"radians":-2.900501720059263},"translation":{"x":5.6054192581541935,"y":2.0239381757523893}},"time":2.1308650376371308,"velocity":1.6083069212501755,"position":2.987938994258696,"holonomicRotation":209.6871504667129,"angularVelocity":0.021488655309743903,"angularAcceleration":-0.6603972156477428,"curveRadius":84.27909443646803},{"acceleration":-2.977882659648975,"curvature":0.010369565754711154,"pose":{"rotation":{"radians":-2.9004224939027234},"translation":{"x":5.59891253559715,"y":2.0223377998748084}},"time":2.135063954851065,"velocity":1.595803038489499,"position":2.994639639107058,"holonomicRotation":209.84754209344746,"angularVelocity":0.018868234952749863,"angularAcceleration":-0.6240704980555618,"curveRadius":96.43605370318183},{"acceleration":-2.9775304518424233,"curvature":0.008920089478038885,"pose":{"rotation":{"radians":-2.9003527633171364},"translation":{"x":5.592359513974446,"y":2.0207255518069966}},"time":2.139326727109453,"velocity":1.5831105042808793,"position":3.0013880786466696,"holonomicRotation":210.00793372018205,"angularVelocity":0.0163580368268092,"angularAcceleration":-0.5888651735971102,"curveRadius":112.10649875900725},{"acceleration":-2.9771693463936844,"curvature":0.007516521155078032,"pose":{"rotation":{"radians":-2.900292350242433},"translation":{"x":5.5857594777200354,"y":2.0191013138004648}},"time":2.143655383402799,"velocity":1.5702233614532555,"position":3.008185035882183,"holonomicRotation":210.16832534691665,"angularVelocity":0.013956542309942078,"angularAcceleration":-0.5547898364115197,"curveRadius":133.04026947684665},{"acceleration":-2.9767986450401933,"curvature":0.006158417282704069,"pose":{"rotation":{"radians":-2.9002410757241237},"translation":{"x":5.579111711267876,"y":2.017464968106725}},"time":2.1480520453728205,"velocity":1.5571353840581963,"position":3.0150312338074463,"holonomicRotation":210.3287169736512,"angularVelocity":0.011662147024050714,"angularAcceleration":-0.52184937153134,"curveRadius":162.379383223755},{"acceleration":-2.976417592580032,"curvature":0.004845297405572921,"pose":{"rotation":{"radians":-2.900198760132383},"translation":{"x":5.572415499051922,"y":2.0158163969772867}},"time":2.152518934001147,"velocity":1.54384005816075,"position":3.0219273954071992,"holonomicRotation":210.4891086003858,"angularVelocity":0.009473169192645145,"angularAcceleration":-0.49004531197047996,"curveRadius":206.38568003066828},{"acceleration":-2.976025371283648,"curvature":0.0035766350618232894,"pose":{"rotation":{"radians":-2.900165223373964},"translation":{"x":5.56567012550613,"y":2.0141554826636625}},"time":2.157058376935489,"velocity":1.5303305608166529,"position":3.0288742436587066,"holonomicRotation":210.64950022712037,"angularVelocity":0.007387857696162727,"angularAcceleration":-0.45937607910132483,"curveRadius":279.59240535158824},{"acceleration":-2.9756210939213625,"curvature":0.002351859117512644,"pose":{"rotation":{"radians":-2.9001402850934968},"translation":{"x":5.558874875064457,"y":2.0124821074173624}},"time":2.1616728165294012,"velocity":1.5165997370243822,"position":3.0358725015333485,"holonomicRotation":210.80989185385496,"angularVelocity":0.005404400677440356,"angularAcceleration":-0.4298370318552213,"curveRadius":425.19553682178577},{"acceleration":-2.975203796717629,"curvature":0.0011703673500697738,"pose":{"rotation":{"radians":-2.900123764869361},"translation":{"x":5.552029032160857,"y":2.0107961534898977}},"time":2.166364818682751,"velocity":1.5026400744035284,"position":3.0429228919981597,"holonomicRotation":210.97028348058956,"angularVelocity":0.003520932769391574,"angularAcceleration":-0.4014209385441303,"curveRadius":854.4325847268235},{"acceleration":-2.9747724303072145,"curvature":0.00003155094291629433,"pose":{"rotation":{"radians":-2.9001154823988045},"translation":{"x":5.5451318812292865,"y":2.0090975031327796}},"time":2.1711370825829017,"velocity":1.48844367532321,"position":3.050026138017312,"holonomicRotation":211.13067510732412,"angularVelocity":0.0017355432829788318,"angularAcceleration":-0.37411792888410733,"curveRadius":31694.77383458974},{"acceleration":-2.974325850165087,"curvature":-0.0010653563558956705,"pose":{"rotation":{"radians":-2.9001152576759615},"translation":{"x":5.538182706703703,"y":2.007386038597519}},"time":2.175992451461758,"velocity":1.4740022261547403,"position":3.057182962553549,"holonomicRotation":211.29106673405872,"angularVelocity":0.00004628337179063526,"angularAcceleration":-0.3479158748461707,"curveRadius":-938.6530567598446},{"acceleration":-2.9738628055781766,"curvature":-0.002120947177569887,"pose":{"rotation":{"radians":-2.900122911161933},"translation":{"x":5.531180793018059,"y":2.005661642135627}},"time":2.180933924501696,"velocity":1.4593069632765014,"position":3.0643940885695735,"holonomicRotation":211.4514583607933,"angularVelocity":-0.0015488268194101566,"angularAcceleration":-0.32280054516311085,"curveRadius":-471.4874611567497},{"acceleration":-2.973381926559085,"curvature":-0.0031359802240431335,"pose":{"rotation":{"radians":-2.9001382639454714},"translation":{"x":5.524125424606313,"y":2.0039241959986143}},"time":2.1859646700444975,"velocity":1.4443486354024182,"position":3.0716602390293755,"holonomicRotation":211.61184998752788,"angularVelocity":-0.0030517909140181107,"angularAcceleration":-0.29875573745895145,"curveRadius":-318.8795619095861},{"acceleration":-2.972881709412179,"curvature":-0.004111204293528915,"pose":{"rotation":{"radians":-2.900161137897021},"translation":{"x":5.5170158859024205,"y":2.0021735824379925}},"time":2.191088040282569,"velocity":1.4291174617311087,"position":3.078982136899517,"holonomicRotation":211.77224161426247,"angularVelocity":-0.004464629821164784,"angularAcceleration":-0.2757635777808783,"curveRadius":-243.23773001843088},{"acceleration":-2.9723604995763284,"curvature":-0.0050473792210037885,"pose":{"rotation":{"radians":-2.9001913558135333},"translation":{"x":5.509851461340339,"y":2.0004096837052723}},"time":2.1963075876416447,"velocity":1.413603085335324,"position":3.08636050515036,"holonomicRotation":211.93263324099706,"angularVelocity":-0.00578937490807519,"angularAcceleration":-0.2538045918113857,"curveRadius":-198.12262091159593},{"acceleration":-2.971816472013301,"curvature":-0.005945274497820833,"pose":{"rotation":{"radians":-2.900228741556566},"translation":{"x":5.50263143535402,"y":1.9986323820519645}},"time":2.2016270831001026,"velocity":1.397794521109079,"position":3.0937960667572573,"holonomicRotation":212.09302486773163,"angularVelocity":-0.007028061838735343,"angularAcceleration":-0.23285797315432727,"curveRadius":-168.20081232019442},{"acceleration":-2.9712476085299393,"curvature":-0.006805696774984328,"pose":{"rotation":{"radians":-2.900273120181495},"translation":{"x":5.495355092377423,"y":1.9968415597295803}},"time":2.207050536733202,"velocity":1.3816800974717591,"position":3.1012895447016717,"holonomicRotation":212.25341649446622,"angularVelocity":-0.008182724133167101,"angularAcceleration":-0.21290166239918107,"curveRadius":-146.93572650425682},{"acceleration":-2.970651670958995,"curvature":-0.007629447254546974,"pose":{"rotation":{"radians":-2.9003243180600644},"translation":{"x":5.488021716844504,"y":1.995037098989631}},"time":2.2125822208228425,"velocity":1.3652473908876515,"position":3.108841661972268,"holonomicRotation":212.41380812120082,"angularVelocity":-0.00925538728168425,"angularAcceleration":-0.19391258270261608,"curveRadius":-131.07109422691443},{"acceleration":-2.970026170153419,"curvature":-0.008417346102073618,"pose":{"rotation":{"radians":-2.9003821629951076},"translation":{"x":5.480630593189216,"y":1.9932188820836274}},"time":2.2182266959369215,"velocity":1.3484831520820573,"position":3.11645314156595,"holonomicRotation":212.57419974793538,"angularVelocity":-0.010248062729332734,"angularAcceleration":-0.17586674182909678,"curveRadius":-118.8022908733252},{"acceleration":-2.9693683293269584,"curvature":-0.009170213040035458,"pose":{"rotation":{"radians":-2.900446484327984},"translation":{"x":5.473181005845516,"y":1.9913867912630805}},"time":2.2239888404599713,"velocity":1.3313732226263084,"position":3.1241247064888413,"holonomicRotation":212.73459137466998,"angularVelocity":-0.011162742034510332,"angularAcceleration":-0.15873938973913063,"curveRadius":-109.04872063867923},{"acceleration":-2.96867504077758,"curvature":-0.009888886761233171,"pose":{"rotation":{"radians":-2.9005171130391227},"translation":{"x":5.465672239247362,"y":1.9895407087795016}},"time":2.229873884152108,"velocity":1.3139024403035766,"position":3.131857079757233,"holonomicRotation":212.89498300140454,"angularVelocity":-0.012001391125284396,"angularAcceleration":-0.1425051596294217,"curveRadius":-101.1236172629908},{"acceleration":-2.9679428146970444,"curvature":-0.010574196830937533,"pose":{"rotation":{"radians":-2.9005938818413886},"translation":{"x":5.458103577828708,"y":1.9876805168844012}},"time":2.235887446431116,"velocity":1.2960545313468614,"position":3.139650984398478,"holonomicRotation":213.05537462813913,"angularVelocity":-0.012765944494130547,"angularAcceleration":-0.12713818089404796,"curveRadius":-94.56983031318678},{"acceleration":-2.9671677178423685,"curvature":-0.011226982620788294,"pose":{"rotation":{"radians":-2.900676625267235},"translation":{"x":5.45047430602351,"y":1.9858060978292909}},"time":2.242035580219008,"velocity":1.2778119872464526,"position":3.147507143451841,"holonomicRotation":213.2157662548737,"angularVelocity":-0.013458299493991273,"angularAcceleration":-0.1126122208375238,"curveRadius":-89.0711274593374},{"acceleration":-2.966345300276796,"curvature":-0.011848082505752663,"pose":{"rotation":{"radians":-2.900765179748589},"translation":{"x":5.442783708265724,"y":1.9839173338656815}},"time":2.2483248223777927,"velocity":1.2591559233264387,"position":3.1554262799693094,"holonomicRotation":213.3761578816083,"angularVelocity":-0.014080310332833674,"angularAcceleration":-0.09890076151282845,"curveRadius":-84.40184304206733},{"acceleration":-2.9654705070065863,"curvature":-0.012438333748497269,"pose":{"rotation":{"radians":-2.9008593836909022},"translation":{"x":5.435031068989307,"y":1.9820141072450834}},"time":2.2547622519903388,"velocity":1.2400659156695026,"position":3.163409117016349,"holonomicRotation":213.5365495083429,"angularVelocity":-0.014633782112270443,"angularAcceleration":-0.0859771388192111,"curveRadius":-80.39662065835904},{"acceleration":-2.96453757071282,"curvature":-0.012998573193668907,"pose":{"rotation":{"radians":-2.9009590775417684},"translation":{"x":5.427215672628213,"y":1.980096300219009}},"time":2.2613555580358176,"velocity":1.2205198121824727,"position":3.1714563776726385,"holonomicRotation":213.69694113507745,"angularVelocity":-0.015120464631628867,"angularAcceleration":-0.07381464109225673,"curveRadius":-76.93152049080746},{"acceleration":-2.963539880857217,"curvature":-0.013529630841456633,"pose":{"rotation":{"radians":-2.9010641038513576},"translation":{"x":5.4193368036164,"y":1.978163795038968}},"time":2.268113118384973,"velocity":1.2004935125904512,"position":3.179568785032738,"holonomicRotation":213.85733276181205,"angularVelocity":-0.015542045377711224,"angularAcceleration":-0.06238653068559678,"curveRadius":-73.91184665111953},{"acceleration":-2.962469822838559,"curvature":-0.014032336214996903,"pose":{"rotation":{"radians":-2.90117430733042},"translation":{"x":5.411393746387821,"y":1.9762164739564723}},"time":2.275044092525689,"velocity":1.179960710855705,"position":3.18774706220674,"holonomicRotation":214.01772438854664,"angularVelocity":-0.015900142869517783,"angularAcceleration":-0.051666257085408174,"curveRadius":-71.26397092247983},{"acceleration":-2.9613185789604173,"curvature":-0.0145075106462983,"pose":{"rotation":{"radians":-2.901289534899745},"translation":{"x":5.403385785376434,"y":1.9742542192230326}},"time":2.282158531061384,"velocity":1.1588925918410797,"position":3.1959919323208656,"holonomicRotation":214.1781160152812,"angularVelocity":-0.016196298379292103,"angularAcceleration":-0.04162739031174876,"curveRadius":-68.92981327952066},{"acceleration":-2.9600758797055575,"curvature":-0.014955966668040171,"pose":{"rotation":{"radians":-2.9014096357362136},"translation":{"x":5.395312205016195,"y":1.9722769130901596}},"time":2.289467505856406,"velocity":1.1372574718449602,"position":3.2043041185180305,"holonomicRotation":214.3385076420158,"angularVelocity":-0.016431967524393427,"angularAcceleration":-0.03224380322967375,"curveRadius":-66.86294655476388},{"acceleration":-2.958729691024974,"curvature":-0.015378510523757112,"pose":{"rotation":{"radians":-2.9015344613132803},"translation":{"x":5.387172289741059,"y":1.970284437809365}},"time":2.296983265808318,"velocity":1.115020369724621,"position":3.212684343958373,"holonomicRotation":214.4988992687504,"angularVelocity":-0.016608510365603624,"angularAcceleration":-0.023489685985151696,"curveRadius":-65.02580327627794},{"acceleration":-2.9572658169810198,"curvature":-0.01577594098126528,"pose":{"rotation":{"radians":-2.901663865436236},"translation":{"x":5.378965323984983,"y":1.9682766756321595}},"time":2.3047194247139626,"velocity":1.092142491438225,"position":3.221133331819746,"holonomicRotation":214.65929089548496,"angularVelocity":-0.01672718005590519,"angularAcceleration":-0.015339613850871342,"curveRadius":-63.38766107121915},{"acceleration":-2.955667389654358,"curvature":-0.01614904428106677,"pose":{"rotation":{"radians":-2.9017977042731995},"translation":{"x":5.370690592181921,"y":1.966253508810054}},"time":2.312691189720765,"velocity":1.0685806055696316,"position":3.2296518052981735,"holonomicRotation":214.81968252221955,"angularVelocity":-0.01678910967008939,"angularAcceleration":-0.007768620140126346,"curveRadius":-61.92316911115327},{"acceleration":-2.953914207927873,"curvature":-0.016498596944072456,"pose":{"rotation":{"radians":-2.9019358363816994},"translation":{"x":5.362347378765831,"y":1.96421481959456}},"time":2.320915641648563,"velocity":1.044286280167689,"position":3.2382404876082718,"holonomicRotation":214.98007414895415,"angularVelocity":-0.01679529647842086,"angularAcceleration":-0.0007522456676485055,"curveRadius":-60.61121460144983},{"acceleration":-2.951981868924023,"curvature":-0.016825365308932992,"pose":{"rotation":{"radians":-2.9020781227305643},"translation":{"x":5.353934968170666,"y":1.9621604902371876}},"time":2.3294120823794646,"velocity":1.01920494117968,"position":3.246900101983647,"holonomicRotation":215.1404657756887,"angularVelocity":-0.016746582877631574,"angularAcceleration":0.005733412652678613,"curveRadius":-59.434073592986174},{"acceleration":-2.9498406134116837,"curvature":-0.01713010154496796,"pose":{"rotation":{"radians":-2.902224426718256},"translation":{"x":5.345452644830386,"y":1.9600904029894486}},"time":2.3382024700803705,"velocity":0.9932746985319132,"position":3.255631371677243,"holonomicRotation":215.3008574024233,"angularVelocity":-0.016643633099005354,"angularAcceleration":0.011711631173629689,"curveRadius":-58.376770118666},{"acceleration":-2.9474537674855625,"curvature":-0.017413549834836957,"pose":{"rotation":{"radians":-2.9023746141872806},"translation":{"x":5.336899693178944,"y":1.9580044401028542}},"time":2.3473119710865857,"velocity":0.9664248654712306,"position":3.2644350199616845,"holonomicRotation":215.4612490291579,"angularVelocity":-0.0164869040490724,"angularAcceleration":0.017205009344202504,"curveRadius":-57.42654481623465},{"acceleration":-2.944775606667873,"curvature":-0.01767643558612113,"pose":{"rotation":{"radians":-2.9025285534341028},"translation":{"x":5.328275397650297,"y":1.9559024838289147}},"time":2.356769669186029,"velocity":0.9385740668127606,"position":3.2733117701295664,"holonomicRotation":215.62164065589246,"angularVelocity":-0.016276608240563845,"angularAcceleration":0.022235411439167258,"curveRadius":-56.57249138990228},{"acceleration":-2.941748375054788,"curvature":-0.017919474136406675,"pose":{"rotation":{"radians":-2.902686115217202},"translation":{"x":5.3195790426783995,"y":1.9537844164191416}},"time":2.3666094910263866,"velocity":0.9096277869030603,"position":3.282262345493731,"holonomicRotation":215.78203228262706,"angularVelocity":-0.016012666251039736,"angularAcceleration":0.026823858582638704,"curveRadius":-55.80520903614676},{"acceleration":-2.9382980422049085,"curvature":-0.01814336831937277,"pose":{"rotation":{"radians":-2.902847172760054},"translation":{"x":5.310809912697208,"y":1.9516501201250458}},"time":2.3768714341893897,"velocity":0.8794751393979903,"position":3.2912874693875076,"holonomicRotation":215.94242390936162,"angularVelocity":-0.015694643820750212,"angularAcceleration":0.030990468884691837,"curveRadius":-55.11655732261355},{"acceleration":-2.9343281257213154,"curvature":-0.01834880456576999,"pose":{"rotation":{"radians":-2.9030116017522833},"translation":{"x":5.30196729214068,"y":1.9494994771981382}},"time":2.387603228726807,"velocity":0.8479845328473838,"position":3.3003878651649337,"holonomicRotation":216.10281553609622,"angularVelocity":-0.015321667933152143,"angularAcceleration":0.03475428888408661,"curveRadius":-54.499463243808115},{"acceleration":-2.929710464710926,"curvature":-0.018536456520065355,"pose":{"rotation":{"radians":-2.903179280347402},"translation":{"x":5.293050465442769,"y":1.9473323698899303}},"time":2.398862635581182,"velocity":0.8149977307596835,"position":3.3095642562009493,"holonomicRotation":216.26320716283078,"angularVelocity":-0.014892311583306566,"angularAcceleration":0.03813312329847506,"curveRadius":-53.94774340594813},{"acceleration":-2.9242710273957435,"curvature":-0.018706978706335965,"pose":{"rotation":{"radians":-2.90335008915734},"translation":{"x":5.284058717037433,"y":1.9451486804519325}},"time":2.4107207089089866,"velocity":0.7803215104864508,"position":3.3188173658915607,"holonomicRotation":216.42359878956538,"angularVelocity":-0.01440443191875108,"angularAcceleration":0.04114324908174779,"curveRadius":-53.45598643683198},{"acceleration":-2.9177673206688266,"curvature":-0.018861021132600738,"pose":{"rotation":{"radians":-2.9035239112455753},"translation":{"x":5.274991331358627,"y":1.9429482911356564}},"time":2.4232665686790913,"velocity":0.7437156108395456,"position":3.3281479176539914,"holonomicRotation":216.58399041629997,"angularVelocity":-0.013854936323269146,"angularAcceleration":0.04379895882395535,"curveRadius":-53.01939873613356},{"acceleration":-2.9098509524100153,"curvature":-0.018999207368097435,"pose":{"rotation":{"radians":-2.9037006321162324},"translation":{"x":5.265847592840306,"y":1.9407310841926126}},"time":2.4366146390002585,"velocity":0.7048747157026612,"position":3.3375566349268033,"holonomicRotation":216.74438204303453,"angularVelocity":-0.013239432098052308,"angularAcceleration":0.04611185065760229,"curveRadius":-52.633774695209254},{"acceleration":-2.9000025194838615,"curvature":-0.01912215362454421,"pose":{"rotation":{"radians":-2.903880139702234},"translation":{"x":5.256626785916426,"y":1.9384969418743123}},"time":2.4509161171783935,"velocity":0.6634003929537263,"position":3.347044241169997,"holonomicRotation":216.90477366976913,"angularVelocity":-0.012551680586124615,"angularAcceleration":0.04808954035109264,"curveRadius":-52.29536482315734},{"acceleration":-2.8874114800948636,"curvature":-0.019230459205648472,"pose":{"rotation":{"radians":-2.9040623243505856},"translation":{"x":5.247328195020945,"y":1.9362457464322667}},"time":2.4663781611177775,"velocity":0.6187551097774178,"position":3.356611459865094,"holonomicRotation":217.06516529650372,"angularVelocity":-0.011782701502211907,"angularAcceleration":0.04973333971416355,"curveRadius":-52.00083832144137},{"acceleration":-2.8707375027037454,"curvature":-0.019324706558379236,"pose":{"rotation":{"radians":-2.9042470788059114},"translation":{"x":5.2379511045878155,"y":1.9339773801179865}},"time":2.4832982978057463,"velocity":0.5701818388363923,"position":3.366259014515203,"holonomicRotation":217.2255569232383,"angularVelocity":-0.010919205839341846,"angularAcceleration":0.05103361035399074,"curveRadius":-51.74722819097079},{"acceleration":-2.8475885317682796,"curvature":-0.01940546518761772,"pose":{"rotation":{"radians":-2.904434298191892},"translation":{"x":5.2284947990509965,"y":1.9316917251829828}},"time":2.50213209197484,"velocity":0.5165509425507961,"position":3.3759876286450563,"holonomicRotation":217.38594854997288,"angularVelocity":-0.009940609114633726,"angularAcceleration":0.051959616629663925,"curveRadius":-51.53187467199096},{"acceleration":-2.8132193316756147,"curvature":-0.019473288983633517,"pose":{"rotation":{"radians":-2.9046238799914033},"translation":{"x":5.218958562844444,"y":1.9293886638787667}},"time":2.523644637954182,"velocity":0.4560314323281515,"position":3.3857980258010407,"holonomicRotation":217.54634017670747,"angularVelocity":-0.008812615656626827,"angularAcceleration":0.052434214857232604,"curveRadius":-51.352393570518984},{"acceleration":-2.756591808807488,"curvature":-0.019528716195704038,"pose":{"rotation":{"radians":-2.9048157240247128},"translation":{"x":5.209341680402111,"y":1.9270680784568495}},"time":2.5493242729341596,"velocity":0.3852431608891787,"position":3.3956909295512077,"holonomicRotation":217.70673180344204,"angularVelocity":-0.007470668234151234,"angularAcceleration":0.05225726236069566,"curveRadius":-51.20664307774526},{"acceleration":-2.643690169101191,"curvature":-0.019572272267270655,"pose":{"rotation":{"radians":-2.9050097324260076},"translation":{"x":5.199643436157955,"y":1.9247298511687416}},"time":2.5830042445826455,"velocity":0.29620375094646967,"position":3.40566706348526,"holonomicRotation":217.86712343017663,"angularVelocity":-0.005760349305505433,"angularAcceleration":0.05078148362166714,"curveRadius":-51.092687979424355},{"acceleration":-2.1168899880421375,"curvature":-0.019572272267270655,"pose":{"rotation":{"radians":-2.9052058096193827},"translation":{"x":5.189863114545932,"y":1.922373864265955}},"time":2.6648988424072284,"velocity":0.1228418967368728,"position":3.415727151214535,"holonomicRotation":218.02751505691123,"angularVelocity":-0.0023942628522958887,"angularAcceleration":0.041102667851421124,"curveRadius":-51.092687979424355}] \ No newline at end of file diff --git a/src/main/deploy/pathplanner/generatedJSON/Blue4(3).wpilib.json b/src/main/deploy/pathplanner/generatedJSON/Blue4(3).wpilib.json new file mode 100644 index 0000000..be07e5e --- /dev/null +++ b/src/main/deploy/pathplanner/generatedJSON/Blue4(3).wpilib.json @@ -0,0 +1 @@ +[{"acceleration":0.0,"curvature":-0.09233908070716977,"pose":{"rotation":{"radians":-2.905993218990811},"translation":{"x":5.18,"y":1.92}},"time":0.0,"velocity":0,"position":0.0,"holonomicRotation":-141.81,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-10.8296508081042},{"acceleration":1.4999999999999998,"curvature":-0.09233908070716977,"pose":{"rotation":{"radians":-2.905993218990811},"translation":{"x":5.168377982491239,"y":1.9172100464722623}},"time":0.08926440857987275,"velocity":0.1338966128698091,"position":0.011952201958671688,"holonomicRotation":-141.80248,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-10.8296508081042},{"acceleration":5.1461151912409955,"curvature":-0.0944379215859265,"pose":{"rotation":{"radians":-2.9070924822977577},"translation":{"x":5.156845431049349,"y":1.9144549742954224}},"time":0.1259874976340713,"velocity":0.32287785932091617,"position":0.023809274340142683,"holonomicRotation":-141.79496,"angularVelocity":-0.029933846396323106,"angularAcceleration":-0.8151233234258862,"curveRadius":-10.588966627035806},{"acceleration":3.466747111416081,"curvature":-0.09658122370260186,"pose":{"rotation":{"radians":-2.908207780676135},"translation":{"x":5.145401685306295,"y":1.91173460539188}},"time":0.1539954877114717,"velocity":0.4199744780183143,"position":0.03557191535324104,"holonomicRotation":-141.78744,"angularVelocity":-0.03982072170459052,"angularAcceleration":-0.35300195697531034,"curveRadius":-10.353979393336889},{"acceleration":3.290054333066062,"curvature":-0.09876970255398322,"pose":{"rotation":{"radians":-2.9093393045820246},"translation":{"x":5.134046084894042,"y":1.9090487616840357}},"time":0.17746515806731022,"velocity":0.4971909686681729,"position":0.0472408234917831,"holonomicRotation":-141.77992,"angularVelocity":-0.04821217719439708,"angularAcceleration":-0.35754466775963994,"curveRadius":-10.124562230542747},{"acceleration":3.2128770357141954,"curvature":-0.1010040706152409,"pose":{"rotation":{"radians":-2.9104872447559136},"translation":{"x":5.122777969444555,"y":1.9063972650942889}},"time":0.19801800850533308,"velocity":0.563224749858965,"position":0.05881669753862724,"holonomicRotation":-141.7724,"angularVelocity":-0.055853088473084934,"angularAcceleration":-0.37176893306011427,"curveRadius":-9.900591074287911},{"acceleration":3.169202795819821,"curvature":-0.10328503696519216,"pose":{"rotation":{"radians":-2.9116517921155736},"translation":{"x":5.111596678589797,"y":1.9037799375450397}},"time":0.2164874693367187,"velocity":0.621758216763077,"position":0.07030023656972506,"holonomicRotation":-141.76488,"angularVelocity":-0.06305259099285884,"angularAcceleration":-0.3898057764382386,"curveRadius":-9.681944542818991},{"acceleration":3.141024665624428,"curvature":-0.10561330553051783,"pose":{"rotation":{"radians":-2.9128331376422643},"translation":{"x":5.100501551961737,"y":1.9011966009586885}},"time":0.23336972091246677,"velocity":0.6747857853737785,"position":0.08169213995814394,"holonomicRotation":-141.75736,"angularVelocity":-0.06997559071964868,"angularAcceleration":-0.41007561673437914,"curveRadius":-9.468503944430012},{"acceleration":3.1213141982055146,"curvature":-0.10798957400380434,"pose":{"rotation":{"radians":-2.9140314722622396},"translation":{"x":5.089491929192336,"y":1.898647077257635}},"time":0.2489887646435649,"velocity":0.723537728334048,"position":0.09299310737809283,"holonomicRotation":-141.74984,"angularVelocity":-0.07672266245015918,"angularAcceleration":-0.43197726100713985,"curveRadius":-9.26015320668615},{"acceleration":3.1067444366818715,"curvature":-0.11041453299075515,"pose":{"rotation":{"radians":-2.915246986721436},"translation":{"x":5.078567149913561,"y":1.8961311883642793}},"time":0.2635701536073446,"velocity":0.768838377376365,"position":0.10420383880889884,"holonomicRotation":-141.74232,"angularVelocity":-0.08336067724519727,"angularAcceleration":-0.45523885355002724,"curveRadius":-9.05677878548586},{"acceleration":3.095532544505503,"curvature":-0.11288886457413184,"pose":{"rotation":{"radians":-2.9164798714547118},"translation":{"x":5.067726553757378,"y":1.8936487562010218}},"time":0.27727848160164814,"velocity":0.8112729528134874,"position":0.11532503453897328,"holonomicRotation":-141.7348,"angularVelocity":-0.08993691526699649,"angularAcceleration":-0.47972575681964624,"curveRadius":-8.858269624488251},{"acceleration":3.086635817197859,"curvature":-0.11541324037655935,"pose":{"rotation":{"radians":-2.917730316448426},"translation":{"x":5.0569694803557494,"y":1.8911996026902615}},"time":0.2902382873545348,"velocity":0.8512751534342742,"position":0.12635739516974023,"holonomicRotation":-141.72728,"angularVelocity":-0.09648639937643756,"angularAcceleration":-0.5053690027709142,"curveRadius":-8.664517144976564},{"acceleration":3.0794032435392773,"curvature":-0.1179883205665227,"pose":{"rotation":{"radians":-2.9189985110968557},"translation":{"x":5.04629526934064,"y":1.8887835497543994}},"time":0.3025465491672489,"velocity":0.8891772547826766,"position":0.1373016216195158,"holonomicRotation":-141.71976,"angularVelocity":-0.1030360474717766,"angularAcceleration":-0.5321342846780707,"curveRadius":-8.475415152944672},{"acceleration":3.0734071723482765,"curvature":-0.12061475245422529,"pose":{"rotation":{"radians":-2.9202846440514136},"translation":{"x":5.035703260344018,"y":1.886400419315835}},"time":0.314280570114613,"velocity":0.9252406789227905,"position":0.14815841512734926,"holonomicRotation":-141.71224,"angularVelocity":-0.10960718072067503,"angularAcceleration":-0.5600069471816083,"curveRadius":-8.290859780021616},{"acceleration":3.06835499626061,"curvature":-0.1232931685796038,"pose":{"rotation":{"radians":-2.9215889030640825},"translation":{"x":5.025192792997846,"y":1.8840500332969687}},"time":0.32550317689880187,"velocity":0.9596756205201246,"position":0.15892847725681905,"holonomicRotation":-141.70472,"angularVelocity":-0.11621711762247312,"angularAcceleration":-0.5889840951311426,"curveRadius":-8.110749456117299},{"acceleration":3.0640397014004095,"curvature":-0.12602418501460885,"pose":{"rotation":{"radians":-2.922911474822566},"translation":{"x":5.014763206934089,"y":1.8817322136202004}},"time":0.3362662733606165,"velocity":0.9926541753891268,"position":0.16961250989975526,"holonomicRotation":-141.6972,"angularVelocity":-0.12288022904709103,"angularAcceleration":-0.6190701205974825,"curveRadius":-7.93498485932743},{"acceleration":3.0603106785500698,"curvature":-0.12880839933202812,"pose":{"rotation":{"radians":-2.924252544779438},"translation":{"x":5.004413841784712,"y":1.8794467822079297}},"time":0.3466133439246203,"velocity":1.0243194259278587,"position":0.18021121527991069,"holonomicRotation":-141.68968,"angularVelocity":-0.1296086605939759,"angularAcceleration":-0.6502740563394118,"curveRadius":-7.763468882353782},{"acceleration":3.057055723660951,"curvature":-0.13164638961138325,"pose":{"rotation":{"radians":-2.9256122969732874},"translation":{"x":4.994144037181681,"y":1.8771935609825572}},"time":0.3565812632547694,"velocity":1.0547919107690817,"position":0.19072529595655074,"holonomicRotation":-141.68216,"angularVelocity":-0.13641284091621708,"angularAcceleration":-0.6826078840406686,"curveRadius":-7.596106531686697},{"acceleration":3.0541895213008874,"curvature":-0.13453871155312203,"pose":{"rotation":{"radians":-2.926990913842615},"translation":{"x":4.98395313275696,"y":1.8749723718664826}},"time":0.3662016337374591,"velocity":1.084174345488345,"position":0.20115545482797625,"holonomicRotation":-141.67464,"angularVelocity":-0.14330184807415625,"angularAcceleration":-0.7160854325033335,"curveRadius":-7.432804941090538},{"acceleration":3.0516460398069767,"curvature":-0.1374858964362667,"pose":{"rotation":{"radians":-2.928388576031917},"translation":{"x":4.973840468142513,"y":1.872783036782106}},"time":0.375501793280178,"velocity":1.1125551405264562,"position":0.21150239513494434,"holonomicRotation":-141.66712,"angularVelocity":-0.15028367877797966,"angularAcceleration":-0.7507216055545509,"curveRadius":-7.273473322869611},{"acceleration":3.049373370447789,"curvature":-0.14048844965438156,"pose":{"rotation":{"radians":-2.9298054621902097},"translation":{"x":4.963805382970307,"y":1.8706253776518271}},"time":0.38450558770452864,"velocity":1.1400110714770573,"position":0.22176682046400745,"holonomicRotation":-141.6596,"angularVelocity":-0.15736544966651872,"angularAcceleration":-0.7865318281131037,"curveRadius":-7.118022887006868},{"acceleration":3.047330140436747,"curvature":-0.14354684807822837,"pose":{"rotation":{"radians":-2.931241748761344},"translation":{"x":4.9538472168723064,"y":1.8684992163980465}},"time":0.39323397170195723,"velocity":1.1666093391097272,"position":0.23194943475074353,"holonomicRotation":-141.65208,"angularVelocity":-0.16455354983895135,"angularAcceleration":-0.8235316153082018,"curveRadius":-6.966366823011206},{"acceleration":3.045482966731066,"curvature":-0.14666153752484887,"pose":{"rotation":{"radians":-2.9326976097663144},"translation":{"x":4.943965309480475,"y":1.8664043749431638}},"time":0.40170548272988965,"velocity":1.1924091816477698,"position":0.2420509422828805,"holonomicRotation":-141.64456,"angularVelocity":-0.17185375786800303,"angularAcceleration":-0.8617362363079385,"curveRadius":-6.818420268030874},{"acceleration":3.0438046144316906,"curvature":-0.14983293051998622,"pose":{"rotation":{"radians":-2.934173216577251},"translation":{"x":4.93415900042678,"y":1.8643406752095792}},"time":0.40993661925009134,"velocity":1.2174631529699769,"position":0.25207204770329156,"holonomicRotation":-141.63704,"angularVelocity":-0.17927133237495715,"angularAcceleration":-0.9011604276941789,"curveRadius":-6.674100256395972},{"acceleration":3.042272642247735,"curvature":-0.15306140389131148,"pose":{"rotation":{"radians":-2.9356687376830863},"translation":{"x":4.924427629343184,"y":1.8623079391196928}},"time":0.4179421459268179,"velocity":1.2418181477653665,"position":0.26201345601287035,"holonomicRotation":-141.62952,"angularVelocity":-0.18681108267153892,"angularAcceleration":-0.9418181465188455,"curveRadius":-6.5333256756882845},{"acceleration":3.0408683910644845,"curvature":-0.1563472959081442,"pose":{"rotation":{"radians":-2.9371843384466843},"translation":{"x":4.914770535861653,"y":1.8603059885959043}},"time":0.42573534233783045,"velocity":1.2655162323969718,"position":0.27187587257326457,"holonomicRotation":-141.622,"angularVelocity":-0.19447742411011465,"angularAcceleration":-0.9837223437282324,"curveRadius":-6.396017239642643},{"acceleration":3.0395762182770043,"curvature":-0.15969090342772105,"pose":{"rotation":{"radians":-2.93872018085327},"translation":{"x":4.905187059614152,"y":1.858334645560614}},"time":0.43332820748977674,"velocity":1.288595324741412,"position":0.28166000310945455,"holonomicRotation":-141.61448000000001,"angularVelocity":-0.20227442155906064,"angularAcceleration":-1.0268847520553388,"curveRadius":-6.2620974553670665},{"acceleration":3.0383829109280542,"curvature":-0.1630924797068051,"pose":{"rotation":{"radians":-2.9402764232502965},"translation":{"x":4.895676540232645,"y":1.8563937319362218}},"time":0.4407316293862472,"velocity":1.3110897553140384,"position":0.2913665537121846,"holonomicRotation":-141.60696000000002,"angularVelocity":-0.21020582357575332,"angularAcceleration":-1.0713156872059277,"curveRadius":-6.131490561659997},{"acceleration":3.0372772307536784,"curvature":-0.16655223081412204,"pose":{"rotation":{"radians":-2.9418532200782432},"translation":{"x":4.886238317349099,"y":1.8544830696451275}},"time":0.4479555266915195,"velocity":1.3330307341166447,"position":0.300996230840215,"holonomicRotation":-141.59944000000002,"angularVelocity":-0.21827508909850493,"angularAcceleration":-1.1170238420834613,"curveRadius":-6.004122521277028},{"acceleration":3.0362495577806587,"curvature":-0.17007031260421834,"pose":{"rotation":{"radians":-2.9434507215928156},"translation":{"x":4.876871730595477,"y":1.8526024806097314}},"time":0.455008967913379,"velocity":1.3544467419073476,"position":0.3105497413223976,"holonomicRotation":-141.59192000000002,"angularVelocity":-0.22648540823187446,"angularAcceleration":-1.1640160986845247,"curveRadius":-5.8799209849585266},{"acceleration":3.035291608420719,"curvature":-0.17364682826387517,"pose":{"rotation":{"radians":-2.9450690735778893},"translation":{"x":4.867576119603745,"y":1.8507517867524337}},"time":0.46190027232405867,"velocity":1.3753638603561562,"position":0.32002779235955936,"holonomicRotation":-141.58440000000002,"angularVelocity":-0.2348397180896039,"angularAcceleration":-1.2122973184557837,"curveRadius":-5.758815234335243},{"acceleration":3.03439621054425,"curvature":-0.1772818244426589,"pose":{"rotation":{"radians":-2.9467084170495923},"translation":{"x":4.858350824005868,"y":1.848930809995634}},"time":0.46863709593257974,"velocity":1.3958060523849576,"position":0.32943109152618294,"holonomicRotation":-141.57688,"angularVelocity":-0.2433407146996549,"angularAcceleration":-1.2618701489079378,"curveRadius":-5.6407361732868795},{"acceleration":3.0335571224837516,"curvature":-0.18097528804048824,"pose":{"rotation":{"radians":-2.948368887951413},"translation":{"x":4.849195183433809,"y":1.8471393722617329}},"time":0.4752265051333376,"velocity":1.4157954015988765,"position":0.3387603467718692,"holonomicRotation":-141.56936,"angularVelocity":-0.2519908615828404,"angularAcceleration":-1.312734817286904,"curveRadius":-5.525616291746294},{"acceleration":3.0327688863069198,"curvature":-0.18472714328300915,"pose":{"rotation":{"radians":-2.950050616840004},"translation":{"x":4.840108537519536,"y":1.8453772954731296}},"time":0.48167504012738327,"velocity":1.4353523178910796,"position":0.34801626642257444,"holonomicRotation":-141.56184,"angularVelocity":-0.2607923955043589,"angularAcceleration":-1.3648889134734445,"curveRadius":-5.413389620105591},{"acceleration":3.03202670800737,"curvature":-0.18853724755348605,"pose":{"rotation":{"radians":-2.951753728562451},"translation":{"x":4.831090225895013,"y":1.8436444015522246}},"time":0.4879887698035742,"velocity":1.4544957148964293,"position":0.35719955918160856,"holonomicRotation":-141.55432,"angularVelocity":-0.26974732999249135,"angularAcceleration":-1.4183271928637529,"curveRadius":-5.303991720343273},{"acceleration":3.031326359027119,"curvature":-0.19240538836629958,"pose":{"rotation":{"radians":-2.9534783419237547},"translation":{"x":4.822139588192203,"y":1.8419405124214179}},"time":0.49417333944705155,"velocity":1.4732431638759411,"position":0.36631093413037624,"holonomicRotation":-141.5468,"angularVelocity":-0.27885745665790895,"angularAcceleration":-1.473041325523067,"curveRadius":-5.197359639929674},{"acceleration":3.0306640947878702,"curvature":-0.19633127947618187,"pose":{"rotation":{"radians":-2.9552245693461696},"translation":{"x":4.813255964043073,"y":1.8402654500031095}},"time":0.5002340123907708,"velocity":1.4916110277567234,"position":0.3753511007288547,"holonomicRotation":-141.53928,"angularVelocity":-0.2881243450406873,"angularAcceleration":-1.529019709334706,"curveRadius":-5.093431890567983},{"acceleration":3.03003658696305,"curvature":-0.20031455678445564,"pose":{"rotation":{"radians":-2.956992516518968},"translation":{"x":4.804438693079589,"y":1.8386190362196995}},"time":0.5061757065260939,"velocity":1.5096145783752961,"position":0.3843207688157854,"holonomicRotation":-141.53176,"angularVelocity":-0.29754934073232236,"angularAcceleration":-1.5862472010472455,"curveRadius":-4.992148429212907},{"acceleration":3.029440866740327,"curvature":-0.20435477579370362,"pose":{"rotation":{"radians":-2.958782282040103},"translation":{"x":4.7956871149337115,"y":1.8370010929935874}},"time":0.5120030264289376,"velocity":1.52726809943254,"position":0.3932206486085869,"holonomicRotation":-141.52424,"angularVelocity":-0.30713356242233686,"angularAcceleration":-1.6447049157774003,"curveRadius":-4.893450598920679},{"acceleration":3.028874277214911,"curvature":-0.20845140605285944,"pose":{"rotation":{"radians":-2.960593957048516},"translation":{"x":4.78700056923741,"y":1.8354114422471737}},"time":0.5177202917296386,"velocity":1.5445849772378468,"position":0.40205145070293297,"holonomicRotation":-141.51672,"angularVelocity":-0.31687789758340956,"angularAcceleration":-1.7043699476177643,"curveRadius":-4.797281145450362},{"acceleration":3.0283344330833226,"curvature":-0.21260382850879114,"pose":{"rotation":{"radians":-2.96242762484863},"translation":{"x":4.7783783956226475,"y":1.8338499059028586}},"time":0.5233315622509546,"velocity":1.5615777809708933,"position":0.4108138860720369,"holonomicRotation":-141.5092,"angularVelocity":-0.3267829973886673,"angularAcceleration":-1.7652151625252264,"curveRadius":-4.703584159391796},{"acceleration":3.027819186451694,"curvature":-0.21681133111071335,"pose":{"rotation":{"radians":-2.9642833605259233},"translation":{"x":4.769819933721389,"y":1.8323163058830418}},"time":0.5288406603540602,"velocity":1.5782583339075211,"position":0.41950866606557746,"holonomicRotation":-141.50168,"angularVelocity":-0.33684927052707936,"angularAcceleration":-1.8272089097011084,"curveRadius":-4.612305062088089},{"acceleration":3.027326597741435,"curvature":-0.22107310460324023,"pose":{"rotation":{"radians":-2.966161230555009},"translation":{"x":4.7613245231656,"y":1.8308104641101233}},"time":0.5342511908633002,"velocity":1.594637776826035,"position":0.4281365024082814,"holonomicRotation":-141.49416,"angularVelocity":-0.34707687645020724,"angularAcceleration":-1.8903148047425953,"curveRadius":-4.523390585185382},{"acceleration":3.0268549106951417,"curvature":-0.22538823881372436,"pose":{"rotation":{"radians":-2.968061292399639},"translation":{"x":4.752891503587246,"y":1.8293322025065033}},"time":0.5395665588835389,"velocity":1.6107266246202463,"position":0.43669810719813484,"holonomicRotation":-141.48664,"angularVelocity":-0.3574657177819556,"angularAcceleration":-1.9544914467243,"curveRadius":-4.436788739568907},{"acceleration":3.026402530967606,"curvature":-0.22975571835448227,"pose":{"rotation":{"radians":-2.9699835941050776},"translation":{"x":4.744520214618289,"y":1.8278813429945815}},"time":0.5447899857769158,"velocity":1.6265348169906866,"position":0.44519419290421797,"holonomicRotation":-141.47912,"angularVelocity":-0.3680154321440231,"angularAcceleration":-2.019692163289196,"curveRadius":-4.352448797192216},{"acceleration":3.0259680076074678,"curvature":-0.2341744188277644,"pose":{"rotation":{"radians":-2.971928173883584},"translation":{"x":4.736209995890697,"y":1.8264577074967583}},"time":0.5499245235267155,"velocity":1.6420717639554332,"position":0.45362547236412726,"holonomicRotation":-141.4716,"angularVelocity":-0.3787253835230555,"angularAcceleration":-2.0858647654212477,"curveRadius":-4.270321263124395},{"acceleration":3.0255500171117298,"curvature":-0.23864310234619163,"pose":{"rotation":{"radians":-2.9738950596928455},"translation":{"x":4.727960187036434,"y":1.8250611179354332}},"time":0.5549730676834681,"velocity":1.6573463868152853,"position":0.4619926587809986,"holonomicRotation":-141.46408,"angularVelocity":-0.3895946530705556,"angularAcceleration":-2.152951268726063,"curveRadius":-4.190357861461813},{"acceleration":3.025147349430835,"curvature":-0.24316041396740118,"pose":{"rotation":{"radians":-2.975884268808424},"translation":{"x":4.719770127687465,"y":1.8236913962330068}},"time":0.5599383690610318,"velocity":1.6723671551167474,"position":0.47029646572009204,"holonomicRotation":-141.45656,"angularVelocity":-0.40062202962485494,"angularAcceleration":-2.220887659332807,"curveRadius":-4.112511504993831},{"acceleration":3.024758895972097,"curvature":-0.24772487704798504,"pose":{"rotation":{"radians":-2.9778958073896185},"translation":{"x":4.711639157475755,"y":1.822348364311879}},"time":0.5648230443274127,"velocity":1.687142120082668,"position":0.4785376071049293,"holonomicRotation":-141.44904,"angularVelocity":-0.4118059996820735,"angularAcceleration":-2.2896035964136474,"curveRadius":-4.036736285497468},{"acceleration":3.0243836389225924,"curvature":-0.2523348899306863,"pose":{"rotation":{"radians":-2.9799296700406295},"translation":{"x":4.703566616033268,"y":1.8210318440944495}},"time":0.5696295856156444,"velocity":1.7016789449146017,"position":0.48671679721297584,"holonomicRotation":-141.44152,"angularVelocity":-0.42314473735838537,"angularAcceleration":-2.359022215012209,"curveRadius":-3.96298744210398},{"acceleration":3.024020642021325,"curvature":-0.25698872135434697,"pose":{"rotation":{"radians":-2.981985839366385},"translation":{"x":4.695551842991971,"y":1.8197416575031187}},"time":0.5743603692635453,"velocity":1.715984932318791,"position":0.49483475067083393,"holonomicRotation":-141.434,"angularVelocity":-0.4346360938885959,"angularAcceleration":-2.4290598314106693,"curveRadius":-3.891221352944737},{"acceleration":3.023669042423768,"curvature":-0.26168450701492213,"pose":{"rotation":{"radians":-2.9840642855243282},"translation":{"x":4.6875941779838275,"y":1.8184776264602862}},"time":0.5790176637771687,"velocity":1.7300670495610841,"position":0.5028921824489554,"holonomicRotation":-141.42648,"angularVelocity":-0.4462775870976682,"angularAcceleration":-2.4996257322827367,"curveRadius":-3.8213955094520617},{"acceleration":3.023328043470909,"curvature":-0.26642024587617946,"pose":{"rotation":{"radians":-2.9861649657724647},"translation":{"x":4.679692960640803,"y":1.8172395728883524}},"time":0.583603637100747,"velocity":1.743931951316868,"position":0.5108898078558305,"holonomicRotation":-141.41896,"angularVelocity":-0.4580663906909416,"angularAcceleration":-2.5706219294086203,"curveRadius":-3.7534684975283614},{"acceleration":3.02299690841713,"curvature":-0.27119379612487343,"pose":{"rotation":{"radians":-2.9882878240145367},"translation":{"x":4.671847530594862,"y":1.8160273187097171}},"time":0.5881203632656961,"velocity":1.7575860005496757,"position":0.5188283425316613,"holonomicRotation":-141.41144,"angularVelocity":-0.46999932352462914,"angularAcceleration":-2.6419429467055564,"curveRadius":-3.687399985874093},{"acceleration":3.0226749547289318,"curvature":-0.27600287201253976,"pose":{"rotation":{"radians":-2.990432790343057},"translation":{"x":4.6640572274779695,"y":1.8148406858467805}},"time":0.592569828482399,"velocity":1.7710352876221414,"position":0.5267085024414896,"holonomicRotation":-141.40392,"angularVelocity":-0.48207283888144276,"angularAcceleration":-2.7134756130895235,"curveRadius":-3.6231507038613953},{"acceleration":3.022361549204047,"curvature":-0.28084504031320434,"pose":{"rotation":{"radians":-2.9925997805808153},"translation":{"x":4.65632139092209,"y":1.813679496221942}},"time":0.5969539367308931,"velocity":1.7842856478199383,"position":0.5345310038677666,"holonomicRotation":-141.3964,"angularVelocity":-0.4942830137697178,"angularAcceleration":-2.7850988607475817,"curveRadius":-3.5606824278783016},{"acceleration":3.022056103450738,"curvature":-0.2857177169681381,"pose":{"rotation":{"radians":-2.9947886958223116},"translation":{"x":4.64863936055919,"y":1.8125435717576026}},"time":0.6012745149000045,"velocity":1.7973426774463372,"position":0.5422965634023534,"holonomicRotation":-141.38888,"angularVelocity":-0.5066255384858447,"angularAcceleration":-2.856683580999873,"curveRadius":-3.4999579676450914},{"acceleration":3.0217580700023956,"curvature":-0.2906181645096272,"pose":{"rotation":{"radians":-2.996999421974647},"translation":{"x":4.641010476021234,"y":1.8114327343761618}},"time":0.6055333175187708,"velocity":1.8102117486281417,"position":0.5500058979379325,"holonomicRotation":-141.38136,"angularVelocity":-0.5190957060545377,"angularAcceleration":-2.92809239708445,"curveRadius":-3.440941145875531},{"acceleration":3.0214669387747657,"curvature":-0.29554348892072746,"pose":{"rotation":{"radians":-2.9992318293009927},"translation":{"x":4.633434076940184,"y":1.8103468060000194}},"time":0.6097320311190397,"velocity":1.8228980229567382,"position":0.5576597246588243,"holonomicRotation":-141.37384,"angularVelocity":-0.5316884024199219,"angularAcceleration":-2.9991796450650194,"curveRadius":-3.3835967885870977},{"acceleration":3.0211822338601553,"curvature":-0.30049063724788727,"pose":{"rotation":{"radians":-3.0014857719654255},"translation":{"x":4.6259095029480095,"y":1.809285608551576}},"time":0.6138722782637955,"velocity":1.8354064640742647,"position":0.5652587610311741,"holonomicRotation":-141.36632,"angularVelocity":-0.5443980964488377,"angularAcceleration":-3.069791146408844,"curveRadius":-3.3278907095366774},{"acceleration":3.0209035108295104,"curvature":-0.30545639535784325,"pose":{"rotation":{"radians":-3.0037610875814815},"translation":{"x":4.6184360936766735,"y":1.8082489639532309}},"time":0.6179556212720186,"velocity":1.847741849303727,"position":0.5728037247925297,"holonomicRotation":-141.3588,"angularVelocity":-0.5572188306184208,"angularAcceleration":-3.1397641941332033,"curveRadius":-3.2737896969827607},{"acceleration":3.020630354066913,"curvature":-0.3104373858513234,"pose":{"rotation":{"radians":-3.0060575967658707},"translation":{"x":4.61101318875814,"y":1.8072366941273847}},"time":0.6219835656675421,"velocity":1.8599087804093388,"position":0.5802953339407644,"holonomicRotation":-141.35128,"angularVelocity":-0.5701442122541339,"angularAcceleration":-3.2089275239444772,"curveRadius":-3.221261502565693},{"acceleration":3.0203623745646686,"curvature":-0.31543006673858975,"pose":{"rotation":{"radians":-3.008375102696515},"translation":{"x":4.603640127824375,"y":1.8062486209964372}},"time":0.6259575633764886,"velocity":1.871911693566047,"position":0.587734306722346,"holonomicRotation":-141.34376,"angularVelocity":-0.5831674048092389,"angularAcceleration":-3.2771011734069475,"curveRadius":-3.1702748261748375},{"acceleration":3.020099207831725,"curvature":-0.32043072955456514,"pose":{"rotation":{"radians":-3.010713390679231},"translation":{"x":4.596316250507344,"y":1.8052845664827883}},"time":0.6298790156953157,"velocity":1.8837548686076866,"position":0.5951213616199494,"holonomicRotation":-141.33624,"angularVelocity":-0.596281120514977,"angularAcceleration":-3.3440966865205346,"curveRadius":-3.12079931094659},{"acceleration":3.0198405120947354,"curvature":-0.32543549919160053,"pose":{"rotation":{"radians":-3.013072227721478},"translation":{"x":4.58904089643901,"y":1.8043443525088383}},"time":0.6337492760492323,"velocity":1.895442437616798,"position":0.6024572173393887,"holonomicRotation":-141.32872,"angularVelocity":-0.6094776130137195,"angularAcceleration":-3.4097169936870353,"curveRadius":-3.072805525162603},{"acceleration":3.019585966578345,"curvature":-0.33044033272084666,"pose":{"rotation":{"radians":-3.015451362115917},"translation":{"x":4.5818134052513395,"y":1.803427800996987}},"time":0.6375696525587661,"velocity":1.9069783929120319,"position":0.6097425927958584,"holonomicRotation":-141.3212,"angularVelocity":-0.6227486711065963,"angularAcceleration":-3.4737565943457667,"curveRadius":-3.026264959141026},{"acceleration":3.0193352699456453,"curvature":-0.33544101970785983,"pose":{"rotation":{"radians":-3.01785052303523},"translation":{"x":4.5746331165762975,"y":1.8025347338696345}},"time":0.6413414104305073,"velocity":1.9183665944838753,"position":0.6169782070994884,"holonomicRotation":-141.31368,"angularVelocity":-0.636085613365595,"angularAcceleration":-3.536001703322957,"curveRadius":-2.9811500122164953},{"acceleration":3.01908813917457,"curvature":-0.340433182532019,"pose":{"rotation":{"radians":-3.020269420139129},"translation":{"x":4.567499370045848,"y":1.8016649730491807}},"time":0.6450657741864744,"velocity":1.929610776925487,"position":0.6241647795401931,"holonomicRotation":-141.30616,"angularVelocity":-0.6494792835484199,"angularAcceleration":-3.5962304061642514,"curveRadius":-2.9374339850256703},{"acceleration":3.0188443079168463,"curvature":-0.3454122771046961,"pose":{"rotation":{"radians":-3.0227077431949794},"translation":{"x":4.560411505291957,"y":1.800818340458026}},"time":0.6487439297451697,"velocity":1.9407145558974872,"position":0.6313030295718084,"holonomicRotation":-141.29864,"angularVelocity":-0.6629200470017984,"angularAcceleration":-3.65421288982842,"curveRadius":-2.8950910731435737},{"acceleration":3.018603525743801,"curvature":-0.3503735943431845,"pose":{"rotation":{"radians":-3.0251651617140247},"translation":{"x":4.553368861946589,"y":1.79999465801857}},"time":0.6523770263661549,"velocity":1.951681434166961,"position":0.63839367679552,"holonomicRotation":-141.29112,"angularVelocity":-0.6763977882809397,"angularAcceleration":-3.7097117652451557,"curveRadius":-2.854096359272207},{"acceleration":3.0183655569780177,"curvature":-0.35531226220831535,"pose":{"rotation":{"radians":-3.027641324604583},"translation":{"x":4.546370779641709,"y":1.7991937476532127}},"time":0.6559661784688627,"velocity":1.9625148072525296,"position":0.6454374409425656,"holonomicRotation":-141.2836,"angularVelocity":-0.6899019098939666,"angularAcceleration":-3.7624823987924034,"curveRadius":-2.8144258061482605},{"acceleration":3.018130179661684,"curvature":-0.3602232479342556,"pose":{"rotation":{"radians":-3.030135859843349},"translation":{"x":4.539416598009282,"y":1.7984154312843543}},"time":0.659512467335391,"velocity":1.9732179687063969,"position":0.6524350418562227,"holonomicRotation":-141.27608,"angularVelocity":-0.7034213321737267,"angularAcceleration":-3.8122732773867822,"curveRadius":-2.776056253266891},{"acceleration":3.0178971848931404,"curvature":-0.3651013613173236,"pose":{"rotation":{"radians":-3.0326483741670467},"translation":{"x":4.5325056566812725,"y":1.797659530834395}},"time":0.6630169427061257,"velocity":1.9837941150622642,"position":0.6593871994730667,"holonomicRotation":-141.26856,"angularVelocity":-0.7169444946537096,"angularAcceleration":-3.858826514494267,"curveRadius":-2.7389654105695365},{"acceleration":3.017666375983555,"curvature":-0.36994125836157854,"pose":{"rotation":{"radians":-3.035178452785436},"translation":{"x":4.525637295289647,"y":1.796925868225734}},"time":0.6664806242762579,"velocity":1.9942463504735661,"position":0.6662946338035054,"holonomicRotation":-141.26104,"angularVelocity":-0.7304593586796425,"angularAcceleration":-3.901878320014576,"curveRadius":-2.703131855119024},{"acceleration":3.0174375676908993,"curvature":-0.37473744547089494,"pose":{"rotation":{"radians":-3.0377256591185384},"translation":{"x":4.518810853466368,"y":1.7962142653807724}},"time":0.6699045031005542,"velocity":2.004577691065219,"position":0.6731580649116004,"holonomicRotation":-141.25352,"angularVelocity":-0.7439534118518305,"angularAcceleration":-3.941159680194415,"curveRadius":-2.668535029221327},{"acceleration":3.0172105856519815,"curvature":-0.37948428455881805,"pose":{"rotation":{"radians":-3.040289534557291},"translation":{"x":4.512025670843402,"y":1.7955245442219099}},"time":0.6732895429130811,"velocity":2.0147910690204287,"position":0.6799782128941582,"holonomicRotation":-141.246,"angularVelocity":-0.7574136733235505,"angularAcceleration":-3.976396798025238,"curveRadius":-2.6351552374891702},{"acceleration":3.0169852658293976,"curvature":-0.3841759987038812,"pose":{"rotation":{"radians":-3.042869598252387},"translation":{"x":4.505281087052714,"y":1.794856526671546}},"time":0.6766366813680318,"velocity":2.024889336421706,"position":0.6867557978591149,"holonomicRotation":-141.23848,"angularVelocity":-0.7708267016202295,"angularAcceleration":-4.007312059899986,"curveRadius":-2.60297364586482},{"acceleration":3.0167614537832876,"curvature":-0.3888066784311834,"pose":{"rotation":{"radians":-3.0454653469308925},"translation":{"x":4.498576441726268,"y":1.794210034652081}},"time":0.6799468312072718,"velocity":2.0348752688629723,"position":0.6934915399032152,"holonomicRotation":-141.23096,"angularVelocity":-0.7841786035588335,"angularAcceleration":-4.033624635454381,"curveRadius":-2.571972282047605},{"acceleration":3.0165390044763774,"curvature":-0.3933702887028368,"pose":{"rotation":{"radians":-3.0480762547424076},"translation":{"x":4.491911074496029,"y":1.7935848900859155}},"time":0.6832208813597501,"velocity":2.044751568850535,"position":0.7001861590889905,"holonomicRotation":-141.22344,"angularVelocity":-0.797455044950596,"angularAcceleration":-4.0550513197584905,"curveRadius":-2.5421340368576457},{"acceleration":3.01631778156866,"curvature":-0.3978606768816674,"pose":{"rotation":{"radians":-3.050701773137291},"translation":{"x":4.485284324993964,"y":1.7929809148954485}},"time":0.6864596979775033,"velocity":2.054520869005904,"position":0.7068403754210475,"holonomicRotation":-141.21592,"angularVelocity":-0.8106412633837062,"angularAcceleration":-4.0713075142419655,"curveRadius":-2.513442664999593},{"acceleration":3.016097657072924,"curvature":-0.4022715809859828,"pose":{"rotation":{"radians":-3.0533413307786845},"translation":{"x":4.478695532852036,"y":1.7923979310030806}},"time":0.6896641254126029,"velocity":2.064185735085168,"position":0.7134549088216957,"holonomicRotation":-141.2084,"angularVelocity":-0.8237220829159679,"angularAcceleration":-4.082108207220173,"curveRadius":-2.4858827898032527},{"acceleration":3.0158785110649946,"curvature":-0.4065966389659846,"pose":{"rotation":{"radians":-3.055994333488102},"translation":{"x":4.47214403770221,"y":1.791835760331212}},"time":0.692834987139025,"velocity":2.073748668827443,"position":0.7200304791058995,"holonomicRotation":-141.20088,"angularVelocity":-0.8366819301235024,"angularAcceleration":-4.087168828442715,"curveRadius":-2.459439907184424},{"acceleration":3.0156602312130234,"curvature":-0.4108293987343525,"pose":{"rotation":{"radians":-3.0586601642284332},"translation":{"x":4.465629179176453,"y":1.7912942248022423}},"time":0.695973086623133,"velocity":2.0832121106432573,"position":0.7265678059555964,"holonomicRotation":-141.19336,"angularVelocity":-0.8495048528039038,"angularAcceleration":-4.08620655442557,"curveRadius":-2.4341003907722114},{"acceleration":3.015442712481515,"curvature":-0.4149633288550419,"pose":{"rotation":{"radians":-3.061338183124934},"translation":{"x":4.459150296906727,"y":1.7907731463385714}},"time":0.699079208146163,"velocity":2.09257844215396,"position":0.7330676088933995,"holonomicRotation":-141.18584,"angularVelocity":-0.8621745403857721,"angularAcceleration":-4.078941370429408,"curveRadius":-2.4098514988280506},{"acceleration":3.015225856894095,"curvature":-0.41899182959825376,"pose":{"rotation":{"radians":-3.064027727524971},"translation":{"x":4.452706730524999,"y":1.7902723468625998}},"time":0.7021541175818322,"velocity":2.1018499885919977,"position":0.7395306072556823,"holonomicRotation":-141.17832,"angularVelocity":-0.8746743461248799,"angularAcceleration":-4.0650972006228505,"curveRadius":-2.3866813845960677},{"acceleration":3.0150095731907958,"curvature":-0.42290824548623807,"pose":{"rotation":{"radians":-3.0667281120989918},"translation":{"x":4.446297819663233,"y":1.7897916482967275}},"time":0.7051985631319754,"velocity":2.1110290210707374,"position":0.7459575201651042,"holonomicRotation":-141.1708,"angularVelocity":-0.8869873116612554,"angularAcceleration":-4.044403269356061,"curveRadius":-2.3645791035600445},{"acceleration":3.014793776549373,"curvature":-0.42670587788378955,"pose":{"rotation":{"radians":-3.0694386289835363},"translation":{"x":4.439922903953394,"y":1.7893308725633539}},"time":0.708213276022872,"velocity":2.1201177587322957,"position":0.7523490665025733,"holonomicRotation":-141.16328000000001,"angularVelocity":-0.8990961934482429,"angularAcceleration":-4.016595352596286,"curveRadius":-2.343534626144389},{"acceleration":3.0145783884431627,"curvature":-0.4303779982484269,"pose":{"rotation":{"radians":-3.072158547968135},"translation":{"x":4.433581323027448,"y":1.78888984158488}},"time":0.7111989711647468,"velocity":2.1291183707814714,"position":0.758705964878692,"holonomicRotation":-141.15576000000001,"angularVelocity":-0.9109834913991235,"angularAcceleration":-3.9814171862891645,"curveRadius":-2.323538852055282},{"acceleration":3.0143633362669715,"curvature":-0.43391786294835727,"pose":{"rotation":{"radians":-3.0748871167253005},"translation":{"x":4.427272416517358,"y":1.788468377283705}},"time":0.7141563477767368,"velocity":2.138032978412187,"position":0.7650289336047114,"holonomicRotation":-141.14824000000002,"angularVelocity":-0.9226314788936172,"angularAcceleration":-3.938621630829823,"curveRadius":-2.3045836214376245},{"acceleration":3.014148553384407,"curvature":-0.4373187272050718,"pose":{"rotation":{"radians":-3.077623561088126},"translation":{"x":4.42099552405509,"y":1.788066301582229}},"time":0.7170860899794497,"velocity":2.1468636566342836,"position":0.7713186906630234,"holonomicRotation":-141.14072000000002,"angularVelocity":-0.934022235912701,"angularAcceleration":-3.8879724668388995,"curveRadius":-2.2866617361462094},{"acceleration":3.0139339785218455,"curvature":-0.44057386106852825,"pose":{"rotation":{"radians":-3.080367085372815},"translation":{"x":4.414749985272611,"y":1.7876834364028524}},"time":0.7199888673570983,"velocity":2.1556124360048634,"position":0.7775759536772364,"holonomicRotation":-141.13320000000002,"angularVelocity":-0.945137682901145,"angularAcceleration":-3.8292454233772104,"curveRadius":-2.269766975223382},{"acceleration":3.0137195559516607,"curvature":-0.44367656490292073,"pose":{"rotation":{"radians":-3.0831168727490468},"translation":{"x":4.408535139801883,"y":1.7873196036679748}},"time":0.7228653354910409,"velocity":2.164281304272198,"position":0.7838014398818631,"holonomicRotation":-141.12568000000002,"angularVelocity":-0.9559596172069934,"angularAcceleration":-3.7622298603445565,"curveRadius":-2.2538941181597147},{"acceleration":3.0135052352699634,"curvature":-0.44662018636996687,"pose":{"rotation":{"radians":-3.0858720856590702},"translation":{"x":4.402350327274871,"y":1.7869746252999965}},"time":0.7257161364664386,"velocity":2.1728722079362717,"position":0.7899958660916624,"holonomicRotation":-141.11816000000002,"angularVelocity":-0.9664697514140191,"angularAcceleration":-3.686730255015275,"curveRadius":-2.2390389653629086},{"acceleration":3.013290970897727,"curvature":-0.44939813671289847,"pose":{"rotation":{"radians":-3.088631866284273},"translation":{"x":4.396194887323542,"y":1.7866483232213173}},"time":0.728541899353625,"velocity":2.1813870537301283,"position":0.7961599486706818,"holonomicRotation":-141.11064,"angularVelocity":-0.9766497527861551,"angularAcceleration":-3.602567440565457,"curveRadius":-2.2251983671193054},{"acceleration":3.013076722392356,"curvature":-0.45200390868342144,"pose":{"rotation":{"radians":-3.0913953370619507},"translation":{"x":4.39006815957986,"y":1.7863405193543378}},"time":0.731343240665668,"velocity":2.189827710028921,"position":0.8022944035010424,"holonomicRotation":-141.10312,"angularVelocity":-0.9864812851605658,"angularAcceleration":-3.5095803328729605,"curveRadius":-2.2123702489935524},{"acceleration":3.012862453985254,"curvature":-0.45443109361526124,"pose":{"rotation":{"radians":-3.094161601250236},"translation":{"x":4.38396948367579,"y":1.7860510356214572}},"time":0.7341207647935099,"velocity":2.198196008188734,"position":0.8083999459515122,"holonomicRotation":-141.0956,"angularVelocity":-0.9959460515774966,"angularAcceleration":-3.407627074075175,"curveRadius":-2.2005536461962225},{"acceleration":3.012648134487677,"curvature":-0.45667340029012815,"pose":{"rotation":{"radians":-3.096929743544},"translation":{"x":4.377898199243296,"y":1.7857796939450759}},"time":0.7368750644199777,"velocity":2.2064937438202326,"position":0.81447729084592,"holonomicRotation":-141.08808,"angularVelocity":-1.0050258392961573,"angularAcceleration":-3.2965867734239898,"curveRadius":-2.189748733700479},{"acceleration":3.012433737153473,"curvature":-0.4587246724469661,"pose":{"rotation":{"radians":-3.0996988307385234},"translation":{"x":4.371853645914344,"y":1.785526316247594}},"time":0.7396067209138714,"velocity":2.214722678000752,"position":0.8205271524314542,"holonomicRotation":-141.08056,"angularVelocity":-1.013702564987016,"angularAcceleration":-3.1763604648881403,"curveRadius":-2.179956867516455},{"acceleration":3.0122192396766545,"curvature":-0.46057890752741604,"pose":{"rotation":{"radians":-3.1024679124433563},"translation":{"x":4.365835163320899,"y":1.7852907244514116}},"time":0.7423163047052606,"velocity":2.2228845384286906,"position":0.8265502443469103,"holonomicRotation":-141.07304,"angularVelocity":-1.0219583220245145,"angularAcceleration":-3.04687275726059,"curveRadius":-2.17118062433303},{"acceleration":3.0120046238147,"curvature":-0.4622302752382785,"pose":{"rotation":{"radians":-3.1052360218447514},"translation":{"x":4.359842091094925,"y":1.7850727404789282}},"time":0.7450043756430464,"velocity":2.2309810205224436,"position":0.8325472795909286,"holonomicRotation":-141.06552,"angularVelocity":-1.02977542835056,"angularAcceleration":-2.9080729292376026,"curveRadius":-2.163423846446455},{"acceleration":3.011789875501033,"curvature":-0.4636731360330336,"pose":{"rotation":{"radians":-3.108002176516292},"translation":{"x":4.353873768868389,"y":1.7848721862525443}},"time":0.7476714833357795,"velocity":2.239013788468288,"position":0.8385189704902877,"holonomicRotation":-141.058,"angularVelocity":-1.0371364752452863,"angularAcceleration":-2.7599361341061037,"curveRadius":-2.1566916913831227},{"acceleration":3.0115749844220217,"curvature":-0.46490205976773125,"pose":{"rotation":{"radians":-3.110765379276606},"translation":{"x":4.347929536273254,"y":1.78468888369466}},"time":0.7503181674766646,"velocity":2.246984476218644,"position":0.8444660286683106,"holonomicRotation":-141.05048,"angularVelocity":-1.0440243766260917,"angularAcceleration":-2.6024644476473107,"curveRadius":-2.1509906850049405},{"acceleration":3.0113599443701724,"curvature":-0.46591184408600517,"pose":{"rotation":{"radians":-3.1135246190940373},"translation":{"x":4.342008732941485,"y":1.784522654727675}},"time":0.7529449581536204,"velocity":2.2548946884454737,"position":0.8503891650134363,"holonomicRotation":-141.04296,"angularVelocity":-1.0504224191282365,"angularAcceleration":-2.435687989253679,"curveRadius":-2.1463287802046187},{"acceleration":3.011144752420856,"curvature":-0.4666975322729113,"pose":{"rotation":{"radians":-3.1162788720364687},"translation":{"x":4.336110698505048,"y":1.784373321273989}},"time":0.7555523761452152,"velocity":2.262746001448232,"position":0.8562890896480216,"holonomicRotation":-141.03544,"angularVelocity":-1.056314312208435,"angularAcceleration":-2.2596657303092478,"curveRadius":-2.142715422406024},{"acceleration":3.01092940960896,"curvature":-0.4672544316974728,"pose":{"rotation":{"radians":-3.119027102265288},"translation":{"x":4.330234772595907,"y":1.7842407052560028}},"time":0.7581409332032482,"velocity":2.2705399640227144,"position":0.8621665118974385,"holonomicRotation":-141.02792,"angularVelocity":-1.0616842384411143,"angularAcceleration":-2.074486330527239,"curveRadius":-2.140161616802935},{"acceleration":3.010713920036275,"curvature":-0.4675781307872016,"pose":{"rotation":{"radians":-3.121768263071188},"translation":{"x":4.324380294846028,"y":1.7841246285961159}},"time":0.7607111323226964,"velocity":2.278278098288902,"position":0.8680221402595188,"holonomicRotation":-141.0204,"angularVelocity":-1.0665169033629238,"angularAcceleration":-1.8802686862825813,"curveRadius":-2.1386800069464917},{"acceleration":3.0104982914076337,"curvature":-0.4676645164399537,"pose":{"rotation":{"radians":-3.124501297951981},"translation":{"x":4.318546604887376,"y":1.7840249132167287}},"time":0.7632634679997116,"velocity":2.285961900483655,"position":0.8738566823744207,"holonomicRotation":-141.01288,"angularVelocity":-1.0707975856800906,"angularAcceleration":-1.677162747720101,"curveRadius":-2.138284956088594},{"acceleration":3.010282534319217,"curvature":-0.46750979045264407,"pose":{"rotation":{"radians":-3.127225141727948},"translation":{"x":4.312733042351915,"y":1.783941381040241}},"time":0.7657984264783054,"velocity":2.2935928417169906,"position":0.8796708449949734,"holonomicRotation":-141.00536,"angularVelocity":-1.074512185887266,"angularAcceleration":-1.4653495268434422,"curveRadius":-2.1389926380617563},{"acceleration":3.0100666627903943,"curvature":-0.46711048511347864,"pose":{"rotation":{"radians":-3.129938721695154},"translation":{"x":4.306938946871609,"y":1.7838738539890522}},"time":0.7683164859863237,"velocity":2.301172368696999,"position":0.8854653339575599,"holonomicRotation":-140.99784,"angularVelocity":-1.0776472750405106,"angularAcceleration":-1.2450417248923398,"curveRadius":-2.140821137331273},{"acceleration":3.0098506933278615,"curvature":-0.46646347851001857,"pose":{"rotation":{"radians":-3.1326409588128383},"translation":{"x":4.301163658078425,"y":1.7838221539855634}},"time":0.7708181169612859,"velocity":2.308701904421439,"position":0.8912408541536146,"holonomicRotation":-140.99032,"angularVelocity":-1.080190141843463,"angularAcceleration":-1.0164835774752226,"curveRadius":-2.143790556110005},{"acceleration":3.0096346456564134,"curvature":-0.46556600890345656,"pose":{"rotation":{"radians":-3.1353307689223975},"translation":{"x":4.295406515604328,"y":1.7837861029521742}},"time":0.7733037822666186,"velocity":2.3161828488418745,"position":0.8969981095017875,"holonomicRotation":-140.9828,"angularVelocity":-1.082128838419442,"angularAcceleration":-0.7799507728654748,"curveRadius":-2.1479231320071905},{"acceleration":3.0094185419610078,"curvature":-0.464415688019375,"pose":{"rotation":{"radians":-3.138007063997224},"translation":{"x":4.289666859081281,"y":1.7837655228112843}},"time":0.7757739373987942,"velocity":2.323616579498164,"position":0.9027378029208433,"holonomicRotation":-140.97528,"angularVelocity":-1.0834522253139942,"angularAcceleration":-0.5357505191937236,"curveRadius":-2.1532433675200933},{"acceleration":3.009202406980889,"curvature":-0.4630105134969534,"pose":{"rotation":{"radians":-3.1406687534185065},"translation":{"x":4.283944028141251,"y":1.7837602354852942}},"time":0.7782290306858487,"velocity":2.331004452126931,"position":0.9084606363033543,"holonomicRotation":-140.96776,"angularVelocity":-1.08415001389861,"angularAcceleration":-0.2842208026453229,"curveRadius":-2.1597781710124817},{"acceleration":3.008986268086409,"curvature":-0.46134888044143724,"pose":{"rotation":{"radians":3.139870561904747},"translation":{"x":4.278237362416202,"y":1.7837700628966033}},"time":0.7806695034777336,"velocity":2.338347801245351,"position":0.9141673104902573,"holonomicRotation":-140.96024,"angularVelocity":2573.492864254624,"angularAcceleration":1054950.09935353,"curveRadius":-2.167557010311068},{"acceleration":3.008770154697677,"curvature":-0.4594295914479363,"pose":{"rotation":{"radians":3.13724135949584},"translation":{"x":4.272546201538098,"y":1.7837948269676125}},"time":0.783095790328924,"velocity":2.345647940709948,"position":0.9198585252463237,"holonomicRotation":-140.95272,"angularVelocity":-1.083632138391546,"angularAcceleration":-1061117.9362942453,"curveRadius":-2.17661208292745},{"acceleration":3.0085540986197223,"curvature":-0.45725186607131074,"pose":{"rotation":{"radians":3.134630037049967},"translation":{"x":4.266869885138907,"y":1.783834349620721}},"time":0.7855083191736884,"velocity":2.3529061642539024,"position":0.9255349792366102,"holonomicRotation":-140.9452,"angularVelocity":-1.0824005074758192,"angularAcceleration":0.5105144829250884,"curveRadius":-2.1869784996001416},{"acceleration":3.0083381335996777,"curvature":-0.4548153484603197,"pose":{"rotation":{"radians":3.1320376823617364},"translation":{"x":4.2612077528505905,"y":1.7838884527783292}},"time":0.7879075114944011,"velocity":2.360123746002142,"position":0.9311973700039503,"holonomicRotation":-140.93768,"angularVelocity":-1.0805114145499608,"angularAcceleration":0.787387034190397,"curveRadius":-2.198694488621122},{"acceleration":3.0081222953748687,"curvature":-0.45212011396608737,"pose":{"rotation":{"radians":3.1294653791409957},"translation":{"x":4.255559144305115,"y":1.783956958362837}},"time":0.7902937824832519,"velocity":2.3673019409665104,"position":0.9368463939475289,"holonomicRotation":-140.93016,"angularVelocity":-1.0779593905131224,"angularAcceleration":1.0694611168480195,"curveRadius":-2.211801618883534},{"acceleration":3.0079066214628125,"curvature":-0.4491666744998133,"pose":{"rotation":{"radians":3.1269142056400585},"translation":{"x":4.249923399134445,"y":1.7840396882966445}},"time":0.792667541197701,"velocity":2.374441985521457,"position":0.9424827463026143,"holonomicRotation":-140.92264,"angularVelocity":-1.0747400253480277,"angularAcceleration":1.3562310042290113,"curveRadius":-2.2263450446620694},{"acceleration":3.0076911510766764,"curvature":-0.44595598239521567,"pose":{"rotation":{"radians":3.1243852332774416},"translation":{"x":4.244299856970547,"y":1.7841364645021518}},"time":0.7950291907099931,"velocity":2.3815450978615225,"position":0.9481071211214807,"holonomicRotation":-140.91512,"angularVelocity":-1.0708499925386639,"angularAcceleration":1.647167705926159,"curveRadius":-2.242373775611286},{"acceleration":3.0074759250408003,"curvature":-0.44248943286388503,"pose":{"rotation":{"radians":3.1218795252604696},"translation":{"x":4.238687857445384,"y":1.7842471089017586}},"time":0.7973791282510412,"velocity":2.388612478441574,"position":0.9537202112555864,"holonomicRotation":-140.9076,"angularVelocity":-1.0662870706999226,"angularAcceleration":1.9417204751349473,"curveRadius":-2.2599409742460717},{"acceleration":3.0072609854049897,"curvature":-0.4387688646043675,"pose":{"rotation":{"radians":3.119398135210703},"translation":{"x":4.233086740190922,"y":1.7843714434178652}},"time":0.799717745348962,"velocity":2.3956453103999524,"position":0.9593227083390415,"holonomicRotation":-140.90008,"angularVelocity":-1.0610501616415837,"angularAcceleration":2.2393187251537587,"curveRadius":-2.279104286266273},{"acceleration":3.007046375834989,"curvature":-0.4347965600914379,"pose":{"rotation":{"radians":3.1169421057962454},"translation":{"x":4.227495844839125,"y":1.7845092899728716}},"time":0.8020454279625405,"velocity":2.402644759967208,"position":0.9649153027734227,"holonomicRotation":-140.89256,"angularVelocity":-1.0551393047017326,"angularAcceleration":2.539374099101923,"curveRadius":-2.29992619948442},{"acceleration":3.0068321409233056,"curvature":-0.43057524335431835,"pose":{"rotation":{"radians":3.1145124673737197},"translation":{"x":4.22191451102196,"y":1.7846604704891775}},"time":0.8043625566098737,"velocity":2.4096119768586632,"position":0.970498683713959,"holonomicRotation":-140.88504,"angularVelocity":-1.048555687800117,"angularAcceleration":2.841282424777276,"curveRadius":-2.3224744465326927},{"acceleration":3.0066183263168074,"curvature":-0.42610807618823776,"pose":{"rotation":{"radians":3.1121102366439657},"translation":{"x":4.216342078371389,"y":1.7848248068891837}},"time":0.8066695064924461,"velocity":2.4165480946535,"position":0.9760735390571504,"holonomicRotation":-140.87752,"angularVelocity":-1.0413016545792202,"angularAcceleration":3.14442601276108,"curveRadius":-2.346822451584418},{"acceleration":3.0064049788165756,"curvature":-0.42139865357109074,"pose":{"rotation":{"radians":3.109736415325746},"translation":{"x":4.21077788651938,"y":1.785002121095289}},"time":0.8089666476148556,"velocity":2.423454231160956,"position":0.9816405554298276,"holonomicRotation":-140.87,"angularVelocity":-1.0333807074637427,"angularAcceleration":3.4481760995027795,"curveRadius":-2.3730498223609016},{"acceleration":3.006192145885173,"curvature":-0.41645099740585206,"pose":{"rotation":{"radians":3.1073919888487516},"translation":{"x":4.205221275097896,"y":1.7851922350298945}},"time":0.8112543449004165,"velocity":2.430331488772972,"position":0.9872004181797067,"holonomicRotation":-140.86248,"angularVelocity":-1.0247975078659568,"angularAcceleration":3.7518948210324417,"curveRadius":-2.401242898274177},{"acceleration":3.005979875563759,"curvature":-0.41126954868796317,"pose":{"rotation":{"radians":3.105077925072806},"translation":{"x":4.199671583738902,"y":1.7853949706154}},"time":0.8135329583028393,"velocity":2.437180954804845,"position":0.9927538113674548,"holonomicRotation":-140.85496,"angularVelocity":-1.015557871065364,"angularAcceleration":4.054938319404319,"curveRadius":-2.431495361594875},{"acceleration":3.0057682168427444,"curvature":-0.4058591584068581,"pose":{"rotation":{"radians":3.1027951730333583},"translation":{"x":4.194128152074364,"y":1.785610149774205}},"time":0.8158028429141794,"velocity":2.4440037018255114,"position":0.9983014177602866,"holonomicRotation":-140.84744,"angularVelocity":-1.0056687586864126,"angularAcceleration":4.3566586290540315,"curveRadius":-2.4639089183680283},{"acceleration":3.0055572187676205,"curvature":-0.4002250766170894,"pose":{"rotation":{"radians":3.1005446617183487},"translation":{"x":4.188590319736246,"y":1.78583759442871}},"time":0.8180643490692444,"velocity":2.4508007879751545,"position":1.0038439188271306,"holonomicRotation":-140.83992,"angularVelocity":-0.9951382665791616,"angularAcceleration":4.656406565008059,"curveRadius":-2.4985940622524714},{"acceleration":3.0053469309348255,"curvature":-0.39437294090203756,"pose":{"rotation":{"radians":3.0983272988798816},"translation":{"x":4.183057426356514,"y":1.7860771265013147}},"time":0.8203178224466242,"velocity":2.4575732572738063,"position":1.0093819947353577,"holonomicRotation":-140.8324,"angularVelocity":-0.9839756088201043,"angularAcceleration":4.953534339969256,"curveRadius":-2.535670925375178},{"acceleration":3.00513740320319,"curvature":-0.38830876287817917,"pose":{"rotation":{"radians":3.096143969882352},"translation":{"x":4.177528811567132,"y":1.7863285679144194}},"time":0.8225636041665123,"velocity":2.464322139919672,"position":1.0149163243491048,"holonomicRotation":-140.82488,"angularVelocity":-0.9721910986248932,"angularAcceleration":5.247397861889401,"curveRadius":-2.5752702374984042},{"acceleration":3.004928685548058,"curvature":-0.38203891441651977,"pose":{"rotation":{"radians":3.093995536591512},"translation":{"x":4.172003815000065,"y":1.7865917405904241}},"time":0.8248020308854661,"velocity":2.4710484525779535,"position":1.0204475852291848,"holonomicRotation":-140.81736,"angularVelocity":-0.9597961249514697,"angularAcceleration":5.537359596572649,"curveRadius":-2.6175343983669297},{"acceleration":3.0047208278640283,"curvature":-0.37557011101367327,"pose":{"rotation":{"radians":3.0918828363062874},"translation":{"x":4.166481776287278,"y":1.7868664664517286}},"time":0.827033434888255,"velocity":2.4777531986605124,"position":1.0259764536345988,"holonomicRotation":-140.80984,"angularVelocity":-0.9468031260068988,"angularAcceleration":5.822790910266331,"curveRadius":-2.662618698013467},{"acceleration":3.00451388018618,"curvature":-0.36890939615688756,"pose":{"rotation":{"radians":3.0898066807362996},"translation":{"x":4.160962035060736,"y":1.7871525674207331}},"time":0.8292581441769303,"velocity":2.4844373685977166,"position":1.0315036045256503,"holonomicRotation":-140.80232,"angularVelocity":-0.9332255592028127,"angularAcceleration":6.103074623368198,"curveRadius":-2.710692680689342},{"acceleration":3.0043078922380193,"curvature":-0.36206412327127785,"pose":{"rotation":{"radians":3.087767855027885},"translation":{"x":4.155443930952406,"y":1.7874498654198376}},"time":0.8314764825572419,"velocity":2.4911019401013412,"position":1.0370297115686458,"holonomicRotation":-140.7948,"angularVelocity":-0.9190778677003962,"angularAcceleration":6.377607504779855,"curveRadius":-2.761941699621938},{"acceleration":3.0041029133149664,"curvature":-0.35504193674513546,"pose":{"rotation":{"radians":3.0857671168404037},"translation":{"x":4.149926803594249,"y":1.7877581823714421}},"time":0.8336887697225278,"velocity":2.497747878419666,"position":1.0425554471421936,"holonomicRotation":-140.78728,"angularVelocity":-0.9043754440543458,"angularAcceleration":6.645802532670112,"curveRadius":-2.8165686824704417},{"acceleration":3.0038989928815125,"curvature":-0.34785075305000174,"pose":{"rotation":{"radians":3.083805195475083},"translation":{"x":4.1444099926182325,"y":1.7880773401979466}},"time":0.8358953213351772,"velocity":2.5043761365866444,"position":1.0480814823450595,"holonomicRotation":-140.77976,"angularVelocity":-0.8891345908582361,"angularAcceleration":6.907091186419246,"curveRadius":-2.8747961337782564},{"acceleration":3.0036961792931827,"curvature":-0.3404987403617854,"pose":{"rotation":{"radians":3.0818827910588094},"translation":{"x":4.138892837656321,"y":1.7884071608217509}},"time":0.838096449105789,"velocity":2.510987655661367,"position":1.053608487005599,"holonomicRotation":-140.77224,"angularVelocity":-0.8733724783906943,"angularAcceleration":7.160925720891235,"curveRadius":-2.936868426994719},{"acceleration":3.0034945211541317,"curvature":-0.3329942969072833,"pose":{"rotation":{"radians":3.080000573783608},"translation":{"x":4.133374678340481,"y":1.7887474661652554}},"time":0.8402924608701092,"velocity":2.517583364963893,"position":1.0591371296927168,"holonomicRotation":-140.76472,"angularVelocity":-0.8571071001453163,"angularAcceleration":7.406781015316006,"curveRadius":-3.0030544345281482},{"acceleration":3.0032940655722054,"curvature":-0.3253460311836531,"pose":{"rotation":{"radians":3.078159183204723},"translation":{"x":4.127854854302674,"y":1.7890980781508599}},"time":0.8424836606638502,"velocity":2.524164182300918,"position":1.0646680777283428,"holonomicRotation":-140.7572,"angularVelocity":-0.8403572253634018,"angularAcceleration":7.644156790156571,"curveRadius":-3.0736505263699208},{"acceleration":3.0030948598510934,"curvature":-0.3175627382285688,"pose":{"rotation":{"radians":3.0763592275968774},"translation":{"x":4.122332705174868,"y":1.7894588187009643}},"time":0.8446703487954709,"velocity":2.5307310141890857,"position":1.0702019972013945,"holonomicRotation":-140.74968,"angularVelocity":-0.8231423502131201,"angularAcceleration":7.872579039207849,"curveRadius":-3.148984057695839},{"acceleration":3.0028969497884486,"curvature":-0.30965337821241695,"pose":{"rotation":{"radians":3.074601283371465},"translation":{"x":4.1168075705890255,"y":1.7898295097379688}},"time":0.8468528219170072,"velocity":2.5372847560687424,"position":1.0757395529831983,"holonomicRotation":-140.74216,"angularVelocity":-0.8054826462994746,"angularAcceleration":8.091602017629588,"curveRadius":-3.229417375559898},{"acceleration":3.002700381026561,"curvature":-0.30162705387225563,"pose":{"rotation":{"radians":3.0728858945542785},"translation":{"x":4.1112787901771135,"y":1.7902099731842738}},"time":0.8490313730930177,"velocity":2.543826292515035,"position":1.0812814087443234,"holonomicRotation":-140.73464,"angularVelocity":-0.78739890807967,"angularAcceleration":8.300809464077252,"curveRadius":-3.3153524763846867},{"acceleration":3.0025051979117383,"curvature":-0.29349298732158513,"pose":{"rotation":{"radians":3.0712135723257408},"translation":{"x":4.105745703571096,"y":1.7906000309622785}},"time":0.8512062918677269,"velocity":2.5503564974411352,"position":1.0868282269728098,"holonomicRotation":-140.72712,"angularVelocity":-0.7689124982432225,"angularAcceleration":8.499816200685057,"curveRadius":-3.407236435616376},{"acceleration":3.0023114439374767,"curvature":-0.2852604971482792,"pose":{"rotation":{"radians":3.0695847946220005},"translation":{"x":4.10020765040294,"y":1.7909995049943834}},"time":0.8533778643304214,"velocity":2.5568762342972224,"position":1.0923806689937277,"holonomicRotation":-140.7196,"angularVelocity":-0.7500452928562458,"angularAcceleration":8.688268851763826,"curveRadius":-3.5055677529728104},{"acceleration":3.0021191616740395,"curvature":-0.27693897587314226,"pose":{"rotation":{"radians":3.0680000058000796},"translation":{"x":4.094663970304606,"y":1.7914082172029886}},"time":0.8555463731791683,"velocity":2.563386356264305,"position":1.0979393949900438,"holonomicRotation":-140.71208000000001,"angularVelocity":-0.7308196242024746,"angularAcceleration":8.865847453138727,"curveRadius":-3.6109037987418247},{"acceleration":3.001928392745772,"curvature":-0.26853786709908706,"pose":{"rotation":{"radians":3.0664596163641775},"translation":{"x":4.0891140029080635,"y":1.7918259895104938}},"time":0.8577120977829036,"velocity":2.5698877064431263,"position":1.1035050640247246,"holonomicRotation":-140.70456000000001,"angularVelocity":-0.7112582242660451,"angularAcceleration":9.032265645729412,"curveRadius":-3.723869600971444},{"acceleration":3.0017391772967437,"curvature":-0.2600666421362148,"pose":{"rotation":{"radians":3.064964002754951},"translation":{"x":4.083557087845274,"y":1.7922526438392992}},"time":0.8598753142419577,"velocity":2.5763811180372422,"position":1.109078334064059,"holonomicRotation":-140.69704000000002,"angularVelocity":-0.6913841668347362,"angularAcceleration":9.187271735163593,"curveRadius":-3.8451682683557364},{"acceleration":3.001551554933426,"curvature":-0.25153477914672107,"pose":{"rotation":{"radians":3.063513507200501},"translation":{"x":4.077992564748206,"y":1.7926880021118048}},"time":0.8620362954470496,"velocity":2.5828674145335677,"position":1.1146598620021104,"holonomicRotation":-140.68952000000002,"angularVelocity":-0.6712208098026525,"angularAcceleration":9.330648959173287,"curveRadius":-3.975593368806851},{"acceleration":3.0013655634339553,"curvature":-0.24295173976977485,"pose":{"rotation":{"radians":3.062108437628856},"translation":{"x":4.0724197732488205,"y":1.7931318862504109}},"time":0.8641953111368137,"velocity":2.589347409875739,"position":1.120250303686282,"holonomicRotation":-140.68200000000002,"angularVelocity":-0.6507917373210633,"angularAcceleration":9.462215850697069,"curveRadius":-4.116043791032807},{"acceleration":3.001181240076679,"curvature":-0.2343269476845986,"pose":{"rotation":{"radians":3.0607490676409355},"translation":{"x":4.066838052979086,"y":1.793584118177517}},"time":0.8663526279538845,"velocity":2.595821908636034,"position":1.1258503139439033,"holonomicRotation":-140.67448000000002,"angularVelocity":-0.6301207023298531,"angularAcceleration":9.581826288860846,"curveRadius":-4.267541611756871},{"acceleration":3.000998620307161,"curvature":-0.22566976880009462,"pose":{"rotation":{"radians":3.0594356365430966},"translation":{"x":4.0612467435709645,"y":1.7940445198155233}},"time":0.8685085094995945,"velocity":2.6022917061802553,"position":1.1314605466098115,"holonomicRotation":-140.66696000000002,"angularVelocity":-0.6092315695416944,"angularAcceleration":9.689369450620323,"curveRadius":-4.431253708979653},{"acceleration":3.000817738549085,"curvature":-0.21698948980025576,"pose":{"rotation":{"radians":3.0581683494386493},"translation":{"x":4.055645184656423,"y":1.7945129130868296}},"time":0.8706632163873091,"velocity":2.6087575888302834,"position":1.1370816545548421,"holonomicRotation":-140.65944000000002,"angularVelocity":-0.5881482588990737,"angularAcceleration":9.784769688550062,"curveRadius":-4.608518140304975},{"acceleration":3.000638628227627,"curvature":-0.20829529772252528,"pose":{"rotation":{"radians":3.056947377376172},"translation":{"x":4.050032715867426,"y":1.7949891199138366}},"time":0.8728170062944414,"velocity":2.615220334022711,"position":1.1427142897151872,"holonomicRotation":-140.65192000000002,"angularVelocity":-0.5668946903474473,"angularAcceleration":9.867985954082972,"curveRadius":-4.80087650049653},{"acceleration":3.0004613207535495,"curvature":-0.19959626323937038,"pose":{"rotation":{"radians":3.055772857554567},"translation":{"x":4.044408676835938,"y":1.7954729622189438}},"time":0.8749701340131734,"velocity":2.621680710461409,"position":1.1483591031225466,"holonomicRotation":-140.6444,"angularVelocity":-0.5454947290803502,"angularAcceleration":9.939011550926391,"curveRadius":-5.010113835651959},{"acceleration":3.0002858470731453,"curvature":-0.19090131932211202,"pose":{"rotation":{"radians":3.0546448935813455},"translation":{"x":4.038772407193925,"y":1.7959642619245513}},"time":0.8771228514999163,"velocity":2.6281394782696306,"position":1.1540167449350172,"holonomicRotation":-140.63688,"angularVelocity":-0.5239721329751318,"angularAcceleration":9.997873031533748,"curveRadius":-5.238308480795137},{"acceleration":3.000112236175314,"curvature":-0.1822192463585329,"pose":{"rotation":{"radians":3.053563555784507},"translation":{"x":4.03312324657335,"y":1.796462840953059}},"time":0.8792754079235342,"velocity":2.6345973891351844,"position":1.159687864468647,"holonomicRotation":-140.62936,"angularVelocity":-0.5023505005370134,"angularAcceleration":10.044629818240983,"curveRadius":-5.487894500630352},{"acceleration":2.999940515924073,"curvature":-0.17355865419368874,"pose":{"rotation":{"radians":3.0525288815748977},"translation":{"x":4.027460534606179,"y":1.7969685212268671}},"time":0.8814280497123598,"velocity":2.6410551864537535,"position":1.1653731102296019,"holonomicRotation":-140.62184,"angularVelocity":-0.4806532210701554,"angularAcceleration":10.079372973008882,"curveRadius":-5.761740920645856},{"acceleration":2.9997707130200433,"curvature":-0.1649279665639465,"pose":{"rotation":{"radians":3.051540875857702},"translation":{"x":4.021783610924378,"y":1.7974811246683757}},"time":0.8835810206000237,"velocity":2.6475136054685526,"position":1.17107312994687,"holonomicRotation":-140.61432,"angularVelocity":-0.45890342635687237,"angularAcceleration":10.102224251105453,"curveRadius":-6.06325307243921},{"acceleration":2.9996028524353875,"curvature":-0.1563354059159957,"pose":{"rotation":{"radians":3.050599511490683},"translation":{"x":4.0160918151599105,"y":1.7980004731999846}},"time":0.8857345616701219,"velocity":2.6539733734052557,"position":1.176788570605445,"holonomicRotation":-140.6068,"angularVelocity":-0.4371239444140086,"angularAcceleration":10.113334844304292,"curveRadius":-6.396503684759253},{"acceleration":2.9994369580186406,"curvature":-0.14778898203015048,"pose":{"rotation":{"radians":3.0497047297872135},"translation":{"x":4.0103844869447425,"y":1.7985263887440939}},"time":0.8878889113997394,"velocity":2.660435209604768,"position":1.182520078479922,"holonomicRotation":-140.59928,"angularVelocity":-0.41533725521369197,"angularAcceleration":10.112884134269615,"curveRadius":-6.766404276307889},{"acceleration":2.9992730523965907,"curvature":-0.13929647569232426,"pose":{"rotation":{"radians":3.0488564410622763},"translation":{"x":4.004660965910838,"y":1.7990586932231039}},"time":0.8900443057018531,"velocity":2.666899825652387,"position":1.1882682991684412,"holonomicRotation":-140.59176,"angularVelocity":-0.39356544837543206,"angularAcceleration":10.101078404498287,"curveRadius":-7.178932525247684},{"acceleration":2.9991111565327233,"curvature":-0.13086542962985814,"pose":{"rotation":{"radians":3.0480545252186655},"translation":{"x":3.9989205916901627,"y":1.7995972085594139}},"time":0.8922009779666298,"velocity":2.6733679255026632,"position":1.1940338776269164,"holonomicRotation":-140.58424,"angularVelocity":-0.371830183337485,"angularAcceleration":10.078149282546544,"curveRadius":-7.641437489094071},{"acceleration":2.998951290412122,"curvature":-0.12250313629424679,"pose":{"rotation":{"radians":3.0472988323708625},"translation":{"x":3.9931627039146806,"y":1.8001417566754243}},"time":0.8943591591016394,"velocity":2.6798402056024435,"position":1.199817458203488,"holonomicRotation":-140.57672,"angularVelocity":-0.35015265194577355,"angularAcceleration":10.044352181595048,"curveRadius":-8.163056312273074},{"acceleration":2.9987934722595777,"curvature":-0.11421662923542207,"pose":{"rotation":{"radians":3.046589183505437},"translation":{"x":3.987386642216358,"y":1.8006921594935357}},"time":0.8965190775709978,"velocity":2.6863173550089683,"position":1.2056196846731297,"holonomicRotation":-140.5692,"angularVelocity":-0.32855354287343586,"angularAcceleration":9.999964988842375,"curveRadius":-8.755292523462682},{"acceleration":2.9986377193847806,"curvature":-0.10601267318169667,"pose":{"rotation":{"radians":3.045925371174555},"translation":{"x":3.9815917462271595,"y":1.8012482389361473}},"time":0.8986809594334589,"velocity":2.692800055506598,"position":1.2114412002723638,"holonomicRotation":-140.56168,"angularVelocity":-0.30705300895872056,"angularAcceleration":9.945286228655716,"curveRadius":-9.432834490326316},{"acceleration":2.99848404769178,"curvature":-0.0978977571924484,"pose":{"rotation":{"radians":3.0453071602196196},"translation":{"x":3.9757773555790488,"y":1.8018098169256593}},"time":0.9008450283794681,"velocity":2.6992889817193118,"position":1.2172826477340073,"holonomicRotation":-140.55416,"angularVelocity":-0.2856706372851881,"angularAcceleration":9.880633291727744,"curveRadius":-10.214738607690366},{"acceleration":2.9983324716343884,"curvature":-0.08987808917411602,"pose":{"rotation":{"radians":3.044734288524643},"translation":{"x":3.9699428099039924,"y":1.8023767153844716}},"time":0.903011505767193,"velocity":2.705784801219989,"position":1.2231446693219001,"holonomicRotation":-140.54664,"angularVelocity":-0.2644254208340731,"angularAcceleration":9.80634119307625,"curveRadius":-11.126182245182733},{"acceleration":2.9981830044488955,"curvature":-0.08195958727045037,"pose":{"rotation":{"radians":3.044206467794789},"translation":{"x":3.9640874488339546,"y":1.8029487562349849}},"time":0.9051806106575502,"velocity":2.712288174637125,"position":1.2290279068655634,"holonomicRotation":-140.53912,"angularVelocity":-0.24333573364766714,"angularAcceleration":9.722760425353817,"curveRadius":-12.201135136273912},{"acceleration":2.998035658207373,"curvature":-0.07414787748383013,"pose":{"rotation":{"radians":3.0437233843593146},"translation":{"x":3.9582106120009004,"y":1.8035257613995987}},"time":0.9073525598482354,"velocity":2.7187997557586137,"position":1.2349330017947184,"holonomicRotation":-140.5316,"angularVelocity":-0.22241930775652247,"angularAcceleration":9.630255615945629,"curveRadius":-13.486562716755795},{"acceleration":2.9978904438056424,"curvature":-0.0664482901273198,"pose":{"rotation":{"radians":3.0432846999950005},"translation":{"x":3.952311639036795,"y":1.8041075528007129}},"time":0.9095275679067769,"velocity":2.7253201916325156,"position":1.2408605951736251,"holonomicRotation":-140.52408,"angularVelocity":-0.20169321331536014,"angularAcceleration":9.529203517094233,"curveRadius":-15.049296198351028},{"acceleration":2.9977473706360516,"curvature":-0.05886585597966748,"pose":{"rotation":{"radians":3.04289005276871},"translation":{"x":3.9463898695736024,"y":1.8046939523607277}},"time":0.9117058472026245,"velocity":2.7318501226641536,"position":1.246811327735183,"holonomicRotation":-140.51656,"angularVelocity":-0.18117384076626747,"angularAcceleration":9.419991544797991,"curveRadius":-16.987776417375198},{"acceleration":2.9976064470571417,"curvature":-0.051405305170531386,"pose":{"rotation":{"radians":3.0425390578968527},"translation":{"x":3.9404446432432887,"y":1.8052847820020432}},"time":0.9138876079382858,"velocity":2.738390182711308,"position":1.2527858399147431,"holonomicRotation":-140.50904,"angularVelocity":-0.1608768854074268,"angularAcceleration":9.303016149792512,"curveRadius":-19.453245082051573},{"acceleration":2.99746768046564,"curvature":-0.04407106680816387,"pose":{"rotation":{"radians":3.0422313086184865},"translation":{"x":3.9344752996778185,"y":1.8058798636470592}},"time":0.9160730581795283,"velocity":2.7449409991766984,"position":1.2587847718835903,"holonomicRotation":-140.50152,"angularVelocity":-0.14081733482585823,"angularAcceleration":9.178680988940767,"curveRadius":-22.690623858797917},{"acceleration":2.9973310766941346,"curvature":-0.036867267135229156,"pose":{"rotation":{"radians":3.041966377080267},"translation":{"x":3.928481178509157,"y":1.806479019218176}},"time":0.918262403884656,"velocity":2.7515031930963043,"position":1.2648087635820406,"holonomicRotation":-140.494,"angularVelocity":-0.12100945848752931,"angularAcceleration":9.04739543505496,"curveRadius":-27.124332170648817},{"acceleration":2.9971966406405315,"curvature":-0.029797732651577105,"pose":{"rotation":{"radians":3.041743815231708},"translation":{"x":3.922461619369268,"y":1.8070820706377932}},"time":0.9204558489328784,"velocity":2.758077379226266,"position":1.2708584547521187,"holonomicRotation":-140.48648,"angularVelocity":-0.10146679933447438,"angularAcceleration":8.909573170703643,"curveRadius":-33.559600379429305},{"acceleration":2.9970643762568274,"curvature":-0.022865989780728672,"pose":{"rotation":{"radians":3.0415631557266423},"translation":{"x":3.916415961890118,"y":1.8076888398283113}},"time":0.9226535951517832,"velocity":2.764664166126999,"position":1.2769344849697661,"holonomicRotation":-140.47896,"angularVelocity":-0.08220216852678146,"angularAcceleration":8.765630281594664,"curveRadius":-43.733072986973625},{"acceleration":2.996934286077364,"curvature":-0.016075269152134735,"pose":{"rotation":{"radians":3.04142391283164},"translation":{"x":3.910343545703671,"y":1.80829914871213}},"time":0.9248558423439303,"velocity":2.771264156243562,"position":1.2830374936765512,"holonomicRotation":-140.47144,"angularVelocity":-0.06322764106533946,"angularAcceleration":8.615984404068367,"curveRadius":-62.20735656343296},{"acceleration":2.9968063718954063,"curvature":-0.009428506085268934,"pose":{"rotation":{"radians":3.0413255833361768},"translation":{"x":3.9042437104418917,"y":1.8089128192116495}},"time":0.9270627883125758,"velocity":2.777877945984828,"position":1.2891681202108318,"holonomicRotation":-140.46392,"angularVelocity":-0.04455455496431375,"angularAcceleration":8.46105267927589,"curveRadius":-106.06134110284943},{"acceleration":2.996680634151126,"curvature":-0.002928345162241794,"pose":{"rotation":{"radians":3.041267647464989},"translation":{"x":3.898115795736747,"y":1.8095296732492696}},"time":0.9292746288865473,"velocity":2.784506125798678,"position":1.2953270038383455,"holonomicRotation":-140.4564,"angularVelocity":-0.02619351135403191,"angularAcceleration":8.301250924841028,"curveRadius":-341.4897987074892},{"acceleration":2.9965570726638484,"curvature":0.0034228398883690498,"pose":{"rotation":{"radians":3.041249569789562},"translation":{"x":3.891959141220199,"y":1.8101495327473907}},"time":0.9314915579442817,"velocity":2.791149280246226,"position":1.3015147837821979,"holonomicRotation":-140.44888,"angularVelocity":-0.00815437704883051,"angularAcceleration":8.136992134352063,"curveRadius":292.15506205769105},{"acceleration":2.9964356859299577,"curvature":0.009622991270902525,"pose":{"rotation":{"radians":3.0412708001370428},"translation":{"x":3.8857730865242144,"y":1.8107722196284124}},"time":0.9337137674370373,"velocity":2.797807988071931,"position":1.3077320992521986,"holonomicRotation":-140.44136,"angularVelocity":0.009553711092553452,"angularAcceleration":7.968685310324179,"curveRadius":103.91779144846004},{"acceleration":2.996316471693303,"curvature":0.015670288497210496,"pose":{"rotation":{"radians":3.041330774495024},"translation":{"x":3.8795569712807585,"y":1.8113975558147346}},"time":0.935941447411303,"velocity":2.804482822272485,"position":1.3139795894735473,"holonomicRotation":-140.43384,"angularVelocity":0.02692234013594607,"angularAcceleration":7.796734380178321,"curveRadius":63.81503443143452},{"acceleration":2.9961994266629897,"curvature":0.02156320435124434,"pose":{"rotation":{"radians":3.0414289159102403},"translation":{"x":3.873310135121795,"y":1.812025363228758}},"time":0.9381747860304156,"velocity":2.8111743501626143,"position":1.3202578937148242,"holonomicRotation":-140.42632,"angularVelocity":0.043943813256296295,"angularAcceleration":7.621537090113912,"curveRadius":46.37529671893562},{"acceleration":2.9960845466620625,"curvature":0.02730045944920149,"pose":{"rotation":{"radians":3.041564635380274},"translation":{"x":3.8670319176792898,"y":1.812655463792882}},"time":0.9404139695953984,"velocity":2.817883133438799,"position":1.3265676513152624,"holonomicRotation":-140.4188,"angularVelocity":0.060611140665723456,"angularAcceleration":7.443484165424143,"curveRadius":36.62942017004219},{"acceleration":2.9959718266231565,"curvature":0.03288104046648053,"pose":{"rotation":{"radians":3.04173733273537},"translation":{"x":3.860721658585207,"y":1.8132876794295067}},"time":0.9426591825650434,"velocity":2.8246097282406244,"position":1.332909501711294,"holonomicRotation":-140.41128,"angularVelocity":0.0769180284591228,"angularAcceleration":7.262958130861451,"curveRadius":30.412662914952964},{"acceleration":2.9958612608619757,"curvature":0.038304177370680356,"pose":{"rotation":{"radians":3.041946397510433},"translation":{"x":3.854378697471513,"y":1.8139218320610326}},"time":0.9449106075752485,"velocity":2.8313546852104334,"position":1.339284084462338,"holonomicRotation":-140.40376,"angularVelocity":0.09285886676898722,"angularAcceleration":7.080332783730037,"curveRadius":26.10681311134076},{"acceleration":2.995752842493079,"curvature":0.04356934367059782,"pose":{"rotation":{"radians":3.04219120980535},"translation":{"x":3.848002373970171,"y":1.8145577436098592}},"time":0.9471684254576287,"velocity":2.8381185495494057,"position":1.3456920392758256,"holonomicRotation":-140.39624,"angularVelocity":0.10842871642903909,"angularAcceleration":6.895972337519952,"curveRadius":22.95191792560411},{"acceleration":2.995646563960673,"curvature":0.04867624419119523,"pose":{"rotation":{"radians":3.0424711411313847},"translation":{"x":3.841592027713147,"y":1.8151952359983865}},"time":0.9494328152574162,"velocity":2.8449018610726067,"position":1.3521340060314349,"holonomicRotation":-140.38872,"angularVelocity":0.12362329403760243,"angularAcceleration":6.7102305486402205,"curveRadius":20.543902197386142},{"acceleration":2.995542417178371,"curvature":0.05362480902295912,"pose":{"rotation":{"radians":3.0427855552442513},"translation":{"x":3.8351469983324056,"y":1.815834131149015}},"time":0.9517039542506684,"velocity":2.8517051542622016,"position":1.3586106248045382,"holonomicRotation":-140.3812,"angularVelocity":0.13843895675286258,"angularAcceleration":6.523450462203622,"curveRadius":18.648085060253667},{"acceleration":2.995440392933044,"curvature":0.058415184771360026,"pose":{"rotation":{"radians":3.043133808961659},"translation":{"x":3.828666625459912,"y":1.816474250984144}},"time":0.9539820179608004,"velocity":2.8585289583172058,"position":1.365122535888842,"holonomicRotation":-140.37368,"angularVelocity":0.15287268563160306,"angularAcceleration":6.335963658322991,"curveRadius":17.118836547621143},{"acceleration":2.9953404816343046,"curvature":0.0630477259176045,"pose":{"rotation":{"radians":3.0435152529639136},"translation":{"x":3.822150248727631,"y":1.8171154174261743}},"time":0.9562671801744573,"velocity":2.8653737972028734,"position":1.3716703798182126,"holonomicRotation":-140.36616,"angularVelocity":0.16692206792797443,"angularAcceleration":6.148089712147052,"curveRadius":15.861000304862303},{"acceleration":2.995242672750745,"curvature":0.06752298658545955,"pose":{"rotation":{"radians":3.043929232578293},"translation":{"x":3.815597207767528,"y":1.8177574523975055}},"time":0.9585596129567482,"velocity":2.8722401896968037,"position":1.3782547973876869,"holonomicRotation":-140.35864,"angularVelocity":0.1805852793492575,"angularAcceleration":5.960136116893805,"curveRadius":14.809771465519576},{"acceleration":2.9951469551720824,"curvature":0.07184171019939141,"pose":{"rotation":{"radians":3.044375088544447},"translation":{"x":3.8090068422115673,"y":1.8184001778205376}},"time":0.9608594866658554,"velocity":2.8791286494339166,"position":1.3848764296736573,"holonomicRotation":-140.35112,"angularVelocity":0.19386106480040569,"angularAcceleration":5.772397587996967,"curveRadius":13.919490463472725},{"acceleration":2.9950533171447127,"curvature":0.07600482361168374,"pose":{"rotation":{"radians":3.044852157761491},"translation":{"x":3.802378491691714,"y":1.8190434156176707}},"time":0.9631669699670395,"velocity":2.886039684949384,"position":1.3915359180532327,"holonomicRotation":-140.3436,"angularVelocity":0.20674871917787627,"angularAcceleration":5.585156074957083,"curveRadius":13.15705967701603},{"acceleration":2.994961746207397,"curvature":0.08001342421282431,"pose":{"rotation":{"radians":3.045359774015402},"translation":{"x":3.7957114958399334,"y":1.8196869877113049}},"time":0.9654822298460576,"velocity":2.892973799719572,"position":1.3982339042227738,"holonomicRotation":-140.33608,"angularVelocity":0.21924806735998828,"angularAcceleration":5.398680422611265,"curveRadius":12.49790281865881},{"acceleration":2.994872229581827,"curvature":0.08386877437627455,"pose":{"rotation":{"radians":3.0458972686864905},"translation":{"x":3.78900519428819,"y":1.82033071602384}},"time":0.9678054316220123,"velocity":2.899931492202094,"position":1.4049710302156047,"holonomicRotation":-140.32856,"angularVelocity":0.23135944395861596,"angularAcceleration":5.213226300006028,"curveRadius":11.923388739574664},{"acceleration":2.9947847535013237,"curvature":0.08757229041746536,"pose":{"rotation":{"radians":3.046463971435902},"translation":{"x":3.7822589266684488,"y":1.820974422477676}},"time":0.9701367389596508,"velocity":2.9069132558725794,"position":1.4117479384188991,"holonomicRotation":-140.32104,"angularVelocity":0.24308367252241073,"angularAcceleration":5.029036015333211,"curveRadius":11.419137209189183},{"acceleration":2.994699303816628,"curvature":0.09112553514860063,"pose":{"rotation":{"radians":3.04705921087137},"translation":{"x":3.775472032612676,"y":1.8216179289952132}},"time":0.9724763138811319,"velocity":2.9139195792611656,"position":1.4185652715897512,"holonomicRotation":-140.31352,"angularVelocity":0.25442204479230934,"angularAcceleration":4.84633860869087,"curveRadius":10.973872453744997},{"acceleration":2.994615866054458,"curvature":0.094530208004347,"pose":{"rotation":{"radians":3.0476823151915697},"translation":{"x":3.768643851752834,"y":1.8222610574988514}},"time":0.9748243167772799,"velocity":2.9209509459875123,"position":1.4254236728704361,"holonomicRotation":-140.306,"angularVelocity":0.26537629967231224,"angularAcceleration":4.665349816209258,"curveRadius":10.578629002424439},{"acceleration":2.9945344250495816,"curvature":0.09778813706367112,"pose":{"rotation":{"radians":3.0483326128081343},"translation":{"x":3.76177372372089,"y":1.8229036299109909}},"time":0.9771809064183409,"velocity":2.9280078347933847,"position":1.4323237858028557,"holonomicRotation":-140.29848,"angularVelocity":0.2759486018413293,"angularAcceleration":4.486272019874072,"curveRadius":10.226189290720274},{"acceleration":2.99445496503517,"curvature":0.100901269114981,"pose":{"rotation":{"radians":3.049009432946653},"translation":{"x":3.754860988148809,"y":1.8235454681540313}},"time":0.9795462399642659,"velocity":2.935090719573944,"position":1.4392662543421972,"holonomicRotation":-140.29096,"angularVelocity":0.2861415210065346,"angularAcceleration":4.309294637437272,"curveRadius":9.91067811902802},{"acceleration":2.9943774699054924,"curvature":0.10387166349259429,"pose":{"rotation":{"radians":3.049712106224379},"translation":{"x":3.747904984668554,"y":1.8241863941503726}},"time":0.9819204729745337,"velocity":2.942200069408196,"position":1.4462517228697982,"holonomicRotation":-140.28344,"angularVelocity":0.2959580103078247,"angularAcceleration":4.1345938915166185,"curveRadius":9.62726470700353},{"acceleration":2.99430192325254,"curvature":0.10670148150952946,"pose":{"rotation":{"radians":3.0504399652063245},"translation":{"x":3.7409050529120913,"y":1.8248262298224154}},"time":0.984303759417532,"velocity":2.9493363485881274,"position":1.4532808362052305,"holonomicRotation":-140.27592,"angularVelocity":0.30540138558829566,"angularAcceleration":3.9623333184367526,"curveRadius":9.371941100093258},{"acceleration":2.994228307968351,"curvature":0.1093929792378581,"pose":{"rotation":{"radians":3.0511923449390386},"translation":{"x":3.733860532511386,"y":1.8254647970925593}},"time":0.9866962516795204,"velocity":2.956500016645568,"position":1.4603542396176235,"holonomicRotation":-140.2684,"angularVelocity":0.31447530454654044,"angularAcceleration":3.792663868723929,"curveRadius":9.141354472352882},{"acceleration":2.9941566067825915,"curvature":0.11194849914955035,"pose":{"rotation":{"radians":3.051968583461434},"translation":{"x":3.7267707630984024,"y":1.8261019178832043}},"time":0.989098100573187,"velocity":2.9636915283790337,"position":1.46747257883623,"holonomicRotation":-140.26088000000001,"angularVelocity":0.32318374583934245,"angularAcceleration":3.6257240477387587,"curveRadius":8.932678933588155},{"acceleration":2.9940868019441105,"curvature":0.11437046326599466,"pose":{"rotation":{"radians":3.052768022293713},"translation":{"x":3.7196350843051063,"y":1.8267374141167505}},"time":0.9915094553458205,"velocity":2.9709113338785804,"position":1.4746365000602488,"holonomicRotation":-140.25336000000001,"angularVelocity":0.3315309888665245,"angularAcceleration":3.4616403699344653,"curveRadius":8.743516214271786},{"acceleration":2.9940188751888255,"curvature":0.11666136399978577,"pose":{"rotation":{"radians":3.053590006903988},"translation":{"x":3.712452835763462,"y":1.8273711077155976}},"time":0.993930463687115,"velocity":2.978159878549406,"position":1.4818466499679257,"holonomicRotation":-140.24584000000002,"angularVelocity":0.33952159364940504,"angularAcceleration":3.300527572163527,"curveRadius":8.57181817282572},{"acceleration":2.993952808291727,"curvature":0.11882375817252294,"pose":{"rotation":{"radians":3.0544338871524306},"translation":{"x":3.7052233571054347,"y":1.8280028206021464}},"time":0.9963612717366243,"velocity":2.985437603135652,"position":1.4891036757249354,"holonomicRotation":-140.23832000000002,"angularVelocity":0.3471603809330414,"angularAcceleration":3.1424888876678647,"curveRadius":8.415825381891027},{"acceleration":2.9938885823054613,"curvature":0.12086025893549956,"pose":{"rotation":{"radians":3.0552990177142454},"translation":{"x":3.6979459879629886,"y":1.8286323746987962}},"time":0.9988020240908846,"velocity":2.9927449437413074,"position":1.4964082249920727,"holonomicRotation":-140.23080000000002,"angularVelocity":0.3544524131277485,"angularAcceleration":2.987616577314304,"curveRadius":8.274018348195645},{"acceleration":2.993826178264358,"curvature":0.1227735293811993,"pose":{"rotation":{"radians":3.056184758479826},"translation":{"x":3.6906200679680903,"y":1.8292595919279473}},"time":1.0012528638102212,"velocity":3.0000823318517873,"position":1.503760945932255,"holonomicRotation":-140.22328000000002,"angularVelocity":0.361402974903819,"angularAcceleration":2.83599197500846,"curveRadius":8.145078218734772},{"acceleration":2.9937655766019753,"curvature":0.12456627558506683,"pose":{"rotation":{"radians":3.057090474934403},"translation":{"x":3.683244936752703,"y":1.8298842942119997}},"time":1.0037139324252604,"velocity":3.0074501943531473,"position":1.5111624872168712,"holonomicRotation":-140.21576000000002,"angularVelocity":0.36801755507433787,"angularAcceleration":2.687686206755093,"curveRadius":8.027855013752063},{"acceleration":2.993706758072339,"curvature":0.12624124003624757,"pose":{"rotation":{"radians":3.058015538516008},"translation":{"x":3.6758199339487927,"y":1.8305063034733535}},"time":1.0061853699431567,"velocity":3.014848953552627,"position":1.5186134980314714,"holonomicRotation":-140.20824000000002,"angularVelocity":0.37430182835145004,"angularAcceleration":2.5427603294059864,"curveRadius":7.921341708247406},{"acceleration":2.993649702471842,"curvature":0.12780119591879893,"pose":{"rotation":{"radians":3.0589593269527593},"translation":{"x":3.6683443991883244,"y":1.8311254416344083}},"time":1.0086673148535588,"velocity":3.0222790271952036,"position":1.5261146280808335,"holonomicRotation":-140.20072000000002,"angularVelocity":0.38026163787755257,"angularAcceleration":2.401265838385181,"curveRadius":7.824652913540576},{"acceleration":2.9935943896562613,"curvature":0.12924894061546818,"pose":{"rotation":{"radians":3.0599212245793304},"translation":{"x":3.660817672103262,"y":1.8317415306175646}},"time":1.0111599041343287,"velocity":3.0297408284818337,"position":1.5336665275934183,"holonomicRotation":-140.19320000000002,"angularVelocity":0.3859029780766596,"angularAcceleration":2.263244988907494,"curveRadius":7.737007322753426},{"acceleration":2.99354079955245,"curvature":0.13058729030791794,"pose":{"rotation":{"radians":3.06090062263396},"translation":{"x":3.653239092325572,"y":1.8323543923452221}},"time":1.0136632732570257,"velocity":3.037234766086967,"position":1.5412698473252222,"holonomicRotation":-140.18568,"angularVelocity":0.39123197843656954,"angularAcceleration":2.1287313611061807,"curveRadius":7.657713071785569},{"acceleration":2.993488911571519,"curvature":0.13181907478597654,"pose":{"rotation":{"radians":3.06189691953485},"translation":{"x":3.6456079994872184,"y":1.8329638487397812}},"time":1.016177556192179,"velocity":3.0447612441739023,"position":1.5489252385630652,"holonomicRotation":-140.17816,"angularVelocity":0.39625488721263247,"angularAcceleration":1.9977500168478084,"curveRadius":7.586155506125462},{"acceleration":2.993438704711205,"curvature":0.13294713144057987,"pose":{"rotation":{"radians":3.0629095211380992},"translation":{"x":3.637923733220166,"y":1.8335697217236415}},"time":1.0187028854143585,"velocity":3.0523206624097123,"position":1.5566333531273104,"holonomicRotation":-140.17064,"angularVelocity":0.40097805638796513,"angularAcceleration":1.8703181881594355,"curveRadius":7.521786962714163},{"acceleration":2.9933901585126788,"curvature":0.133974301481331,"pose":{"rotation":{"radians":3.063937840976028},"translation":{"x":3.6301856331563798,"y":1.8341718332192032}},"time":1.0212393919070595,"velocity":3.059913415981967,"position":1.5643948433740515,"holonomicRotation":-140.16312,"angularVelocity":0.4054079265666836,"angularAcceleration":1.7464454325135055,"curveRadius":7.464118035646917},{"acceleration":2.9933432517650282,"curvature":0.13490342403849157,"pose":{"rotation":{"radians":3.0649813004776805},"translation":{"x":3.6223930389278256,"y":1.8347700051488665}},"time":1.0237872051674195,"velocity":3.067539895611623,"position":1.5722103621967742,"holonomicRotation":-140.1556,"angularVelocity":0.4095510129753244,"angularAcceleration":1.6261342513208221,"curveRadius":7.412710293510958},{"acceleration":2.9932979632997943,"curvature":0.13573733241061467,"pose":{"rotation":{"radians":3.066039329171222},"translation":{"x":3.6145452901664683,"y":1.8353640594350311}},"time":1.0263464532107798,"velocity":3.0752004875673924,"position":1.5800805630275216,"holonomicRotation":-140.14808,"angularVelocity":0.4134138917430372,"angularAcceleration":1.509380373557252,"curveRadius":7.367169976310806},{"acceleration":2.993254271614403,"curvature":0.1364788504772548,"pose":{"rotation":{"radians":3.0671113648686674},"translation":{"x":3.606641726504271,"y":1.8359538180000972}},"time":1.0289172625751053,"velocity":3.082895573678666,"position":1.5880060998375725,"holonomicRotation":-140.14056,"angularVelocity":0.41700318674811104,"angularAcceleration":1.3961731487684663,"curveRadius":7.327142604902415},{"acceleration":2.9932121559137994,"curvature":0.13713078720266178,"pose":{"rotation":{"radians":3.068196853833911},"translation":{"x":3.598681687573201,"y":1.8365391027664648}},"time":1.0314997583252747,"velocity":3.090625531350669,"position":1.5959876271376507,"holonomicRotation":-140.13304,"angularVelocity":0.42032555723369874,"angularAcceleration":1.2864960127697056,"curveRadius":7.292308462592925},{"acceleration":2.993171594022482,"curvature":0.13769593438784733,"pose":{"rotation":{"radians":3.0692952509345166},"translation":{"x":3.590664513005222,"y":1.8371197356565334}},"time":1.0340940640572622,"velocity":3.0983907335738636,"position":1.6040257999776983,"holonomicRotation":-140.12552,"angularVelocity":0.4233876859856737,"angularAcceleration":1.1803268651875862,"curveRadius":7.262378547672337},{"acceleration":2.9931325647615616,"curvature":0.13817706198809837,"pose":{"rotation":{"radians":3.070406019776828},"translation":{"x":3.582589542432299,"y":1.8376955385927038}},"time":1.0367003019022136,"velocity":3.1061915489391017,"position":1.6121212739462116,"holonomicRotation":-140.118,"angularVelocity":0.42619626772092634,"angularAcceleration":1.077638305610971,"curveRadius":7.237091204661256},{"acceleration":2.993095046577972,"curvature":0.13857691672411965,"pose":{"rotation":{"radians":3.071528632826876},"translation":{"x":3.574456115486398,"y":1.838266333497376}},"time":1.039318592530436,"velocity":3.1140283416489356,"position":1.62027470516917,"holonomicRotation":-140.11048,"angularVelocity":0.42875799880561505,"angularAcceleration":0.9783982943207211,"curveRadius":7.216209045773549},{"acceleration":2.993059017533048,"curvature":0.13889821668350927,"pose":{"rotation":{"radians":3.072662571515304},"translation":{"x":3.566263571799482,"y":1.8388319422929496}},"time":1.0419490551553137,"velocity":3.1219014715286093,"position":1.6284867503085765,"holonomicRotation":-140.10296,"angularVelocity":0.4310795666526117,"angularAcceleration":0.8825701703724631,"curveRadius":7.199516479600168},{"acceleration":2.9930244560401214,"curvature":0.13914365024737171,"pose":{"rotation":{"radians":3.0738073263285903},"translation":{"x":3.558011251003518,"y":1.8393921869018244}},"time":1.044591807537157,"velocity":3.1298112940387246,"position":1.6367580665606174,"holonomicRotation":-140.09544,"angularVelocity":0.43316764035519306,"angularAcceleration":0.7901132610558581,"curveRadius":7.186817351867545},{"acceleration":2.992991340284148,"curvature":0.13931587254271388,"pose":{"rotation":{"radians":3.074962396886094},"translation":{"x":3.549698492730469,"y":1.839946889246401}},"time":1.0472469659870023,"velocity":3.137758160286194,"position":1.6450893116534724,"holonomicRotation":-140.08792,"angularVelocity":0.435028861486939,"angularAcceleration":0.7009830738554775,"curveRadius":7.177933007550181},{"acceleration":2.992959648638199,"curvature":0.1394175044837766,"pose":{"rotation":{"radians":3.0761272920043874},"translation":{"x":3.5413246366123023,"y":1.840495871249079}},"time":1.0499146453703676,"velocity":3.1457424170361103,"position":1.6534811438447774,"holonomicRotation":-140.0804,"angularVelocity":0.4366698357970953,"angularAcceleration":0.6151317584822329,"curveRadius":7.172700470451797},{"acceleration":2.992929359122206,"curvature":0.13945112864489329,"pose":{"rotation":{"radians":3.0773015297480466},"translation":{"x":3.532889022280981,"y":1.841038954832259}},"time":1.0525949591109822,"velocity":3.1537644067220545,"position":1.6619342219187758,"holonomicRotation":-140.07288,"angularVelocity":0.4380971249246184,"angularAcceleration":0.5325082306207235,"curveRadius":7.170971004088895},{"acceleration":2.9929004501223533,"curvature":0.1394192885119979,"pose":{"rotation":{"radians":3.0784846374689523},"translation":{"x":3.52439098936847,"y":1.8415759619183405}},"time":1.0552880191944922,"velocity":3.161824467458198,"position":1.6704492051831528,"holonomicRotation":-140.06536,"angularVelocity":0.4393172392068137,"angularAcceleration":0.45305869321900916,"curveRadius":7.172608687598802},{"acceleration":2.9928728999032344,"curvature":0.13932448672698022,"pose":{"rotation":{"radians":3.079676151833337},"translation":{"x":3.515829877506736,"y":1.8421067144297234}},"time":1.0579939361721582,"velocity":3.1699229330500427,"position":1.6790267534655856,"holonomicRotation":-140.05784,"angularVelocity":0.4403366305098392,"angularAcceleration":0.3767267478785556,"curveRadius":7.177489208767706},{"acceleration":2.992846686578264,"curvature":0.1391691829395779,"pose":{"rotation":{"radians":3.0808756188378914},"translation":{"x":3.5072050263277417,"y":1.842631034288808}},"time":1.060712819164554,"velocity":3.1780601330050287,"position":1.6876675271100243,"holonomicRotation":-140.05032,"angularVelocity":0.44116168585002136,"angularAcceleration":0.3034537869006068,"curveRadius":7.185498821489546},{"acceleration":2.9928217886842545,"curvature":0.13895579238147499,"pose":{"rotation":{"radians":3.082082593815186},"translation":{"x":3.4985157754634537,"y":1.8431487434179943}},"time":1.0634447758652712,"velocity":3.186236392544677,"position":1.6963721869727055,"holonomicRotation":-140.0428,"angularVelocity":0.44179872139916765,"angularAcceleration":0.23317922607597405,"curveRadius":7.196533392826853},{"acceleration":2.9927981845161424,"curvature":0.13868668521859753,"pose":{"rotation":{"radians":3.0832966414289147},"translation":{"x":3.489761464545837,"y":1.8436596637396823}},"time":1.0661899125446435,"velocity":3.194452032614951,"position":1.705141394417932,"holonomicRotation":-140.03528,"angularVelocity":0.4422539769517718,"angularAcceleration":0.1658407597789546,"curveRadius":7.210497521256658},{"acceleration":2.992775852326488,"curvature":0.13836418500086042,"pose":{"rotation":{"radians":3.084517335659214},"translation":{"x":3.480941433206855,"y":1.844163617176272}},"time":1.068948334053498,"velocity":3.2027073698971886,"position":1.7139758113136234,"holonomicRotation":-140.02776,"angularVelocity":0.4425336107556599,"angularAcceleration":0.1013745734618313,"curveRadius":7.227303799706416},{"acceleration":2.9927547709309326,"curvature":0.13799056704429996,"pose":{"rotation":{"radians":3.0857442597791223},"translation":{"x":3.4720550210784733,"y":1.8446604256501635}},"time":1.0717201438269373,"velocity":3.211002716820762,"position":1.7228761000266473,"holonomicRotation":-140.02024,"angularVelocity":0.4426436949840645,"angularAcceleration":0.03971565056861403,"curveRadius":7.246872169740152},{"acceleration":2.9927349185818097,"curvature":0.13756805883808565,"pose":{"rotation":{"radians":3.0869770063220208},"translation":{"x":3.463101567792659,"y":1.8451499110837564}},"time":1.074505443888166,"velocity":3.2193383815727294,"position":1.731842923417958,"holonomicRotation":-140.01272,"angularVelocity":0.44259021139527066,"angularAcceleration":-0.019202092276627808,"curveRadius":7.269129247342048},{"acceleration":2.9927162741413786,"curvature":0.1370988389593325,"pose":{"rotation":{"radians":3.088215177040879},"translation":{"x":3.454080412981374,"y":1.8456318953994515}},"time":1.077304334852368,"velocity":3.227714668110844,"position":1.7408769448375558,"holonomicRotation":-140.0052,"angularVelocity":0.4423790475207054,"angularAcceleration":-0.0754455522798365,"curveRadius":7.294007794600136},{"acceleration":2.992698816286504,"curvature":0.13658503575917563,"pose":{"rotation":{"radians":3.0894583828600712},"translation":{"x":3.4449908962765847,"y":1.846106200519648}},"time":1.0801169159306334,"velocity":3.2361318761744786,"position":1.7499788281192554,"holonomicRotation":-139.99768,"angularVelocity":0.4420159933519917,"angularAcceleration":-0.12908220549417898,"curveRadius":7.321446265630319},{"acceleration":2.9926825239098926,"curvature":0.13602872768670857,"pose":{"rotation":{"radians":3.090706243818936},"translation":{"x":3.4358323573102556,"y":1.8465726483667466}},"time":1.0829432849339546,"velocity":3.2445903012968387,"position":1.7591492375753175,"holonomicRotation":-139.99016,"angularVelocity":0.44150673793779993,"angularAcceleration":-0.1801800874526147,"curveRadius":7.351388320731243},{"acceleration":2.9926673759828093,"curvature":0.13543194273816753,"pose":{"rotation":{"radians":3.0919583890095392},"translation":{"x":3.4266041357143524,"y":1.8470310608631468}},"time":1.0857835382772867,"velocity":3.2530902348169546,"position":1.7683888379909172,"holonomicRotation":-139.98264,"angularVelocity":0.44085686706178545,"angularAcceleration":-0.22880736239256874,"curveRadius":7.383782435531579},{"acceleration":2.9926533514468865,"curvature":0.13479665827860732,"pose":{"rotation":{"radians":3.0932144565069626},"translation":{"x":3.4173055711208393,"y":1.8474812599312487}},"time":1.0886377709836847,"velocity":3.261631963891566,"position":1.7776982946184898,"holonomicRotation":-139.97512,"angularVelocity":0.44007186050658886,"angularAcceleration":-0.27503242935900535,"curveRadius":7.418581534366592},{"acceleration":2.9926404296077753,"curvature":0.1341248011945456,"pose":{"rotation":{"radians":3.0944740932940333},"translation":{"x":3.4079360031616823,"y":1.8479230674934526}},"time":1.0915060766885187,"velocity":3.270215771508327,"position":1.7870782731719452,"holonomicRotation":-139.9676,"angularVelocity":0.43915709017622206,"angularAcceleration":-0.3189235822475711,"curveRadius":7.455742644863407},{"acceleration":2.992628589853986,"curvature":0.13341824700076957,"pose":{"rotation":{"radians":3.0957369551804037},"translation":{"x":3.3984947714688447,"y":1.8483563054721583}},"time":1.0943885476437754,"velocity":3.2788419364984516,"position":1.7965294398207794,"holonomicRotation":-139.96008,"angularVelocity":0.43811781834864644,"angularAcceleration":-0.3605489330882443,"curveRadius":7.495226646129085},{"acceleration":2.9926178115282043,"curvature":0.1326788210220034,"pose":{"rotation":{"radians":3.0970027067158963},"translation":{"x":3.388981215674293,"y":1.848780795789766}},"time":1.097285274722447,"velocity":3.2875107335492206,"position":1.8060524611840754,"holonomicRotation":-139.95256,"angularVelocity":0.43695919605687494,"angularAcceleration":-0.3999763389179118,"curveRadius":7.536997934539684},{"acceleration":0.06575690921671164,"curvature":0.1316396350008129,"pose":{"rotation":{"radians":3.098271021099374},"translation":{"x":3.379394675409991,"y":1.8491963603686754}},"time":1.1002038912014434,"velocity":3.2877026527480684,"position":1.8156480043244256,"holonomicRotation":-139.94504,"angularVelocity":0.434560139232031,"angularAcceleration":-0.8219842662126593,"curveRadius":7.596496298351365},{"acceleration":-2.2006332802607766,"curvature":0.07387278615541837,"pose":{"rotation":{"radians":3.1001802478026153},"translation":{"x":3.36,"y":1.85}},"time":1.1061316304860314,"velocity":3.274657872401695,"position":1.8350593224382465,"holonomicRotation":-139.93,"angularVelocity":0.32208344726047566,"angularAcceleration":-18.974635450650183,"curveRadius":13.536784681386392},{"acceleration":-4.038971999994151,"curvature":-0.021919302102742393,"pose":{"rotation":{"radians":3.101318989522492},"translation":{"x":3.348590776135541,"y":1.8504597398371714}},"time":1.109633681287243,"velocity":3.260513187273044,"position":1.846477805258097,"holonomicRotation":-139.92024,"angularVelocity":0.32516424932578114,"angularAcceleration":0.8797136992529169,"curveRadius":-45.62189048322332},{"acceleration":-3.0040405789393105,"curvature":-0.020314617612254046,"pose":{"rotation":{"radians":3.101069442155173},"translation":{"x":3.3372489325887322,"y":1.8509195995053924}},"time":1.1131263238896576,"velocity":3.2500211471676583,"position":1.8578289675754434,"holonomicRotation":-139.91048,"angularVelocity":-0.07144944265016444,"angularAcceleration":-113.55690722599095,"curveRadius":-49.22563737536397},{"acceleration":-3.0040307366046495,"curvature":-0.018656375015070056,"pose":{"rotation":{"radians":3.1008395268488647},"translation":{"x":3.3259740088440597,"y":1.8513793424462874}},"time":1.1166096063626927,"velocity":3.2395572595543847,"position":1.8691132605980427,"holonomicRotation":-139.90072,"angularVelocity":-0.06600535790260702,"angularAcceleration":1.5629179630711454,"curveRadius":-53.60098085465318},{"acceleration":-3.0040204316124663,"curvature":-0.016943444405964427,"pose":{"rotation":{"radians":3.1006296224072036},"translation":{"x":3.3147655443860065,"y":1.851838732101481}},"time":1.120083577593159,"velocity":3.22912137899923,"position":1.8803311353683698,"holonomicRotation":-139.89096,"angularVelocity":-0.06042204374641504,"angularAcceleration":1.6071849148395199,"curveRadius":-59.01987671691951},{"acceleration":-3.0040096542226222,"curvature":-0.015174682782485422,"pose":{"rotation":{"radians":3.1004401118263725},"translation":{"x":3.303623078699058,"y":1.8522975319125972}},"time":1.123548287298468,"velocity":3.2187133575954032,"position":1.891483042777038,"holonomicRotation":-139.8812,"angularVelocity":-0.05469739082058825,"angularAcceleration":1.65227491268751,"curveRadius":-65.8992358742548},{"acceleration":-3.00399839396767,"curvature":-0.013348936506075909,"pose":{"rotation":{"radians":3.100271382267398},"translation":{"x":3.2925461512676995,"y":1.8527555053212603}},"time":1.1270037860401554,"velocity":3.2083330449250167,"position":1.9025694335766907,"holonomicRotation":-139.87144,"angularVelocity":-0.04882929255303764,"angularAcceleration":1.6981914062816088,"curveRadius":-74.9123347425347},{"acceleration":-3.003986640752306,"curvature":-0.0114650409009334,"pose":{"rotation":{"radians":3.1001238250253196},"translation":{"x":3.2815343015764147,"y":1.8532124157690943}},"time":1.1304501252377346,"velocity":3.1979802880159878,"position":1.9135907583963658,"holonomicRotation":-139.86168,"angularVelocity":-0.04281564687017054,"angularAcceleration":1.7449372618607166,"curveRadius":-87.22166877909588},{"acceleration":-3.0039743836861676,"curvature":-0.009521823561694242,"pose":{"rotation":{"radians":3.099997835493851},"translation":{"x":3.2705870691096894,"y":1.853668026697724}},"time":1.133887357182879,"velocity":3.1876549313019864,"position":1.924547467756334,"holonomicRotation":-139.85192,"angularVelocity":-0.03665435835555252,"angularAcceleration":1.7925146201791424,"curveRadius":-105.02189979899894},{"acceleration":-3.0039616121230495,"curvature":-0.00751810156518465,"pose":{"rotation":{"radians":3.0998938131266818},"translation":{"x":3.2597039933520082,"y":1.8541221015487732}},"time":1.1373155350539528,"velocity":3.177356816577751,"position":1.9354400120834314,"holonomicRotation":-139.84216,"angularVelocity":-0.030343340130349623,"angularAcceleration":1.840924964382321,"curveRadius":-133.01230255133422},{"acceleration":-3.0039483149880795,"curvature":-0.005452679437038294,"pose":{"rotation":{"radians":3.0998121613940897},"translation":{"x":3.2488846137878546,"y":1.854574403763867}},"time":1.1407347129308938,"velocity":3.1670857829556693,"position":1.9462688417268879,"holonomicRotation":-139.8324,"angularVelocity":-0.02388051617401202,"angularAcceleration":1.890168978900741,"curveRadius":-183.39607371878904},{"acceleration":-3.0039344808956594,"curvature":-0.003324361684455138,"pose":{"rotation":{"radians":3.0997532877356733},"translation":{"x":3.2381284699017154,"y":1.8550246967846284}},"time":1.144144945810456,"velocity":3.1568416668208683,"position":1.9570344069746524,"holonomicRotation":-139.82264,"angularVelocity":-0.01726382346766584,"angularAcceleration":1.9402465872640324,"curveRadius":-300.80962750715247},{"acceleration":-3.0039200983249965,"curvature":-0.0011319408212423642,"pose":{"rotation":{"radians":3.099717603507945},"translation":{"x":3.2274351011780733,"y":1.8554727440526828}},"time":1.1475462896218291,"velocity":3.146624301784571,"position":1.9677371580702436,"holonomicRotation":-139.81288,"angularVelocity":-0.010491214563180279,"angularAcceleration":1.9911568133276807,"curveRadius":-883.4384105897407},{"acceleration":-3.003905155640235,"curvature":0.0011257983382181108,"pose":{"rotation":{"radians":3.0997055239281646},"translation":{"x":3.2168040471014145,"y":1.855918309009654}},"time":1.1509388012426356,"velocity":3.1364335186362613,"position":1.978377545230104,"holonomicRotation":-139.80312,"angularVelocity":-0.0035606598091984017,"angularAcceleration":2.042897867018768,"curveRadius":888.2585504458804},{"acceleration":-3.0038896407155264,"curvature":0.003450076809717216,"pose":{"rotation":{"radians":3.099717468012473},"translation":{"x":3.2062348471562228,"y":1.8563611550971666}},"time":1.1543225385153235,"velocity":3.126269145295931,"position":1.988956018661496,"holonomicRotation":-139.79336,"angularVelocity":0.0035298497920261316,"angularAcceleration":2.095466943741786,"curveRadius":289.8486193650757},{"acceleration":-3.0038735412829345,"curvature":0.005842110836291091,"pose":{"rotation":{"radians":3.099753858509543},"translation":{"x":3.195727040826984,"y":1.8568010457568445}},"time":1.1576975602639585,"velocity":3.116131006763952,"position":1.9994730285809204,"holonomicRotation":-139.7836,"angularVelocity":0.010782300020762747,"angularAcceleration":2.1488602945061803,"curveRadius":171.17100788092162},{"acceleration":-3.003856844881008,"curvature":0.008303136358416778,"pose":{"rotation":{"radians":3.099815121828717},"translation":{"x":3.185280167598181,"y":1.857237744430312}},"time":1.161063926311432,"velocity":3.1060189250698738,"position":2.0099290252330855,"holonomicRotation":-139.77384,"angularVelocity":0.018198650506128365,"angularAcceleration":2.203073100422888,"curveRadius":120.43641785869426},{"acceleration":-3.003839538821645,"curvature":0.010834380823841656,"pose":{"rotation":{"radians":3.0999016879629937},"translation":{"x":3.1748937669543005,"y":1.8576710145591935}},"time":1.1644216974970891,"velocity":3.0959327192200807,"position":2.020324458910416,"holonomicRotation":-139.76408,"angularVelocity":0.025780831834698037,"angularAcceleration":2.2580994681702014,"curveRadius":92.29876780770384},{"acceleration":-3.003821609890098,"curvature":0.013437076420544045,"pose":{"rotation":{"radians":3.100013990406157},"translation":{"x":3.164567378379826,"y":1.8581006195851135}},"time":1.1677709356947952,"velocity":3.085872205145142,"position":2.0306597799731274,"holonomicRotation":-139.75432,"angularVelocity":0.03353074237611176,"angularAcceleration":2.3139323284685362,"curveRadius":74.42095056266054},{"acceleration":-3.003803045055472,"curvature":0.016112457442011414,"pose":{"rotation":{"radians":3.1001524660645456},"translation":{"x":3.154300541359243,"y":1.858526322949696}},"time":1.1711117038314438,"velocity":3.0758371956434525,"position":2.0409354388698517,"holonomicRotation":-139.74456,"angularVelocity":0.04145024519041935,"angularAcceleration":2.3705634424100506,"curveRadius":62.063779134808634},{"acceleration":-3.003783830453073,"curvature":0.018861757214512106,"pose":{"rotation":{"radians":3.1003175551622464},"translation":{"x":3.144092795377036,"y":1.8589478880945653}},"time":1.1744440659059234,"velocity":3.0658275003269155,"position":2.051151886158838,"holonomicRotation":-139.7348,"angularVelocity":0.04954116449861579,"angularAcceleration":2.427983252528137,"curveRadius":53.01732964893679},{"acceleration":-3.003763952629002,"curvature":0.021686205497999978,"pose":{"rotation":{"radians":3.100509701140666},"translation":{"x":3.1339436799176896,"y":1.859365078461346}},"time":1.1777680870085527,"velocity":3.0558429255610595,"position":2.0613095725297232,"holonomicRotation":-139.72504,"angularVelocity":0.05780528236351414,"angularAcceleration":2.4861809265775787,"curveRadius":46.11226247451291},{"acceleration":-3.0037433971025456,"curvature":0.024587031489835764,"pose":{"rotation":{"radians":3.1007293505514895},"translation":{"x":3.1238527344656886,"y":1.8597776574916618}},"time":1.1810838333409939,"velocity":3.0458832744085225,"position":2.071408948825887,"holonomicRotation":-139.71528,"angularVelocity":0.0662443350006201,"angularAcceleration":2.5451442272705194,"curveRadius":40.671847693911246},{"acceleration":-3.0037221497213324,"curvature":0.02756545872423086,"pose":{"rotation":{"radians":3.100976952942777},"translation":{"x":3.113819498505518,"y":1.8601853886271378}},"time":1.1843913722366586,"velocity":3.0359483465665495,"position":2.081450466067385,"holonomicRotation":-139.70552,"angularVelocity":0.07486000893653731,"angularAcceleration":2.604859446161022,"curveRadius":36.27728491675599},{"acceleration":-3.003700195941555,"curvature":0.03062270676925453,"pose":{"rotation":{"radians":3.1012529607390427},"translation":{"x":3.103843511521662,"y":1.8605880353093973}},"time":1.187690772181619,"velocity":3.0260379383053824,"position":2.091434575474478,"holonomicRotation":-139.69576,"angularVelocity":0.08365393734317614,"angularAcceleration":2.6653114364237247,"curveRadius":32.6555065016006},{"acceleration":-3.003677520386418,"curvature":0.03375998496198865,"pose":{"rotation":{"radians":3.101557829113109},"translation":{"x":3.093924312998605,"y":1.8609853609800655}},"time":1.1909821028360312,"velocity":3.0161518424065656,"position":2.1013617284917525,"holonomicRotation":-139.686,"angularVelocity":0.09262769562748037,"angularAcceleration":2.726483366924671,"curveRadius":29.62086627484962},{"acceleration":-3.0036541083432695,"curvature":0.0369784967213473,"pose":{"rotation":{"radians":3.1018920158520893},"translation":{"x":3.0840614424208335,"y":1.8613771290807661}},"time":1.194265435056091,"velocity":3.006289848094727,"position":2.1112323768128407,"holonomicRotation":-139.67624,"angularVelocity":0.10178279765251586,"angularAcceleration":2.78835689215411,"curveRadius":27.042743449944258},{"acceleration":-3.003629943823807,"curvature":0.04027943256621179,"pose":{"rotation":{"radians":3.1022559812147232},"translation":{"x":3.074254439272831,"y":1.8617631030531236}},"time":1.1975408409165287,"velocity":2.9964517409741407,"position":2.121046972405746,"holonomicRotation":-139.66648,"angularVelocity":0.11112069103561902,"angularAcceleration":2.8509118506173605,"curveRadius":24.826566222257195},{"acceleration":-3.003605011400646,"curvature":0.043663973294366006,"pose":{"rotation":{"radians":3.102650187781819},"translation":{"x":3.0645028430390817,"y":1.8621430463387623}},"time":1.2008083937336582,"velocity":2.986637302957594,"position":2.130805967538769,"holonomicRotation":-139.65672,"angularVelocity":0.12064275289731316,"angularAcceleration":2.9141263797715853,"curveRadius":22.902175971443963},{"acceleration":-3.0035792945651334,"curvature":0.04713328322693851,"pose":{"rotation":{"radians":3.1030751002983945},"translation":{"x":3.0548061932040715,"y":1.8625167223793064}},"time":1.2040681680889929,"velocity":2.9768463121989566,"position":2.140509814807048,"holonomicRotation":-139.64696,"angularVelocity":0.130350285098728,"angularAcceleration":2.9779767380304722,"curveRadius":21.21642990973438},{"acceleration":-3.003552777157972,"curvature":0.05068851236478955,"pose":{"rotation":{"radians":3.1035311855079404},"translation":{"x":3.045164029252285,"y":1.8628838946163802}},"time":1.2073202398534428,"velocity":2.967078543019326,"position":2.1501589671597063,"holonomicRotation":-139.6372,"angularVelocity":0.1402445095251501,"angularAcceleration":3.042437296304723,"curveRadius":19.728335935434625},{"acceleration":-3.003525442382997,"curvature":0.05433079225318585,"pose":{"rotation":{"radians":3.1040189119780224},"translation":{"x":3.035575890668206,"y":1.863244326491608}},"time":1.2105646862121051,"velocity":2.957333765834637,"position":2.1597538779276175,"holonomicRotation":-139.62744,"angularVelocity":0.1503265630451323,"angularAcceleration":3.107480415900341,"curveRadius":18.405768782827973},{"acceleration":-3.00349727317764,"curvature":0.058061233795577816,"pose":{"rotation":{"radians":3.104538749917779},"translation":{"x":3.0260413169363196,"y":1.863597781446614}},"time":1.2138015856896616,"velocity":2.947611747080246,"position":2.169295000851781,"holonomicRotation":-139.61768,"angularVelocity":0.16059749255754896,"angularAcceleration":3.1730764528314013,"curveRadius":17.223195833571214},{"acceleration":-3.0034682521509715,"curvature":0.06188092715098377,"pose":{"rotation":{"radians":3.1050911709859648},"translation":{"x":3.016559847541111,"y":1.8639440229230229}},"time":1.2170310181763973,"velocity":2.9379122491338703,"position":2.1787827901123125,"holonomicRotation":-139.60792,"angularVelocity":0.17105824953918458,"angularAcceleration":3.239193581101729,"curveRadius":16.16006815088746},{"acceleration":-3.0034383617817433,"curvature":0.06579093698052767,"pose":{"rotation":{"radians":3.105676648090798},"translation":{"x":3.0071310219670653,"y":1.8642828143624584}},"time":1.2202530649548562,"velocity":2.9282350302359914,"position":2.188217700358055,"holonomicRotation":-139.59816,"angularVelocity":0.18170968489571623,"angularAcceleration":3.3057978635636314,"curveRadius":15.19966192753833},{"acceleration":-3.003407583878885,"curvature":0.0697923014254418,"pose":{"rotation":{"radians":3.106295655179653},"translation":{"x":2.997754379698666,"y":1.8646139192065452}},"time":1.2234678087271447,"velocity":2.918579844410073,"position":2.197600186736799,"holonomicRotation":-139.5884,"angularVelocity":0.1925525431268054,"angularAcceleration":3.3728530169514777,"curveRadius":14.328227892990276},{"acceleration":-3.00337590050119,"curvature":0.07388602955301253,"pose":{"rotation":{"radians":3.106948667020117},"translation":{"x":2.9884294602203987,"y":1.8649371008969071}},"time":1.2266753336428995,"velocity":2.9089464413778376,"position":2.2069307049261147,"holonomicRotation":-139.57864,"angularVelocity":0.2035874568756966,"angularAcceleration":3.4403205084049597,"curveRadius":13.534358336070953},{"acceleration":-3.0033432926899515,"curvature":0.07807309878596051,"pose":{"rotation":{"radians":3.1076361589706156},"translation":{"x":2.9791558030167478,"y":1.8652521228751688}},"time":1.229875725327935,"velocity":2.8993345664766053,"position":2.2162097111648027,"holonomicRotation":-139.56888,"angularVelocity":0.21481494084403455,"angularAcceleration":3.50815933588236,"curveRadius":12.808509147837551},{"acceleration":-3.0033097416580588,"curvature":0.08235445208424093,"pose":{"rotation":{"radians":3.1083586067417635},"translation":{"x":2.9699329475721985,"y":1.8655587485829548}},"time":1.2330690709135832,"velocity":2.8897439605707476,"position":2.2254376622849446,"holonomicRotation":-139.55912,"angularVelocity":0.22623538598350737,"angularAcceleration":3.5763260922337685,"curveRadius":12.142634365135393},{"acceleration":-3.003275228345547,"curvature":0.08673099554738314,"pose":{"rotation":{"radians":3.109116486147233},"translation":{"x":2.9607604333712354,"y":1.865856741461889}},"time":1.2362554590667427,"velocity":2.88017435996247,"position":2.234615015744563,"holonomicRotation":-139.54936,"angularVelocity":0.237849053235389,"angularAcceleration":3.644774802581997,"curveRadius":11.529903394844315},{"acceleration":-3.0032397329795777,"curvature":0.09120359551393176,"pose":{"rotation":{"radians":3.109910272844281},"translation":{"x":2.951637799898342,"y":1.8661458649535954}},"time":1.2394349800206517,"velocity":2.8706254963018494,"position":2.2437422296608798,"holonomicRotation":-139.5396,"angularVelocity":0.24965606723626843,"angularAcceleration":3.7134568924176294,"curveRadius":10.96448001161583},{"acceleration":-3.0032032357952048,"curvature":0.09577307545040488,"pose":{"rotation":{"radians":3.110740442063759},"translation":{"x":2.9425645866380052,"y":1.8664258824996989}},"time":1.2426077256063977,"velocity":2.861097096492382,"position":2.2528197628441666,"holonomicRotation":-139.52984,"angularVelocity":0.2616564098955015,"angularAcceleration":3.782321126895998,"curveRadius":10.441347897591948},{"acceleration":-3.0031657166290264,"curvature":0.10044021360480618,"pose":{"rotation":{"radians":3.1116074683297725},"translation":{"x":2.9335403330747085,"y":1.8666965575418235}},"time":1.2457737892851866,"velocity":2.851588882595579,"position":2.2618480748321907,"holonomicRotation":-139.52008,"angularVelocity":0.27384991395529107,"angularAcceleration":3.851313585851144,"curveRadius":9.95617157819494},{"acceleration":-3.0031271550138765,"curvature":0.1052057388612443,"pose":{"rotation":{"radians":3.1125118251677377},"translation":{"x":2.9245645786929364,"y":1.8669576535215935}},"time":1.2489332661813777,"velocity":2.8421005717329884,"position":2.2708276259252327,"holonomicRotation":-139.51032,"angularVelocity":0.2862362560889219,"angularAcceleration":3.9203774993775355,"curveRadius":9.505184896034033},{"acceleration":-3.0030875300406215,"curvature":0.11007032871157574,"pose":{"rotation":{"radians":3.11345398480181},"translation":{"x":2.9156368629771743,"y":1.8672089338806332}},"time":1.2520862531163066,"velocity":2.8326318759863223,"position":2.279758877221681,"holonomicRotation":-139.50056,"angularVelocity":0.29881495024134586,"angularAcceleration":3.989453306347896,"curveRadius":9.08510051442077},{"acceleration":-3.0030468206577594,"curvature":0.11503460475177643,"pose":{"rotation":{"radians":3.1144344178409757},"translation":{"x":2.9067567254119067,"y":1.8674501620605668}},"time":1.2552328486429116,"velocity":2.823182502294255,"position":2.2886422906541894,"holonomicRotation":-139.4908,"angularVelocity":0.31158534068833643,"angularAcceleration":4.0584785489633814,"curveRadius":8.693036344653128},{"acceleration":-3.0030050057127444,"curvature":0.12009913122136752,"pose":{"rotation":{"radians":3.1154535929533758},"translation":{"x":2.8979237054816185,"y":1.867681101503019}},"time":1.2583731530811786,"velocity":2.8137521523466775,"position":2.297478329026387,"holonomicRotation":-139.48104,"angularVelocity":0.32454659490354026,"angularAcceleration":4.127387796310844,"curveRadius":8.326454902965063},{"acceleration":-3.0029620629897114,"curvature":0.1252644094377813,"pose":{"rotation":{"radians":3.11651197652967},"translation":{"x":2.889137342670794,"y":1.8679015156496135}},"time":1.2615072685544202,"velocity":2.804340522479504,"position":2.3062674560501284,"holonomicRotation":-139.47128,"angularVelocity":0.3376976966326016,"angularAcceleration":4.196112696338903,"curveRadius":7.983113515548875},{"acceleration":-3.0029179708627525,"curvature":0.13053087573401304,"pose":{"rotation":{"radians":3.1176100323337144},"translation":{"x":2.880397176463918,"y":1.8681111679419748}},"time":1.2646352990264083,"velocity":2.7949473035617647,"position":2.3150101363832705,"holonomicRotation":-139.46152,"angularVelocity":0.35103743837457985,"angularAcceleration":4.264581774838022,"curveRadius":7.6610226843013915},{"acceleration":-3.002872707019188,"curvature":0.1358988968082375,"pose":{"rotation":{"radians":3.1187482211423925},"translation":{"x":2.8717027463454756,"y":1.8683098218217271}},"time":1.2677573503393758,"velocity":2.785572180884141,"position":2.3237068356679655,"holonomicRotation":-139.45176,"angularVelocity":0.3645644144126075,"angularAcceleration":4.332720600024448,"curveRadius":7.358411462390806},{"acceleration":-3.00282624856303,"curvature":0.1413687670299931,"pose":{"rotation":{"radians":3.119927000372587},"translation":{"x":2.8630535917999516,"y":1.8684972407304952}},"time":1.2708735302529035,"velocity":2.776214834044555,"position":2.332358020569453,"holonomicRotation":-139.442,"angularVelocity":0.37827701317156187,"angularAcceleration":4.400451559111255,"curveRadius":7.073698250391034},{"acceleration":-3.002778573028619,"curvature":0.14694070424024094,"pose":{"rotation":{"radians":3.1211468236968765},"translation":{"x":2.85444925231183,"y":1.8686731881099028}},"time":1.2739839484837125,"velocity":2.766874936827924,"position":2.340964158815331,"holonomicRotation":-139.43224,"angularVelocity":0.3921734100601025,"angularAcceleration":4.46769400683652,"curveRadius":6.805466226465394},{"acceleration":-3.0027296569197794,"curvature":0.15261484529340985,"pose":{"rotation":{"radians":3.1224081406462445},"translation":{"x":2.845889267365597,"y":1.8688374274015742}},"time":1.277088716746375,"velocity":2.7575521570877646,"position":2.3495257192352934,"holonomicRotation":-139.42248,"angularVelocity":0.40625155974972776,"angularAcceleration":4.534364080864806,"curveRadius":6.552442510277745},{"acceleration":-3.002679476986564,"curvature":0.15839124351244407,"pose":{"rotation":{"radians":3.1237113962011938},"translation":{"x":2.8373731764457357,"y":1.868989722047134}},"time":1.2801879487949672,"velocity":2.7482461566210374,"position":2.358043171801314,"holonomicRotation":-139.41272,"angularVelocity":0.42050918889445704,"angularAcceleration":4.600374841633819,"curveRadius":6.313480327726795},{"acceleration":-3.0026280096763514,"curvature":0.16426986328933343,"pose":{"rotation":{"radians":3.1250570303705176},"translation":{"x":2.8289005190367313,"y":1.8691298354882064}},"time":1.2832817604656779,"velocity":2.738956591041898,"position":2.3665169876682493,"holonomicRotation":-139.40296,"angularVelocity":0.4349437886161886,"angularAcceleration":4.66563619834555,"curveRadius":6.0875438743056},{"acceleration":-3.0025752307339357,"curvature":0.1702505771671018,"pose":{"rotation":{"radians":3.126445477757459},"translation":{"x":2.820470834623069,"y":1.8692575311664157}},"time":1.2863702697203907,"velocity":2.729683109653805,"position":2.3749476392148483,"holonomicRotation":-139.3932,"angularVelocity":0.449552606916283,"angularAcceleration":4.730054889038297,"curveRadius":5.8736952123134065},{"acceleration":-3.0025211162408896,"curvature":0.1763331606146866,"pose":{"rotation":{"radians":3.127877167114063},"translation":{"x":2.812083662689234,"y":1.869372572523386}},"time":1.2894535966912635,"velocity":2.7204253553154842,"position":2.3833356000851387,"holonomicRotation":-139.38344,"angularVelocity":0.4643326413736547,"angularAcceleration":4.793534580339382,"curveRadius":5.671083059556474},{"acceleration":-3.0024656417765496,"curvature":0.18251728941448583,"pose":{"rotation":{"radians":3.1293525208830326},"translation":{"x":2.8037385427197092,"y":1.8694747230007416}},"time":1.2925318637263192,"velocity":2.711182964306516,"position":2.391681345230168,"holonomicRotation":-139.37368,"angularVelocity":0.479280631656787,"angularAcceleration":4.855975817855435,"curveRadius":5.478932999761244},{"acceleration":-3.0024087825887915,"curvature":0.18880253400900746,"pose":{"rotation":{"radians":3.1308719547273607},"translation":{"x":2.7954350141989814,"y":1.869563746040107}},"time":1.2956051954360661,"velocity":2.7019555661893633,"position":2.399985350950065,"holonomicRotation":-139.36392,"angularVelocity":0.4943930521750302,"angularAcceleration":4.917276085205858,"curveRadius":5.296539081156038},{"acceleration":-3.0023505139814435,"curvature":0.1951883560192808,"pose":{"rotation":{"radians":3.1324358770484357},"translation":{"x":2.7871726166115347,"y":1.8696394050831064}},"time":1.2986737187411734,"velocity":2.6927427836671103,"position":2.408248094936407,"holonomicRotation":-139.35416,"angularVelocity":0.5096661050193179,"angularAcceleration":4.977329915945837,"curveRadius":5.123256429810903},{"acceleration":-3.002290810893616,"curvature":0.20167410403837924,"pose":{"rotation":{"radians":3.1340446884913544},"translation":{"x":2.7789508894418526,"y":1.869701463571364}},"time":1.3017375629212158,"velocity":2.6835442324393592,"position":2.4164700563148527,"holonomicRotation":-139.3444,"angularVelocity":0.5250957125686628,"angularAcceleration":5.036028806507935,"curveRadius":4.95849481899618},{"acceleration":-3.0022296480771065,"curvature":0.20825900939961586,"pose":{"rotation":{"radians":3.135698781439246},"translation":{"x":2.770769372174422,"y":1.869749684946504}},"time":1.3047968596645072,"velocity":2.674359521054384,"position":2.4246517156880047,"holonomicRotation":-139.33464,"angularVelocity":0.5406775107771443,"angularAcceleration":5.093261463651754,"curveRadius":4.801713034566295},{"acceleration":-3.0021670002264864,"curvature":0.21494218155984782,"pose":{"rotation":{"radians":3.137398539495535},"translation":{"x":2.762627604293726,"y":1.869783832650151}},"time":1.3078517431190508,"velocity":2.6651882507576152,"position":2.4327935551784883,"holonomicRotation":-139.32488,"angularVelocity":0.5564068422188357,"angularAcceleration":5.1489137558739415,"curveRadius":4.652413931704528},{"acceleration":-3.0021028417502773,"curvature":0.22172260420832154,"pose":{"rotation":{"radians":3.139144336955131},"translation":{"x":2.7545251252842493,"y":1.869803670123929}},"time":1.310902349944617,"velocity":2.65603001533752,"position":2.4408960584721857,"holonomicRotation":-139.31512,"angularVelocity":0.5722787495801769,"angularAcceleration":5.202868894255189,"curveRadius":4.5101400624919625},{"acceleration":-3.0020371471406992,"curvature":0.2285991312025079,"pose":{"rotation":{"radians":3.140936538264216},"translation":{"x":2.7464614746304776,"y":1.8698089608094621}},"time":1.3139488193659774,"velocity":2.646884400966968,"position":2.4489597108616072,"holonomicRotation":-139.30536,"angularVelocity":0.5882879691878563,"angularAcceleration":5.2550074835580896,"curveRadius":4.37446981858446},{"acceleration":-3.001969890353399,"curvature":0.23557048189389912,"pose":{"rotation":{"radians":-3.140409809710005},"translation":{"x":2.738436191816895,"y":1.8697994681483754}},"time":1.3169912932273142,"velocity":2.6377509860430477,"position":2.4569849992893587,"holonomicRotation":-139.2956,"angularVelocity":-2064.5522802336504,"angularAcceleration":-678770.1923905573,"curveRadius":4.245014027056241},{"acceleration":-3.0019010458530615,"curvature":0.24263523772063159,"pose":{"rotation":{"radians":-3.1385237495220673},"translation":{"x":2.730448816327987,"y":1.8697749555822925}},"time":1.3200299160478273,"velocity":2.6286293410201966,"position":2.4649724123916528,"holonomicRotation":-139.28584,"angularVelocity":0.6206957228140402,"angularAcceleration":679641.1064956668,"curveRadius":4.12141290520791},{"acceleration":-3.0018305873940223,"curvature":0.2497918373765234,"pose":{"rotation":{"radians":-3.136590256797348},"translation":{"x":2.7224988876482374,"y":1.8697351865528378}},"time":1.3230648350785628,"velocity":2.6195190282434706,"position":2.4729224405418426,"holonomicRotation":-139.27608,"angularVelocity":0.637082144577301,"angularAcceleration":5.399294543712958,"curveRadius":4.003333377514059},{"acceleration":-3.0017584892735667,"curvature":0.25703857345225034,"pose":{"rotation":{"radians":-3.1346090120942387},"translation":{"x":2.7145859452621313,"y":1.8696799245016356}},"time":1.3260962003604848,"velocity":2.610419601774372,"position":2.4808355758939102,"holonomicRotation":-139.26632,"angularVelocity":0.653581643533538,"angularAcceleration":5.4429266755260395,"curveRadius":3.8904666586385663},{"acceleration":-3.0016847251566685,"curvature":0.26437358835111063,"pose":{"rotation":{"radians":-3.1325797086737883},"translation":{"x":2.706709528654154,"y":1.86960893287031}},"time":1.3291241647838161,"velocity":2.6013306072165405,"position":2.4887123124258848,"holonomicRotation":-139.25656,"angularVelocity":0.6701873393273816,"angularAcceleration":5.484111922152098,"curveRadius":3.7825261072294216},{"acceleration":-3.0016092692394025,"curvature":0.271794870199996,"pose":{"rotation":{"radians":-3.1305020530981666},"translation":{"x":2.6988691773087887,"y":1.8695219751004857}},"time":1.3321488841486742,"velocity":2.5922515815341347,"position":2.496553145983135,"holonomicRotation":-139.2468,"angularVelocity":0.6868920137717249,"angularAcceleration":5.522718781260327,"curveRadius":3.679245304608456},{"acceleration":-3.0015320952385056,"curvature":0.2793002499740369,"pose":{"rotation":{"radians":-3.128375765836982},"translation":{"x":2.691064430710522,"y":1.8694188146337867}},"time":1.3351705172270223,"velocity":2.5831820528694385,"position":2.5043585743214805,"holonomicRotation":-139.23704,"angularVelocity":0.7036881070772137,"angularAcceleration":5.558614454495887,"curveRadius":3.580376315785459},{"acceleration":-3.001453177446819,"curvature":0.2868873971366916,"pose":{"rotation":{"radians":-3.1262005818811183},"translation":{"x":2.6832948283438376,"y":1.8692992149118375}},"time":1.3381892258259716,"velocity":2.574121540353336,"position":2.5121290971500856,"holonomicRotation":-139.22728,"angularVelocity":0.7205677144924887,"angularAcceleration":5.591665065369453,"curveRadius":3.48568814796537},{"acceleration":-3.0013724895610414,"curvature":0.29455381696665645,"pose":{"rotation":{"radians":-3.1239762513628997},"translation":{"x":2.6755599096932197,"y":1.869162939376262}},"time":1.341205174852452,"velocity":2.565069553915339,"position":2.5198652161740713,"holonomicRotation":-139.21752,"angularVelocity":0.7375225836672329,"angularAcceleration":5.621735986211243,"curveRadius":3.394965342150702},{"acceleration":-3.001290006095139,"curvature":0.302296847054748,"pose":{"rotation":{"radians":-3.1217025401824317},"translation":{"x":2.6678592142431548,"y":1.869009751468685}},"time":1.344218532379287,"velocity":2.556025594085258,"position":2.527567435136791,"holonomicRotation":-139.20776,"angularVelocity":0.7545441124127757,"angularAcceleration":5.648692063241895,"curveRadius":3.3080067150647228},{"acceleration":-3.0012057010016924,"curvature":0.31011365450778705,"pose":{"rotation":{"radians":-3.1193792306385997},"translation":{"x":2.6601922814781265,"y":1.8688394146307303}},"time":1.3472294697127005,"velocity":2.5469891517948584,"position":2.5352362598617293,"holonomicRotation":-139.198,"angularVelocity":0.7716233473374986,"angularAcceleration":5.672398005494211,"curveRadius":3.224624215877246},{"acceleration":-3.001119548781547,"curvature":0.31800123332059615,"pose":{"rotation":{"radians":-3.117006122064507},"translation":{"x":2.6525586508826193,"y":1.8686516923040226}},"time":1.350238161461285,"velocity":2.5379597081719236,"position":2.542872198293946,"holonomicRotation":-139.18824,"angularVelocity":0.7887509829510567,"angularAcceleration":5.692718644778404,"curveRadius":3.14464189197606},{"acceleration":-3.0010315240025482,"curvature":0.32595640172376167,"pose":{"rotation":{"radians":-3.11458303146587},"translation":{"x":2.6449578619411187,"y":1.8684463479301858}},"time":1.3532447856064647,"velocity":2.5289367343314124,"position":2.5504757605410187,"holonomicRotation":-139.17848,"angularVelocity":0.8059173616767895,"angularAcceleration":5.709519346891075,"curveRadius":3.0678949537781133},{"acceleration":-3.0009416014957417,"curvature":0.33397580015424605,"pose":{"rotation":{"radians":-3.1121097941619773},"translation":{"x":2.637389454138108,"y":1.8682231449508444}},"time":1.3562495235744882,"velocity":2.5199196911615767,"position":2.558047458913422,"holonomicRotation":-139.16872,"angularVelocity":0.8231124744363374,"angularAcceleration":5.722666316510202,"curveRadius":2.994228921790597},{"acceleration":-3.0008497561054694,"curvature":0.3420558892458048,"pose":{"rotation":{"radians":-3.10958626442739},"translation":{"x":2.6298529669580746,"y":1.8679818468076228}},"time":1.3592525603099832,"velocity":2.510908029106291,"position":2.5655878079642775,"holonomicRotation":-139.15896,"angularVelocity":0.8403259623034329,"angularAcceleration":5.732027072342299,"curveRadius":2.923498853374192},{"acceleration":-3.0007559631757186,"curvature":0.3501929484238671,"pose":{"rotation":{"radians":-3.1070123161339307},"translation":{"x":2.6223479398855005,"y":1.867722216942145}},"time":1.3622540843511148,"velocity":2.50190118794125,"position":2.573097324528419,"holonomicRotation":-139.1492,"angularVelocity":0.8575471187926326,"angularAcceleration":5.737470782578486,"curveRadius":2.855568635807076},{"acceleration":-3.000660198099127,"curvature":0.3583830744742706,"pose":{"rotation":{"radians":-3.104387843391576},"translation":{"x":2.614873912404872,"y":1.8674440187960353}},"time":1.3652542879063805,"velocity":2.4928985965467687,"position":2.5805765277606953,"holonomicRotation":-139.13944,"angularVelocity":0.8747648931181198,"angularAcceleration":5.738868716180394,"curveRadius":2.790310344502034},{"acceleration":-3.000562436975735,"curvature":0.36662218084743387,"pose":{"rotation":{"radians":-3.1017127611868696},"translation":{"x":2.607430424000673,"y":1.8671470158109182}},"time":1.3682533669330887,"velocity":2.483899672673706,"position":2.5880259391734586,"holonomicRotation":-139.12968,"angularVelocity":0.8919678944381485,"angularAcceleration":5.736094703349795,"curveRadius":2.7276036536811175},{"acceleration":-3.000462655758294,"curvature":0.3749059972117328,"pose":{"rotation":{"radians":-3.098987006017488},"translation":{"x":2.6000170141573893,"y":1.8668309714284181}},"time":1.3712515212175607,"velocity":2.4749038227069464,"position":2.5954460826731633,"holonomicRotation":-139.11992,"angularVelocity":0.9091443971041873,"angularAcceleration":5.7290256058534155,"curveRadius":2.6673352985474854},{"acceleration":-3.0003608311831043,"curvature":0.38323006899201156,"pose":{"rotation":{"radians":-3.0962105365220727},"translation":{"x":2.5926332223595048,"y":1.8664956490901587}},"time":1.3742489544571013,"velocity":2.4659104414209425,"position":2.6028374845960087,"holonomicRotation":-139.11016,"angularVelocity":0.9262823467724187,"angularAcceleration":5.717541742767247,"curveRadius":2.6093985856335427},{"acceleration":-3.00025694021356,"curvature":0.39158975816986114,"pose":{"rotation":{"radians":-3.0933833341036694},"translation":{"x":2.5852785880915046,"y":1.866140812237765}},"time":1.3772458743437896,"velocity":2.4569189117316417,"position":2.610200673742558,"holonomicRotation":-139.1004,"angularVelocity":0.9433693676501208,"angularAcceleration":5.7015274093907795,"curveRadius":2.553692937919553},{"acceleration":-3.0001509603686767,"curvature":0.39998024395752385,"pose":{"rotation":{"radians":-3.0905054035445354},"translation":{"x":2.5779526508378727,"y":1.8657662243128605}},"time":1.3802424926501382,"velocity":2.4479286044419917,"position":2.617536181411263,"holonomicRotation":-139.09064,"angularVelocity":0.9603927710902903,"angularAcceleration":5.680871469050339,"curveRadius":2.5001234813642337},{"acceleration":-3.0000428694259895,"curvature":0.4083965239943242,"pose":{"rotation":{"radians":-3.087576773612521},"translation":{"x":2.570654950083095,"y":1.8653716487570702}},"time":1.3832390253166744,"velocity":2.4389388779827477,"position":2.6248445414308237,"holonomicRotation":-139.08088,"angularVelocity":0.9773395647308822,"angularAcceleration":5.6554676776413295,"curveRadius":2.4486006644216634},{"acceleration":-2.999932646031347,"curvature":0.4168334161448957,"pose":{"rotation":{"radians":-3.084597497655478},"translation":{"x":2.5633850253116552,"y":1.8649568490120183}},"time":1.3862356925415062,"velocity":2.4299490781456825,"position":2.632126290191313,"holonomicRotation":-139.07112,"angularVelocity":0.994196463442828,"angularAcceleration":5.625215430082243,"curveRadius":2.3990399072333237},{"acceleration":-2.9998202690404736,"curvature":0.42528556101623427,"pose":{"rotation":{"radians":-3.0815676541833636},"translation":{"x":2.5561424160080386,"y":1.8645215885193285}},"time":1.3892327188719267,"velocity":2.4209585378128393,"position":2.6393819666739944,"holonomicRotation":-139.06136,"angularVelocity":1.0109499010272345,"angularAcceleration":5.59002015242766,"curveRadius":2.351361277374351},{"acceleration":-2.999705718119788,"curvature":0.4337474244521028,"pose":{"rotation":{"radians":-3.078487347436446},"translation":{"x":2.54892666165673,"y":1.8640656307206258}},"time":1.392230333298128,"velocity":2.4119665766778446,"position":2.6466121124797595,"holonomicRotation":-139.0516,"angularVelocity":1.027586043086014,"angularAcceleration":5.549793833845738,"curveRadius":2.305489194000797},{"acceleration":-2.9995889733238674,"curvature":0.44221330117407964,"pose":{"rotation":{"radians":-3.075356707936175},"translation":{"x":2.5417373017422142,"y":1.8635887390575339}},"time":1.3952287693490928,"velocity":2.402972500962154,"position":2.6538172718561213,"holonomicRotation":-139.04184,"angularVelocity":1.044090801690879,"angularAcceleration":5.504455764382472,"curveRadius":2.261352151427812},{"acceleration":-2.999470015643599,"curvature":0.4506773189409981,"pose":{"rotation":{"radians":-3.0721758930198058},"translation":{"x":2.534573875748975,"y":1.8630906769716775}},"time":1.3982282651907338,"velocity":2.393975603123104,"position":2.660997991722679,"holonomicRotation":-139.03208,"angularVelocity":1.0604498503419166,"angularAcceleration":5.45393276561019,"curveRadius":2.2188824641759224},{"acceleration":-2.9993488262916443,"curvature":0.45913344251966415,"pose":{"rotation":{"radians":-3.068945087353778},"translation":{"x":2.527435923161499,"y":1.8625712079046806}},"time":1.4012290637263638,"velocity":2.3849751615573247,"position":2.668154821694994,"holonomicRotation":-139.02232,"angularVelocity":1.0766486412423275,"angularAcceleration":5.398160092413626,"curveRadius":2.178016034972602},{"acceleration":-2.999225387738794,"curvature":0.46757547947924166,"pose":{"rotation":{"radians":-3.065664503427113},"translation":{"x":2.520322983464269,"y":1.8620300952981679}},"time":1.4042314126995807,"velocity":2.375970440294001,"position":2.6752883141068047,"holonomicRotation":-139.01256,"angularVelocity":1.0926724228029727,"angularAcceleration":5.337081632944269,"curveRadius":2.138692133971058},{"acceleration":-2.9990996826130347,"curvature":0.47599708548906944,"pose":{"rotation":{"radians":-3.06233438202},"translation":{"x":2.5132345961417704,"y":1.861467102593763}},"time":1.4072355647996524,"velocity":2.3669606886841548,"position":2.6823990240305022,"holonomicRotation":-139.0028,"angularVelocity":1.1085062593979287,"angularAcceleration":5.27065077516491,"curveRadius":2.100853199494986},{"acceleration":-2.9989716947203364,"curvature":0.4843917711562676,"pose":{"rotation":{"radians":-3.0589549926487254},"translation":{"x":2.506170300678489,"y":1.860881993233091}},"time":1.4102417777695027,"velocity":2.3579451410792727,"position":2.68948750929581,"holonomicRotation":-138.99304,"angularVelocity":1.1241350513642754,"angularAcceleration":5.19883059619863,"curveRadius":2.064444649034705},{"acceleration":-2.9988414083831865,"curvature":0.4927529087404581,"pose":{"rotation":{"radians":-3.055526633982012},"translation":{"x":2.499129636558908,"y":1.8602745306577753}},"time":1.4132503145163986,"velocity":2.3489230165040387,"position":2.696554330506592,"holonomicRotation":-138.98328,"angularVelocity":1.1395435572626516,"angularAcceleration":5.12159471353438,"curveRadius":2.029414707172674},{"acceleration":-2.9987088086353357,"curvature":0.5010737398921762,"pose":{"rotation":{"radians":-3.0520496342297303},"translation":{"x":2.4921121432675126,"y":1.859644478309441}},"time":1.4162614432254466,"velocity":2.339893518320282,"position":2.7036000510557217,"holonomicRotation":-138.97352,"angularVelocity":1.1547164164168922,"angularAcceleration":5.038927465521013,"curveRadius":1.9957142440056537},{"acceleration":-2.998573881772681,"curvature":0.5093473841076127,"pose":{"rotation":{"radians":-3.0485243514994633},"translation":{"x":2.485117360288788,"y":1.8589915996297117}},"time":1.4192754374760175,"velocity":2.330855833880707,"position":2.710625237137948,"holonomicRotation":-138.96376,"angularVelocity":1.1696381735297636,"angularAcceleration":4.950824677268366,"curveRadius":1.963296624664169},{"acceleration":-2.9984366142433303,"curvature":0.5175668476514449,"pose":{"rotation":{"radians":-3.0449511741217847},"translation":{"x":2.4781448271072186,"y":1.8583156580602123}},"time":1.4222925763612244,"velocity":2.321809134177045,"position":2.717630457760702,"holonomicRotation":-138.954,"angularVelocity":1.1842933035658112,"angularAcceleration":4.857293811664361,"curveRadius":1.9321175700060476},{"acceleration":-2.9982969938287622,"curvature":0.5257250329073742,"pose":{"rotation":{"radians":-3.041330520939434},"translation":{"x":2.4711940832072896,"y":1.8576164170425669}},"time":1.4253131446105873,"velocity":2.3127525734753256,"position":2.724616284752774,"holonomicRotation":-138.94424,"angularVelocity":1.198666238749697,"angularAcceleration":4.758354719154969,"curveRadius":1.902135027639414},{"acceleration":-2.9981550090757088,"curvature":0.5338147489659559,"pose":{"rotation":{"radians":-3.037662841561172},"translation":{"x":2.464264668073485,"y":1.8568936400183995}},"time":1.4283374327160274,"velocity":2.3036852889431123,"position":2.731583292770802,"holonomicRotation":-138.93448,"angularVelocity":1.2127413957898918,"angularAcceleration":4.654039744056304,"curveRadius":1.8733090495103109},{"acceleration":-2.9980106491686147,"curvature":0.5418287221428607,"pose":{"rotation":{"radians":-3.0339486165769984},"translation":{"x":2.4573561211902897,"y":1.8561470904293347}},"time":1.431365737061344,"velocity":2.2946064002669297,"position":2.7385320593035214,"holonomicRotation":-138.92472,"angularVelocity":1.2265032046457924,"angularAcceleration":4.544394250592457,"curveRadius":1.845601680260014},{"acceleration":-2.9978639042651523,"curvature":0.549759607666675,"pose":{"rotation":{"radians":-3.0301883577332065},"translation":{"x":2.450467982042189,"y":1.8553765317169963}},"time":1.4343983600553387,"velocity":2.2855150092579883,"position":2.7454631646737173,"holonomicRotation":-138.91496,"angularVelocity":1.2399361382005134,"angularAcceleration":4.429476918601832,"curveRadius":1.818976851071806},{"acceleration":-2.9977147654716916,"curvature":0.5576000016272051,"pose":{"rotation":{"radians":-3.0263826080662453},"translation":{"x":2.443599790113667,"y":1.8545817273230092}},"time":1.4374356102687644,"velocity":2.27641019944677,"position":2.7523771920378315,"holonomicRotation":-138.9052,"angularVelocity":1.2530247426236019,"angularAcceleration":4.309359948427109,"curveRadius":1.7934002817104913},{"acceleration":-2.9975632245374517,"curvature":0.5653424534857233,"pose":{"rotation":{"radians":-3.022531941992498},"translation":{"x":2.436751084889209,"y":1.8537624406889974}},"time":1.4404778025752802,"velocity":2.2672910356667875,"position":2.7592747273831693,"holonomicRotation":-138.89544,"angularVelocity":1.2657536689905384,"angularAcceleration":4.184129431815854,"curveRadius":1.7688393890009768},{"acceleration":-2.997409274132034,"curvature":0.5729794793201083,"pose":{"rotation":{"radians":-3.0186369653539704},"translation":{"x":2.429921405853299,"y":1.8529184352565853}},"time":1.4435252582966227,"velocity":2.258156563625129,"position":2.7661563595226757,"holonomicRotation":-138.88568,"angularVelocity":1.2781077051422614,"angularAcceleration":4.053885365816155,"curveRadius":1.7452632006762092},{"acceleration":-2.997252907927479,"curvature":0.5805035755585541,"pose":{"rotation":{"radians":-3.0146983154169193},"translation":{"x":2.423110292490423,"y":1.852049474467397}},"time":1.4465783053521992,"velocity":2.2490058094597627,"position":2.7730226800872213,"holonomicRotation":-138.87592,"angularVelocity":1.2900718087056517,"angularAcceleration":3.918741947176168,"curveRadius":1.7226422749210648},{"acceleration":-2.997094120091743,"curvature":0.5879072330033758,"pose":{"rotation":{"radians":-3.0107166608231504},"translation":{"x":2.416317284285064,"y":1.851155321763057}},"time":1.4496372784133404,"velocity":2.2398377792846973,"position":2.7798742835153796,"holonomicRotation":-138.86616,"angularVelocity":1.3016311403159357,"angularAcceleration":3.7788275278146806,"curveRadius":1.7009486256724757},{"acceleration":-2.9969329058035172,"curvature":0.5951829514305141,"pose":{"rotation":{"radians":-3.0066927014917337},"translation":{"x":2.4095419207217086,"y":1.8502357405851892}},"time":1.4527025190624536,"velocity":2.2306514587191635,"position":2.786711767040649,"holonomicRotation":-138.8564,"angularVelocity":1.3127710976235532,"angularAcceleration":3.634284737428488,"curveRadius":1.6801556523023948},{"acceleration":-2.9967692607145198,"curvature":0.6023232546693427,"pose":{"rotation":{"radians":-3.0026271684709935},"translation":{"x":2.40278374128484,"y":1.849290494375418}},"time":1.455774375957343,"velocity":2.2214458124032452,"position":2.793535730676103,"holonomicRotation":-138.84664,"angularVelocity":1.323477349320561,"angularAcceleration":3.485270331056082,"curveRadius":1.6602380735722546},{"acceleration":-2.99660318162421,"curvature":0.6093207060705385,"pose":{"rotation":{"radians":-2.9985208237386947},"translation":{"x":2.396042285458944,"y":1.8483193465753682}},"time":1.4588532050009764,"velocity":2.2122197834954163,"position":2.800346777196429,"holonomicRotation":-138.83688,"angularVelocity":1.333735869742488,"angularAcceleration":3.331955193530506,"curveRadius":1.64117186571407},{"acceleration":-2.996434665556561,"curvature":0.6161679239844726,"pose":{"rotation":{"radians":-2.9943744599498734},"translation":{"x":2.3893170927285046,"y":1.8473220606266638}},"time":1.4619393695170029,"velocity":2.202972293155984,"position":2.8071455121173567,"holonomicRotation":-138.82712,"angularVelocity":1.3435329734656525,"angularAcceleration":3.174524129315868,"curveRadius":1.6229342052300664},{"acceleration":-2.9962637104725407,"curvature":0.6228575979235315,"pose":{"rotation":{"radians":-2.9901889001319897},"translation":{"x":2.382607702578007,"y":1.8462983999709288}},"time":1.4650332404313393,"velocity":2.193702240010471,"position":2.81393254367244,"holonomicRotation":-138.81736,"angularVelocity":1.352855349746036,"angularAcceleration":3.013175577941977,"curveRadius":1.6055034141572284},{"acceleration":-2.9960903147634945,"curvature":0.6293825046275511,"pose":{"rotation":{"radians":-2.985964997326112},"translation":{"x":2.3759136544919355,"y":1.8452481280497877}},"time":1.468135196460176,"velocity":2.184408499595651,"position":2.820708482787203,"holonomicRotation":-138.8076,"angularVelocity":1.3616900970261787,"angularAcceleration":2.8481213782568173,"curveRadius":1.5888589095621093},{"acceleration":-2.9959144772836224,"curvature":0.6357355245563847,"pose":{"rotation":{"radians":-2.9817036341735057},"translation":{"x":2.3692344879547753,"y":1.8441710083048646}},"time":1.4712456243047654,"velocity":2.1750899237855,"position":2.827473943050631,"holonomicRotation":-138.79784,"angularVelocity":1.3700247572111754,"angularAcceleration":2.6795864110769467,"curveRadius":1.5729811554856847},{"acceleration":-2.9957361974073353,"curvature":0.6419096583239227,"pose":{"rotation":{"radians":-2.9774057224481894},"translation":{"x":2.362569742451011,"y":1.8430668041777842}},"time":1.4743649188533918,"velocity":2.1657453401958042,"position":2.834229540684017,"holonomicRotation":-138.78808,"angularVelocity":1.3778473492376222,"angularAcceleration":2.5078080650932097,"curveRadius":1.557851618265224},{"acceleration":-2.995555475049765,"curvature":0.6478980431663827,"pose":{"rotation":{"radians":-2.97307220253403},"translation":{"x":2.3559189574651276,"y":1.8419352791101704}},"time":1.4774934833909446,"velocity":2.1563735515662916,"position":2.8409758945071637,"holonomicRotation":-138.77832,"angularVelocity":1.3851464024932774,"angularAcceleration":2.333035859750793,"curveRadius":1.5434527246182719},{"acceleration":-2.9953723098340004,"curvature":0.6536939693916819,"pose":{"rotation":{"radians":-2.968704042847944},"translation":{"x":2.349281672481609,"y":1.8407761965436478}},"time":1.4806317298165421,"velocity":2.146973335121621,"position":2.8477136259019624,"holonomicRotation":-138.76856,"angularVelocity":1.3919109890340422,"angularAcceleration":2.1555307083562636,"curveRadius":1.529767822289359},{"acceleration":-2.942612981232134,"curvature":0.6592908968951109,"pose":{"rotation":{"radians":-2.964302239207405},"translation":{"x":2.3426574269849407,"y":1.8395893199198403}},"time":1.483779834035557,"velocity":2.1377096827804762,"position":2.8544433587733526,"holonomicRotation":-138.7588,"angularVelocity":1.3982394909138385,"angularAcceleration":2.010258059936967,"curveRadius":1.5167811427541882},{"acceleration":-2.8155336355129243,"curvature":0.6646824715113233,"pose":{"rotation":{"radians":-2.9598678141447516},"translation":{"x":2.3360457604596077,"y":1.8383744126803723}},"time":1.4869376230715916,"velocity":2.128818821535667,"position":2.861165719507702,"holonomicRotation":-138.74904,"angularVelocity":1.4042816071785165,"angularAcceleration":1.913400862353178,"curveRadius":1.5044777662426507},{"acceleration":-2.667891518963659,"curvature":0.669862540775336,"pose":{"rotation":{"radians":-2.9554018161672473},"translation":{"x":2.3294462123900934,"y":1.8371312382668683}},"time":1.4901048157251686,"velocity":2.120369095116265,"position":2.867881336928626,"holonomicRotation":-138.73928,"angularVelocity":1.4100809347547834,"angularAcceleration":1.8310624614884596,"curveRadius":1.4928435897349097},{"acceleration":-2.5227460645960087,"curvature":0.6748251699728826,"pose":{"rotation":{"radians":-2.9509053189640255},"translation":{"x":2.3228583222608843,"y":1.8358595601209526}},"time":1.4932811293405426,"velocity":2.1123560624431574,"position":2.874590842250282,"holonomicRotation":-138.72952,"angularVelocity":1.4156338912687532,"angularAcceleration":1.7482393700333765,"curveRadius":1.4818652956293619},{"acceleration":-2.3799728367335495,"curvature":0.6795646573936258,"pose":{"rotation":{"radians":-2.9463794205617715},"translation":{"x":2.316281629556464,"y":1.8345591416842493}},"time":1.4964662798744384,"velocity":2.104775490691578,"position":2.881294869028189,"holonomicRotation":-138.71976,"angularVelocity":1.42093704962772,"angularAcceleration":1.6649631791438584,"curveRadius":1.4715303233033905},{"acceleration":-2.2394520161872338,"curvature":0.6840755494612331,"pose":{"rotation":{"radians":-2.941825242428922},"translation":{"x":2.3097156737613176,"y":1.8332297463983827}},"time":1.4996599819685206,"velocity":2.0976233480978843,"position":2.887994053107605,"holonomicRotation":-138.71,"angularVelocity":1.4259871455412907,"angularAcceleration":1.5812670577284749,"curveRadius":1.4618268417685503},{"acceleration":-2.1010681183349487,"curvature":0.6883526549757281,"pose":{"rotation":{"radians":-2.93724392853054},"translation":{"x":2.3031599943599295,"y":1.8318711377049768}},"time":1.5028619490253645,"velocity":2.0908957971987907,"position":2.894689032569529,"holonomicRotation":-138.70024,"angularVelocity":1.4307810845804023,"angularAcceleration":1.497185621839853,"curveRadius":1.4527437248502526},{"acceleration":-1.964709798328954,"curvature":0.6923910594044593,"pose":{"rotation":{"radians":-2.9326366443353398},"translation":{"x":2.2966141308367845,"y":1.8304830790456563}},"time":1.506071893288028,"velocity":2.084589188253846,"position":2.9013804476743745,"holonomicRotation":-138.69048,"angularVelocity":1.4353159488749045,"angularAcceleration":1.412754840403204,"curveRadius":1.4442705266300258},{"acceleration":-1.8302696072557265,"curvature":0.6961861378899206,"pose":{"rotation":{"radians":-2.928004575776049},"translation":{"x":2.2900776226763675,"y":1.8290653338620455}},"time":1.5092895259230241,"velocity":2.0787000530346984,"position":2.9080689408033873,"holonomicRotation":-138.68072,"angularVelocity":1.4395890037012071,"angularAcceleration":1.328012023444571,"curveRadius":1.4363974597812486},{"acceleration":-1.6976437302799032,"curvature":0.6997335680452212,"pose":{"rotation":{"radians":-2.9233489281658365},"translation":{"x":2.283550009363164,"y":1.8276176655957688}},"time":1.5125145571063205,"velocity":2.073225099066418,"position":2.9147551563978693,"holonomicRotation":-138.67096,"angularVelocity":1.443597703589934,"angularAcceleration":1.2429956986119197,"curveRadius":1.4291153742896805},{"acceleration":-1.5667318649138866,"curvature":0.7030293418852781,"pose":{"rotation":{"radians":-2.9186709250720577},"translation":{"x":2.2770308303816575,"y":1.82613983768845}},"time":1.5157466961126222,"velocity":2.068161203893414,"position":2.921439740896293,"holonomicRotation":-138.6612,"angularVelocity":1.44733969815594,"angularAcceleration":1.1577455544796937,"curveRadius":1.42241573775335},{"acceleration":-1.437436961778274,"curvature":0.7060697767894712,"pose":{"rotation":{"radians":-2.913971807150271},"translation":{"x":2.270519625216333,"y":1.8246316135817136}},"time":1.5189856514074436,"velocity":2.0635054098350905,"position":2.928123342669371,"holonomicRotation":-138.65144,"angularVelocity":1.450812837491107,"angularAcceleration":1.0723023379544343,"curveRadius":1.416290617263129},{"acceleration":-1.3096650238776688,"curvature":0.7088515256894204,"pose":{"rotation":{"radians":-2.909252830940108},"translation":{"x":2.2640159333516765,"y":1.823092756717184}},"time":1.5222311307417082,"velocity":2.0592549190652862,"position":2.93480661195318,"holonomicRotation":-138.64168,"angularVelocity":1.4540151774630103,"angularAcceleration":0.9867078610220157,"curveRadius":1.4107326622841252},{"acceleration":-1.1833250126241521,"curvature":0.7113715866063445,"pose":{"rotation":{"radians":-2.9045152676267265},"translation":{"x":2.257519294272171,"y":1.8215230305364851}},"time":1.5254828412490975,"velocity":2.0554070886880798,"position":2.9414902007804296,"holonomicRotation":-138.63192,"angularVelocity":1.456944984067776,"angularAcceleration":0.9010047475345198,"curveRadius":1.4057350881423036},{"acceleration":-1.0583286464881692,"curvature":0.7136273108099879,"pose":{"rotation":{"radians":-2.899760401769416},"translation":{"x":2.251029247462302,"y":1.819922198481242}},"time":1.528740489545768,"velocity":2.05195942617553,"position":2.948174762909947,"holonomicRotation":-138.62216,"angularVelocity":1.4596007377992002,"angularAcceleration":0.8152364802973479,"curveRadius":1.40129166142054},{"acceleration":-0.9345901715415995,"curvature":0.7156164100628538,"pose":{"rotation":{"radians":-2.8949895300007875},"translation":{"x":2.2445453324065543,"y":1.8182900239930782}},"time":1.532003781831874,"velocity":2.048909585278068,"position":2.9548609537545136,"holonomicRotation":-138.6124,"angularVelocity":1.4619811375589382,"angularAcceleration":0.7294473038388157,"curveRadius":1.3973966861829905},{"acceleration":-0.8120263470543042,"curvature":0.717336963335472,"pose":{"rotation":{"radians":-2.890203959699852},"translation":{"x":2.2380670885894127,"y":1.816626270513618}},"time":1.53527242399537,"velocity":2.0462553617222166,"position":2.9615494303071186,"holonomicRotation":-138.60264,"angularVelocity":1.4640851037107678,"angularAcceleration":0.6436820081826625,"curveRadius":1.3940449901678034},{"acceleration":-0.6905562212216043,"curvature":0.718787421564959,"pose":{"rotation":{"radians":-2.8854050076414617},"translation":{"x":2.2315940554953615,"y":1.8149307014844862}},"time":1.5385461217174663,"velocity":2.043994689393824,"position":2.9682408510657643,"holonomicRotation":-138.59288,"angularVelocity":1.4659117810416795,"angularAcceleration":0.5579859492164483,"curveRadius":1.3912319136341855},{"acceleration":-0.5701010021948096,"curvature":0.7199666122155406,"pose":{"rotation":{"radians":-2.880593998625254},"translation":{"x":2.225125772608886,"y":1.8132030803473067}},"time":1.541824580579543,"velocity":2.0421256367108995,"position":2.974935875956913,"holonomicRotation":-138.58312,"angularVelocity":1.4674605412496977,"angularAcceleration":0.4724049540268338,"curveRadius":1.388953297324049},{"acceleration":-0.4505839559309514,"curvature":0.7208737419301438,"pose":{"rotation":{"radians":-2.875772264088596},"translation":{"x":2.2186617794144707,"y":1.811443170543704}},"time":1.5451075061714428,"velocity":2.0406464031106744,"position":2.9816351662577034,"holonomicRotation":-138.57336,"angularVelocity":1.4687309845081238,"angularAcceleration":0.3869850908472386,"curveRadius":1.387205472795408},{"acceleration":-0.33193025007016114,"curvature":0.7215083986705894,"pose":{"rotation":{"radians":-2.8709411407052006},"translation":{"x":2.2122016153966,"y":1.8096507355153024}},"time":1.5483946042007388,"velocity":2.039555315839805,"position":2.9883393845170407,"holonomicRotation":-138.5636,"angularVelocity":1.4697229411286874,"angularAcceleration":0.30177275265990416,"curveRadius":1.385985252344316},{"acceleration":-0.2140668837163275,"curvature":0.7218705522927892,"pose":{"rotation":{"radians":-2.8661019689740104},"translation":{"x":2.2057448200397594,"y":1.8078255387037259}},"time":1.551685580602995,"velocity":2.03885082677699,"position":2.9950491944756843,"holonomicRotation":-138.55384,"angularVelocity":1.4704364722495837,"angularAcceleration":0.21681441422890999,"curveRadius":1.3852899205041989},{"acceleration":-0.09692258673540362,"curvature":0.7219605544338441,"pose":{"rotation":{"radians":-2.861256091801925},"translation":{"x":2.1992909328284327,"y":1.8059673435505992}},"time":1.554980141652852,"velocity":2.03853150939788,"position":3.0017652609854526,"holonomicRotation":-138.54408,"angularVelocity":1.4708718699553684,"angularAcceleration":0.13215651469066592,"curveRadius":1.3851172253921715},{"acceleration":0.01957237793389356,"curvature":0.7217791363562804,"pose":{"rotation":{"radians":-2.856404853082332},"translation":{"x":2.192839493247106,"y":1.804075913497546}},"time":1.5582779940752216,"velocity":2.038596056211861,"position":3.008488249927664,"holonomicRotation":-138.53432,"angularVelocity":1.471029657569543,"angularAcceleration":0.04784556552749879,"curveRadius":1.3854653724797967},{"acceleration":0.1354862196874811,"curvature":0.7213274069887556,"pose":{"rotation":{"radians":-2.851549596275759},"translation":{"x":2.1863900407802626,"y":1.802151011986191}},"time":1.5615788451568775,"velocity":2.039043276046666,"position":3.015218828130946,"holonomicRotation":-138.52456,"angularVelocity":1.470910588349618,"angularAcceleration":-0.03607227862735064,"curveRadius":1.38633301647942},{"acceleration":0.2508857340181583,"curvature":0.7206068484201925,"pose":{"rotation":{"radians":-2.8466916629924457},"translation":{"x":2.179942114912388,"y":1.8001924024581586}},"time":1.5648824028581179,"velocity":2.039872091545413,"position":3.021957663288516,"holonomicRotation":-138.5148,"angularVelocity":1.4705156448422936,"angularAcceleration":-0.11955096385215579,"curveRadius":1.38771925661313},{"acceleration":0.36583645462166686,"curvature":0.7196193114315697,"pose":{"rotation":{"radians":-2.8418323915841333},"translation":{"x":2.1734952551279667,"y":1.7981998483550725}},"time":1.5681883759239736,"velocity":2.0410815370109003,"position":3.0287054238750897,"holonomicRotation":-138.50504,"angularVelocity":1.4698460367082782,"angularAcceleration":-0.20254494536907655,"curveRadius":1.389623630320116},{"acceleration":0.4804026316001696,"curvature":0.7183670093147188,"pose":{"rotation":{"radians":-2.8369731157459004},"translation":{"x":2.1670490009114833,"y":1.7961731131185577}},"time":1.5714964739953206,"velocity":2.042670756029967,"position":3.035462779063509,"holonomicRotation":-138.49528,"angularVelocity":1.4689031985845535,"angularAcceleration":-0.2850091210690019,"curveRadius":1.3920461087904679},{"acceleration":0.5946474341890243,"curvature":0.7168525107275232,"pose":{"rotation":{"radians":-2.8321151631320585},"translation":{"x":2.1606028917474234,"y":1.7941119601902382}},"time":1.5748064077190582,"velocity":2.044638999626123,"position":3.042230398641241,"holonomicRotation":-138.48552,"angularVelocity":1.4676887875435123,"angularAcceleration":-0.3668988996160038,"curveRadius":1.3949870929308938},{"acceleration":0.7086329453426341,"curvature":0.7150787318565966,"pose":{"rotation":{"radians":-2.827259853990382},"translation":{"x":2.154156467120271,"y":1.7920161530117382}},"time":1.578117888857607,"velocity":2.0469856242587796,"position":3.0490089529268545,"holonomicRotation":-138.47576,"angularVelocity":1.4662046795785173,"angularAcceleration":-0.44817044183599075,"curveRadius":1.3984474092854744},{"acceleration":0.8224202948237053,"curvature":0.7130489270373735,"pose":{"rotation":{"radians":-2.8224084998166794},"translation":{"x":2.1477092665145103,"y":1.7898854550246819}},"time":1.5814306303972234,"velocity":2.0497100901324656,"position":3.055799112686607,"holonomicRotation":-138.466,"angularVelocity":1.4644529661268328,"angularAcceleration":-0.5287805978027846,"curveRadius":1.4024283076266186},{"acceleration":0.9360697103453625,"curvature":0.7107666791340569,"pose":{"rotation":{"radians":-2.8175624020335683},"translation":{"x":2.141260829414627,"y":1.7877196296706939}},"time":1.5847443466550641,"velocity":2.0528119595501093,"position":3.062601549051258,"holonomicRotation":-138.45624,"angularVelocity":1.462435949862794,"angularAcceleration":-0.6086870773158075,"curveRadius":1.4069314577581529},{"acceleration":1.0496405767500032,"curvature":0.7082358884296807,"pose":{"rotation":{"radians":-2.8127228506961917},"translation":{"x":2.134810695305106,"y":1.785518440391398}},"time":1.588058753384879,"velocity":2.056290895341576,"position":3.069416933433235,"holonomicRotation":-138.44648,"angularVelocity":1.4601561401147543,"angularAcceleration":-0.6878485152505925,"curveRadius":1.411958948052218},{"acceleration":1.16319152333627,"curvature":0.7054607612324971,"pose":{"rotation":{"radians":-2.8078911232283796},"translation":{"x":2.128358403670431,"y":1.783281650628419}},"time":1.5913735678810486,"velocity":2.060146659464953,"position":3.076245937444265,"holonomicRotation":-138.43672,"angularVelocity":1.4576162477252301,"angularAcceleration":-0.76622459340003,"curveRadius":1.4175132834502644},{"acceleration":1.2767805157509349,"curvature":0.7024457970801085,"pose":{"rotation":{"radians":-2.803068483190669},"translation":{"x":2.1219034939950876,"y":1.7810090238233809}},"time":1.5946885090806615,"velocity":2.0643791117994787,"position":3.0830892328135895,"holonomicRotation":-138.42696,"angularVelocity":1.4548191799823769,"angularAcceleration":-0.8437759750247896,"curveRadius":1.4235973852455948},{"acceleration":1.3904648858588788,"curvature":0.6991957760506639,"pose":{"rotation":{"radians":-2.7982561790850795},"translation":{"x":2.11544550576356,"y":1.7787003234179082}},"time":1.5980032976636482,"velocity":2.0689882089281677,"position":3.0899474913068787,"holonomicRotation":-138.4172,"angularVelocity":1.4517680344045893,"angularAcceleration":-0.9204646092506873,"curveRadius":1.430214589751097},{"acceleration":1.504301388204763,"curvature":0.6957157446665152,"pose":{"rotation":{"radians":-2.7934554431963687},"translation":{"x":2.1089839784603335,"y":1.776355312853625}},"time":1.6013176561508446,"velocity":2.0739740030014655,"position":3.0968213846459514,"holonomicRotation":-138.40744,"angularVelocity":1.4484660929879298,"angularAcceleration":-0.9962535523586648,"curveRadius":1.4373686490009516},{"acceleration":1.6183463186259874,"curvature":0.6920110017417362,"pose":{"rotation":{"radians":-2.788667490474734},"translation":{"x":2.1025184515698925,"y":1.7739737555721553}},"time":1.604631308999527,"velocity":2.079336640890335,"position":3.103711584429407,"holonomicRotation":-138.39768,"angularVelocity":1.44491681545298,"angularAcceleration":-1.0711072333244813,"curveRadius":1.445063730898902},{"acceleration":1.7326554993543932,"curvature":0.6880870835538808,"pose":{"rotation":{"radians":-2.7838935174603137},"translation":{"x":2.0960484645767217,"y":1.771555415015124}},"time":1.607943982696672,"velocity":2.08507636318926,"position":3.110618762054283,"holonomicRotation":-138.38792,"angularVelocity":1.441123832550963,"angularAcceleration":-1.1449914023484788,"curveRadius":1.4533044201834588},{"acceleration":1.8472844319187396,"curvature":0.6839497483384192,"pose":{"rotation":{"radians":-2.7791347012519463},"translation":{"x":2.089573556965306,"y":1.769100054624155}},"time":1.6112554058493012,"velocity":2.091193503626607,"position":3.11754358863882,"holonomicRotation":-138.37816,"angularVelocity":1.4370909391597828,"angularAcceleration":-1.2178731636813378,"curveRadius":1.462095720379151},{"acceleration":1.9622882669460293,"curvature":0.6796049610467602,"pose":{"rotation":{"radians":-2.7743921985227376},"translation":{"x":2.0830932682201295,"y":1.7666074378408727}},"time":1.6145653092722492,"velocity":2.0976884882781826,"position":3.1244867349464505,"holonomicRotation":-138.3684,"angularVelocity":1.4328220866893913,"angularAcceleration":-1.2897211564527868,"curveRadius":1.4714430548884634},{"acceleration":2.077721876652302,"curvature":0.6750588771115987,"pose":{"rotation":{"radians":-2.769667144582736},"translation":{"x":2.076607137825678,"y":1.7640773281069015}},"time":1.617873426073141,"velocity":2.1045618349259168,"position":3.131448871311085,"holonomicRotation":-138.35864,"angularVelocity":1.4283213756925008,"angularAcceleration":-1.360505468149413,"curveRadius":1.481352270010491},{"acceleration":2.1936399879472095,"curvature":0.670317826343197,"pose":{"rotation":{"radians":-2.764960652491206},"translation":{"x":2.070114705266436,"y":1.7615094888638654}},"time":1.62117949173407,"velocity":2.1118141527625096,"position":3.1384306675637967,"holonomicRotation":-138.34888,"angularVelocity":1.423593048121085,"angularAcceleration":-1.4301977202979257,"curveRadius":1.4918296376740077},{"acceleration":1.6493780603889263,"curvature":0.6653882967043168,"pose":{"rotation":{"radians":-2.7602738122193955},"translation":{"x":2.0636155100268883,"y":1.7589036835533887}},"time":1.62448664153448,"velocity":2.1172688930857255,"position":3.1454327929609796,"holonomicRotation":-138.33912,"angularVelocity":1.4171841478814298,"angularAcceleration":-1.9378923322011754,"curveRadius":1.5028818585373722},{"acceleration":-0.9781245678898652,"curvature":0.6602769178348922,"pose":{"rotation":{"radians":-2.7556076898644144},"translation":{"x":2.0571090915915184,"y":1.7562596756170958}},"time":1.6278088074283856,"velocity":2.1140194010062907,"position":3.1524559161140573,"holonomicRotation":-138.32936,"angularVelocity":1.404542248639964,"angularAcceleration":-3.8053184714999295,"curveRadius":1.5145160658941261},{"acceleration":-2.988309219207022,"curvature":0.6549904446210729,"pose":{"rotation":{"radians":-2.7509633269155627},"translation":{"x":2.0505949894448126,"y":1.7535772284966114}},"time":1.6311570691851611,"velocity":2.1040137595302,"position":3.1595007049208217,"holonomicRotation":-138.3196,"angularVelocity":1.387096734433461,"angularAcceleration":-5.210319704306383,"curveRadius":1.526739829889462},{"acceleration":-2.988092768929316,"curvature":0.6495357407986543,"pose":{"rotation":{"radians":-2.746341739573892},"translation":{"x":2.0440727430712546,"y":1.750856105633559}},"time":1.6345321226361047,"velocity":2.0939287867186858,"position":3.1665678264984667,"holonomicRotation":-138.30984,"angularVelocity":1.3693375257149019,"angularAcceleration":-5.261904434015459,"curveRadius":1.5395611622085998},{"acceleration":-2.987875120357178,"curvature":0.6439197626097253,"pose":{"rotation":{"radians":-2.741743918124912},"translation":{"x":2.0375418919553296,"y":1.7480960704695634}},"time":1.6379346798179448,"velocity":2.083762370769473,"position":3.1736579471183766,"holonomicRotation":-138.30008,"angularVelocity":1.3512841087635672,"angularAcceleration":-5.3058379290987405,"curveRadius":1.5529885213448436},{"acceleration":-2.987656215689583,"curvature":0.6381495427704633,"pose":{"rotation":{"radians":-2.737170826364814},"translation":{"x":2.0310019755815225,"y":1.7452968864462486}},"time":1.6413654696192914,"velocity":2.0735123502947554,"position":3.180771732142734,"holonomicRotation":-138.29032,"angularVelocity":1.3329559736662975,"angularAcceleration":-5.342249498956741,"curveRadius":1.567030817978179},{"acceleration":-2.9874359911768753,"curvature":0.632232174495323,"pose":{"rotation":{"radians":-2.7326234010809785},"translation":{"x":2.024452533434318,"y":1.742458317005239}},"time":1.6448252384648663,"velocity":2.0631765123243326,"position":3.1879098459629955,"holonomicRotation":-138.28056,"angularVelocity":1.3143725742405068,"angularAcceleration":-5.371283532297064,"curveRadius":1.581697421201707},{"acceleration":-2.987214376346578,"curvature":0.6261747958932774,"pose":{"rotation":{"radians":-2.7281025515857618},"translation":{"x":2.0178931049982003,"y":1.739580125588159}},"time":1.6483147510400846,"velocity":2.0527525901931982,"position":3.1950729519402867,"holonomicRotation":-138.2708,"angularVelocity":1.2955532893971062,"angularAcceleration":-5.393098445052317,"curveRadius":1.5969981649827307},{"acceleration":-2.9869912941577663,"curvature":0.6199845744782165,"pose":{"rotation":{"radians":-2.72360915930359},"translation":{"x":2.0113232297576547,"y":1.736662075636633}},"time":1.6518347910587652,"velocity":2.0422382613023125,"position":3.2022617123477515,"holonomicRotation":-138.26104,"angularVelocity":1.276517385690406,"angularAcceleration":-5.407865707684662,"curveRadius":1.6129433556336579},{"acceleration":-2.9867666602512863,"curvature":0.6136686923752745,"pose":{"rotation":{"radians":-2.7191440774117526},"translation":{"x":2.0047424471971658,"y":1.733703930592285}},"time":1.6553861620769796,"velocity":2.031631144746927,"position":3.2094767883149076,"holonomicRotation":-138.25128,"angularVelocity":1.2572839810137357,"angularAcceleration":-5.415768889824506,"curveRadius":1.6295437789556872},{"acceleration":-2.986540382870855,"curvature":0.6072343318423582,"pose":{"rotation":{"radians":-2.714708130532991},"translation":{"x":1.9981502968012181,"y":1.730705453896739}},"time":1.6589696883562908,"velocity":2.020928798800685,"position":3.2167188397740265,"holonomicRotation":-138.24152,"angularVelocity":1.2378720101403349,"angularAcceleration":-5.417002516619592,"curveRadius":1.6468107080935046},{"acceleration":-2.9863123624742234,"curvature":0.6006886609356528,"pose":{"rotation":{"radians":-2.7103021144800747},"translation":{"x":1.9915463180542967,"y":1.72766640899162}},"time":1.6625862157799116,"velocity":2.0101287182462992,"position":3.223988525408572,"holonomicRotation":-138.23176,"angularVelocity":1.2183001915425733,"angularAcceleration":-5.41177110117595,"curveRadius":1.6647559127258478},{"acceleration":-2.9860824911867105,"curvature":0.5940388200745621,"pose":{"rotation":{"radians":-2.705926796050985},"translation":{"x":1.9849300504408864,"y":1.724586559318552}},"time":1.6662366128256167,"velocity":1.9992283315422394,"position":3.231286502603724,"holonomicRotation":-138.222,"angularVelocity":1.1985869959646038,"angularAcceleration":-5.400288059394247,"curveRadius":1.6833916676935066},{"acceleration":-2.985850652389817,"curvature":0.5872919089719677,"pose":{"rotation":{"radians":-2.7015829128744917},"translation":{"x":1.9783010334454714,"y":1.7214656683191591}},"time":1.6699217715995651,"velocity":1.9882249978128856,"position":3.2386134273989975,"holonomicRotation":-138.21224,"angularVelocity":1.1787506164460622,"angularAcceleration":-5.382774728397516,"curveRadius":1.7027307625444088},{"acceleration":-2.985616720607988,"curvature":0.5804549739633098,"pose":{"rotation":{"radians":-2.697271173303876},"translation":{"x":1.9716588065525373,"y":1.7183034994350657}},"time":1.673642608935565,"velocity":1.977116003647862,"position":3.245969954442973,"holonomicRotation":-138.20248,"angularVelocity":1.158808940369122,"angularAcceleration":-5.359459249669597,"curveRadius":1.7227865120563328},{"acceleration":-2.9853805603232093,"curvature":0.5735349961852331,"pose":{"rotation":{"radians":-2.692992256358703},"translation":{"x":1.965002909246568,"y":1.715099816107896}},"time":1.677400067564716,"velocity":1.9658985597001757,"position":3.2533567369501544,"holonomicRotation":-138.19272,"angularVelocity":1.138779522940377,"angularAcceleration":-5.330575637840101,"curveRadius":1.7435727665291982},{"acceleration":-2.985142026217629,"curvature":0.5665388801561911,"pose":{"rotation":{"radians":-2.6887468117120723},"translation":{"x":1.9583328810120484,"y":1.7118543817792746}},"time":1.6811951173608073,"velocity":1.954569797062275,"position":3.2607744266599417,"holonomicRotation":-138.18296,"angularVelocity":1.1186795627828987,"angularAcceleration":-5.296362692837516,"curveRadius":1.7651039231840653},{"acceleration":-2.9849009619898457,"curvature":0.5594734429971727,"pose":{"rotation":{"radians":-2.684535459723401},"translation":{"x":1.9516482613334634,"y":1.7085669598908253}},"time":1.68502875666735,"velocity":1.9431267634082534,"position":3.268223673797739,"holonomicRotation":-138.1732,"angularVelocity":1.0985258789171586,"angularAcceleration":-5.257063133546304,"curveRadius":1.7873949380740375},{"acceleration":-2.984657199962897,"curvature":0.552345404350619,"pose":{"rotation":{"radians":-2.6803587915140294},"translation":{"x":1.9449485896952978,"y":1.7052373138841728}},"time":1.6889020137126727,"velocity":1.9315664188806243,"position":3.2757051270381767,"holonomicRotation":-138.16344,"angularVelocity":1.0783348898610734,"angularAcceleration":-5.212922566156077,"curveRadius":1.8104613383643144},{"acceleration":-2.984410560637797,"curvature":0.5451613768749871,"pose":{"rotation":{"radians":-2.6762173690843336},"translation":{"x":1.9382334055820363,"y":1.701865207200941}},"time":1.6928159481201164,"velocity":1.9198856317014057,"position":3.2832194334704496,"holonomicRotation":-138.15368,"angularVelocity":1.058122594446012,"angularAcceleration":-5.164188591566778,"curveRadius":1.8343192354019489},{"acceleration":-2.9841608513022355,"curvature":0.5379278573705385,"pose":{"rotation":{"radians":-2.672111725471225},"translation":{"x":1.9315022484781637,"y":1.6984504032827545}},"time":1.696771652521047,"velocity":1.9080811734888246,"position":3.2907672385657523,"holonomicRotation":-138.14392,"angularVelocity":1.0379045542793113,"angularAcceleration":-5.111109961084091,"curveRadius":1.8589853384580795},{"acceleration":-2.983907865875381,"curvature":0.5306512185906609,"pose":{"rotation":{"radians":-2.6680423649436373},"translation":{"x":1.9247546578681647,"y":1.6949926655712377}},"time":1.7007702542791618,"velocity":1.8961497142502826,"position":3.2983491861468024,"holonomicRotation":-138.13416,"angularVelocity":1.017695878147711,"angularAcceleration":-5.053935689041398,"curveRadius":1.8844769689889096},{"acceleration":-2.9836513836862832,"curvature":0.5233377016732124,"pose":{"rotation":{"radians":-2.6640097632345947},"translation":{"x":1.917990173236524,"y":1.6914917575080146}},"time":1.7048129173354079,"velocity":1.8840878170287367,"position":3.3059659183594277,"holonomicRotation":-138.1244,"angularVelocity":0.9975112080667129,"angularAcceleration":-4.992914274617154,"curveRadius":1.9108120756498255},{"acceleration":-2.9833911685050243,"curvature":0.5159934093040172,"pose":{"rotation":{"radians":-2.6600143678082637},"translation":{"x":1.9112083340677262,"y":1.6879474425347096}},"time":1.7089008441837754,"velocity":1.8718919321718224,"position":3.3136180756461955,"holonomicRotation":-138.11464,"angularVelocity":0.977364706985026,"angularAcceleration":-4.928292953610961,"curveRadius":1.9380092496701093},{"acceleration":-2.9831269675758065,"curvature":0.5086242993067133,"pose":{"rotation":{"radians":-2.656056598159407},"translation":{"x":1.9044086798462563,"y":1.6843594840929468}},"time":1.7130352779892881,"velocity":1.8595583911909404,"position":3.32130629672206,"holonomicRotation":-138.10488,"angularVelocity":0.9572700483388341,"angularAcceleration":-4.860316936117921,"curveRadius":1.96608774170456},{"acceleration":-2.982858510291385,"curvature":0.5012361790976528,"pose":{"rotation":{"radians":-2.6521368461446904},"translation":{"x":1.897590750056599,"y":1.6807276456243507}},"time":1.7172175048606924,"velocity":1.847083400175603,"position":3.3290312185519992,"holonomicRotation":-138.09512,"angularVelocity":0.9372404069032239,"angularAcceleration":-4.78922881313826,"curveRadius":1.9950674785691715},{"acceleration":-2.9825855071062928,"curvature":0.493834700579755,"pose":{"rotation":{"radians":-2.648255476342309},"translation":{"x":1.8907540841832389,"y":1.6770516905705455}},"time":1.7214488562916832,"velocity":1.8344630327220561,"position":3.3367934763306075,"holonomicRotation":-138.08536,"angularVelocity":0.9172884516171027,"angularAcceleration":-4.7152678314523815,"curveRadius":2.024969081407228},{"acceleration":-2.982307647924085,"curvature":0.48642535576360835,"pose":{"rotation":{"radians":-2.644412826439816},"translation":{"x":1.8838982217106608,"y":1.6733313823731555}},"time":1.725730711785997,"velocity":1.8216932223340583,"position":3.344593703463613,"holonomicRotation":-138.0756,"angularVelocity":0.8974263394913181,"angularAcceleration":-4.638669416135349,"curveRadius":2.055813884188178},{"acceleration":-2.9820246005240354,"curvature":0.4790134730466638,"pose":{"rotation":{"radians":-2.640609207646897},"translation":{"x":1.8770227021233494,"y":1.669566484473805}},"time":1.7300645016833933,"velocity":1.80876975424652,"position":3.3524325315512824,"holonomicRotation":-138.06584,"angularVelocity":0.8776657112990884,"angularAcceleration":-4.559664556904726,"curveRadius":2.0876239527036926},{"acceleration":-2.9817360089906417,"curvature":0.4716042137223367,"pose":{"rotation":{"radians":-2.6368449051321377},"translation":{"x":1.87012706490579,"y":1.6657567603141183}},"time":1.7344517102054526,"velocity":1.795688256617345,"position":3.360310590373676,"holonomicRotation":-138.05608,"angularVelocity":0.8580176884303675,"angularAcceleration":-4.47847937245944,"curveRadius":2.1204221058736414},{"acceleration":-2.9814414916016476,"curvature":0.46420256933505605,"pose":{"rotation":{"radians":-2.6331201784815366},"translation":{"x":1.8632108495424662,"y":1.6619019733357194}},"time":1.7388938787422776,"velocity":1.7824441910289677,"position":3.368228507877711,"holonomicRotation":-138.04632,"angularVelocity":0.838492871155965,"angularAcceleration":-4.3953346462531275,"curveRadius":2.1542319367866565},{"acceleration":-2.981140638715885,"curvature":0.4568133597815737,"pose":{"rotation":{"radians":-2.6294352621770978},"translation":{"x":1.8562735955178633,"y":1.658001886980233}},"time":1.7433926094036265,"velocity":1.7690328422317834,"position":3.3761869101659925,"holonomicRotation":-138.03656,"angularVelocity":0.8191013380947612,"angularAcceleration":-4.31044543915631,"curveRadius":2.1890778336214862},{"acceleration":-2.9808330105841176,"curvature":0.44944123149043047,"pose":{"rotation":{"radians":-2.625790366093515},"translation":{"x":1.8493148423164667,"y":1.6540562646892836}},"time":1.747949568860803,"velocity":1.7554493070539379,"position":3.384186421487366,"holonomicRotation":-138.0268,"angularVelocity":0.7998526468877505,"angularAcceleration":-4.224020728711237,"curveRadius":2.2249850034537655},{"acceleration":-2.9805181343563474,"curvature":0.4420906560566678,"pose":{"rotation":{"radians":-2.6221856760118225},"translation":{"x":1.84233412942276,"y":1.6500648699044946}},"time":1.7525664925087838,"velocity":1.7416884823961927,"position":3.3922276642291567,"holonomicRotation":-138.01704,"angularVelocity":0.7807558358191523,"angularAcceleration":-4.136263132042577,"curveRadius":2.2619794974174225},{"acceleration":-2.980195501492344,"curvature":0.4347659299790691,"pose":{"rotation":{"radians":-2.618621354147339},"translation":{"x":1.835330996321229,"y":1.646027466067491}},"time":1.757245188981687,"velocity":1.7277450522147988,"position":3.40031125891103,"holonomicRotation":-138.00728,"angularVelocity":0.7618194266557715,"angularAcceleration":-4.047368593592679,"curveRadius":2.3000882337954653},{"acceleration":-2.979864564187434,"curvature":0.42747117411326074,"pose":{"rotation":{"radians":-2.615097539691231},"translation":{"x":1.8283049824963578,"y":1.6419438166198967}},"time":1.7619875450588383,"velocity":1.7136134733897366,"position":3.408437824180448,"holonomicRotation":-137.99752,"angularVelocity":0.7430514281890394,"angularAcceleration":-3.9575262087881415,"curveRadius":2.339339025781993},{"acceleration":-2.9795247318917997,"curvature":0.4202103342071601,"pose":{"rotation":{"radians":-2.6116143493631845},"translation":{"x":1.8212556274326313,"y":1.6378136850033362}},"time":1.7667955310034296,"velocity":1.6992879603572386,"position":3.416607976809659,"holonomicRotation":-137.98776,"angularVelocity":0.7244593408108262,"angularAcceleration":-3.866917996948,"curveRadius":2.3797606069988},{"acceleration":-2.9791753671152765,"curvature":0.412987181069177,"pose":{"rotation":{"radians":-2.6081718779744856},"translation":{"x":1.8141824706145342,"y":1.6336368346594339}},"time":1.7716712063812439,"velocity":1.6847624683736038,"position":3.4248223316941737,"holonomicRotation":-137.978,"angularVelocity":0.706050161658244,"angularAcceleration":-3.775718793000283,"curveRadius":2.421382662316814},{"acceleration":-2.9788157806250197,"curvature":0.40580531215965937,"pose":{"rotation":{"radians":-2.60477019899918},"translation":{"x":1.8070850515265513,"y":1.6294130290298139}},"time":1.7766167264132233,"velocity":1.6700306752589462,"position":3.433081501852687,"holonomicRotation":-137.96824,"angularVelocity":0.6878303905977694,"angularAcceleration":-3.6840960996334413,"curveRadius":2.4642358540801004},{"acceleration":-2.9784452265245167,"curvature":0.3986681522529941,"pose":{"rotation":{"radians":-2.601409365152476},"translation":{"x":1.799962909653167,"y":1.6251420315561005}},"time":1.781634348922957,"velocity":1.6550859614463282,"position":3.441386098428384,"holonomicRotation":-137.95848,"angularVelocity":0.6698060366606536,"angularAcceleration":-3.592210036157697,"curveRadius":2.5083518569233534},{"acceleration":-2.978062896075056,"curvature":0.3915789556244072,"pose":{"rotation":{"radians":-2.5980894089745328},"translation":{"x":1.7928155844788667,"y":1.620823605679918}},"time":1.7867264419486228,"velocity":1.63992138814323,"position":3.4497367306915887,"holonomicRotation":-137.94872,"angularVelocity":0.6519826250639171,"angularAcceleration":-3.500213273186539,"curveRadius":2.5537633870170877},{"acceleration":-2.977667911241681,"curvature":0.384540808009916,"pose":{"rotation":{"radians":-2.594810343418713},"translation":{"x":1.7856426154881349,"y":1.6164575148428906}},"time":1.7918954920987764,"velocity":1.6245296733795187,"position":3.4581340060437,"holonomicRotation":-137.93896,"angularVelocity":0.6343652045477832,"angularAcceleration":-3.4082510334341642,"curveRadius":2.6005042356238386},{"acceleration":-2.977259317030016,"curvature":0.3775566285074399,"pose":{"rotation":{"radians":-2.591572162442471},"translation":{"x":1.778443542165456,"y":1.6120435224866427}},"time":1.7971441137428625,"velocity":1.6089031656880979,"position":3.4665785300223693,"holonomicRotation":-137.9292,"angularVelocity":0.6169583551313287,"angularAcceleration":-3.3164610819428506,"curveRadius":2.6486093065117373},{"acceleration":-2.976836072854138,"curvature":0.37062917243714977,"pose":{"rotation":{"radians":-2.5883748416001273},"translation":{"x":1.771217903995315,"y":1.6075813920527984}},"time":1.802475059140797,"velocity":1.5930338151251109,"position":3.4750709063078644,"holonomicRotation":-137.91944,"angularVelocity":0.5997661959888634,"angularAcceleration":-3.224973782160043,"curveRadius":2.69811465035062},{"acceleration":-2.9763970429278515,"curvature":0.3637610342492779,"pose":{"rotation":{"radians":-2.585218338636276},"translation":{"x":1.7639652404621968,"y":1.6030708869829824}},"time":1.8078912296317804,"velocity":1.5769131412917547,"position":3.483611736730573,"holonomicRotation":-137.90968,"angularVelocity":0.5827923934643428,"angularAcceleration":-3.1339121530198883,"curveRadius":2.7490575016199252},{"acceleration":-2.9759409848896166,"curvature":0.3569546499835396,"pose":{"rotation":{"radians":-2.582102594078176},"translation":{"x":1.7566850910505858,"y":1.5985117707188183}},"time":1.8133956880211624,"velocity":1.5605321979711735,"position":3.492201621279596,"holonomicRotation":-137.89992,"angularVelocity":0.5660401692036587,"angularAcceleration":-3.043391933527714,"curveRadius":2.8014763221213492},{"acceleration":-2.975466537058236,"curvature":0.35021230097040235,"pose":{"rotation":{"radians":-2.579027531827215},"translation":{"x":1.749376995244967,"y":1.5939038067019313}},"time":1.81899167232625,"velocity":1.543881533929482,"position":3.50084115811238,"holonomicRotation":-137.89016,"angularVelocity":0.5495123079893254,"angularAcceleration":-2.9535217243741734,"curveRadius":2.8554108385944827},{"acceleration":-2.974972203751908,"curvature":0.34353611700983605,"pose":{"rotation":{"radians":-2.57599305974685},"translation":{"x":1.7420404925298252,"y":1.5892467583739451}},"time":1.8246826110682057,"velocity":1.526951149358909,"position":3.5095309435653403,"holonomicRotation":-137.8804,"angularVelocity":0.5332111656717996,"angularAcceleration":-2.8644030548682147,"curveRadius":2.9109020871053515},{"acceleration":-2.974456338188464,"curvature":0.3369280796854399,"pose":{"rotation":{"radians":-2.572999070247955},"translation":{"x":1.7346751223896444,"y":1.5845403891764838}},"time":1.8304721403284776,"velocity":1.5097304473555657,"position":3.5182715721654287,"holonomicRotation":-137.87064,"angularVelocity":0.517138676444774,"angularAcceleration":-2.7761305806529224,"curveRadius":2.967992459796203},{"acceleration":-2.9739171228801324,"curvature":0.33039002654186544,"pose":{"rotation":{"radians":-2.5700454408689053},"translation":{"x":1.7272804243089106,"y":1.579784462551172}},"time":1.8363641228257288,"velocity":1.4922081797192803,"position":3.52706363664259,"holonomicRotation":-137.86088,"angularVelocity":0.501296359998946,"angularAcceleration":-2.688792177033614,"curveRadius":3.026725747344207},{"acceleration":-2.973352546738258,"curvature":0.32392365416600283,"pose":{"rotation":{"radians":-2.5671320348510074},"translation":{"x":1.7198559377721077,"y":1.574978741939634}},"time":1.8423626693144066,"velocity":1.4743723862404423,"position":3.535907727943076,"holonomicRotation":-137.85112,"angularVelocity":0.48568532783682383,"angularAcceleration":-2.6024691467487595,"curveRadius":3.087147193911084},{"acceleration":-2.9727603784854373,"curvature":0.31753052254849545,"pose":{"rotation":{"radians":-2.564258701707656},"translation":{"x":1.7124012022637203,"y":1.5701229907834942}},"time":1.8484721626606968,"velocity":1.4562103264879704,"position":3.5448044352435533,"holonomicRotation":-137.84136,"angularVelocity":0.4703062889979253,"angularAcceleration":-2.5172363676010874,"curveRadius":3.149303544031025},{"acceleration":-2.9721381353561287,"curvature":0.3112120589496282,"pose":{"rotation":{"radians":-2.561425277786653},"translation":{"x":1.7049157572682336,"y":1.5652169725243765}},"time":1.8546972850180279,"velocity":1.4377084029324887,"position":3.553754345965971,"holonomicRotation":-137.8316,"angularVelocity":0.45515955484252313,"angularAcceleration":-2.4331624803429728,"curveRadius":3.2132430966046104},{"acceleration":-2.9714830465126356,"curvature":0.30496956181313956,"pose":{"rotation":{"radians":-2.5586315868257983},"translation":{"x":1.6973991422701324,"y":1.5602604506039055}},"time":1.8610430486054113,"velocity":1.4188520740154018,"position":3.5627580457931414,"holonomicRotation":-137.82184,"angularVelocity":0.44024504259963443,"angularAcceleration":-2.350310098621023,"curveRadius":3.279015761621215},{"acceleration":-2.9707920097281297,"curvature":0.2988042047232934,"pose":{"rotation":{"radians":-2.555877440499817},"translation":{"x":1.6898508967539012,"y":1.555253188463705}},"time":1.8675148306915996,"velocity":1.3996257555050517,"position":3.571816118684987,"holonomicRotation":-137.81208,"angularVelocity":0.4255622777934976,"angularAcceleration":-2.268735969567297,"curveRadius":3.346673119697384},{"acceleration":-2.9700615399788486,"curvature":0.2927170408977632,"pose":{"rotation":{"radians":-2.5531626389593534},"translation":{"x":1.6822705602040249,"y":1.5501949495454002}},"time":1.8741184135112596,"velocity":1.3800127081463145,"position":3.5809291468954143,"holonomicRotation":-137.80232,"angularVelocity":0.4111103948573203,"angularAcceleration":-2.188491207099202,"curveRadius":3.4162684787089947},{"acceleration":-2.9692877082091984,"curvature":0.2867090067280589,"pose":{"rotation":{"radians":-2.5504869713606078},"translation":{"x":1.674657672104988,"y":1.5450854972906145}},"time":1.8808600299925953,"velocity":1.359994909194824,"position":3.5900977109897747,"holonomicRotation":-137.79256,"angularVelocity":0.39688813597647726,"angularAcceleration":-2.1096214713812005,"curveRadius":3.487856943916979},{"acceleration":-2.968466067866388,"curvature":0.2807809265936036,"pose":{"rotation":{"radians":-2.547850216386056},"translation":{"x":1.6670117719412751,"y":1.5399245951409728}},"time":1.887746416367689,"velocity":1.3395529049101411,"position":3.599322389862865,"holonomicRotation":-137.7828,"angularVelocity":0.38289384750296834,"angularAcceleration":-2.0321671935404026,"curveRadius":3.561495476675946},{"acceleration":-2.967591566382049,"curvature":0.27493351634188307,"pose":{"rotation":{"radians":-2.5452521427548027},"translation":{"x":1.6593323991973716,"y":1.5347120065380988}},"time":1.8947848729786754,"velocity":1.3186656404310317,"position":3.6086037607574375,"holonomicRotation":-137.77304,"angularVelocity":0.3691254737861191,"angularAcceleration":-1.9561637554684848,"curveRadius":3.637242971702614},{"acceleration":-2.966658437845799,"curvature":0.2691673879798224,"pose":{"rotation":{"radians":-2.542692509723523},"translation":{"x":1.6516190933577617,"y":1.5294474949236172}},"time":1.9019833349000252,"velocity":1.2973102626325475,"position":3.6179423992831743,"holonomicRotation":-137.76328,"angularVelocity":0.3555805475177962,"angularAcceleration":-1.8816417196220852,"curveRadius":3.7151603227466876},{"acceleration":-2.965660071900144,"curvature":0.2634830533328396,"pose":{"rotation":{"radians":-2.5401710675761304},"translation":{"x":1.64387139390693,"y":1.5241308237391524}},"time":1.9093504543904574,"velocity":1.2754618905148556,"position":3.6273388794360897,"holonomicRotation":-137.75352,"angularVelocity":0.3422561763342323,"angularAcceleration":-1.8086269946983586,"curveRadius":3.7953105042272695},{"acceleration":-2.964588852674865,"curvature":0.2578809281643157,"pose":{"rotation":{"radians":-2.5376875581032836},"translation":{"x":1.6360888403293619,"y":1.518761756426328}},"time":1.9168956976957523,"velocity":1.2530933463212586,"position":3.63679377361833,"holonomicRotation":-137.74376,"angularVelocity":0.32914902440640836,"angularAcceleration":-1.7371410566211778,"curveRadius":3.877758650545974},{"acceleration":-2.963435959399999,"curvature":0.2523613365736925,"pose":{"rotation":{"radians":-2.5352417150711366},"translation":{"x":1.6282709721095419,"y":1.513340056426769}},"time":1.9246294593853128,"velocity":1.2301748388289848,"position":3.6463076526583267,"holonomicRotation":-137.734,"angularVelocity":0.3162552882187396,"angularAcceleration":-1.6672011247868501,"curveRadius":3.962572133976586},{"acceleration":-2.962191117507933,"curvature":0.24692451447318395,"pose":{"rotation":{"radians":-2.5328332646782843},"translation":{"x":1.6204173287319543,"y":1.5078654871820998}},"time":1.9325631982758333,"velocity":1.2066735879588577,"position":3.65588108583128,"holonomicRotation":-137.72424,"angularVelocity":0.30357066524208487,"angularAcceleration":-1.5988203231405473,"curveRadius":4.049820659295455},{"acceleration":-2.960842285371277,"curvature":0.2415706139696145,"pose":{"rotation":{"radians":-2.5304619260017724},"translation":{"x":1.6125274496810844,"y":1.502337812133944}},"time":1.94070960015298,"velocity":1.182553376807374,"position":3.6655146408799295,"holonomicRotation":-137.71448,"angularVelocity":0.29109031352408893,"angularAcceleration":-1.5320078614102552,"curveRadius":4.139576348163701},{"acceleration":-2.959375256397718,"curvature":0.23629970675559142,"pose":{"rotation":{"radians":-2.52812741143223},"translation":{"x":1.6046008744414166,"y":1.4967567947239258}},"time":1.9490827740588506,"velocity":1.1577740131328256,"position":3.6752088840355883,"holonomicRotation":-137.70472,"angularVelocity":0.27880880007826,"angularAcceleration":-1.4667691826176212,"curveRadius":4.231913842509826},{"acceleration":-2.957773148370859,"curvature":0.23111178834677026,"pose":{"rotation":{"radians":-2.5258294270966193},"translation":{"x":1.5966371424974357,"y":1.4911221983936702}},"time":1.9576984910329382,"velocity":1.132290676812906,"position":3.6849643800394065,"holonomicRotation":-137.69496,"angularVelocity":0.26672003531709815,"angularAcceleration":-1.4031060673789009,"curveRadius":4.326910397575896},{"acceleration":-2.9560157411623313,"curvature":0.22600678145006892,"pose":{"rotation":{"radians":-2.5235676732698686},"translation":{"x":1.5886357933336264,"y":1.4854337865848013}},"time":1.9665744771200395,"velocity":1.1060531222210968,"position":3.694781692163836,"holonomicRotation":-137.6852,"angularVelocity":0.2548171892740416,"angularAcceleration":-1.3410167530967556,"curveRadius":4.424645993292583},{"acceleration":-2.9540786071753242,"curvature":0.2209845399276742,"pose":{"rotation":{"radians":-2.521341844775107},"translation":{"x":1.5805963664344733,"y":1.4796913227389432}},"time":1.9757307765559469,"velocity":1.0790046939365914,"position":3.704661382234269,"holonomicRotation":-137.67544,"angularVelocity":0.24309258454709537,"angularAcceleration":-1.280495991750449,"curveRadius":4.5252034387893785},{"acceleration":-2.9519319550325855,"curvature":0.21604485194873957,"pose":{"rotation":{"radians":-2.519151631371995},"translation":{"x":1.5725184012844617,"y":1.4738945702977204}},"time":1.9851902068730811,"velocity":1.0510810993070387,"position":3.7146040106508207,"holonomicRotation":-137.66568,"angularVelocity":0.23153755878348606,"angularAcceleration":-1.2215350582665871,"curveRadius":4.628668496286445},{"acceleration":-2.9495390693023795,"curvature":0.21118744400009853,"pose":{"rotation":{"radians":-2.516996718133634},"translation":{"x":1.5644014373680761,"y":1.4680432927027567}},"time":1.9949789361154895,"velocity":1.0222088599677326,"position":3.7246101364102358,"holonomicRotation":-137.65592,"angularVelocity":0.22014228660294818,"angularAcceleration":-1.1641217055191775,"curveRadius":4.735129991911514},{"acceleration":-2.946854171594505,"curvature":0.2064119836933961,"pose":{"rotation":{"radians":-2.5148767858120182},"translation":{"x":1.556245014169801,"y":1.4621372533956767}},"time":2.005127224831706,"velocity":0.9923033330298044,"position":3.734680317127886,"holonomicRotation":-137.64616,"angularVelocity":0.20889554691406537,"angularAcceleration":-1.1082400199071005,"curveRadius":4.844679955624077},{"acceleration":-2.9438194357924763,"curvature":0.2017180835655789,"pose":{"rotation":{"radians":-2.5127915111916943},"translation":{"x":1.5480486711741217,"y":1.4561762158181049}},"time":2.015670394356215,"velocity":0.9612661456687004,"position":3.7448151090598425,"holonomicRotation":-137.6364,"angularVelocity":0.19778441534838853,"angularAcceleration":-1.0538701421662333,"curveRadius":4.95741374458824},{"acceleration":-2.9403607392159214,"curvature":0.19710530399632784,"pose":{"rotation":{"radians":-2.5107405674325385},"translation":{"x":1.5398119478655223,"y":1.4501599434116654}},"time":2.0266501120451093,"velocity":0.9289818148486008,"position":3.755015067124997,"holonomicRotation":-137.62664,"angularVelocity":0.1867938518337572,"angularAcceleration":-1.0009878055196175,"curveRadius":5.0734301904865555},{"acceleration":-2.9363814769713574,"curvature":0.19257315654112309,"pose":{"rotation":{"radians":-2.5087236244007407},"translation":{"x":1.5315343837284874,"y":1.4440881996179824}},"time":2.038116130507048,"velocity":0.8953132106223526,"position":3.7652807449272103,"holonomicRotation":-137.61688,"angularVelocity":0.17590613851643533,"angularAcceleration":-0.9495635606608853,"curveRadius":5.192831742291427},{"acceleration":-2.9317533230404207,"curvature":0.18812110650219807,"pose":{"rotation":{"radians":-2.5067403489889535},"translation":{"x":1.5232155182475022,"y":1.43796074787868}},"time":2.050128693995562,"velocity":0.8600953376966677,"position":3.7756126947774664,"holonomicRotation":-137.60712,"angularVelocity":0.165100098216635,"angularAcceleration":-0.8995615557106291,"curveRadius":5.315724633951777},{"acceleration":-2.926302019065229,"curvature":0.18374857651507545,"pose":{"rotation":{"radians":-2.5047904054253958},"translation":{"x":1.5148548909070514,"y":1.4317773516353829}},"time":2.062761954687831,"velocity":0.8231266014255029,"position":3.7860114677160164,"holonomicRotation":-137.59736,"angularVelocity":0.15434998224575192,"angularAcceleration":-0.8509375554532396,"curveRadius":5.4422190308394365},{"acceleration":-2.9197847538723263,"curvature":0.17945494884578592,"pose":{"rotation":{"radians":-2.502873455571695},"translation":{"x":1.5064520411916198,"y":1.4255377743297155}},"time":2.0761089715414296,"velocity":0.7841561851066889,"position":3.796477613534489,"holonomicRotation":-137.5876,"angularVelocity":0.14362384304503062,"angularAcceleration":-0.8036356976524984,"curveRadius":5.572429216534714},{"acceleration":-2.9118526763405326,"curvature":0.17523956857829473,"pose":{"rotation":{"radians":-2.5009891592103317},"translation":{"x":1.4980065085856924,"y":1.4192417794033014}},"time":2.0902892933383814,"velocity":0.7428651771308648,"position":3.807011680797954,"holonomicRotation":-137.57784,"angularVelocity":0.1328810719773997,"angularAcceleration":-0.7575830239579014,"curveRadius":5.706473761108429},{"acceleration":-2.901985697629541,"curvature":0.1711017454989879,"pose":{"rotation":{"radians":-2.499137174321621},"translation":{"x":1.4895178325737533,"y":1.4128891302977653}},"time":2.1054609764243017,"velocity":0.698837169806556,"position":3.8176142168669207,"holonomicRotation":-137.56808,"angularVelocity":0.12206851924224162,"angularAcceleration":-0.7126798440175959,"curveRadius":5.844475736256677},{"acceleration":-2.88937220628491,"curvature":0.16704075782316652,"pose":{"rotation":{"radians":-2.4973171573496287},"translation":{"x":1.4809855526402875,"y":1.4064795904547314}},"time":2.1218406942032564,"velocity":0.6515100685092536,"position":3.8282857679192497,"holonomicRotation":-137.55832,"angularVelocity":0.11111406170444672,"angularAcceleration":-0.6687818243040577,"curveRadius":5.986562878615677},{"acceleration":-2.872670106761207,"curvature":0.1630558534734762,"pose":{"rotation":{"radians":-2.4955287634586996},"translation":{"x":1.47240920826978,"y":1.4000129233158245}},"time":2.139739806704812,"velocity":0.6000918230884793,"position":3.839026878971974,"holonomicRotation":-137.54856,"angularVelocity":0.0999152271250146,"angularAcceleration":-0.6256642377357474,"curveRadius":6.1328678406670445},{"acceleration":-2.8494842122059114,"curvature":0.1591462530034819,"pose":{"rotation":{"radians":-2.493771646779227},"translation":{"x":1.4637883389467148,"y":1.3934888923226683}},"time":2.15963531086076,"velocity":0.5433998981022281,"position":3.8498380939030086,"holonomicRotation":-137.5388,"angularVelocity":0.0883172733749217,"angularAcceleration":-0.5829434458752077,"curveRadius":6.28352839685218},{"acceleration":-2.81506313027526,"curvature":0.15531115209566207,"pose":{"rotation":{"radians":-2.4920454606441527},"translation":{"x":1.4551224841555772,"y":1.386907260916887}},"time":2.182328712832784,"velocity":0.4795165389102676,"position":3.860719955472733,"holonomicRotation":-137.52904,"angularVelocity":0.07606555144099371,"angularAcceleration":-0.5398803559304026,"curveRadius":6.438687669923804},{"acceleration":-2.7583546513181156,"curvature":0.151549723003125,"pose":{"rotation":{"radians":-2.4903498578154704},"translation":{"x":1.4464111833808522,"y":1.380267792540105}},"time":2.209379991995117,"velocity":0.4048995172087416,"position":3.8716730053454405,"holonomicRotation":-137.51928,"angularVelocity":0.06268105912874233,"angularAcceleration":-0.4947822331037253,"curveRadius":6.598494409517197},{"acceleration":-2.645300585630344,"curvature":0.1478611175378568,"pose":{"rotation":{"radians":-2.4886844907015657},"translation":{"x":1.4376539761070244,"y":1.3735702506339469}},"time":2.244809048133403,"velocity":0.31117901425780287,"position":3.8826977841106367,"holonomicRotation":-137.50952,"angularVelocity":0.04700568672798959,"angularAcceleration":-0.4424439742218607,"curveRadius":6.763103219099981},{"acceleration":-2.1178638049478296,"curvature":0.1478611175378568,"pose":{"rotation":{"radians":-2.487049011565017},"translation":{"x":1.428850401818578,"y":1.3668143986400367}},"time":2.330820858150196,"velocity":0.12901771502518822,"position":3.893794831304184,"holonomicRotation":-137.49976,"angularVelocity":0.019014588069122436,"angularAcceleration":-0.32543320101509565,"curveRadius":6.763103219099981}] \ No newline at end of file diff --git a/src/main/deploy/pathplanner/generatedJSON/Blue4(4).wpilib.json b/src/main/deploy/pathplanner/generatedJSON/Blue4(4).wpilib.json new file mode 100644 index 0000000..bbaecbe --- /dev/null +++ b/src/main/deploy/pathplanner/generatedJSON/Blue4(4).wpilib.json @@ -0,0 +1 @@ +[{"acceleration":0.0,"curvature":-0.02631475804278537,"pose":{"rotation":{"radians":0.656733166607347},"translation":{"x":1.42,"y":1.36}},"time":0.0,"velocity":0,"position":0.0,"holonomicRotation":-137.49,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-38.00148944459578},{"acceleration":1.5,"curvature":-0.02631475804278537,"pose":{"rotation":{"radians":0.656733166607347},"translation":{"x":1.432909930999439,"y":1.3699520535488952}},"time":0.104245236255259,"velocity":0.1563678543828885,"position":0.016300603922872147,"holonomicRotation":-137.56596000000002,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-38.00148944459578},{"acceleration":5.145574138868843,"curvature":-0.027391041336082982,"pose":{"rotation":{"radians":0.6563058902188788},"translation":{"x":1.4457235527775862,"y":1.3798211382614904}},"time":0.1471377542583099,"velocity":0.3770744857703536,"position":0.0324742780922682,"holonomicRotation":-137.64192,"angularVelocity":-0.009961559926090087,"angularAcceleration":-0.23224469883958615,"curveRadius":-36.50828706109366},{"acceleration":3.4664943956800913,"curvature":-0.028499284838492588,"pose":{"rotation":{"radians":0.6558646032303943},"translation":{"x":1.4584416038271586,"y":1.3896076755880944}},"time":0.17985525253641976,"velocity":0.4904895101920944,"position":0.048521867797408996,"holonomicRotation":-137.71788,"angularVelocity":-0.013487797408388527,"angularAcceleration":-0.10777833477132706,"curveRadius":-35.08859979003224},{"acceleration":3.28983181603231,"curvature":-0.02964030760406245,"pose":{"rotation":{"radians":0.6554090430082509},"translation":{"x":1.4710648226408742,"y":1.3993120869790148}},"time":0.20727472680074294,"velocity":0.5806949690057439,"position":0.06444421855548393,"holonomicRotation":-137.79384000000002,"angularVelocity":-0.016614476913446443,"angularAcceleration":-0.11403134410662981,"curveRadius":-33.73784150144723},{"acceleration":3.212670424781582,"curvature":-0.030814944559315233,"pose":{"rotation":{"radians":0.6549389431578749},"translation":{"x":1.483593947711451,"y":1.4089347938845596}},"time":0.23128939465590248,"velocity":0.6578461821849679,"position":0.08024217612044071,"holonomicRotation":-137.8698,"angularVelocity":-0.01957552997240131,"angularAcceleration":-0.12330185355108651,"curveRadius":-32.451786440021486},{"acceleration":3.169007544675149,"curvature":-0.03202404602138064,"pose":{"rotation":{"radians":0.6544540335192699},"translation":{"x":1.4960297175316066,"y":1.418476217755037}},"time":0.2528722819817662,"velocity":0.7262425149565037,"position":0.09591658649199883,"holonomicRotation":-137.94576,"angularVelocity":-0.022467320117264714,"angularAcceleration":-0.13398532370588087,"curveRadius":-31.226535189599613},{"acceleration":3.1408388095978146,"curvature":-0.03326847849799846,"pose":{"rotation":{"radians":0.6539540401655932},"translation":{"x":1.5083728705940591,"y":1.4279367800407552}},"time":0.27260263623681297,"velocity":0.788212377327868,"position":0.11146829592489026,"holonomicRotation":-138.02172000000002,"angularVelocity":-0.025341326730045084,"angularAcceleration":-0.14566421746052718,"curveRadius":-30.058483139232333},{"acceleration":3.1211367664034135,"curvature":-0.0345491235413109,"pose":{"rotation":{"radians":0.6534386854050336},"translation":{"x":1.520624145391526,"y":1.437316902192022}},"time":0.2908586723689344,"velocity":0.8451919629086214,"position":0.1268981509383287,"holonomicRotation":-138.09768,"angularVelocity":-0.02822928026817788,"angularAcceleration":-0.15819170805931138,"curveRadius":-28.944294311960913},{"acceleration":3.1065749258430913,"curvature":-0.03586687822554903,"pose":{"rotation":{"radians":0.6529076877859983},"translation":{"x":1.5327842804167249,"y":1.4466170056591456}},"time":0.30790366277535003,"velocity":0.8981435027164282,"position":0.14220699832571473,"holonomicRotation":-138.17364,"angularVelocity":-0.031152708589113492,"angularAcceleration":-0.17151246502522252,"curveRadius":-27.880876437349674},{"acceleration":3.09537070200906,"curvature":-0.037222655044811606,"pose":{"rotation":{"radians":0.6523607621058893},"translation":{"x":1.544854014162374,"y":1.455837511892434}},"time":0.32392970962291084,"velocity":0.9477500585973926,"position":0.15739568516457506,"holonomicRotation":-138.24960000000002,"angularVelocity":-0.034127298223403595,"angularAcceleration":-0.18560969293203078,"curveRadius":-26.86535924952479},{"acceleration":3.0864815378942105,"curvature":-0.03861738160180433,"pose":{"rotation":{"radians":0.6517976194237214},"translation":{"x":1.5568340851211906,"y":1.4649788423421952}},"time":0.33908215211729253,"velocity":0.9945177926103054,"position":0.17246505882674212,"holonomicRotation":-138.32556,"angularVelocity":-0.03716514234432865,"angularAcceleration":-0.2004854413439577,"curveRadius":-25.895075184312258},{"acceleration":3.0792565154842557,"curvature":-0.04005200010334542,"pose":{"rotation":{"radians":0.6512179670766662},"translation":{"x":1.568725231785893,"y":1.4740414184587374}},"time":0.3534741546315906,"velocity":1.0388344601233235,"position":0.18741596698877647,"holonomicRotation":-138.40152,"angularVelocity":-0.04027600373744235,"angularAcceleration":-0.21615208794072574,"curveRadius":-24.967542130723032},{"acceleration":3.073268046003389,"curvature":-0.0415274677120044,"pose":{"rotation":{"radians":0.6506215087008842},"translation":{"x":1.5805281926491987,"y":1.4830256616923685}},"time":0.367195912869985,"velocity":1.0810051012523647,"position":0.20224925764263246,"holonomicRotation":-138.47748,"angularVelocity":-0.043468072051663795,"angularAcceleration":-0.2326282287418407,"curveRadius":-24.08044735438874},{"acceleration":3.068223565934044,"curvature":-0.043044755834706905,"pose":{"rotation":{"radians":0.6500079442566804},"translation":{"x":1.5922437062038257,"y":1.4919319934933963}},"time":0.3803207235186059,"velocity":1.1212749545828855,"position":0.21696577910657386,"holonomicRotation":-138.55344,"angularVelocity":-0.04674844160652828,"angularAcceleration":-0.24993652424305016,"curveRadius":-23.231633694009755},{"acceleration":3.06391609351837,"curvature":-0.044604849749585805,"pose":{"rotation":{"radians":0.6493769700585719},"translation":{"x":1.6038725109424914,"y":1.5007608353121293}},"time":0.3929091328677558,"velocity":1.159844784579543,"position":0.23156638003633773,"holonomicRotation":-138.6294,"angularVelocity":-0.050123425494671095,"angularAcceleration":-0.2681024897216842,"curveRadius":-22.41908683952659},{"acceleration":3.0601950439290815,"curvature":-0.04620874853888759,"pose":{"rotation":{"radians":0.6487282788098869},"translation":{"x":1.6154153453579136,"y":1.5095126085988753}},"time":0.40501185944492324,"velocity":1.1968814884690195,"position":0.24605190943655145,"holonomicRotation":-138.70536,"angularVelocity":-0.053598769215255845,"angularAcceleration":-0.287153782945176,"curveRadius":-21.640923669647464},{"acceleration":3.056948232255124,"curvature":-0.04785746431133283,"pose":{"rotation":{"radians":0.6480615596429389},"translation":{"x":1.6268729479428108,"y":1.5181877348039425}},"time":0.4166719066383082,"velocity":1.232525649124849,"position":0.26042321667240464,"holonomicRotation":-138.78132000000002,"angularVelocity":-0.057179800037712905,"angularAcceleration":-0.307119753725239,"curveRadius":-20.89538203475599},{"acceleration":3.0540903585067545,"curvature":-0.049552021938841194,"pose":{"rotation":{"radians":0.6473764981643386},"translation":{"x":1.6382460571899002,"y":1.526786635377639}},"time":0.4279261240615992,"velocity":1.2668970460498608,"position":0.27468115148157485,"holonomicRotation":-138.85728,"angularVelocity":-0.060871534006664944,"angularAcceleration":-0.3280311575740376,"curveRadius":-20.180811213601622},{"acceleration":3.0515554038125092,"curvature":-0.05129345800635584,"pose":{"rotation":{"radians":0.6466727765060893},"translation":{"x":1.6495354115918996,"y":1.5353097317702722}},"time":0.43880638402102734,"velocity":1.3000987621239386,"position":0.28882656398641404,"holonomicRotation":-138.93324,"angularVelocity":-0.06467875408063921,"angularAcceleration":-0.34991995486975164,"curveRadius":-19.49566355764294},{"acceleration":3.04929147026477,"curvature":-0.05308282142172789,"pose":{"rotation":{"radians":0.6459500733826964},"translation":{"x":1.6607417496415267,"y":1.543757445432151}},"time":0.4493404831575521,"velocity":1.332220300767867,"position":0.3028603047063936,"holonomicRotation":-139.00920000000002,"angularVelocity":-0.06860606816269024,"angularAcceleration":-0.37281916860207864,"curveRadius":-18.838486222412424},{"acceleration":3.047257194421756,"curvature":-0.054921171297538186,"pose":{"rotation":{"radians":0.6452080641542457},"translation":{"x":1.6718658098314996,"y":1.5521301978135829}},"time":0.45955284394783025,"velocity":1.3633399906580728,"position":0.31678322457080826,"holonomicRotation":-139.08516,"angularVelocity":-0.072657952817047,"angularAcceleration":-0.39676277969086465,"curveRadius":-18.207914659766633},{"acceleration":3.0454192014426043,"curvature":-0.05680957689019302,"pose":{"rotation":{"radians":0.6444464208965175},"translation":{"x":1.682908330654536,"y":1.5604284103648762}},"time":0.4694650678745918,"velocity":1.3935268677336312,"position":0.33059617493174265,"holonomicRotation":-139.16112,"angularVelocity":-0.07683878646767461,"angularAcceleration":-0.4217856337304868,"curveRadius":-17.60266586623054},{"acceleration":3.043750263725711,"curvature":-0.0587491168462076,"pose":{"rotation":{"radians":0.6436648124773456},"translation":{"x":1.6938700506033535,"y":1.568652504536339}},"time":0.4790963769272999,"velocity":1.4228421672028353,"position":0.3443000075772981,"holonomicRotation":-139.23708000000002,"angularVelocity":-0.08115287495131138,"angularAcceleration":-0.4479233778116325,"curveRadius":-17.021532470314103},{"acceleration":3.0422279465532904,"curvature":-0.06074087853462168,"pose":{"rotation":{"radians":0.6428629046404208},"translation":{"x":1.70475170817067,"y":1.576802901778279}},"time":0.48846396983816065,"velocity":1.4513405201481904,"position":0.35789557474508327,"holonomicRotation":-139.31304,"angularVelocity":-0.08560447113314121,"angularAcceleration":-0.4752123863824895,"curveRadius":-16.46337728602345},{"acceleration":3.0408335967775373,"curvature":-0.06278595636098579,"pose":{"rotation":{"radians":0.6420403600966553},"translation":{"x":1.7155540418492032,"y":1.5848800235410045}},"time":0.49758331237824904,"velocity":1.4790709233246138,"position":0.37138372913596523,"holonomicRotation":-139.389,"angularVelocity":-0.09019779004348491,"angularAcceleration":-0.5036897002334972,"curveRadius":-15.927128580323489},{"acceleration":3.0395515772566086,"curvature":-0.06488545120007724,"pose":{"rotation":{"radians":0.641196838622824},"translation":{"x":1.7262777901316713,"y":1.5928842912748236}},"time":0.5064683760631599,"velocity":1.5060775326621099,"position":0.38476532392808144,"holonomicRotation":-139.46496000000002,"angularVelocity":-0.09493702057126484,"angularAcceleration":-0.5333929722786782,"curveRadius":-15.411775390394597},{"acceleration":3.0383686800615295,"curvature":-0.06704046943791496,"pose":{"rotation":{"radians":0.6403319971688792},"translation":{"x":1.7369236915107913,"y":1.6008161264300442}},"time":0.5151318360647187,"velocity":1.532400318191812,"position":0.3980412127911122,"holonomicRotation":-139.54092,"angularVelocity":-0.09982633425780334,"angularAcceleration":-0.5643603924596827,"curveRadius":-14.916363330750288},{"acceleration":3.037273671565694,"curvature":-0.0692521215533816,"pose":{"rotation":{"radians":0.6394454899731068},"translation":{"x":1.7474924844792818,"y":1.6086759504569745}},"time":0.5235852365507222,"velocity":1.5580756089231511,"position":0.4112122499008134,"holonomicRotation":-139.61688,"angularVelocity":-0.10486989197308758,"angularAcceleration":-0.5966306368230123,"curveRadius":-14.439990827272636},{"acceleration":3.0362569360817755,"curvature":-0.07152152078901998,"pose":{"rotation":{"radians":0.6385369686865685},"translation":{"x":1.7579849075298601,"y":1.6164641848059222}},"time":0.5318391297838118,"velocity":1.5831365495017977,"position":0.42427928995380304,"holonomicRotation":-139.69284000000002,"angularVelocity":-0.11007184862727078,"angularAcceleration":-0.63024278449941,"curveRadius":-13.981805601559866},{"acceleration":3.0353101939888245,"curvature":-0.07384978163720608,"pose":{"rotation":{"radians":0.6376060825062293},"translation":{"x":1.768401699155244,"y":1.6241812509271958}},"time":0.5399031939046152,"velocity":1.6076134855326518,"position":0.4372431881826066,"holonomicRotation":-139.7688,"angularVelocity":-0.11543635645675714,"angularAcceleration":-0.6652362566968162,"curveRadius":-13.541001446864026},{"acceleration":3.034426276807969,"curvature":-0.0762380186650819,"pose":{"rotation":{"radians":0.6366524783176648},"translation":{"x":1.7787435978481518,"y":1.6318275702711031}},"time":0.5477863332668749,"velocity":1.6315342907572319,"position":0.4501048003709514,"holonomicRotation":-139.84476,"angularVelocity":-0.12096756694799102,"angularAcceleration":-0.7016507303821605,"curveRadius":-13.116815173188838},{"acceleration":3.033598946245888,"curvature":-0.07868734487957404,"pose":{"rotation":{"radians":0.6356758008477508},"translation":{"x":1.7890113421013005,"y":1.639403564287952}},"time":0.5554967643886023,"velocity":1.6549246464832057,"position":0.46286498286930927,"holonomicRotation":-139.92072000000002,"angularVelocity":-0.1266696316321183,"angularAcceleration":-0.7395260516703526,"curveRadius":-12.708523861498136},{"acceleration":3.0328227474426983,"curvature":-0.08119886956605199,"pose":{"rotation":{"radians":0.6346756928271913},"translation":{"x":1.7992056704074086,"y":1.646909654428051}},"time":0.5630420899664537,"velocity":1.6778082815325746,"position":0.47552459261068786,"holonomicRotation":-139.99668,"angularVelocity":-0.13254670196011503,"angularAcceleration":-0.7789021517173945,"curveRadius":-12.315442386627568},{"acceleration":3.0320928891835957,"curvature":-0.08377369722861895,"pose":{"rotation":{"radians":0.6336517951638871},"translation":{"x":1.8093273212591932,"y":1.6543462621417078}},"time":0.5704293629227353,"velocity":1.7002071793337743,"position":0.4880844871266561,"holonomicRotation":-140.07264,"angularVelocity":-0.13860292822041728,"angularAcceleration":-0.8198189367231201,"curveRadius":-11.936920932007975},{"acceleration":3.031405145415134,"curvature":-0.0864129249638827,"pose":{"rotation":{"radians":0.6326037471269452},"translation":{"x":1.8193770331493726,"y":1.6617138088792307}},"time":0.5776651420812416,"velocity":1.722141757505958,"position":0.5005455245636112,"holonomicRotation":-140.14860000000002,"angularVelocity":-0.14484245773446994,"angularAcceleration":-0.8623161897799869,"curveRadius":-11.572342915344688},{"acceleration":3.0307557737845388,"curvature":-0.08911764092613818,"pose":{"rotation":{"radians":0.6315311865421505},"translation":{"x":1.8293555445706644,"y":1.6690127160909272}},"time":0.584755540774245,"velocity":1.7436310242832123,"position":0.512908563699269,"holonomicRotation":-140.22456,"angularVelocity":-0.15126943226100278,"angularAcceleration":-0.906433446806718,"curveRadius":-11.221122884399652},{"acceleration":3.0301414478811415,"curvature":-0.09188892158583793,"pose":{"rotation":{"radians":0.6304337499990802},"translation":{"x":1.8392635940157864,"y":1.6762434052271058}},"time":0.5917062694498469,"velocity":1.7646927153361298,"position":0.5251744639593817,"holonomicRotation":-140.30052,"angularVelocity":-0.15788798474071025,"angularAcceleration":-0.9522098744753917,"curveRadius":-10.882704712840178},{"acceleration":3.0295592005251106,"curvature":-0.09472783013549806,"pose":{"rotation":{"radians":0.62931107306997},"translation":{"x":1.8491019199774565,"y":1.6834062977380746}},"time":0.5985226731626626,"velocity":1.785343413918784,"position":0.5373440854346687,"holonomicRotation":-140.37648000000002,"angularVelocity":-0.16470223543235826,"angularAcceleration":-0.9996841411896411,"curveRadius":-10.556559762528147},{"acceleration":3.0290063761000567,"curvature":-0.0976354136114055,"pose":{"rotation":{"radians":0.6281627905413081},"translation":{"x":1.8588712609483924,"y":1.6905018150741413}},"time":0.6052097646810596,"velocity":1.805598656765573,"position":0.5494182888979547,"holonomicRotation":-140.45244,"angularVelocity":-0.17171628734299338,"angularAcceleration":-1.048894260133668,"curveRadius":-10.24218531997065},{"acceleration":3.0284805903110503,"curvature":-0.10061270024450596,"pose":{"rotation":{"radians":0.6269885366580419},"translation":{"x":1.8685723554213118,"y":1.6975303786856144}},"time":0.6117722538230002,"velocity":1.8254730277560671,"position":0.5613979358215093,"holonomicRotation":-140.5284,"angularVelocity":-0.17893422112679658,"angularAcceleration":-1.099877444013386,"curveRadius":-9.93910309105938},{"acceleration":3.027979695928456,"curvature":-0.10366069734419923,"pose":{"rotation":{"radians":0.6257879453807877},"translation":{"x":1.8782059418889328,"y":1.7044924100228014}},"time":0.6182145735339108,"velocity":1.8449802410353844,"position":0.5732838883945723,"holonomicRotation":-140.60436,"angularVelocity":-0.18636008939773965,"angularAcceleration":-1.1526699394267328,"curveRadius":-9.64685773509278},{"acceleration":3.027501753642427,"curvature":-0.10678038743930741,"pose":{"rotation":{"radians":0.6245606506569148},"translation":{"x":1.8877727588439726,"y":1.711388330536011}},"time":0.6245409031392904,"velocity":1.8641332150097911,"position":0.5850770095410602,"holonomicRotation":-140.68032,"angularVelocity":-0.1939979103885641,"angularAcceleration":-1.2073068378115508,"curveRadius":-9.365015654849417},{"acceleration":3.0270450071823594,"curvature":-0.10997272664787525,"pose":{"rotation":{"radians":0.6233062867048531},"translation":{"x":1.8972735447791496,"y":1.7182185616755503}},"time":0.6307551891383534,"velocity":1.8829441384164578,"position":0.5967781629374392,"holonomicRotation":-140.75628,"angularVelocity":-0.20185166119661005,"angularAcceleration":-1.2638219111946645,"curveRadius":-9.093163645945854},{"acceleration":3.0266078617534338,"curvature":-0.1132386400245709,"pose":{"rotation":{"radians":0.6220244883135129},"translation":{"x":1.9067090381871812,"y":1.7249835248917285}},"time":0.6368611638500987,"velocity":1.901424529482694,"position":0.6083882130307529,"holonomicRotation":-140.83224,"angularVelocity":-0.2099252702233755,"angularAcceleration":-1.3222473737461131,"curveRadius":-8.83090789312744},{"acceleration":3.0261888655891345,"curvature":-0.11657901959478797,"pose":{"rotation":{"radians":0.6207148911552101},"translation":{"x":1.916079977560785,"y":1.7316836416348529}},"time":0.6428623621775721,"velocity":1.919585289041486,"position":0.6199080250567911,"holonomicRotation":-140.90820000000002,"angularVelocity":-0.2182226093591177,"angularAcceleration":-1.382613718623017,"curveRadius":-8.577872789425209},{"acceleration":3.025786693969972,"curvature":-0.1199947204943207,"pose":{"rotation":{"radians":0.6193771321143737},"translation":{"x":1.9253871013926795,"y":1.7383193333552316}},"time":0.6487621367180164,"velocity":1.9374367483433852,"position":0.6313384650583886,"holonomicRotation":-140.98416,"angularVelocity":-0.22674748529213776,"angularAcceleration":-1.444949442488024,"curveRadius":-8.333699981803196},{"acceleration":3.02540013519854,"curvature":-0.12348655676201573,"pose":{"rotation":{"radians":0.6180108496311041},"translation":{"x":1.9346311481755816,"y":1.7448910215031728}},"time":0.6545636714146975,"velocity":1.9549887121990832,"position":0.6426803999038315,"holonomicRotation":-141.06012,"angularVelocity":-0.23550363045337921,"angularAcceleration":-1.5092808401629678,"curveRadius":-8.098047481615412},{"acceleration":3.0250280785807955,"curvature":-0.12705529857248507,"pose":{"rotation":{"radians":0.6166156840599859},"translation":{"x":1.9438128564022101,"y":1.7513991275289844}},"time":0.6602699939193384,"velocity":1.9722504980010593,"position":0.6539346973053641,"holonomicRotation":-141.13608000000002,"angularVelocity":-0.24449469338326324,"angularAcceleration":-1.5756317527745272,"curveRadius":-7.870588721882385},{"acceleration":3.0246695037777402,"curvature":-0.13070166768646704,"pose":{"rotation":{"radians":0.6151912780454367},"translation":{"x":1.952932964565282,"y":1.7578440728829745}},"time":0.6658839868114006,"velocity":1.989230971096105,"position":0.6651022258377677,"holonomicRotation":-141.21204,"angularVelocity":-0.25372422835860603,"angularAcceleration":-1.6440232741285967,"curveRadius":-7.65101178661962},{"acceleration":3.0243234715183744,"curvature":-0.13442633378493515,"pose":{"rotation":{"radians":0.613737276912345},"translation":{"x":1.9619922111575152,"y":1.7642262790154515}},"time":0.6714083978012215,"velocity":2.0059385769189344,"position":0.6761838549570044,"holonomicRotation":-141.288,"angularVelocity":-0.26319568471114385,"angularAcceleration":-1.7144735194375604,"curveRadius":-7.439018619669204},{"acceleration":3.023989115431921,"curvature":-0.1382299099683554,"pose":{"rotation":{"radians":0.6122533290735546},"translation":{"x":1.970991334671628,"y":1.7705461673767229}},"time":0.6768458490276282,"velocity":2.0223813702432802,"position":0.6871804550188958,"holonomicRotation":-141.36396000000002,"angularVelocity":-0.27291239534871575,"angularAcceleration":-1.78699729578873,"curveRadius":-7.234324324083892},{"acceleration":3.023665634861707,"curvature":-0.14211294858267984,"pose":{"rotation":{"radians":0.6107390864540299},"translation":{"x":1.9799310736003375,"y":1.7768041594170974}},"time":0.6821988455466738,"velocity":2.0385670418614525,"position":0.6980928972978211,"holonomicRotation":-141.43992,"angularVelocity":-0.2828775647690328,"angularAcceleration":-1.861605809916332,"curveRadius":-7.036656476226797},{"acceleration":3.023352288509901,"curvature":-0.14607593667340663,"pose":{"rotation":{"radians":0.6091942049311574},"translation":{"x":1.9888121664363618,"y":1.783000676586882}},"time":0.6874697830961545,"velocity":2.054502942964268,"position":0.7089220540054101,"holonomicRotation":-141.51588,"angularVelocity":-0.2930942566421917,"angularAcceleration":-1.9383063785617065,"curveRadius":-6.845754494361231},{"acceleration":3.0230483887599546,"curvature":-0.1501192914500985,"pose":{"rotation":{"radians":0.6076183447929937},"translation":{"x":1.997635351672419,"y":1.789136140336386}},"time":0.6926609552102724,"velocity":2.0701961074596276,"position":0.7196687983092099,"holonomicRotation":-141.59184000000002,"angularVelocity":-0.3035653805193591,"angularAcceleration":-2.017102043041526,"curveRadius":-6.661369037519154},{"acceleration":3.022753296778197,"curvature":-0.1542433552299059,"pose":{"rotation":{"radians":0.6060111712126024},"translation":{"x":2.0064013678012262,"y":1.7952109721159166}},"time":0.6977745597499212,"velocity":2.085653272440271,"position":0.7303340043512939,"holonomicRotation":-141.6678,"angularVelocity":-0.31429367834957406,"angularAcceleration":-2.0979912989031653,"curveRadius":-6.483261457256684},{"acceleration":3.0224664179447953,"curvature":-0.15844839076648837,"pose":{"rotation":{"radians":0.6043723547403608},"translation":{"x":2.0151109533155016,"y":1.801225593375782}},"time":0.7028127049064098,"velocity":2.100880896984489,"position":0.7409185472667957,"holonomicRotation":-141.74376,"angularVelocity":-0.32528171010138546,"angularAcceleration":-2.1809676796747284,"curveRadius":-6.311203257808653},{"acceleration":3.0221871979621127,"curvature":-0.16273457598067592,"pose":{"rotation":{"radians":0.602701571813387},"translation":{"x":2.0237648467079628,"y":1.8071804255662902}},"time":0.7077774147297691,"velocity":2.115885179454242,"position":0.7514233032023325,"holonomicRotation":-141.81972000000002,"angularVelocity":-0.3365318390034832,"angularAcceleration":-2.2660194255795516,"curveRadius":-6.144975608126118},{"acceleration":3.0219151193318767,"curvature":-0.16710199862402675,"pose":{"rotation":{"radians":0.6009985052819595},"translation":{"x":2.032363786471328,"y":1.8130758901377493}},"time":0.7126706342270104,"velocity":2.130672073435165,"position":0.761849149334293,"holonomicRotation":-141.89568,"angularVelocity":-0.34804621627696053,"angularAcceleration":-2.3531291167234323,"curveRadius":-5.984368877896922},{"acceleration":3.0216496981042376,"curvature":-0.17155065168474642,"pose":{"rotation":{"radians":0.599262844953997},"translation":{"x":2.0409085110983143,"y":1.8189124085404675}},"time":0.7174942340706562,"velocity":2.145247302446493,"position":0.7721969638869555,"holonomicRotation":-141.97164,"angularVelocity":-0.3598267651179634,"angularAcceleration":-2.442273244643548,"curveRadius":-5.82918216969336},{"acceleration":3.0213904811418044,"curvature":-0.17608042693868756,"pose":{"rotation":{"radians":0.5974942881557181},"translation":{"x":2.0493997590816404,"y":1.824690402224753}},"time":0.7222500149534612,"velocity":2.1596163735361964,"position":0.7824676261504117,"holonomicRotation":-142.04760000000002,"angularVelocity":-0.37187516453358643,"angularAcceleration":-2.5334218948532965,"curveRadius":-5.679222940254496},{"acceleration":3.0211370434670597,"curvature":-0.18069111013536232,"pose":{"rotation":{"radians":0.5956925403108073},"translation":{"x":2.0578382689140233,"y":1.8304102926409132}},"time":0.7269397116213746,"velocity":2.1737845898622536,"position":0.7926620164982502,"holonomicRotation":-142.12356,"angularVelocity":-0.38419283218001393,"angularAcceleration":-2.6265382430177517,"curveRadius":-5.534306581274881},{"acceleration":3.020888986076699,"curvature":-0.18538237478038938,"pose":{"rotation":{"radians":0.5938573155355327},"translation":{"x":2.066224779088181,"y":1.8360725012392571}},"time":0.7315649966134162,"velocity":2.187757062352178,"position":0.8027810164049808,"holonomicRotation":-142.19952,"angularVelocity":-0.39678090721596154,"angularAcceleration":-2.721578250336348,"curveRadius":-5.394256067679767},{"acceleration":3.0206459337765876,"curvature":-0.19015377716836898,"pose":{"rotation":{"radians":0.5919883372508479},"translation":{"x":2.0745600280968315,"y":1.8416774494700916}},"time":0.7361274837341454,"velocity":2.2015387205213166,"position":0.8128255084631458,"holonomicRotation":-142.27548000000002,"angularVelocity":-0.4096402324498193,"angularAcceleration":-2.8184901992233202,"curveRadius":-5.258901584240234},{"acceleration":3.0204075333984055,"curvature":-0.19500474966059506,"pose":{"rotation":{"radians":0.5900853388117593},"translation":{"x":2.0828447544326925,"y":1.8472255587837256}},"time":0.7406287312817846,"velocity":2.2151343225238973,"position":0.8227963764000981,"holonomicRotation":-142.35144,"angularVelocity":-0.42277133593477745,"angularAcceleration":-2.917214249157429,"curveRadius":-5.1280802223561},{"acceleration":3.020173452043948,"curvature":-0.19993459564814728,"pose":{"rotation":{"radians":0.588148064151667},"translation":{"x":2.0910796965884813,"y":1.8527172506304668}},"time":0.7450702450527243,"velocity":2.228548464501777,"position":0.8326945050943892,"holonomicRotation":-142.4274,"angularVelocity":-0.43617441259951917,"angularAcceleration":-3.017682113795625,"curveRadius":-5.001635643687394},{"acceleration":3.01994337564344,"curvature":-0.20494248335090126,"pose":{"rotation":{"radians":0.5861762684433991},"translation":{"x":2.0992655930569164,"y":1.8581529464606235}},"time":0.7494534811410891,"velocity":2.2417855892907155,"position":0.8425207805917444,"holonomicRotation":-142.50336000000001,"angularVelocity":-0.44984930506070303,"angularAcceleration":-3.119816543189092,"curveRadius":-4.879417793956396},{"acceleration":3.019717007553609,"curvature":-0.21002743963047,"pose":{"rotation":{"radians":0.5841697187751125},"translation":{"x":2.107403182330715,"y":1.8635330677245034}},"time":0.7537798485502097,"velocity":2.2548499945369627,"position":0.8522760901205649,"holonomicRotation":-142.57932,"angularVelocity":-0.46379548441875573,"angularAcceleration":-3.2235309762763302,"curveRadius":-4.761282629352797},{"acceleration":3.019494067257852,"curvature":-0.21518834453662275,"pose":{"rotation":{"radians":0.582128194840875},"translation":{"x":2.115493202902596,"y":1.868858035872415}},"time":0.7580507116312345,"velocity":2.2677458402721875,"position":0.8619613221069309,"holonomicRotation":-142.65528,"angularVelocity":-0.4780120307082438,"angularAcceleration":-3.3287291162883417,"curveRadius":-4.647091840189377},{"acceleration":3.019274289311781,"curvature":-0.2204239251458927,"pose":{"rotation":{"radians":0.5800514896455358},"translation":{"x":2.1235363932652755,"y":1.8741282723546657}},"time":0.7622673923626561,"velocity":2.280477155990805,"position":0.8715773661890444,"holonomicRotation":-142.73124,"angularVelocity":-0.4924976130784948,"angularAcceleration":-3.4353045186249016,"curveRadius":-4.536712606574476},{"acceleration":3.0190574223364965,"curvature":-0.22573274999570242,"pose":{"rotation":{"radians":0.5779394102225366},"translation":{"x":2.1315334919114726,"y":1.879344198621564}},"time":0.7664311724832535,"velocity":2.293047847268872,"position":0.8811251132310813,"holonomicRotation":-142.8072,"angularVelocity":-0.507250469963843,"angularAcceleration":-3.5431402374895957,"curveRadius":-4.430017354677327},{"acceleration":3.0188432279296573,"curvature":-0.23111322289884403,"pose":{"rotation":{"radians":0.5757917783647062},"translation":{"x":2.139485237333904,"y":1.8845062361234177}},"time":0.770543295489787,"velocity":2.305461701959559,"position":0.8906054553363909,"holonomicRotation":-142.88316,"angularVelocity":-0.5222683889606922,"angularAcceleration":-3.652108405558007,"curveRadius":-4.3268835398383505},{"acceleration":3.0186314800544705,"curvature":-0.23656357757700963,"pose":{"rotation":{"radians":0.5736084313661975},"translation":{"x":2.147392368025289,"y":1.8896148063105354}},"time":0.7746049685097588,"velocity":2.317722395999334,"position":0.9000192858600059,"holonomicRotation":-142.95912,"angularVelocity":-0.5375486869013828,"angularAcceleration":-3.7620699316648967,"curveRadius":-4.227193426149744},{"acceleration":3.0184219640775334,"curvature":-0.2420818721156989,"pose":{"rotation":{"radians":0.5713892227753963},"translation":{"x":2.155255622478344,"y":1.8946703306332247}},"time":0.7786173640586257,"velocity":2.329833498852601,"position":0.9093674994204031,"holonomicRotation":-143.03508,"angularVelocity":-0.553088189779289,"angularAcceleration":-3.872874119376026,"curveRadius":-4.130833883844335},{"acceleration":3.0182144761661465,"curvature":-0.24766598332378129,"pose":{"rotation":{"radians":0.5691340231570607},"translation":{"x":2.1630757391857873,"y":1.8996732305417934}},"time":0.7825816216900208,"velocity":2.3417984786229296,"position":0.9186509919104734,"holonomicRotation":-143.11104,"angularVelocity":-0.5688832129565456,"angularAcceleration":-3.9843583959244846,"curveRadius":-4.037696201067183},{"acceleration":3.0180088227094677,"curvature":-0.2533136018570465,"pose":{"rotation":{"radians":0.5668427208631148},"translation":{"x":2.1708534566403364,"y":1.9046239274865497}},"time":0.7864988495467927,"velocity":2.3536207068552306,"position":0.927870660507642,"holonomicRotation":-143.187,"angularVelocity":-0.5849295414319088,"angularAcceleration":-4.096347994570409,"curveRadius":-3.947675895289405},{"acceleration":3.0178048195218943,"curvature":-0.2590222269085873,"pose":{"rotation":{"radians":0.5645152228099248},"translation":{"x":2.17858951333471,"y":1.9095228429178022}},"time":0.7903701258200031,"velocity":2.3653034630502257,"position":0.9370274036830907,"holonomicRotation":-143.26296000000002,"angularVelocity":-0.6012224106288958,"angularAcceleration":-4.208655762890219,"curveRadius":-3.8606725451129513},{"acceleration":3.017602291586898,"curvature":-0.26478916161048693,"pose":{"rotation":{"radians":0.5621514552617914},"translation":{"x":2.186284647761625,"y":1.914370398285858}},"time":0.7941965001224075,"velocity":2.3768499389136304,"position":0.9461221212100213,"holonomicRotation":-143.33892,"angularVelocity":-0.617756487296095,"angularAcceleration":-4.321081880779301,"curveRadius":-3.77658962292056},{"acceleration":3.0174010724493674,"curvature":-0.27061150844927095,"pose":{"rotation":{"radians":0.5597513646182222},"translation":{"x":2.193939598413799,"y":1.919167015041026}},"time":0.7979789947824104,"velocity":2.388263242357257,"position":0.9551557141709188,"holonomicRotation":-143.41488,"angularVelocity":-0.634525851139583,"angularAcceleration":-4.433413752255009,"curveRadius":-3.695334340104241},{"acceleration":3.017201003732745,"curvature":-0.2764861654119173,"pose":{"rotation":{"radians":0.557314918203399},"translation":{"x":2.2015551037839507,"y":1.9239131146336141}},"time":0.801718606063976,"velocity":2.3995464012695673,"position":0.9641290849637467,"holonomicRotation":-143.49084000000002,"angularVelocity":-0.6515239770597663,"angularAcceleration":-4.545425885298633,"curveRadius":-3.6168174943226195},{"acceleration":3.017001934902629,"curvature":-0.28240982181940205,"pose":{"rotation":{"radians":0.5548421050573271},"translation":{"x":2.2091319023647973,"y":1.9286091185139298}},"time":0.8054163053175349,"velocity":2.4107023670722425,"position":0.9730431373070224,"holonomicRotation":-143.5668,"angularVelocity":-0.6687437177839304,"angularAcceleration":-4.656879736119901,"curveRadius":-3.540953333554698},{"acceleration":3.01680372274146,"curvature":-0.2883789551977863,"pose":{"rotation":{"radians":0.552332936725004},"translation":{"x":2.2166707326490567,"y":1.933255448132282}},"time":0.8090730400665219,"velocity":2.4217340180760645,"position":0.981898776243725,"holonomicRotation":-143.64276,"angularVelocity":-0.6861772878161798,"angularAcceleration":-4.7675238235639155,"curveRadius":-3.4676594181920954},{"acceleration":3.0166062311456057,"curvature":-0.29438982828637644,"pose":{"rotation":{"radians":0.5497874480428426},"translation":{"x":2.2241723331294465,"y":1.9378525249389777}},"time":0.812689735033802,"velocity":2.4326441626505146,"position":0.9906969081439665,"holonomicRotation":-143.71872000000002,"angularVelocity":-0.7038162480359018,"angularAcceleration":-4.877093694464121,"curveRadius":-3.3968564940607267},{"acceleration":3.016409330740238,"curvature":-0.30043848668950585,"pose":{"rotation":{"radians":0.5472056979205333},"translation":{"x":2.231637442298685,"y":1.9424007703843258}},"time":0.8162672931119164,"velocity":2.443435542218604,"position":0.9994384407063823,"holonomicRotation":-143.79468,"angularVelocity":-0.7216514913071992,"angularAcceleration":-4.985312015031782,"curveRadius":-3.3284683697447526},{"acceleration":3.0162128987332104,"curvature":-0.3065207564195031,"pose":{"rotation":{"radians":0.5445877701150268},"translation":{"x":2.2390667986494894,"y":1.9469006059186338}},"time":0.819806596280764,"velocity":2.4541108340890094,"position":1.008124282958177,"holonomicRotation":-143.87064,"angularVelocity":-0.7396732296201899,"angularAcceleration":-5.09188884174009,"curveRadius":-3.2624218068658424},{"acceleration":3.0160168185841125,"curvature":-0.3126322433723417,"pose":{"rotation":{"radians":0.5419337739956469},"translation":{"x":2.2464611406745774,"y":1.9513524529922102}},"time":0.8233085064760659,"velocity":2.464672654135211,"position":1.0167553452537748,"holonomicRotation":-143.94660000000002,"angularVelocity":-0.7578709822257731,"angularAcceleration":-5.196521781168768,"curveRadius":-3.1986464006817448},{"acceleration":3.015820979798885,"curvature":-0.31876833175077657,"pose":{"rotation":{"radians":0.5392438452967694},"translation":{"x":2.2538212068666676,"y":1.9557567330553627}},"time":0.8267738664116976,"velocity":2.4751235593316436,"position":1.0253325392720207,"holonomicRotation":-144.02256,"angularVelocity":-0.7762335655869423,"angularAcceleration":-5.298896421223274,"curveRadius":-3.1370744844937497},{"acceleration":3.0156252777140984,"curvature":-0.3249241845936412,"pose":{"rotation":{"radians":0.5365181468572633},"translation":{"x":2.261147735718477,"y":1.9601138675583996}},"time":0.8302035003587457,"velocity":2.4854660501556682,"position":1.0338567780118701,"holonomicRotation":-144.09852,"angularVelocity":-0.7947490844765288,"angularAcceleration":-5.398686616547776,"curveRadius":-3.0776410233994325},{"acceleration":3.0154296133990144,"curvature":-0.3310947438491106,"pose":{"rotation":{"radians":0.5337568693418633},"translation":{"x":2.268441465722724,"y":1.9644242779516286}},"time":0.8335982148839365,"velocity":2.4957025728639644,"position":1.0423289757865275,"holonomicRotation":-144.17448000000002,"angularVelocity":-0.8134049254833317,"angularAcceleration":-5.495555183908811,"curveRadius":-3.02028352481406},{"acceleration":3.0152338935042144,"curvature":-0.33727473210153847,"pose":{"rotation":{"radians":0.5309602319444888},"translation":{"x":2.2757031353721255,"y":1.9686883856853583}},"time":0.8369587995498821,"velocity":2.505835521650714,"position":1.0507500482159686,"holonomicRotation":-144.25044,"angularVelocity":-0.8321877516475427,"angularAcceleration":-5.589154278583258,"curveRadius":-2.9649419444174203},{"acceleration":3.0150380298908206,"curvature":-0.34345865402185505,"pose":{"rotation":{"radians":0.5281284830679303},"translation":{"x":2.2829334831594004,"y":1.972906612209896}},"time":0.8402860275794218,"velocity":2.515867240693895,"position":1.0591209122178062,"holonomicRotation":-144.3264,"angularVelocity":-0.8510834999638606,"angularAcceleration":-5.679126332357684,"curveRadius":-2.9115586062256207},{"acceleration":3.0148419399043975,"curvature":-0.3496407999263613,"pose":{"rotation":{"radians":0.5252619009805963},"translation":{"x":2.2901332475772658,"y":1.9770793789755507}},"time":0.8435806564861656,"velocity":2.5258000260983677,"position":1.0674424859964442,"holonomicRotation":-144.40236000000002,"angularVelocity":-0.87007738002489,"angularAcceleration":-5.765104537919472,"curveRadius":-2.86007811505583},{"acceleration":3.014645545830457,"curvature":-0.3558152493765942,"pose":{"rotation":{"radians":0.5223607944431414},"translation":{"x":2.2973031671184394,"y":1.9812071074326294}},"time":0.8468434286732013,"velocity":2.535636127739074,"position":1.075715689030474,"holonomicRotation":-144.47832,"angularVelocity":-0.8891538762596471,"angularAcceleration":-5.846714125661638,"curveRadius":-2.8104472805818443},{"acceleration":3.01444877510864,"curvature":-0.36197587512005597,"pose":{"rotation":{"radians":0.519425503306834},"translation":{"x":2.30444398027564,"y":1.9852902190314408}},"time":0.8500750720017917,"velocity":2.5453777510125315,"position":1.083941442058276,"holonomicRotation":-144.55428,"angularVelocity":-0.9082967511726507,"angularAcceleration":-5.923572921444137,"curveRadius":-2.762615049050801},{"acceleration":3.0142515601024207,"curvature":-0.36811634947489613,"pose":{"rotation":{"radians":0.5164563990765614},"translation":{"x":2.3115564255415837,"y":1.9893291352222926}},"time":0.8532763003317547,"velocity":2.5550270585003667,"position":1.0921206670617696,"holonomicRotation":-144.63024000000001,"angularVelocity":-0.9274890523997389,"angularAcceleration":-5.99529282164938,"curveRadius":-2.7165324263007107},{"acceleration":3.0140538379970887,"curvature":-0.3742301501906977,"pose":{"rotation":{"radians":0.5134538854380661},"translation":{"x":2.31864124140899,"y":1.9933242774554933}},"time":0.8564478140351148,"velocity":2.5645861715502396,"position":1.100254287248289,"holonomicRotation":-144.7062,"angularVelocity":-0.946713121659914,"angularAcceleration":-6.061480749652078,"curveRadius":-2.672152416074511},{"acceleration":3.013855550913814,"curvature":-0.3803105680276713,"pose":{"rotation":{"radians":0.5104183987457196},"translation":{"x":2.3256991663705753,"y":1.997276067181351}},"time":0.8595903004844938,"velocity":2.574057171779372,"position":1.1083432270305325,"holonomicRotation":-144.78216,"angularVelocity":-0.9659506067071256,"angularAcceleration":-6.1217400160988475,"curveRadius":-2.629429955591558},{"acceleration":3.0136566454611544,"curvature":-0.3863507150304289,"pose":{"rotation":{"radians":0.5073504084669906},"translation":{"x":2.332730938919058,"y":2.001184925850173}},"time":0.8627044345176267,"velocity":2.5834421025031795,"position":1.116388412004566,"holonomicRotation":-144.85812,"angularVelocity":-0.9851824764403267,"angularAcceleration":-6.175671801079644,"curveRadius":-2.5883218565319344},{"acceleration":3.0134570730237655,"curvature":-0.3923435341401717,"pose":{"rotation":{"radians":0.5042504175825773},"translation":{"x":2.3397372975471558,"y":2.005051274912268}},"time":0.8657908788792833,"velocity":2.592742970095308,"position":1.1243907689258414,"holonomicRotation":-144.93408,"angularVelocity":-1.0043890383786107,"angularAcceleration":-6.222876451910201,"curveRadius":-2.5487867467766967},{"acceleration":3.013256789677169,"curvature":-0.3982818091185026,"pose":{"rotation":{"radians":0.5011189629364137},"translation":{"x":2.3467189807475863,"y":2.0088755358179435}},"time":0.8688502846418004,"velocity":2.60196174528159,"position":1.132351225683205,"holonomicRotation":-145.01004,"angularVelocity":-1.0235499601031213,"angularAcceleration":-6.262955361875993,"curveRadius":-2.510785019816121},{"acceleration":3.0130557558625095,"curvature":-0.40415817646824087,"pose":{"rotation":{"radians":0.4979566155355779},"translation":{"x":2.353676727013068,"y":2.012658130017508}},"time":0.8718832916053547,"velocity":2.6111003643706985,"position":1.1402707112708805,"holonomicRotation":-145.086,"angularVelocity":-1.0426442928867654,"angularAcceleration":-6.295512345697905,"curveRadius":-2.4742787804976674},{"acceleration":2.9843043569222556,"curvature":-0.4099651374181016,"pose":{"rotation":{"radians":0.4947639807949815},"translation":{"x":2.3606112748363177,"y":2.0163994789612696}},"time":0.8748906268846293,"velocity":2.6200751681473635,"position":1.1481501557584013,"holonomicRotation":-145.16196,"angularVelocity":-1.0616158306653927,"angularAcceleration":-6.308421248994796,"curveRadius":-2.4392317998009507},{"acceleration":-0.021195685830428294,"curvature":-0.4156950714448627,"pose":{"rotation":{"radians":0.4915416987246002},"translation":{"x":2.3675233627100543,"y":2.020100004099536}},"time":0.8778831075590424,"velocity":2.620011740467135,"position":1.1559904902584848,"holonomicRotation":-145.23792,"angularVelocity":-1.076792942368205,"angularAcceleration":-5.071749278978603,"curveRadius":-2.405609468796983},{"acceleration":-3.002178729547097,"curvature":-0.4213402507536688,"pose":{"rotation":{"radians":0.4882904440578484},"translation":{"x":2.3744137291269944,"y":2.0237601268826153}},"time":0.8808712480002304,"velocity":2.611040808793701,"position":1.1637926468928335,"holonomicRotation":-145.31388,"angularVelocity":-1.0880528310975877,"angularAcceleration":-3.7681926104202907,"curveRadius":-2.3733787555574346},{"acceleration":-3.002023693257749,"curvature":-0.4268928556561913,"pose":{"rotation":{"radians":0.4850109263158351},"translation":{"x":2.381283112579857,"y":2.0273802687608153}},"time":0.8838553624864781,"velocity":2.6020824264025917,"position":1.171557558755872,"holonomicRotation":-145.38984,"angularVelocity":-1.09899193114975,"angularAcceleration":-3.6657776042357866,"curveRadius":-2.3425081651058943},{"acceleration":-3.001865638557353,"curvature":-0.4323449908540233,"pose":{"rotation":{"radians":0.4817038898077368},"translation":{"x":2.3881322515613586,"y":2.030960851184445}},"time":0.8868357700638767,"velocity":2.593135643307103,"position":1.1792861598764068,"holonomicRotation":-145.4658,"angularVelocity":-1.1095920347192154,"angularAcceleration":-3.5565952958412312,"curveRadius":-2.312967702076695},{"acceleration":-3.001704575589711,"curvature":-0.4376887025269774,"pose":{"rotation":{"radians":0.4783701135623599},"translation":{"x":2.3949618845642178,"y":2.034502295603812}},"time":0.889812794599055,"velocity":2.5841994951382152,"position":1.1869793851772288,"holonomicRotation":-145.54176,"angularVelocity":-1.1198349916109052,"angularAcceleration":-3.4406692893030306,"curveRadius":-2.2847288363317166},{"acceleration":-3.0015405169850533,"curvature":-0.4429159968955692,"pose":{"rotation":{"radians":0.4750104111911879},"translation":{"x":2.4017727500811525,"y":2.0380050234692235}},"time":0.8927867648331086,"velocity":2.575273002984396,"position":1.194638170432666,"holonomicRotation":-145.61772000000002,"angularVelocity":-1.1297027565042905,"angularAcceleration":-3.3180442697086177,"curveRadius":-2.257764467775094},{"acceleration":-3.001373477846149,"curvature":-0.4480188588229047,"pose":{"rotation":{"radians":0.47162563067901875},"translation":{"x":2.40856558660488,"y":2.0414694562309887}},"time":0.895758014436822,"velocity":2.5663551732277496,"position":1.202263452224107,"holonomicRotation":-145.69368,"angularVelocity":-1.1391774383205389,"angularAcceleration":-3.18878690110956,"curveRadius":-2.2320488977346495},{"acceleration":-3.0012034756533437,"curvature":-0.45298927178425763,"pose":{"rotation":{"radians":0.468216654100293},"translation":{"x":2.4153411326281184,"y":2.044896015339415}},"time":0.8987268820672902,"velocity":2.5574449973764337,"position":1.2098561678935207,"holonomicRotation":-145.76964,"angularVelocity":-1.1482413509248013,"angularAcceleration":-3.052986435381411,"curveRadius":-2.207557799462111},{"acceleration":-3.0010305302920686,"curvature":-0.4578192382536228,"pose":{"rotation":{"radians":0.46478439726146314},"translation":{"x":2.422100126643585,"y":2.0482851222448106}},"time":0.901693711426047,"velocity":2.5485414518926377,"position":1.2174172554950045,"holonomicRotation":-145.84560000000002,"angularVelocity":-1.1568770642973831,"angularAcceleration":-2.9107549940790918,"curveRadius":-2.1842681924301743},{"acceleration":-3.0008546642220284,"curvature":-0.4625008010269799,"pose":{"rotation":{"radians":0.4613298092654472},"translation":{"x":2.4288433071439983,"y":2.0516371983974837}},"time":0.9046588513188228,"velocity":2.5396434980153306,"position":1.2249476537443984,"holonomicRotation":-145.92156,"angularVelocity":-1.1650674575026365,"angularAcceleration":-2.7622282595193126,"curveRadius":-2.162158417411401},{"acceleration":-3.000675902164112,"curvature":-0.46702606473176145,"pose":{"rotation":{"radians":0.4578538719989673},"translation":{"x":2.4355714126220755,"y":2.0549526652477423}},"time":0.9076226557170539,"velocity":2.5307500815788306,"position":1.2324483019670054,"holonomicRotation":-145.99752,"angularVelocity":-1.172795771729898,"angularAcceleration":-2.6075655437565626,"curveRadius":-2.1412081155991896},{"acceleration":-3.000494271333092,"curvature":-0.4713872182848919,"pose":{"rotation":{"radians":0.45435759954048693},"translation":{"x":2.4422851815705346,"y":2.058231944245894}},"time":0.910585483821284,"velocity":2.5218601328251435,"position":1.2399201400434772,"holonomicRotation":-146.07348000000002,"angularVelocity":-1.1800456643058972,"angularAcceleration":-2.4469501168995715,"curveRadius":-2.121398207695209},{"acceleration":-3.0003098012746108,"curvature":-0.475576557401262,"pose":{"rotation":{"radians":0.45084203748962715},"translation":{"x":2.4489853524820937,"y":2.0614754568422478}},"time":0.9135477001265987,"velocity":2.5129725662108124,"position":1.2473641083539153,"holonomicRotation":-146.14944,"angularVelocity":-1.186801262471049,"angularAcceleration":-2.2805890822459856,"curveRadius":-2.102710876802664},{"acceleration":-3.000122523835559,"curvature":-0.479586507626559,"pose":{"rotation":{"radians":0.4473082622157665},"translation":{"x":2.45567266384947,"y":2.0646836244871105}},"time":0.9165096744902465,"velocity":2.5040862802074093,"position":1.2547811477202517,"holonomicRotation":-146.2254,"angularVelocity":-1.1930472178390925,"angularAcceleration":-2.108713513763011,"curveRadius":-2.0851295524324316},{"acceleration":-2.9999324732381885,"curvature":-0.483409647626316,"pose":{"rotation":{"radians":0.44375738002817666},"translation":{"x":2.462347854165382,"y":2.067856868630791}},"time":0.9194717822016132,"velocity":2.495200157094851,"position":1.2621721993469859,"holonomicRotation":-146.30136000000002,"angularVelocity":-1.1987687598137378,"angularAcceleration":-1.9315779614257496,"curveRadius":-2.0686388964520983},{"acceleration":-2.9997396857919,"curvature":-0.487038732205289,"pose":{"rotation":{"radians":0.44019052626556743},"translation":{"x":2.4690116619225466,"y":2.070995610723597}},"time":0.9224344040547177,"velocity":2.486313062748099,"position":1.2695382047603425,"holonomicRotation":-146.37732,"angularVelocity":-1.203951749316774,"angularAcceleration":-1.7494603631594223,"curveRadius":-2.0532247927634955},{"acceleration":-2.965553074573901,"curvature":-0.49046671610024933,"pose":{"rotation":{"radians":0.436608864308079},"translation":{"x":2.4756648256136824,"y":2.074100272215837}},"time":0.9253978055008867,"velocity":2.477524938478216,"position":1.2768801057459487,"holonomicRotation":-146.45328,"angularVelocity":-1.208632047513737,"angularAcceleration":-1.579366913994612,"curveRadius":-2.0388743357573813},{"acceleration":-2.82839802138736,"curvature":-0.4936867766212113,"pose":{"rotation":{"radians":0.4330135845099661},"translation":{"x":2.482308083731507,"y":2.077171274557818}},"time":0.9283618879695127,"velocity":2.469141333488725,"position":1.2841988442851024,"holonomicRotation":-146.52924000000002,"angularVelocity":-1.2129486396441258,"angularAcceleration":-1.4562996057223925,"curveRadius":-2.0255758253117344},{"acceleration":-2.6225219466555463,"curvature":-0.4966923372189867,"pose":{"rotation":{"radians":0.4294059030579156},"translation":{"x":2.488942174768737,"y":2.08020903919985}},"time":0.9313263048778423,"velocity":2.461367085087594,"position":1.291495362489742,"holonomicRotation":-146.6052,"angularVelocity":-1.2169953024871074,"angularAcceleration":-1.3650788563548677,"curveRadius":-2.0133187590512596},{"acceleration":-2.417065926529,"curvature":-0.4994770896121254,"pose":{"rotation":{"radians":0.4257870607516048},"translation":{"x":2.4955678372180925,"y":2.083213987592239}},"time":0.9342907064433206,"velocity":2.454201931071127,"position":1.2987706025362091,"holonomicRotation":-146.68116,"angularVelocity":-1.2207665616068286,"angularAcceleration":-1.2721822723476885,"curveRadius":-2.0020938313237977},{"acceleration":-2.2118669001003823,"curvature":-0.5020350164109372,"pose":{"rotation":{"radians":0.42215832171522516},"translation":{"x":2.5021858095722895,"y":2.086186541185294}},"time":0.9372547398068755,"velocity":2.447645883783487,"position":1.3060255065979112,"holonomicRotation":-146.75712000000001,"angularVelocity":-1.2242571493957544,"angularAcceleration":-1.1776479414318548,"curveRadius":-1.9918929303956303},{"acceleration":-2.0067596891932915,"curvature":-0.5043604123967721,"pose":{"rotation":{"radians":0.418520972034377},"translation":{"x":2.508796830324046,"y":2.089127121429323}},"time":0.9402180491605673,"velocity":2.4416992340258887,"position":1.3132610167770022,"holonomicRotation":-146.83308,"angularVelocity":-1.2274620185424092,"angularAcceleration":-1.081516900239283,"curveRadius":-1.982709140965085},{"acceleration":-1.8015765857129138,"curvature":-0.5064479055686463,"pose":{"rotation":{"radians":0.4148763183284583},"translation":{"x":2.51540163796608,"y":2.092036149774634}},"time":0.9431802758789265,"velocity":2.4363625557285196,"position":1.3204780750351912,"holonomicRotation":-146.90904,"angularVelocity":-1.2303763528058007,"angularAcceleration":-0.9838322790518034,"curveRadius":-1.9745367470267},{"acceleration":-1.5961471419765008,"curvature":-0.5082924771166965,"pose":{"rotation":{"radians":0.41122568625644274},"translation":{"x":2.5220009709911095,"y":2.0949140476715344}},"time":0.9461410586540596,"velocity":2.4316367107639776,"position":1.3276776231238026,"holonomicRotation":-146.985,"angularVelocity":-1.232995578965232,"angularAcceleration":-0.8846397585900467,"curveRadius":-1.9673712380567354},{"acceleration":-1.3902978867053597,"curvature":-0.5098894807878689,"pose":{"rotation":{"radians":0.40757041896195023},"translation":{"x":2.5285955678918524,"y":2.0977612365703338}},"time":0.9491000336343673,"velocity":2.4275228541020417,"position":1.3348606025132157,"holonomicRotation":-147.06096,"angularVelocity":-1.2353153773920602,"angularAcceleration":-0.7839871719993097,"curveRadius":-1.9612093162910995},{"acceleration":-1.1838518621392504,"curvature":-0.5112346605337821,"pose":{"rotation":{"radians":0.40391187545979523},"translation":{"x":2.5351861671610263,"y":2.100578137921339}},"time":0.952056834566105,"velocity":2.424022439813029,"position":1.3420279543218079,"holonomicRotation":-147.13692,"angularVelocity":-1.2373316928052123,"angularAcceleration":-0.6819246407525649,"curveRadius":-1.9560489090389455},{"acceleration":-0.9766284042116727,"curvature":-0.5123241679728735,"pose":{"rotation":{"radians":0.40025142896981425},"translation":{"x":2.541773507291348,"y":2.1033651731748577}},"time":0.9550110929379377,"velocity":2.421137227173717,"position":1.3491806192445417,"holonomicRotation":-147.21288,"angularVelocity":-1.239040743653769,"angularAcceleration":-0.5785041907138351,"curveRadius":-1.9518891797682048},{"acceleration":-0.7684427323908094,"curvature":-0.5131545774851265,"pose":{"rotation":{"radians":0.3965904651997749},"translation":{"x":2.548358326775537,"y":2.106122763781199}},"time":0.9579624381279983,"velocity":2.4188692874116384,"position":1.3563195374813293,"holonomicRotation":-147.28884,"angularVelocity":-1.240439031790853,"angularAcceleration":-0.47377993661774365,"curveRadius":-1.9487305460682252},{"acceleration":-0.5591055036167808,"curvature":-0.5137229008816682,"pose":{"rotation":{"radians":0.39293038058424923},"translation":{"x":2.554941364106311,"y":2.1088513311906705}},"time":0.9609104975528789,"velocity":2.4172210111621983,"position":1.3634456486653055,"holonomicRotation":-147.3648,"angularVelocity":-1.2415233507967331,"angularAcceleration":-0.3678077167403587,"curveRadius":-1.9465746967553266},{"acceleration":-0.3484225759178572,"curvature":-0.5140266000875252,"pose":{"rotation":{"radians":0.389272580482241},"translation":{"x":2.5615233577763856,"y":2.1115512968535803}},"time":0.9638548968188112,"velocity":2.4161951159854316,"position":1.370559891791162,"holonomicRotation":-147.44076,"angularVelocity":-1.2422907940272436,"angularAcceleration":-0.26064509640050076,"curveRadius":-1.9454246138813172},{"acceleration":-0.13619441054703946,"curvature":-0.5140635983804741,"pose":{"rotation":{"radians":0.3856184773401128},"translation":{"x":2.5681050462784807,"y":2.1142230822202364}},"time":0.9667952598740484,"velocity":2.4157946549723293,"position":1.3776632051436821,"holonomicRotation":-147.51672000000002,"angularVelocity":-1.242738761670879,"angularAcceleration":-0.15235113325118801,"curveRadius":-1.94528459737363},{"acceleration":0.07778428694031264,"curvature":-0.5138322901417923,"pose":{"rotation":{"radians":0.3819694888242897},"translation":{"x":2.5746871681053136,"y":2.1168671087409474}},"time":0.9697312091623994,"velocity":2.4160230256942166,"position":1.3847565262266088,"holonomicRotation":-147.59268,"angularVelocity":-1.242864967150874,"angularAcceleration":-0.04298626018365985,"curveRadius":-1.9461602923476247},{"acceleration":0.29372505288594836,"curvature":-0.5133315487727683,"pose":{"rotation":{"radians":0.3783270359281947},"translation":{"x":2.581270461749602,"y":2.11948379786602}},"time":0.9726623657774993,"velocity":2.416883979826004,"position":1.3918407916920048,"holonomicRotation":-147.66864,"angularVelocity":-1.242667443060133,"angularAcceleration":0.06738776417591656,"curveRadius":-1.948058720315787},{"acceleration":0.5118461671219707,"curvature":-0.5125607330349442,"pose":{"rotation":{"radians":0.3746925410616653},"translation":{"x":2.5878556657040632,"y":2.1220735710457634}},"time":0.9755883496174322,"velocity":2.4183816334395343,"position":1.3989169372702395,"holonomicRotation":-147.7446,"angularVelocity":-1.2421445453412923,"angularAcceleration":0.1787083413463824,"curveRadius":-1.9509883132850607},{"acceleration":-0.6201048899070537,"curvature":-0.5115196913540206,"pose":{"rotation":{"radians":0.371067426124442},"translation":{"x":2.5944435184614156,"y":2.124636849730485}},"time":0.9785135564863802,"velocity":2.41656769835611,"position":1.4059858977007484,"holonomicRotation":-147.82056,"angularVelocity":-1.2392678875826255,"angularAcceleration":0.9834031873791398,"curveRadius":-1.9549589525145066},{"acceleration":-2.4287741276652506,"curvature":-0.5102087648107333,"pose":{"rotation":{"radians":0.36745311057395114},"translation":{"x":2.6010347585143765,"y":2.1271740553704936}},"time":0.9814448120954061,"velocity":2.409448340571334,"position":1.4130486066637065,"holonomicRotation":-147.89652,"angularVelocity":-1.2330263998000053,"angularAcceleration":2.129288132840194,"curveRadius":-1.9599820092682243},{"acceleration":-2.9956438422700513,"curvature":-0.5086287875162183,"pose":{"rotation":{"radians":0.3638510094885308},"translation":{"x":2.6076301243556643,"y":2.1296856094160965}},"time":0.9843846051726025,"velocity":2.4006417675420826,"position":1.4201059967127552,"holonomicRotation":-147.97248000000002,"angularVelocity":-1.2252906891173463,"angularAcceleration":2.6313793112392685,"curveRadius":-1.966070392679285},{"acceleration":-2.9954105966568823,"curvature":-0.506781086143073,"pose":{"rotation":{"radians":0.36026253163705},"translation":{"x":2.6142303544779963,"y":2.1321719333176024}},"time":0.987333420451633,"velocity":2.391808855007691,"position":1.4271589992089222,"holonomicRotation":-148.04844,"angularVelocity":-1.216921886222934,"angularAcceleration":2.838022087692044,"curveRadius":-1.9732385981699458},{"acceleration":-2.9951760360167676,"curvature":-0.5046674764165978,"pose":{"rotation":{"radians":0.35668907755504753},"translation":{"x":2.6208361873740906,"y":2.1346334485253182}},"time":0.990291749646319,"velocity":2.3829481382971185,"position":1.4342085442558694,"holonomicRotation":-148.1244,"angularVelocity":-1.2079298302641002,"angularAcceleration":3.0395724637359285,"curveRadius":-1.981502765148492},{"acceleration":-2.99494022030299,"curvature":-0.502290259135342,"pose":{"rotation":{"radians":0.3531320376387592},"translation":{"x":2.6274483615366644,"y":2.1370705764895535}},"time":0.9932600916119425,"velocity":2.3740581315566596,"position":1.4412555606365987,"holonomicRotation":-148.20036000000002,"angularVelocity":-1.1983255155513068,"angularAcceleration":3.235582296117316,"curveRadius":-1.9908807344212307},{"acceleration":-2.9947032080080533,"curvature":-0.4996522130850495,"pose":{"rotation":{"radians":0.34959279025750156},"translation":{"x":2.634067615458436,"y":2.139483738660615}},"time":0.9962389525152663,"velocity":2.365137327253266,"position":1.448300975751745,"holonomicRotation":-148.27632,"angularVelocity":-1.1881210624197358,"angularAcceleration":3.425622566057055,"curveRadius":-2.0013921159792454},{"acceleration":-2.994465056118016,"curvature":-0.49675658712578985,"pose":{"rotation":{"radians":0.3460726998951782},"translation":{"x":2.640694687632124,"y":2.1418733564888117}},"time":0.9992288460137627,"velocity":2.356184195650504,"position":1.4553457155595806,"holonomicRotation":-148.35228,"angularVelocity":-1.1773296821754904,"angularAcceleration":3.6092858323121626,"curveRadius":-2.0130583587949036},{"acceleration":-2.994225819750998,"curvature":-0.4936070901016645,"pose":{"rotation":{"radians":0.34257311532181944},"translation":{"x":2.6473303165504447,"y":2.144239851424451}},"time":1.002230293444561,"velocity":2.3471971842565824,"position":1.4623907045178446,"holonomicRotation":-148.42824000000002,"angularVelocity":-1.165965639594068,"angularAcceleration":3.7861874457017173,"curveRadius":-2.0259028284906475},{"acceleration":-2.9939855522040695,"curvature":-0.4902078792631958,"pose":{"rotation":{"radians":0.33909536780340543},"translation":{"x":2.653975240706116,"y":2.1465836449178415}},"time":1.0052438240236568,"velocity":2.3381747172416447,"position":1.4694368655275207,"holonomicRotation":-148.5042,"angularVelocity":-1.154044210647303,"angularAcceleration":3.955967471995071,"curveRadius":-2.0399508908405233},{"acceleration":-2.9937443043793923,"curvature":-0.4865635468279827,"pose":{"rotation":{"radians":0.33564076935418186},"translation":{"x":2.6606301985918566,"y":2.148905158419291}},"time":1.0082699750559474,"velocity":2.3291151948245328,"position":1.4764851198786628,"holonomicRotation":-148.58016,"angularVelocity":-1.1415816369907412,"angularAcceleration":4.1182920229623265,"curveRadius":-2.0552300033967303},{"acceleration":-2.993502124931275,"curvature":-0.48267910551412335,"pose":{"rotation":{"radians":0.33221061103625615},"translation":{"x":2.667295928700384,"y":2.151204813379107}},"time":1.0113092921566924,"velocity":2.3200169926251126,"position":1.4835363871983673,"holonomicRotation":-148.65612000000002,"angularVelocity":-1.12859507719181,"angularAcceleration":4.27285451582128,"curveRadius":-2.0717698126477937},{"acceleration":-2.993259060036351,"curvature":-0.4785599722347709,"pose":{"rotation":{"radians":0.3288061613120168},"translation":{"x":2.6739731695244155,"y":2.1534830312475988}},"time":1.0143623294850321,"velocity":2.3108784609814306,"position":1.490591585401,"holonomicRotation":-148.73208,"angularVelocity":-1.1151025546388402,"angularAcceleration":4.41937687028125,"curveRadius":-2.0896022609877245},{"acceleration":-2.9930151527093316,"curvature":-0.4742119503435788,"pose":{"rotation":{"radians":0.32542866445183405},"translation":{"x":2.680662659556669,"y":2.1557402334750733}},"time":1.0174296499902238,"velocity":2.301697924231176,"position":1.4976516306407512,"holonomicRotation":-148.80804,"angularVelocity":-1.101122903350365,"angularAcceleration":4.557610221955552,"curveRadius":-2.108761703022191},{"acceleration":-2.992770443275678,"curvature":-0.4696412112575812,"pose":{"rotation":{"radians":0.3220793390045733},"translation":{"x":2.687365137289863,"y":2.1579768415118386}},"time":1.0205118256713033,"velocity":2.292473679951858,"position":1.5047174372666137,"holonomicRotation":-148.88400000000001,"angularVelocity":-1.0866757102202838,"angularAcceleration":4.687336033039233,"curveRadius":-2.1292850287185217},{"acceleration":-2.9925249688148976,"curvature":-0.46485427418164815,"pose":{"rotation":{"radians":0.3187593763314869},"translation":{"x":2.6940813412167146,"y":2.160193276808203}},"time":1.0236094378509106,"velocity":2.283203998160678,"position":1.5117899177798444,"holonomicRotation":-148.95996,"angularVelocity":-1.071781256202078,"angularAcceleration":4.808366301069244,"curveRadius":-2.151211800215128},{"acceleration":-2.9922787627029264,"curvature":-0.4598579855947459,"pose":{"rotation":{"radians":0.3154699392089455},"translation":{"x":2.7008120098299417,"y":2.162389960814475}},"time":1.0267230774640657,"velocity":2.2738871204715236,"position":1.5188699827939875,"holonomicRotation":-149.03592,"angularVelocity":-1.0564604550390497,"angularAcceleration":4.920544143355084,"curveRadius":-2.1745843963254763},{"acceleration":-2.9920318550688467,"curvature":-0.45465949700392033,"pose":{"rotation":{"radians":0.3122121605026469},"translation":{"x":2.707557881622262,"y":2.1645673149809626}},"time":1.0298533453627277,"velocity":2.2645212592038275,"position":1.525958540997511,"holonomicRotation":-149.11188,"angularVelocity":-1.04073479068393,"angularAcceleration":5.023743929981704,"curveRadius":-2.199448172950795},{"acceleration":-2.9917842720698085,"curvature":-0.4492662426099603,"pose":{"rotation":{"radians":0.3089871419169019},"translation":{"x":2.7143196950863935,"y":2.166725760757973}},"time":1.0330008526370211,"velocity":2.255104596444371,"position":1.5330564991191122,"holonomicRotation":-149.18784,"angularVelocity":-1.024626253316255,"angularAcceleration":5.117871370540664,"curveRadius":-2.2258516335227316},{"acceleration":-2.9915360357885716,"curvature":-0.44368591601928664,"pose":{"rotation":{"radians":0.30579595282070127},"translation":{"x":2.721098188715054,"y":2.168865719595815}},"time":1.0361662209540614,"velocity":2.2456352830574016,"position":1.54016476189573,"holonomicRotation":-149.2638,"angularVelocity":-1.008157274785798,"angularAcceleration":5.202863262956965,"curveRadius":-2.2538466151279204},{"acceleration":-2.991287164209291,"curvature":-0.43792644643617257,"pose":{"rotation":{"radians":0.30263962915287035},"translation":{"x":2.7278941010009614,"y":2.1709876129447965}},"time":1.0393500829153814,"velocity":2.2361114376398907,"position":1.5472842320433042,"holonomicRotation":-149.33976,"angularVelocity":-0.9913506634949406,"angularAcceleration":5.278687171440508,"curveRadius":-2.2834884902201247},{"acceleration":-2.9910376708405977,"curvature":-0.43199597430599257,"pose":{"rotation":{"radians":0.2995191724095805},"translation":{"x":2.734708170436833,"y":2.1730918622552253}},"time":1.0425530824340146,"velocity":2.2265311454199748,"position":1.554415810230306,"holonomicRotation":-149.41572,"angularVelocity":-0.974229538636185,"angularAcceleration":5.345341065196927,"curveRadius":-2.3148363861642776},{"acceleration":-2.990787564607048,"curvature":-0.4259028270856035,"pose":{"rotation":{"radians":0.29643554871327726},"translation":{"x":2.741541135515387,"y":2.1751788889774093}},"time":1.045775875132367,"velocity":2.216892457094436,"position":1.5615603950540624,"holonomicRotation":-149.49168,"angularVelocity":-0.9568172653114538,"angularAcceleration":5.402852418535382,"curveRadius":-2.347953421307079},{"acceleration":-2.990536849540174,"curvature":-0.4196554945100441,"pose":{"rotation":{"radians":0.2933896879671911},"translation":{"x":2.748393734729341,"y":2.1772491145616573}},"time":1.049019128762079,"velocity":2.2071933876023775,"position":1.5687188830198802,"holonomicRotation":-149.56764,"angularVelocity":-0.9391373891275393,"angularAcceleration":5.45127769901994,"curveRadius":-2.382906963168728},{"acceleration":-2.9902855248352633,"curvature":-0.41326260353601413,"pose":{"rotation":{"radians":0.2903824830929733},"translation":{"x":2.755266706571413,"y":2.1793029604582768}},"time":1.0522835236471664,"velocity":2.197431914830154,"position":1.5758921685229796,"holonomicRotation":-149.6436,"angularVelocity":-0.9212135725231763,"angularAcceleration":5.490701105507605,"curveRadius":-2.4197689107208418},{"acceleration":-2.99003358427948,"curvature":-0.4067328943840124,"pose":{"rotation":{"radians":0.28741478935535403},"translation":{"x":2.7621607895343208,"y":2.181340848117576}},"time":1.0555697531518118,"velocity":2.1876059782456143,"position":1.583081143833229,"holonomicRotation":-149.71956,"angularVelocity":-0.9030695310306732,"angularAcceleration":5.52123382339993,"curveRadius":-2.458615995429819},{"acceleration":-2.9897810164552667,"curvature":-0.40007519541310615,"pose":{"rotation":{"radians":0.28448742377096004},"translation":{"x":2.7690767221107815,"y":2.1833631989898623}},"time":1.0588785241742813,"velocity":2.1777134774548377,"position":1.590286699082673,"holonomicRotation":-149.79552,"angularVelocity":-0.8847289717283434,"angularAcceleration":5.54301254991083,"curveRadius":-2.499530117000702},{"acceleration":-2.9895278040231736,"curvature":-0.39329839937509375,"pose":{"rotation":{"radians":0.2816011646030434},"translation":{"x":2.776015242793514,"y":2.1853704345254448}},"time":1.06221055766854,"velocity":2.167752270679815,"position":1.5975097222558332,"holonomicRotation":-149.87148000000002,"angularVelocity":-0.8662155326139204,"angularAcceleration":5.556198383456666,"curveRadius":-2.542598702636181},{"acceleration":-2.9892739241443333,"curvature":-0.38641143940369604,"pose":{"rotation":{"radians":0.2787567509406559},"translation":{"x":2.782977090075235,"y":2.1873629761746307}},"time":1.065566589195258,"velocity":2.1577201731483906,"position":1.6047510991827547,"holonomicRotation":-149.94744,"angularVelocity":-0.8475527240261531,"angularAcceleration":5.560975348172058,"curveRadius":-2.587915102987593},{"acceleration":-2.98901934773012,"curvature":-0.37942326595693615,"pose":{"rotation":{"radians":0.2759548823621989},"translation":{"x":2.789963002448663,"y":2.189341245387729}},"time":1.0689473695040264,"velocity":2.1476149553950568,"position":1.612011713534771,"holonomicRotation":-150.0234,"angularVelocity":-0.8287638718168211,"angularAcceleration":5.55754899559757,"curveRadius":-2.635579021433805},{"acceleration":-2.9887640392930823,"curvature":-0.37234282400410496,"pose":{"rotation":{"radians":0.2731962186808352},"translation":{"x":2.7969737184065155,"y":2.1913056636150468}},"time":1.0723536651487304,"velocity":2.1374343414649646,"position":1.619292446822944,"holonomicRotation":-150.09936000000002,"angularVelocity":-0.8098720631172185,"angularAcceleration":5.546144747880177,"curveRadius":-2.685696985498975},{"acceleration":-2.9885079572074638,"curvature":-0.3651790308978148,"pose":{"rotation":{"radians":0.27048137977292397},"translation":{"x":2.80400997644151,"y":2.1932566523068924}},"time":1.0757862591381866,"velocity":2.1271760070136123,"position":1.6265941783991342,"holonomicRotation":-150.17532,"angularVelocity":-0.7909000937047497,"angularAcceleration":5.527006535216413,"curveRadius":-2.738382862623408},{"acceleration":-2.988251052603325,"curvature":-0.35794075530567404,"pose":{"rotation":{"radians":0.26781094548449236},"translation":{"x":2.811072515046365,"y":2.1951946329135743}},"time":1.079245951624307,"velocity":2.1168375773002794,"position":1.6339177854596572,"holonomicRotation":-150.25128,"angularVelocity":-0.7718704188724639,"angularAcceleration":5.500394878628516,"curveRadius":-2.7937584228038537},{"acceleration":-2.987993269991268,"curvature":-0.3506367963616661,"pose":{"rotation":{"radians":0.26518545561670237},"translation":{"x":2.818162072713798,"y":2.1971200268854}},"time":1.0827335606302335,"velocity":2.10641662506221,"position":1.6412641430514576,"holonomicRotation":-150.32724000000002,"angularVelocity":-0.752805106113792,"angularAcceleration":5.4665854819945725,"curveRadius":-2.851953960269888},{"acceleration":-2.9877345463545875,"curvature":-0.34327586447734837,"pose":{"rotation":{"radians":0.2626054099870565},"translation":{"x":2.825279387936527,"y":2.1990332556726777}},"time":1.0862499228210838,"velocity":2.0959106682671114,"position":1.6486341240807518,"holonomicRotation":-150.4032,"angularVelocity":-0.7337257909208714,"angularAcceleration":5.425867461140893,"curveRadius":-2.913108970019029},{"acceleration":-2.98747481124804,"curvature":-0.3358665624334938,"pose":{"rotation":{"radians":0.2600712685636144},"translation":{"x":2.832425199207269,"y":2.2009347407257156}},"time":1.0897958943201609,"velocity":2.085317167732215,"position":1.6560285993240664,"holonomicRotation":-150.47916,"angularVelocity":-0.7146536355697338,"angularAcceleration":5.378541636925589,"curveRadius":-2.9773728970058273},{"acceleration":-2.98721398622033,"curvature":-0.3284173675530357,"pose":{"rotation":{"radians":0.25758345167035257},"translation":{"x":2.839600245018742,"y":2.2028249034948217}},"time":1.0933723515737164,"velocity":2.074633524603275,"position":1.6634484374416032,"holonomicRotation":-150.55512000000002,"angularVelocity":-0.695609290671264,"angularAcceleration":5.324918920682517,"curveRadius":-3.0449059605183986},{"acceleration":-2.986951984717991,"curvature":-0.3209366152559512,"pose":{"rotation":{"radians":0.2551423402609312},"translation":{"x":2.846805263863665,"y":2.2047041654303037}},"time":1.0969801922676161,"velocity":2.063857077682085,"position":1.6708945049928576,"holonomicRotation":-150.63108,"angularVelocity":-0.6766128597498479,"angularAcceleration":5.265318658203482,"curveRadius":-3.11588006000028},{"acceleration":-2.9866887116144913,"curvature":-0.3134324832161693,"pose":{"rotation":{"radians":0.25274827625826823},"translation":{"x":2.8540409942347544,"y":2.2065729479824703}},"time":1.1006203362995381,"velocity":2.0529851005932924,"position":1.6783676664544072,"holonomicRotation":-150.70704,"angularVelocity":-0.6576838668108593,"angularAcceleration":5.200067022895749,"curveRadius":-3.1904797796925095},{"acceleration":-2.986424062841704,"curvature":-0.3059129767543588,"pose":{"rotation":{"radians":0.250401562955322},"translation":{"x":2.861308174624728,"y":2.208431672601628}},"time":1.1042937268106527,"velocity":2.0420147987786854,"position":1.6858687842397964,"holonomicRotation":-150.78300000000002,"angularVelocity":-0.6388412274289279,"angularAcceleration":5.129495305473014,"curveRadius":-3.26890349866713},{"acceleration":-2.9861579250337664,"curvature":-0.2983859156226146,"pose":{"rotation":{"radians":0.2481024654775137},"translation":{"x":2.8686075435263048,"y":2.210280760738087}},"time":1.108001331281074,"velocity":2.0309433063064466,"position":1.69339871872143,"holonomicRotation":-150.85896,"angularVelocity":-0.6201032219456644,"angularAcceleration":5.053938636861914,"curveRadius":-3.3513646175738274},{"acceleration":-2.9858901751835445,"curvature":-0.29085892108945993,"pose":{"rotation":{"radians":0.24585121129892196},"translation":{"x":2.875939839432201,"y":2.212120633842155}},"time":1.1117441426937522,"velocity":2.0197676824817656,"position":1.7009583282543816,"holonomicRotation":-150.93492,"angularVelocity":-0.6014874730171813,"angularAcceleration":4.973734146856717,"curveRadius":-3.438092929226085},{"acceleration":-2.9856206798967277,"curvature":-0.28333940517331696,"pose":{"rotation":{"radians":0.2436479908136251},"translation":{"x":2.8833058008351355,"y":2.2139517133641387}},"time":1.1155231807719077,"velocity":2.0084849082455074,"position":1.708548469202042,"holonomicRotation":-151.01088000000001,"angularVelocity":-0.5830109249315187,"angularAcceleration":4.889219876472048,"curveRadius":-3.529336130949757},{"acceleration":-2.9853492951654084,"curvature":-0.27583456024140474,"pose":{"rotation":{"radians":0.2414929579561398},"translation":{"x":2.890706166227826,"y":2.2157744207543466}},"time":1.1193394932955552,"velocity":1.9970918823429056,"position":1.716169995963502,"holonomicRotation":-151.08684,"angularVelocity":-0.5646898266669287,"angularAcceleration":4.800733208054887,"curveRadius":-3.6253615178780376},{"acceleration":-2.985075865802527,"curvature":-0.2683513497920963,"pose":{"rotation":{"radians":0.23938623086815092},"translation":{"x":2.8981416741029897,"y":2.2175891774630876}},"time":1.1231941575032036,"velocity":1.9855854172458813,"position":1.7238237610025884,"holonomicRotation":-151.1628,"angularVelocity":-0.5465397177291554,"angularAcceleration":4.708609611638707,"curveRadius":-3.7264578723928325},{"acceleration":-2.9848002245159133,"curvature":-0.26089650052126917,"pose":{"rotation":{"radians":0.23732789260825626},"translation":{"x":2.905613062953345,"y":2.2193964049406683}},"time":1.127088281585371,"velocity":1.973962234811135,"position":1.7315106148784556,"holonomicRotation":-151.23876,"angularVelocity":-0.5285754168236392,"angularAcceleration":4.613181430910445,"curveRadius":-3.832937574869758},{"acceleration":-2.9845221916919353,"curvature":-0.25347649549123613,"pose":{"rotation":{"radians":0.23531799190298885},"translation":{"x":2.9131210712716094,"y":2.221196524637398}},"time":1.131023006277201,"velocity":1.9622189616501702,"position":1.7392314062776375,"holonomicRotation":-151.31472,"angularVelocity":-0.5108110128875709,"angularAcceleration":4.514776846510778,"curveRadius":-3.945138968652716},{"acceleration":-2.984241574425047,"curvature":-0.24609756796036714,"pose":{"rotation":{"radians":0.23335654393215943},"translation":{"x":2.920666437550501,"y":2.2229899580035846}},"time":1.1349995065581684,"velocity":1.9503521241909947,"position":1.7469869820474682,"holonomicRotation":-151.39068,"angularVelocity":-0.49325985973583086,"angularAcceleration":4.413718574532746,"curveRadius":-4.063429022431645},{"acceleration":-2.9839581657518064,"curvature":-0.23876569683965357,"pose":{"rotation":{"radians":0.23144353114930594},"translation":{"x":2.928249900282737,"y":2.2247771264895357}},"time":1.1390189934676511,"velocity":1.9383581434053112,"position":1.754778187230775,"holonomicRotation":-151.46664,"angularVelocity":-0.4759345722311815,"angularAcceleration":4.310323156862564,"curveRadius":-4.18820631789316},{"acceleration":-2.98367174382351,"curvature":-0.2314866022681933,"pose":{"rotation":{"radians":0.2295789041313081},"translation":{"x":2.935872197961035,"y":2.226558451545559}},"time":1.1430827160460248,"velocity":1.92623332917348,"position":1.7626058651017533,"holonomicRotation":-151.5426,"angularVelocity":-0.45884702561168494,"angularAcceleration":4.204899889188518,"curveRadius":-4.319904435944118},{"acceleration":-2.983382070922878,"curvature":-0.2242657435731509,"pose":{"rotation":{"radians":0.22776258245514835},"translation":{"x":2.943534069078114,"y":2.228334354621964}},"time":1.1471919634119148,"velocity":1.9139738742570969,"position":1.7704708572029264,"holonomicRotation":-151.61856,"angularVelocity":-0.44200835686765727,"angularAcceleration":4.097750085283813,"curveRadius":-4.45899576131127},{"acceleration":-2.9830888924991785,"curvature":-0.2171083157764532,"pose":{"rotation":{"radians":0.22599445559720222},"translation":{"x":2.951236252126691,"y":2.230105257169057}},"time":1.1513480669873375,"velocity":1.9015758478451772,"position":1.7783740033830933,"holonomicRotation":-151.69452,"angularVelocity":-0.42542896871050606,"angularAcceleration":3.9891662602428917,"curveRadius":-4.6059958432437735},{"acceleration":-2.9827919359403245,"curvature":-0.21001925007434152,"pose":{"rotation":{"radians":0.22427438385523457},"translation":{"x":2.9589794855994835,"y":2.231871580637147}},"time":1.1555524028837068,"velocity":1.8890351886375025,"position":1.7863161418361866,"holonomicRotation":-151.77048,"angularVelocity":-0.40911853485661,"angularAcceleration":3.8794316762324548,"curveRadius":-4.761468292292374},{"acceleration":-2.9824909093052434,"curvature":-0.2030032123931552,"pose":{"rotation":{"radians":0.22260219928559666},"translation":{"x":2.96676450798921,"y":2.233633746476542}},"time":1.1598063944630432,"velocity":1.8763476974238704,"position":1.7942981091409351,"holonomicRotation":-151.84644,"angularVelocity":-0.39308600838808755,"angularAcceleration":3.7688195121023536,"curveRadius":-4.926030421938869},{"acceleration":-2.982185499884099,"curvature":-0.19606460403542186,"pose":{"rotation":{"radians":0.22097770665674288},"translation":{"x":2.9745920577885876,"y":2.2353921761375504}},"time":1.164111515090298,"velocity":1.863509029114019,"position":1.8023207403012496,"holonomicRotation":-151.9224,"angularVelocity":-0.3773396309895344,"angularAcceleration":3.6575926116601734,"curveRadius":-5.100359674402707},{"acceleration":-2.9818753728322087,"curvature":-0.18920756331040792,"pose":{"rotation":{"radians":0.21940068441352656},"translation":{"x":2.9824628734903347,"y":2.2371472910704795}},"time":1.1684692910944516,"velocity":1.8505146841669144,"position":1.810384868787246,"holonomicRotation":-151.99836,"angularVelocity":-0.3618869445591525,"angularAcceleration":3.5460029188405744,"curveRadius":-5.285200985118294},{"acceleration":-2.9815601691935374,"curvature":-0.18243596708395418,"pose":{"rotation":{"radians":0.21787088565166002},"translation":{"x":2.9903776935871687,"y":2.238899512725638}},"time":1.1728813049580213,"velocity":1.8373599993653653,"position":1.8184913265768143,"holonomicRotation":-152.07432,"angularVelocity":-0.34673480391759215,"angularAcceleration":3.43429125793837,"curveRadius":-5.481375279140081},{"acceleration":-2.9812395041975086,"curvature":-0.17575343332182847,"pose":{"rotation":{"radians":0.21638803909741133},"translation":{"x":2.9983372565718067,"y":2.2406492625533323}},"time":1.1773491987568667,"velocity":1.8240401378716884,"position":1.8266409441976563,"holonomicRotation":-152.15028,"angularVelocity":-0.33188939151416064,"angularAcceleration":3.3226869464238287,"curveRadius":-5.689789275233467},{"acceleration":-2.980912964950863,"curvature":-0.16916332470999154,"pose":{"rotation":{"radians":0.21495185009304096},"translation":{"x":3.006342300936968,"y":2.2423969620038733}},"time":1.1818746778747147,"velocity":1.810550078496681,"position":1.834834550769711,"holonomicRotation":-152.22624000000002,"angularVelocity":-0.31735623278123426,"angularAcceleration":3.211407754730173,"curveRadius":-5.911446832310547},{"acceleration":-2.980580108320262,"curvature":-0.16266875179361956,"pose":{"rotation":{"radians":0.21356200158122984},"translation":{"x":3.0143935651753697,"y":2.2441430325275666}},"time":1.1864595150197157,"velocity":1.7968846041024031,"position":1.8430729740478802,"holonomicRotation":-152.3022,"angularVelocity":-0.30314021367727584,"angularAcceleration":3.1006595554781176,"curveRadius":-6.147462182956416},{"acceleration":-2.9802404580645296,"curvature":-0.15627257797346386,"pose":{"rotation":{"radians":0.21221815509247177},"translation":{"x":3.02249178777973,"y":2.2458878955747217}},"time":1.1911055545736422,"velocity":1.7830382890540233,"position":1.8513570404649906,"holonomicRotation":-152.37816,"angularVelocity":-0.2892455979248706,"angularAcceleration":2.9906365606944725,"curveRadius":-6.39907533981942},{"acceleration":-2.979893502071709,"curvature":-0.14997742360212674,"pose":{"rotation":{"radians":0.21091995172603806},"translation":{"x":3.0306377072427657,"y":2.247631972595645}},"time":1.1958147173080886,"velocity":1.769005485621448,"position":1.8596875751749105,"holonomicRotation":-152.45412000000002,"angularVelocity":-0.2756760468135146,"angularAcceleration":2.8815209574512815,"curveRadius":-6.667670213170801},{"acceleration":-2.9795386889854876,"curvature":-0.14378567141114332,"pose":{"rotation":{"radians":0.2096670131292293},"translation":{"x":3.038832062057195,"y":2.2493756850406466}},"time":1.2005890055063397,"velocity":1.7547803092223921,"position":1.8680654020957543,"holonomicRotation":-152.53008,"angularVelocity":-0.2624346383755641,"angularAcceleration":2.7734832687312574,"curveRadius":-6.95479591384723},{"acceleration":-2.97917542460243,"curvature":-0.13769947262634236,"pose":{"rotation":{"radians":0.20845894246725782},"translation":{"x":3.047075590715736,"y":2.2511194543600332}},"time":1.205430508534502,"velocity":1.7403566223827527,"position":1.8764913439531028,"holonomicRotation":-152.60604,"angularVelocity":-0.2495238885412875,"angularAcceleration":2.6666821768315763,"curveRadius":-7.262191938189724},{"acceleration":-2.978803067705005,"curvature":-0.13172075128619937,"pose":{"rotation":{"radians":0.20729532538697848},"translation":{"x":3.055369031711106,"y":2.252863702004113}},"time":1.210341408911176,"velocity":1.725728017275523,"position":1.8849662223231778,"holonomicRotation":-152.68200000000002,"angularVelocity":-0.23694577186016152,"angularAcceleration":2.561264883496802,"curveRadius":-7.591818223289863},{"acceleration":-2.9784209254973595,"curvature":-0.12585121272203065,"pose":{"rotation":{"radians":0.20617573096900443},"translation":{"x":3.063713123536023,"y":2.2546088494231946}},"time":1.2153239889314844,"velocity":1.710887796680071,"position":1.8934908576759055,"holonomicRotation":-152.75796,"angularVelocity":-0.22470174355668998,"angularAcceleration":2.457367117751471,"curveRadius":-7.945890852944852},{"acceleration":-2.97802824833868,"curvature":-0.12009234884052064,"pose":{"rotation":{"radians":0.20509971266847238},"translation":{"x":3.072108604683205,"y":2.2563553180675857}},"time":1.2203806379088522,"velocity":1.6958289531835369,"position":1.9020660694178118,"holonomicRotation":-152.83392,"angularVelocity":-0.21279276163878985,"angularAcceleration":2.3551134300999617,"curveRadius":-8.32692515097671},{"acceleration":-2.9776242238739625,"curvature":-0.11444544399982885,"pose":{"rotation":{"radians":0.2040668092428639},"translation":{"x":3.0805562136453695,"y":2.258103529387594}},"time":1.225513860106705,"velocity":1.6805441464206827,"position":1.91069267593469,"holonomicRotation":-152.90988000000002,"angularVelocity":-0.20121930939216254,"angularAcceleration":2.254617431419264,"curveRadius":-8.737787762014323},{"acceleration":-2.97720797041369,"curvature":-0.10891158370499776,"pose":{"rotation":{"radians":0.2030765456654966},"translation":{"x":3.0890566889152353,"y":2.259853904833528}},"time":1.2307262834424813,"velocity":1.6650256781202395,"position":1.9193714946339906,"holonomicRotation":-152.98584,"angularVelocity":-0.18998141815736597,"angularAcceleration":2.1559820664725584,"curveRadius":-9.18175979066322},{"acceleration":-2.976778529381571,"curvature":-0.1034916605677269,"pose":{"rotation":{"radians":0.2021284340227245},"translation":{"x":3.0976107689855183,"y":2.261606865855696}},"time":1.2360206690582676,"velocity":1.6492654646929001,"position":1.9281033419868738,"holonomicRotation":-153.0618,"angularVelocity":-0.17907869044239863,"angularAcceleration":2.0592998897659744,"curveRadius":-9.662614306450141},{"acceleration":-2.976334856717385,"curvature":-0.09818638140757359,"pose":{"rotation":{"radians":0.20122197439508804},"translation":{"x":3.106219192348937,"y":2.263362833904405}},"time":1.2413999218663456,"velocity":1.6332550070571226,"position":1.9368890335698934,"holonomicRotation":-153.13776000000001,"angularVelocity":-0.1685103228974913,"angularAcceleration":1.9646534420239123,"curveRadius":-10.184711827284687},{"acceleration":-2.975875813141657,"curvature":-0.09299627555538803,"pose":{"rotation":{"radians":0.20035665572070727},"translation":{"x":3.1148826974982105,"y":2.2651222304299643}},"time":1.2468671021943276,"velocity":1.616985357352997,"position":1.9457293841062486,"holonomicRotation":-153.21372,"angularVelocity":-0.158275129494435,"angularAcceleration":1.8721155676301302,"curveRadius":-10.753118810703402},{"acceleration":-2.9754001529138203,"curvature":-0.08792170045580386,"pose":{"rotation":{"radians":0.19953195663920775},"translation":{"x":3.123602022926055,"y":2.266885476882681}},"time":1.2524254386739164,"velocity":1.600447082141682,"position":1.9546252075065682,"holonomicRotation":-153.28968,"angularVelocity":-0.14837156486080932,"angularAcceleration":1.7817497501263762,"curveRadius":-11.373756362943368},{"acceleration":-2.9749065111669535,"curvature":-0.08296285144864776,"pose":{"rotation":{"radians":0.19874734631748714},"translation":{"x":3.132377907125189,"y":2.2686529947128635}},"time":1.2580783425402338,"velocity":1.5836302216227738,"position":1.9635773169091966,"holonomicRotation":-153.36564,"angularVelocity":-0.1387977471889609,"angularAcceleration":1.693610558087452,"curveRadius":-12.053587630350178},{"acceleration":-2.974393388987456,"curvature":-0.07811976660376341,"pose":{"rotation":{"radians":0.19800228525460772},"translation":{"x":3.1412110885883306,"y":2.27042520537082}},"time":1.2638294235358465,"velocity":1.566524244329892,"position":1.9725865247199288,"holonomicRotation":-153.4416,"angularVelocity":-0.12955148144284412,"angularAcceleration":1.6077439620778078,"curveRadius":-12.800857497080965},{"acceleration":-2.9738591366324463,"curvature":-0.07339233592026162,"pose":{"rotation":{"radians":0.19729622606610953},"translation":{"x":3.150102305808196,"y":2.272202530306859}},"time":1.2696825076461138,"velocity":1.5491179966710953,"position":1.9816536426511735,"holonomicRotation":-153.51756,"angularVelocity":-0.12063028229162988,"angularAcceleration":1.5241877586493147,"curveRadius":-13.625400901348437},{"acceleration":-2.9733019337456277,"curvature":-0.06878030763662119,"pose":{"rotation":{"radians":0.1966286142468352},"translation":{"x":3.159052297277505,"y":2.273985390971287}},"time":1.2756416569313629,"velocity":1.5313996465777853,"position":1.9907794817605082,"holonomicRotation":-153.59352,"angularVelocity":-0.11203139698595763,"angularAcceleration":1.442971956912942,"curveRadius":-14.539045176755838},{"acceleration":-2.97271976651797,"curvature":-0.06428329621722455,"pose":{"rotation":{"radians":0.19599888891363992},"translation":{"x":3.168061801488974,"y":2.2757742088144135}},"time":1.2817111917682278,"velocity":1.5133566203946676,"position":1.9999648524885938,"holonomicRotation":-153.66948,"angularVelocity":-0.1037518277958426,"angularAcceleration":1.364119230328312,"curveRadius":-15.556140690434175},{"acceleration":-2.972110401183069,"curvature":-0.05990078888059135,"pose":{"rotation":{"radians":0.19540648352367773},"translation":{"x":3.177131556935322,"y":2.277569405286546}},"time":1.2878957158691275,"velocity":1.494975531988016,"position":2.009210564696429,"holonomicRotation":-153.74544,"angularVelocity":-0.09578835498045928,"angularAcceleration":1.2876452068841904,"curveRadius":-16.694270955152867},{"acceleration":-2.971471352679463,"curvature":-0.05563215260169395,"pose":{"rotation":{"radians":0.1948508265726483},"translation":{"x":3.1862623021092658,"y":2.279371401837992}},"time":1.2942001445176758,"velocity":1.476242102863843,"position":2.018517427701917,"holonomicRotation":-153.8214,"angularVelocity":-0.08813755885037841,"angularAcceleration":1.2135590005991406,"curveRadius":-17.975216726910382},{"acceleration":-2.970799848130998,"curvature":-0.051476642801176496,"pose":{"rotation":{"radians":0.1943313422694355},"translation":{"x":3.1954547755035225,"y":2.2811806199190605}},"time":1.3006297365419281,"velocity":1.45714107185465,"position":2.0278862503157242,"holonomicRotation":-153.89736,"angularVelocity":-0.08079584229501921,"angularAcceleration":1.1418635160156938,"curveRadius":-19.426286284099806},{"acceleration":-2.970092783522543,"curvature":-0.0474334072789355,"pose":{"rotation":{"radians":0.19384745118835855},"translation":{"x":3.2047097156108117,"y":2.2829974809800593}},"time":1.3071901306506963,"velocity":1.4376560926551338,"position":2.0373178408764137,"holonomicRotation":-153.97332,"angularVelocity":-0.0737594530228299,"angularAcceleration":1.0725558793464782,"curveRadius":-21.082187794763076},{"acceleration":-2.9693466723789816,"curvature":-0.04350149499837563,"pose":{"rotation":{"radians":0.19339857089914014},"translation":{"x":3.21402786092385,"y":2.284822406471296}},"time":1.3138873868858618,"velocity":1.4177696171391758,"position":2.046813007284827,"holonomicRotation":-154.04928,"angularVelocity":-0.06702450577618081,"angularAcceleration":1.005627828794379,"curveRadius":-22.987715710398934},{"acceleration":-2.968557584495397,"curvature":-0.03967986316498604,"pose":{"rotation":{"radians":0.19298411657408243},"translation":{"x":3.223409949935356,"y":2.28665581784308}},"time":1.3207280341024452,"velocity":1.3974627619615299,"position":2.0563725570377183,"holonomicRotation":-154.12524000000002,"angularVelocity":-0.06058700469934676,"angularAcceleration":0.9410660823478779,"curveRadius":-25.201699810356487},{"acceleration":-2.967721072637673,"curvature":-0.03596738045905507,"pose":{"rotation":{"radians":0.19260350157170958},"translation":{"x":3.232856721138046,"y":2.288498136545717}},"time":1.32771912458697,"velocity":1.376715155409889,"position":2.0659972972606053,"holonomicRotation":-154.2012,"angularVelocity":-0.054442865989986926,"angularAcceleration":0.878852694434483,"curveRadius":-27.802970003289246},{"acceleration":-2.966832084030165,"curvature":-0.03236283765858625,"pose":{"rotation":{"radians":0.1922561380002863},"translation":{"x":3.24236891302464,"y":2.2903497840295173}},"time":1.3348682971752839,"velocity":1.3555047608006103,"position":2.07568803473985,"holonomicRotation":-154.27716,"angularVelocity":-0.048587940371042214,"angularAcceleration":0.8189654881902272,"curveRadius":-30.899638979423298},{"acceleration":-2.965884853024535,"curvature":-0.028864949278538953,"pose":{"rotation":{"radians":0.19194143725573243},"translation":{"x":3.251947264087854,"y":2.292211181744787}},"time":1.342183850549257,"velocity":1.3338076718572511,"position":2.0854455759539365,"holonomicRotation":-154.35312,"angularVelocity":-0.04301803684099858,"angularAcceleration":0.7613782916081222,"curveRadius":-34.64409344185124},{"acceleration":-2.9648727702543285,"curvature":-0.025472363389816538,"pose":{"rotation":{"radians":0.19165881054041112},"translation":{"x":3.261592512820406,"y":2.294082751141836}},"time":1.3496748287992455,"velocity":1.3115978744212926,"position":2.0952707271039577,"holonomicRotation":-154.42908,"angularVelocity":-0.037728946192273564,"angularAcceleration":0.7060614077651456,"curveRadius":-39.2582339022293},{"acceleration":-2.96378822152573,"curvature":-0.02218366506309796,"pose":{"rotation":{"radians":0.1914076693576856},"translation":{"x":3.2713053977150146,"y":2.295964913670971}},"time":1.3573511218652403,"velocity":1.2888469674473175,"position":2.105164294143302,"holonomicRotation":-154.50504,"angularVelocity":-0.03271646621180228,"angularAcceleration":0.652981841284311,"curveRadius":-45.07821395408093},{"acceleration":-2.9626223886775587,"curvature":-0.01899738044159299,"pose":{"rotation":{"radians":0.191187425986298},"translation":{"x":3.281086657264397,"y":2.297858090782501}},"time":1.3652235841550058,"velocity":1.2655238344136386,"position":2.1151270828065227,"holonomicRotation":-154.58100000000002,"angularVelocity":-0.027976427613241428,"angularAcceleration":0.6021036905725295,"curveRadius":-52.63883634243559},{"acceleration":-2.961365000783352,"curvature":-0.015911986587708364,"pose":{"rotation":{"radians":0.19099749393252452},"translation":{"x":3.2909370299612712,"y":2.299762703926733}},"time":1.373304175539311,"velocity":1.2415942539025258,"position":2.1251598986374103,"holonomicRotation":-154.65696,"angularVelocity":-0.023504721961611876,"angularAcceleration":0.5533884141592519,"curveRadius":-62.84570405385312},{"acceleration":-2.9600040211818017,"curvature":-0.012925911891862882,"pose":{"rotation":{"radians":0.19083728836170577},"translation":{"x":3.3008572542983545,"y":2.301679174553976}},"time":1.381606130123377,"velocity":1.2170204349500213,"position":2.1352635470162458,"holonomicRotation":-154.73292,"angularVelocity":-0.01929733163395415,"angularAcceleration":0.5067951510759808,"curveRadius":-77.36398084451743},{"acceleration":-2.958525249805511,"curvature":-0.010037542753529093,"pose":{"rotation":{"radians":0.19070622650880198},"translation":{"x":3.3108480687683652,"y":2.3036079241145377}},"time":1.3901441598062811,"velocity":1.1917604585495607,"position":2.1454388331862533,"holonomicRotation":-154.80888000000002,"angularVelocity":-0.015350362761823113,"angularAcceleration":0.46228099675434037,"curveRadius":-99.62597665134832},{"acceleration":-2.956911812887149,"curvature":-0.007245229408561292,"pose":{"rotation":{"radians":0.19060372806892723},"translation":{"x":3.320910211864021,"y":2.3055493740587263}},"time":1.398934701835724,"velocity":1.1657676009810198,"position":2.15568656227924,"holonomicRotation":-154.88484,"angularVelocity":-0.011660081884762832,"angularAcceleration":0.4198012892379205,"curveRadius":-138.0218546038521},{"acceleration":-2.955143501125332,"curvature":-0.0045472910570001236,"pose":{"rotation":{"radians":0.19052921556756308},"translation":{"x":3.3310444220780404,"y":2.3075039458368494}},"time":1.407996222595667,"velocity":1.1389895067969622,"position":2.1660075393404377,"holonomicRotation":-154.9608,"angularVelocity":-0.008222957640127143,"angularAcceleration":0.3793098681437369,"curveRadius":-219.9111487399943},{"acceleration":-2.953195900814296,"curvature":-0.001942015545769553,"pose":{"rotation":{"radians":0.1904821147118958},"translation":{"x":3.3412514379031393,"y":2.309472060899215}},"time":1.4173495941075953,"velocity":1.1113671683891424,"position":2.176402569352541,"holonomicRotation":-155.03676000000002,"angularVelocity":-0.005035708846506745,"angularAcceleration":0.3407593496693387,"curveRadius":-514.9289366804398},{"acceleration":-2.9510392382336126,"curvature":0.0005723328638936691,"pose":{"rotation":{"radians":0.19046185472243504},"translation":{"x":3.3515319978320375,"y":2.3114541406961315}},"time":1.4270185657647552,"velocity":1.082833653635495,"position":2.1868724572589615,"holonomicRotation":-155.11272,"angularVelocity":-0.0020953613454596843,"angularAcceleration":0.30410136727102094,"curveRadius":1747.2349800024504},{"acceleration":-2.948636820558947,"curvature":0.002997508769158759,"pose":{"rotation":{"radians":0.19046786864658527},"translation":{"x":3.361886840357451,"y":2.3134506066779075}},"time":1.4370303625656335,"velocity":1.0533125009484707,"position":2.1974180079862826,"holonomicRotation":-155.18868,"angularVelocity":0.0006006838003044662,"angularAcceleration":0.2692868422506951,"curveRadius":333.61036681158623},{"acceleration":-2.945942898446509,"curvature":0.0053352879254536184,"pose":{"rotation":{"radians":0.1904995936535001},"translation":{"x":3.372316703972099,"y":2.31546188029485}},"time":1.4474164540340302,"velocity":1.0227156685445318,"position":2.2080400264659485,"holonomicRotation":-155.26464,"angularVelocity":0.003054566485513304,"angularAcceleration":0.23626623091811239,"curveRadius":187.4313090450461},{"acceleration":-2.9428996833089998,"curvature":0.007587449744921624,"pose":{"rotation":{"radians":0.19055647131225495},"translation":{"x":3.3828223271686992,"y":2.3174883829972672}},"time":1.4582135575213917,"velocity":0.9909408761109211,"position":2.218739317655175,"holonomicRotation":-155.3406,"angularVelocity":0.005267862702382819,"angularAcceleration":0.20498981226402768,"curveRadius":131.79658958127698},{"acceleration":-2.939433101547956,"curvature":0.009755792247441643,"pose":{"rotation":{"radians":0.19063794785180876},"translation":{"x":3.393404448439968,"y":2.3195305362354683}},"time":1.4694649697708768,"velocity":0.9578681025056224,"position":2.2295166865570977,"holonomicRotation":-155.41656,"angularVelocity":0.007241450028421436,"angularAcceleration":0.17540796499825448,"curveRadius":102.50320780070321},{"acceleration":-2.935446613126039,"curvature":0.011842116025812793,"pose":{"rotation":{"radians":0.1907434744045049},"translation":{"x":3.404063806278625,"y":2.32158876145976}},"time":1.4812223686318882,"velocity":0.9233548858398947,"position":2.240372938240181,"holonomicRotation":-155.49252,"angularVelocity":0.008975331528988916,"angularAcceleration":0.14747152164048768,"curveRadius":84.44436769748371},{"acceleration":-2.9308119792055636,"curvature":0.013848226782674325,"pose":{"rotation":{"radians":0.19087250723443816},"translation":{"x":3.4148011391773867,"y":2.3236634801204508}},"time":1.4935483056158219,"velocity":0.8872298820724489,"position":2.251308877856869,"holonomicRotation":-155.56848,"angularVelocity":0.010468399286922418,"angularAcceleration":0.12113219140091729,"curveRadius":72.21141130148962},{"acceleration":-2.9253550607499674,"curvature":0.01577592933639502,"pose":{"rotation":{"radians":0.19102450794844916},"translation":{"x":3.4256171856289717,"y":2.325755113667849}},"time":1.5065197440910456,"velocity":0.8492838188837463,"position":2.2623253106615224,"holonomicRotation":-155.64444,"angularVelocity":0.011718107772035708,"angularAcceleration":0.09634309159314217,"curveRadius":63.38770786029087},{"acceleration":-2.9188332138096538,"curvature":0.01762702794129567,"pose":{"rotation":{"radians":0.19119894369326218},"translation":{"x":3.4365126841260967,"y":2.327864083552262}},"time":1.5202332359401638,"velocity":0.8092564233972321,"position":2.273423042027627,"holonomicRotation":-155.7204,"angularVelocity":0.012720009369767778,"angularAcceleration":0.07305955396010205,"curveRadius":56.731061148275195},{"acceleration":-2.9108978282746962,"curvature":0.019403321551643364,"pose":{"rotation":{"radians":0.1913952873374205},"translation":{"x":3.4474883731614807,"y":2.329990811223998}},"time":1.534812773424347,"velocity":0.7668168793972735,"position":2.284602877464304,"holonomicRotation":-155.79636,"angularVelocity":0.013467069471259316,"angularAcceleration":0.0512403155657024,"curveRadius":51.537567799328926},{"acceleration":-2.9010291750138983,"curvature":0.021106602637851003,"pose":{"rotation":{"radians":0.19161301763898564},"translation":{"x":3.458544991227841,"y":2.3321357181333657}},"time":1.5504222315400644,"velocity":0.72153338599742,"position":2.2958656226321223,"holonomicRotation":-155.87232,"angularVelocity":0.01394861371554584,"angularAcceleration":0.03084951705028448,"curveRadius":47.378539178383676},{"acceleration":-2.8884162033520484,"curvature":0.022738654877077782,"pose":{"rotation":{"radians":0.1918516193997828},"translation":{"x":3.4696832768178947,"y":2.3342992257306734}},"time":1.5672861856750413,"velocity":0.672823267621367,"position":2.3072120833582344,"holonomicRotation":-155.94828,"angularVelocity":0.014148624865047381,"angularAcceleration":0.011860275941257803,"curveRadius":43.97797518832447},{"acceleration":-2.8717177420963735,"curvature":0.024301250430554294,"pose":{"rotation":{"radians":0.19211058360591515},"translation":{"x":3.4809039684243612,"y":2.336481755466228}},"time":1.5857272471457435,"velocity":0.6198657442128616,"position":2.3186430656508463,"holonomicRotation":-156.02424000000002,"angularVelocity":0.014042803693474172,"angularAcceleration":-0.005738344928860531,"curveRadius":41.1501458683248},{"acceleration":-2.848540244596436,"curvature":0.02579614952515084,"pose":{"rotation":{"radians":0.19238940755669853},"translation":{"x":3.492207804539957,"y":2.3386837287903375}},"time":1.6062394953466415,"velocity":0.561435779705453,"position":2.3301593757130292,"holonomicRotation":-156.1002,"angularVelocity":0.013593046849500124,"angularAcceleration":-0.021926257890851755,"curveRadius":38.765475406514284},{"acceleration":-2.8141355422301686,"curvature":0.02722509701036003,"pose":{"rotation":{"radians":0.19268759497995402},"translation":{"x":3.5035955236574,"y":2.3409055671533108}},"time":1.6296528886478556,"velocity":0.49554731745229247,"position":2.3417618199559014,"holonomicRotation":-156.17616,"angularVelocity":0.012735762792658856,"angularAcceleration":-0.036615113657908385,"curveRadius":36.73081493959297},{"acceleration":-2.757458813062516,"curvature":0.02858982128052916,"pose":{"rotation":{"radians":0.19300465613648088},"translation":{"x":3.515067864269408,"y":2.343147692005456}},"time":1.6575823043766191,"velocity":0.4185331039073267,"position":2.353451205011179,"holonomicRotation":-156.25212,"angularVelocity":0.011352230193642197,"angularAcceleration":-0.049536754096570955,"curveRadius":34.97748342627944},{"acceleration":-2.6444740356693406,"curvature":0.02989203341533014,"pose":{"rotation":{"radians":0.19334010791284717},"translation":{"x":3.5266255648686995,"y":2.3454105247970807}},"time":1.6941878736490077,"velocity":0.3217306264055997,"position":2.365228337743118,"holonomicRotation":-156.32808,"angularVelocity":0.009163954639528613,"angularAcceleration":-0.05977985311006193,"curveRadius":33.45372949727634},{"acceleration":-2.1173587391494926,"curvature":0.02989203341533014,"pose":{"rotation":{"radians":0.19369347390377234},"translation":{"x":3.5382693639479914,"y":2.3476944869784924}},"time":1.783128631148012,"velocity":0.13341113624850737,"position":2.377094025259863,"holonomicRotation":-156.40404,"angularVelocity":0.003973049036929171,"angularAcceleration":-0.05836363157416958,"curveRadius":33.45372949727634}] \ No newline at end of file diff --git a/src/main/deploy/pathplanner/generatedJSON/New Path.wpilib.json b/src/main/deploy/pathplanner/generatedJSON/New Path.wpilib.json new file mode 100644 index 0000000..ca6fb6f --- /dev/null +++ b/src/main/deploy/pathplanner/generatedJSON/New Path.wpilib.json @@ -0,0 +1 @@ +[{"acceleration":0.0,"curvature":0.6639756640813854,"pose":{"rotation":{"radians":0.003994666723425411},"translation":{"x":1.0,"y":3.0}},"time":0.0,"velocity":0,"position":0.0,"holonomicRotation":0.0,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":1.5060792949143798},{"acceleration":2.5,"curvature":0.6639756640813854,"pose":{"rotation":{"radians":0.003994666723425411},"translation":{"x":1.011999936,"y":3.000047936}},"time":0.06928212394059348,"velocity":0.1732053098514837,"position":0.012000031744299389,"holonomicRotation":0.0,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":1.5060792949143798},{"acceleration":8.535371252576768,"curvature":0.6612478412834536,"pose":{"rotation":{"radians":0.011962542633933815},"translation":{"x":1.023999488,"y":3.000191488}},"time":0.09798049270747501,"velocity":0.4181565416201713,"position":0.02400044237799891,"holonomicRotation":0.0,"angularVelocity":0.2776421187988735,"angularAcceleration":9.674491294406874,"curveRadius":1.5122922716224572},{"acceleration":5.757894093816358,"curvature":0.6584819160891061,"pose":{"rotation":{"radians":0.019898056756403104},"translation":{"x":1.035998272,"y":3.000430272}},"time":0.12000267017892227,"velocity":0.5449579072159931,"position":0.036001602125178,"holonomicRotation":0.0,"angularVelocity":0.36034193860975094,"angularAcceleration":3.755297128002054,"curveRadius":1.5186445907873338},{"acceleration":5.46523367160251,"curvature":0.6556801390904735,"pose":{"rotation":{"radians":0.027800989511962193},"translation":{"x":1.047995904,"y":3.000763904}},"time":0.13856965334988583,"velocity":0.6464308088220203,"position":0.048003872073768813,"holonomicRotation":0.0,"angularVelocity":0.4256444185245069,"angularAcceleration":3.5171292672296315,"curveRadius":1.5251338882814869},{"acceleration":5.337340132223491,"curvature":0.6528447360474213,"pose":{"rotation":{"radians":0.035671139219506376},"translation":{"x":1.059992,"y":3.001192}},"time":0.154929150542432,"velocity":0.7337470097307945,"position":0.0600076042194989,"holonomicRotation":0.0,"angularVelocity":0.4810752809157261,"angularAcceleration":3.3882986584988064,"curveRadius":1.5317577745275135},{"acceleration":5.264929926173566,"curvature":0.6499779059037429,"pose":{"rotation":{"radians":0.043508321861275956},"translation":{"x":1.071986176,"y":3.001714176}},"time":0.16972111419916255,"velocity":0.811625661853987,"position":0.07201314151251295,"holonomicRotation":0.0,"angularVelocity":0.5298270617507603,"angularAcceleration":3.2958288680523826,"curveRadius":1.538513833958062},{"acceleration":5.218186305247873,"curvature":0.6470818190817624,"pose":{"rotation":{"radians":0.05131237083808626},"translation":{"x":1.083978048,"y":3.0023300479999997}},"time":0.18332574058935158,"velocity":0.8826171369712852,"position":0.08402081790658558,"holonomicRotation":0.0,"angularVelocity":0.5736319949541719,"angularAcceleration":3.2198556540296854,"curveRadius":1.5453996241449715},{"acceleration":5.185469967192958,"curvature":0.6441586157879952,"pose":{"rotation":{"radians":0.059083136714003004},"translation":{"x":1.095967232,"y":3.0030392320000003}},"time":0.19599077367144688,"velocity":0.9482912856519956,"position":0.09603095841083079,"holonomicRotation":0.0,"angularVelocity":0.613560645720094,"angularAcceleration":3.1526684934103804,"curveRadius":1.5524126752177434},{"acceleration":5.161271006272372,"curvature":0.6412104045031461,"pose":{"rotation":{"radians":0.06682048695107579},"translation":{"x":1.107953344,"y":3.003841344}},"time":0.20788831534631302,"velocity":1.0096977225443995,"position":0.10804387914382022,"holonomicRotation":0.0,"angularVelocity":0.6503318457306292,"angularAcceleration":3.0906552811842904,"curveRadius":1.5595504891641125},{"acceleration":5.142636662349754,"curvature":0.6382392605344197,"pose":{"rotation":{"radians":0.07452430563697954},"translation":{"x":1.119936,"y":3.004736}},"time":0.21914368564028228,"velocity":1.067580002466488,"position":0.12005988739001715,"holonomicRotation":0.0,"angularVelocity":0.6844571510927135,"angularAcceleration":3.0319131641869714,"curveRadius":1.5668105392994245},{"acceleration":5.127839939713169,"curvature":0.6352472246423004,"pose":{"rotation":{"radians":0.08219449320285621},"translation":{"x":1.131914816,"y":3.005722816}},"time":0.2298515013293901,"velocity":1.1224879674241826,"position":0.13207928165843658,"holonomicRotation":0.0,"angularVelocity":0.7163167342970718,"angularAcceleration":2.9753578254775443,"curveRadius":1.5741902698797106},{"acceleration":5.115802568874648,"curvature":0.6322363019942066,"pose":{"rotation":{"radians":0.08983096613524788},"translation":{"x":1.1438894080000002,"y":3.0068014080000003}},"time":0.2400852779688426,"velocity":1.174841948245583,"position":0.14410235174344108,"holonomicRotation":0.0,"angularVelocity":0.7462028146043475,"angularAcceleration":2.9203373651972337,"curveRadius":1.5816870952297255},{"acceleration":5.105816223075832,"curvature":0.6292084609699508,"pose":{"rotation":{"radians":0.09743365668116732},"translation":{"x":1.1558593920000002,"y":3.007971392}},"time":0.24990348439954382,"velocity":1.2249719059209647,"position":0.15612937878758262,"holonomicRotation":0.0,"angularVelocity":0.7743461700037261,"angularAcceleration":2.8664456790575557,"curveRadius":1.5892983995454524},{"acceleration":5.097396249124222,"curvature":0.6261656322069515,"pose":{"rotation":{"radians":0.10500251254764281},"translation":{"x":1.1678243840000002,"y":3.009232384}},"time":0.2593535311858327,"velocity":1.273142538963442,"position":0.16816063534640177,"holonomicRotation":0.0,"angularVelocity":0.8009331633635057,"angularAcceleration":2.813424521702352,"curveRadius":1.5970215364191274},{"acceleration":5.090199765560662,"curvature":0.6231097077741713,"pose":{"rotation":{"radians":0.11253749659552614},"translation":{"x":1.1797840000000002,"y":3.010584}},"time":0.26847449447207833,"velocity":1.319570064144777,"position":0.18019638545509506,"holonomicRotation":0.0,"angularVelocity":0.826117133838929,"angularAcceleration":2.7611086334927637,"curveRadius":1.6048538283444977},{"acceleration":5.083977317704919,"curvature":0.6200425403858878,"pose":{"rotation":{"radians":0.12003858652989674},"translation":{"x":1.191737856,"y":3.012025856}},"time":0.27729903331743866,"velocity":1.3644338194737948,"position":0.19223688469696493,"holonomicRotation":0.0,"angularVelocity":0.8500262807857023,"angularAcceleration":2.7093933593304937,"curveRadius":1.6127925664223668},{"acceleration":5.0785430648490575,"curvature":0.6169659427566434,"pose":{"rotation":{"radians":0.12750577458585077},"translation":{"x":1.203685568,"y":3.013557568}},"time":0.28585477450871083,"velocity":1.4078845195653735,"position":0.20428238027356482,"holonomicRotation":0.0,"angularVelocity":0.8727692772627829,"angularAcceleration":2.6582146384092358,"curveRadius":1.6208350100038518},{"acceleration":5.073755704908961,"curvature":0.6138816870208452,"pose":{"rotation":{"radians":0.1349390672116768},"translation":{"x":1.2156267520000001,"y":3.0151787519999997}},"time":0.29416533519533156,"velocity":1.4500502742601076,"position":0.21633311107645448,"holonomicRotation":0.0,"angularVelocity":0.8944393652997428,"angularAcceleration":2.6075362245831197,"curveRadius":1.6289783864590892},{"acceleration":5.06950587804063,"curvature":0.6107915042289077,"pose":{"rotation":{"radians":0.14233848474922883},"translation":{"x":1.2275610240000001,"y":3.016889024}},"time":0.3022510928089309,"velocity":1.4910410700106613,"position":0.22838930776048252,"holonomicRotation":0.0,"angularVelocity":0.9151174065751126,"angularAcceleration":2.557341224351279,"curveRadius":1.6372198910370368},{"acceleration":5.065707618301824,"curvature":0.6076970841012796,"pose":{"rotation":{"radians":0.1497040611122218},"translation":{"x":1.2394880000000001,"y":3.018688}},"time":0.310129774654749,"velocity":1.5309521686591983,"position":0.24045119281851357,"holonomicRotation":0.0,"angularVelocity":0.9348741968686707,"angularAcceleration":2.5076263618951344,"curveRadius":1.6455566863199538},{"acceleration":5.062292412184033,"curvature":0.6046000745612534,"pose":{"rotation":{"radians":0.15703584346380906},"translation":{"x":1.2514072960000002,"y":3.020575296}},"time":0.3178169162631331,"velocity":1.569866727294705,"position":0.25251898065751843,"holonomicRotation":0.0,"angularVelocity":0.9537722504800447,"angularAcceleration":2.4583980072336105,"curveRadius":1.6539859025417434},{"acceleration":5.059204981038369,"curvature":0.6015020816536292,"pose":{"rotation":{"radians":0.16433389189228276},"translation":{"x":1.263318528,"y":3.022550528}},"time":0.3253262225372852,"velocity":1.6078578470010383,"position":0.2645928776759481,"holonomicRotation":0.0,"angularVelocity":0.9718671954551102,"angularAcceleration":2.409669324229108,"curveRadius":1.662504637142458},{"acceleration":5.05640023061235,"curvature":0.598404669370064,"pose":{"rotation":{"radians":0.17159827908724612},"translation":{"x":1.2752213120000002,"y":3.024613312}},"time":0.3326698557683368,"velocity":1.64499019576406,"position":0.2766730823423151,"holonomicRotation":0.0,"angularVelocity":0.9892088788212979,"angularAcceleration":2.3614582619486866,"curveRadius":1.6711099548282142},{"acceleration":5.053841007338749,"curvature":0.595309359586865,"pose":{"rotation":{"radians":0.178829090015451},"translation":{"x":1.2871152640000003,"y":3.026763264}},"time":0.33985866784585744,"velocity":1.681321309035486,"position":0.2887597852749022,"holonomicRotation":0.0,"angularVelocity":1.0058422518534826,"angularAcceleration":2.31378604042205,"curveRadius":1.679798887580037},{"acceleration":5.051496422970804,"curvature":0.5922176320623258,"pose":{"rotation":{"radians":0.1860264215975338},"translation":{"x":1.2990000000000002,"y":3.0290000000000004}},"time":0.34690238933886214,"velocity":1.7169026429618017,"position":0.3008531693225288,"holonomicRotation":0.0,"angularVelocity":1.0218080867096546,"angularAcceleration":2.266676056404,"curveRadius":1.6885684347452163},{"acceleration":5.0493405862755125,"curvature":0.5891309246519478,"pose":{"rotation":{"radians":0.19319038238530206},"translation":{"x":1.3108751360000002,"y":3.031323136}},"time":0.3538097848541212,"velocity":1.7517804354824567,"position":0.31295340964629886,"holonomicRotation":0.0,"angularVelocity":1.0371435618450469,"angularAcceleration":2.2201530376412983,"curveRadius":1.6974155627474303},{"acceleration":5.0473516309486985,"curvature":0.586050633250819,"pose":{"rotation":{"radians":0.2003210922413352},"translation":{"x":1.3227402880000003,"y":3.033732288}},"time":0.36058878174577724,"velocity":1.785996416499753,"position":0.32506067380225956,"holonomicRotation":0.0,"angularVelocity":1.0518827446004568,"angularAcceleration":2.1742424419093207,"curveRadius":1.7063372058025204},{"acceleration":5.045510961967792,"curvature":0.5829781121894732,"pose":{"rotation":{"radians":0.20741868201941793},"translation":{"x":1.3345950720000002,"y":3.036227072}},"time":0.3672465775605823,"velocity":1.8195883982658954,"position":0.3371751218249021,"holonomicRotation":0.0,"angularVelocity":1.0660569917598954,"angularAcceleration":2.1289699404597293,"curveRadius":1.7153302655640543},{"acceleration":5.043802665249439,"curvature":0.5799146744073622,"pose":{"rotation":{"radians":0.21448329324782645},"translation":{"x":1.3464391040000003,"y":3.038807104}},"time":0.37378973036264074,"velocity":1.852590769808052,"position":0.3492969063114392,"holonomicRotation":0.0,"angularVelocity":1.0796952848458699,"angularAcceleration":2.08436108685769,"curveRadius":1.724391611614139},{"acceleration":5.0422130406748575,"curvature":0.576861591813293,"pose":{"rotation":{"radians":0.22151507781517443},"translation":{"x":1.3582720000000004,"y":3.041472}},"time":0.38022423515961634,"velocity":1.8850349138056472,"position":0.36142617250678816,"holonomicRotation":0.0,"angularVelocity":1.0928245124089613,"angularAcceleration":2.0404410249662925,"curveRadius":1.7335180816192388},{"acceleration":5.040730229482769,"curvature":0.5738200956320813,"pose":{"rotation":{"radians":0.22851419765877612},"translation":{"x":1.3700933760000003,"y":3.044221376}},"time":0.38655558895931247,"velocity":1.916949560297326,"position":0.37356305838920245,"holonomicRotation":0.0,"angularVelocity":1.105469709169879,"angularAcceleration":1.9972342663151608,"curveRadius":1.7427064817213622},{"acceleration":5.03934391448348,"curvature":0.5707913768705666,"pose":{"rotation":{"radians":0.2354808244568085},"translation":{"x":1.3819028480000004,"y":3.047054848}},"time":0.3927888464590037,"velocity":1.9483610885458036,"position":0.38570769475648714,"holonomicRotation":0.0,"angularVelocity":1.1176542599720127,"angularAcceleration":1.954764551719103,"curveRadius":1.7519535867598808},{"acceleration":5.038045076971982,"curvature":0.5677765867125653,"pose":{"rotation":{"radians":0.24241513932314662},"translation":{"x":1.3937000320000004,"y":3.0499720320000003}},"time":0.3989286679659584,"velocity":1.9792937860624034,"position":0.39786020531273486,"holonomicRotation":0.0,"angularVelocity":1.1294000743317183,"angularAcceleration":1.9130546948964007,"curveRadius":1.7612561408881169},{"acceleration":5.036825798293777,"curvature":0.5647768371119535,"pose":{"rotation":{"radians":0.24931733250680344},"translation":{"x":1.4054845440000003,"y":3.0529725439999997}},"time":0.40497936083486147,"velocity":2.0097700720020466,"position":0.4100207067555325,"holonomicRotation":0.0,"angularVelocity":1.1407277370051168,"angularAcceleration":1.872126534733869,"curveRadius":1.7706108577568558},{"acceleration":5.035679096669537,"curvature":0.5617932012303706,"pose":{"rotation":{"radians":0.2561876030951167},"translation":{"x":1.4172560000000003,"y":3.0560560000000003}},"time":0.4109449154636546,"velocity":2.0398106907463003,"position":0.42218930886357575,"holonomicRotation":0.0,"angularVelocity":1.1516566381193567,"angularAcceleration":1.8320008438931956,"curveRadius":1.7800144213385327},{"acceleration":5.034598792278616,"curvature":0.5588267141256478,"pose":{"rotation":{"radians":0.2630261587202831},"translation":{"x":1.4290140160000004,"y":3.059222016}},"time":0.4168290366971277,"velocity":2.069434880401965,"position":0.4343661145846388,"holonomicRotation":0.0,"angularVelocity":1.162205086167131,"angularAcceleration":1.7926972659514717,"curveRadius":1.7894634861266812},{"acceleration":5.033579395005612,"curvature":0.5558783732950194,"pose":{"rotation":{"radians":0.26983321527222115},"translation":{"x":1.4407582080000003,"y":3.062470208}},"time":0.42263517133520734,"velocity":2.098660520080831,"position":0.4465512201238504,"holonomicRotation":0.0,"angularVelocity":1.1723904070866351,"angularAcceleration":1.7542343666479139,"curveRadius":1.79895467793145},{"acceleration":5.0326160105214335,"curvature":0.5529491392614916,"pose":{"rotation":{"radians":0.2766089966139682},"translation":{"x":1.4524881920000003,"y":3.065800192}},"time":0.4283665323211994,"velocity":2.1275042591410127,"position":0.4587447150322232,"holonomicRotation":0.0,"angularVelocity":1.1822290304707068,"angularAcceleration":1.7166295070434598,"curveRadius":1.8084845946872818},{"acceleration":5.031704261299394,"curvature":0.550039936396451,"pose":{"rotation":{"radians":0.2833537343033705},"translation":{"x":1.4642035840000003,"y":3.069211584}},"time":0.4340261200874376,"velocity":2.155981631021591,"position":0.47094668229538716,"holonomicRotation":0.0,"angularVelocity":1.1917365659805728,"angularAcceleration":1.679898943626678,"curveRadius":1.8180498066221003},{"acceleration":5.030840219915007,"curvature":0.5471516534114057,"pose":{"rotation":{"radians":0.2900676673190703},"translation":{"x":1.4759040000000003,"y":3.072704}},"time":0.439616741456685,"velocity":2.1841071538603174,"position":0.48315719842248483,"holonomicRotation":0.0,"angularVelocity":1.2009278704924287,"angularAcceleration":1.644057771899007,"curveRadius":1.8276468576219318},{"acceleration":5.030020352377661,"curvature":0.5442851441519642,"pose":{"rotation":{"radians":0.29675104179171763},"translation":{"x":1.4875890560000005,"y":3.0762770560000003}},"time":0.44514102643327713,"velocity":2.21189441972491,"position":0.4953763335351791,"holonomicRotation":0.0,"angularVelocity":1.2098171077282527,"angularAcceleration":1.6091199627626183,"curveRadius":1.8372722657313616},{"acceleration":5.029241469861432,"curvature":0.5414412284047404,"pose":{"rotation":{"radians":0.30340411074019924},"translation":{"x":1.4992583680000005,"y":3.0799303680000003}},"time":0.45060144316534684,"velocity":2.23935617399656,"position":0.5076041514567335,"holonomicRotation":0.0,"angularVelocity":1.2184178012288531,"angularAcceleration":1.5750983711714714,"curveRadius":1.8469225236990559},{"acceleration":5.028500687331141,"curvature":0.538620692477182,"pose":{"rotation":{"radians":0.3100271338137768},"translation":{"x":1.5109115520000005,"y":3.083663552}},"time":0.45600031131617674,"velocity":2.2665043862038186,"position":0.5198407098011256,"holonomicRotation":0.0,"angularVelocity":1.22674288175744,"angularAcceleration":1.5420047861896957,"curveRadius":1.8565941003879343},{"acceleration":5.027795388007443,"curvature":0.5358242899805497,"pose":{"rotation":{"radians":0.3166203770389595},"translation":{"x":1.5225482240000003,"y":3.087476224}},"time":0.46133981404693414,"velocity":2.2933503134077737,"position":0.5320860600621498,"holonomicRotation":0.0,"angularVelocity":1.2348047295122362,"angularAcceleration":1.5098499169889334,"curveRadius":1.8662834416041494},{"acceleration":5.02712319273624,"curvature":0.5330527427341295,"pose":{"rotation":{"radians":0.32318411257205604},"translation":{"x":1.5341680000000004,"y":3.091368}},"time":0.4666220087833307,"velocity":2.3199045570756622,"position":0.5443402477024772,"holonomicRotation":0.0,"angularVelocity":1.242615212171106,"angularAcceleration":1.478643451944757,"curveRadius":1.8759869705778243},{"acceleration":5.0264819333958135,"curvature":0.530306741366546,"pose":{"rotation":{"radians":0.32971861845760264},"translation":{"x":1.5457704960000005,"y":3.095338496}},"time":0.4718488369139562,"velocity":2.346177114243216,"position":0.5566033122426334,"holonomicRotation":0.0,"angularVelocity":1.2501857191858055,"angularAcceleration":1.448394097816544,"curveRadius":1.8857010895677147},{"acceleration":5.025869629879915,"curvature":0.5275869461466284,"pose":{"rotation":{"radians":0.33622417839207364},"translation":{"x":1.5573553280000003,"y":3.099387328}},"time":0.4770221325472695,"velocity":2.372177423653076,"position":0.5688752873498623,"holonomicRotation":0.0,"angularVelocity":1.2575271926426548,"angularAcceleration":1.4191095922634078,"curveRadius":1.8954221807490992},{"acceleration":5.025284469962086,"curvature":0.5248939877909048,"pose":{"rotation":{"radians":0.3427010814932183},"translation":{"x":1.5689221120000005,"y":3.103514112}},"time":0.48214363043675873,"velocity":2.39791440746007,"position":0.5811562009268448,"holonomicRotation":0.0,"angularVelocity":1.2646501552674898,"angularAcceleration":1.3907967509765777,"curveRadius":1.9051466072390164},{"acceleration":5.024724791773052,"curvature":0.5222284682600525,"pose":{"rotation":{"radians":0.34914962207543976},"translation":{"x":1.5804704640000005,"y":3.1077184640000004}},"time":0.4872149731690263,"velocity":2.4233965090144727,"position":0.593446075200238,"holonomicRotation":0.0,"angularVelocity":1.2715647359408684,"angularAcceleration":1.3634615206310163,"curveRadius":1.9148707142139807},{"acceleration":5.024189068330722,"curvature":0.5195909614569448,"pose":{"rotation":{"radians":0.35557009943017936},"translation":{"x":1.5920000000000005,"y":3.112}},"time":0.4922377176970531,"velocity":2.448631727165203,"position":0.6057449268090098,"holonomicRotation":0.0,"angularVelocity":1.278280692739492,"angularAcceleration":1.337108977203357,"curveRadius":1.9245908304408863},{"acceleration":5.023675894057896,"curvature":0.5169820141397625,"pose":{"rotation":{"radians":0.36196281761306626},"translation":{"x":1.6035103360000005,"y":3.1163583360000002}},"time":0.49721334129025185,"velocity":2.4736276474682612,"position":0.6180527668925416,"holonomicRotation":0.0,"angularVelocity":1.2848074343133964,"angularAcceleration":1.3117434330896347,"curveRadius":1.9343032690681903},{"acceleration":5.023183972798196,"curvature":0.5144021466205864,"pose":{"rotation":{"radians":0.3683280852354529},"translation":{"x":1.6150010880000005,"y":3.120793088}},"time":0.5021432469638396,"velocity":2.498391470635234,"position":0.6303696011784695,"holonomicRotation":0.0,"angularVelocity":1.2911540390090888,"angularAcceleration":1.2873683830696117,"curveRadius":1.9440043292385047},{"acceleration":5.022712107271205,"curvature":0.5118518535480218,"pose":{"rotation":{"radians":0.37466621526293364},"translation":{"x":1.6264718720000004,"y":3.1253038720000004}},"time":0.5070287684422823,"velocity":2.5229300385153417,"position":0.6426954300702444,"holonomicRotation":0.0,"angularVelocity":1.2973292729236137,"angularAcceleration":1.2639866474383685,"curveRadius":1.95369029743326},{"acceleration":5.022259189692621,"curvature":0.5093316047891678,"pose":{"rotation":{"radians":0.3809775248184435},"translation":{"x":1.6379223040000006,"y":3.1298903040000003}},"time":0.5118711747048803,"velocity":2.5472498578678997,"position":0.6550302487343859,"holonomicRotation":0.0,"angularVelocity":1.3033416060642007,"angularAcceleration":1.2416003149147838,"curveRadius":1.963357448462164},{"acceleration":5.021824193554781,"curvature":0.5068418460483123,"pose":{"rotation":{"radians":0.3872623349919482},"translation":{"x":1.6493520000000006,"y":3.1345520000000002}},"time":0.5166716741558056,"velocity":2.571357122151703,"position":0.667374047187408,"holonomicRotation":0.0,"angularVelocity":1.309199227653962,"angularAcceleration":1.220210865482371,"curveRadius":1.9730020474763241},{"acceleration":5.021406166088234,"curvature":0.5043829997706955,"pose":{"rotation":{"radians":0.3935209706549796},"translation":{"x":1.6607605760000006,"y":3.139288576}},"time":0.5214314184559268,"velocity":2.5952577315293346,"position":0.6797268103824001,"holonomicRotation":0.0,"angularVelocity":1.3149100599526125,"angularAcceleration":1.1998191370290998,"curveRadius":1.982620350913143},{"acceleration":5.021004221759715,"curvature":0.5019554658535227,"pose":{"rotation":{"radians":0.3997537602811718},"translation":{"x":1.6721476480000006,"y":3.144099648}},"time":0.5261515060494417,"velocity":2.6189573112634488,"position":0.69208851829524,"holonomicRotation":0.0,"angularVelocity":1.3204817713034869,"angularAcceleration":1.1804254138269692,"curveRadius":1.992208608187192},{"acceleration":5.02061753633249,"curvature":0.4995596223797258,"pose":{"rotation":{"radians":0.4059610357723282},"translation":{"x":1.6835128320000006,"y":3.1489848320000005}},"time":0.5308329854145933,"velocity":2.6424612286601077,"position":0.7044591460104255,"holonomicRotation":0.0,"angularVelocity":1.32592178817718,"angularAcceleration":1.1620294461165557,"curveRadius":2.001763063308345},{"acceleration":5.020245341601659,"curvature":0.497195826433042,"pose":{"rotation":{"radians":0.41214313228956323},"translation":{"x":1.6948557440000005,"y":3.153943744}},"time":0.5354768580644753,"velocity":2.665774608697669,"position":0.7168386638065064,"holonomicRotation":0.0,"angularVelocity":1.3312373063012661,"angularAcceleration":1.144630467896473,"curveRadius":2.011279956177732},{"acceleration":5.01988692061515,"curvature":0.49486441475959786,"pose":{"rotation":{"radians":0.41830038809061465},"translation":{"x":1.7061760000000006,"y":3.158976}},"time":0.5400840813210863,"velocity":2.6889023484638845,"position":0.7292270372411052,"holonomicRotation":0.0,"angularVelocity":1.3364353012883066,"angularAcceleration":1.1282272851834818,"curveRadius":2.020755524492085},{"acceleration":5.019541603414005,"curvature":0.49256570452373255,"pose":{"rotation":{"radians":0.4244331443716547},"translation":{"x":1.7174732160000006,"y":3.164081216}},"time":0.5446555708832902,"velocity":2.71184913051094,"position":0.7416242272355076,"holonomicRotation":0.0,"angularVelocity":1.3415225382432,"angularAcceleration":1.1128182369601232,"curveRadius":2.030186005269919},{"acceleration":5.019208763156362,"curvature":0.4902999940555179,"pose":{"rotation":{"radians":0.4305417451149389},"translation":{"x":1.7287470080000005,"y":3.1692590080000005}},"time":0.5491922032071528,"velocity":2.7346194352260893,"position":0.7540301901588171,"holonomicRotation":0.0,"angularVelocity":1.346505581056927,"angularAcceleration":1.0984012937342293,"curveRadius":2.039567636394398},{"acceleration":5.0188878127210605,"curvature":0.48806756353004915,"pose":{"rotation":{"radians":0.43662653694140374},"translation":{"x":1.7399969920000007,"y":3.1745089920000003}},"time":0.5536948177151946,"velocity":2.7572175523058813,"position":0.766444877911657,"holonomicRotation":0.0,"angularVelocity":1.3513908009662423,"angularAcceleration":1.0849740524288933,"curveRadius":2.048896658420187},{"acceleration":5.018578201432966,"curvature":0.48586867565117137,"pose":{"rotation":{"radians":0.44268786896893575},"translation":{"x":1.7512227840000005,"y":3.1798307840000004}},"time":0.5581642188494038,"velocity":2.7796475914114835,"position":0.7788682380094135,"holonomicRotation":0.0,"angularVelocity":1.3561843847798694,"angularAcceleration":1.0725338070321053,"curveRadius":2.058169316348248},{"acceleration":5.018279412372937,"curvature":0.4837035763245057,"pose":{"rotation":{"radians":0.44872609267459884},"translation":{"x":1.7624240000000007,"y":3.1852240000000003}},"time":0.5626011779813506,"velocity":2.801913492076872,"position":0.7913002136650088,"holonomicRotation":0.0,"angularVelocity":1.3608923422771704,"angularAcceleration":1.0610774986415903,"curveRadius":2.0673818614256487},{"acceleration":5.017990959656474,"curvature":0.48157249540881814,"pose":{"rotation":{"radians":0.45474156176317626},"translation":{"x":1.7736002560000006,"y":3.190688256}},"time":0.5670064351914168,"velocity":2.824019032931946,"position":0.8037407438711965,"holonomicRotation":0.0,"angularVelocity":1.3655205137243211,"angularAcceleration":1.0506018664642707,"curveRadius":2.0765305525829016},{"acceleration":5.017712386125292,"curvature":0.47947564724702235,"pose":{"rotation":{"radians":0.46073463203958775},"translation":{"x":1.7847511680000006,"y":3.1962231680000004}},"time":0.5713807009279798,"velocity":2.8459678402985014,"position":0.8161897634823744,"holonomicRotation":0.0,"angularVelocity":1.3700745764752023,"angularAcceleration":1.0411033588598146,"curveRadius":2.085611658781092},{"acceleration":5.017443261290665,"curvature":0.4774132314234743,"pose":{"rotation":{"radians":0.4667056612864813},"translation":{"x":1.7958763520000005,"y":3.2018283520000006}},"time":0.5757246575563368,"velocity":2.8677633962107905,"position":0.828647203295904,"holonomicRotation":0.0,"angularVelocity":1.3745600515242316,"angularAcceleration":1.0325782305809417,"curveRadius":2.0946214603612057},{"acceleration":5.017183179268821,"curvature":0.47538543331431704,"pose":{"rotation":{"radians":0.4726550091467523},"translation":{"x":1.8069754240000007,"y":3.2075034240000004}},"time":0.5800389608062332,"velocity":2.889409045906435,"position":0.841112990132938,"holonomicRotation":0.0,"angularVelocity":1.3789823096959986,"angularAcceleration":1.0250225623044116,"curveRadius":2.103556251246799},{"acceleration":5.016931757039359,"curvature":0.47339242474423837,"pose":{"rotation":{"radians":0.47858303701043514},"translation":{"x":1.8180480000000006,"y":3.2132480000000005}},"time":0.584324241126019,"velocity":2.9109080048305844,"position":0.8535870469187455,"holonomicRotation":0.0,"angularVelocity":1.3833465774251021,"angularAcceleration":1.0184322619346695,"curveRadius":2.112412340650094},{"acceleration":5.016688632911706,"curvature":0.4714343645997835,"pose":{"rotation":{"radians":0.48449010790589764},"translation":{"x":1.8290936960000006,"y":3.2190616960000002}},"time":0.5885811049507232,"velocity":2.9322633651918313,"position":0.8660692927625362,"holonomicRotation":0.0,"angularVelocity":1.3876579422582063,"angularAcceleration":1.0128030894677875,"curveRadius":2.121186054921842},{"acceleration":5.016453464862565,"curvature":0.46951139933779384,"pose":{"rotation":{"radians":0.4903765863962497},"translation":{"x":1.8401121280000006,"y":3.2249441280000006}},"time":0.5928101358906669,"velocity":2.9534781021035226,"position":0.878559643036778,"holonomicRotation":0.0,"angularVelocity":1.3919213583314447,"angularAcceleration":1.0081307358075862,"curveRadius":2.1298737398291405},{"acceleration":5.016225929281237,"curvature":0.4676236637211531,"pose":{"rotation":{"radians":0.49624283847896633},"translation":{"x":1.8511029120000007,"y":3.230894912}},"time":0.5970118958466426,"velocity":2.9745550793433035,"position":0.8910580094560069,"holonomicRotation":0.0,"angularVelocity":1.3961416511606484,"angularAcceleration":1.0044107405996843,"curveRadius":2.138471761763336},{"acceleration":5.016005719774995,"curvature":0.465771281161275,"pose":{"rotation":{"radians":0.5020892314911949},"translation":{"x":1.8620656640000006,"y":3.2369136640000002}},"time":0.601186926057156,"velocity":2.995497054759472,"position":0.9035643001551315,"holonomicRotation":0.0,"angularVelocity":1.4003235228110353,"angularAcceleration":1.0016386563758004,"curveRadius":2.146976510674445},{"acceleration":5.0157925459230865,"curvature":0.4639543644847911,"pose":{"rotation":{"radians":0.5079161340175653},"translation":{"x":1.8730000000000007,"y":3.2430000000000003}},"time":0.6053357480827395,"velocity":3.0163066853497553,"position":0.9160784197672254,"holonomicRotation":0.0,"angularVelocity":1.4044715561282388,"angularAcceleration":0.9998098958270114,"curveRadius":2.155384401029341},{"acceleration":5.015586132146781,"curvature":0.462173016289964,"pose":{"rotation":{"radians":0.5137239158035309},"translation":{"x":1.8839055360000008,"y":3.249153536}},"time":0.609458864731924,"velocity":3.0369865320366287,"position":0.9286002695008148,"holonomicRotation":0.0,"angularVelocity":1.408590219516179,"angularAcceleration":0.9989199283883466,"curveRadius":2.163691874587086},{"acceleration":5.01538621700277,"curvature":0.4604273295606459,"pose":{"rotation":{"radians":0.5195129476718603},"translation":{"x":1.8947818880000007,"y":3.2553738880000003}},"time":0.6135567609330557,"velocity":3.0575390641624924,"position":0.9411297472166579,"holonomicRotation":0.0,"angularVelocity":1.4126838709898704,"angularAcceleration":0.9989641691170351,"curveRadius":2.171895401939392},{"acceleration":5.015192551907903,"curvature":0.4587173881423953,"pose":{"rotation":{"radians":0.5252836014429918},"translation":{"x":1.9056286720000006,"y":3.2616606720000005}},"time":0.6176299045558008,"velocity":3.077966663722135,"position":0.9536667475040198,"holonomicRotation":0.0,"angularVelocity":1.416756762248005,"angularAcceleration":0.9999380418090288,"curveRadius":2.1799914846253428},{"acceleration":5.015004900736067,"curvature":0.45704326727847255,"pose":{"rotation":{"radians":0.5310362498595436},"translation":{"x":1.9164455040000006,"y":3.2680135040000002}},"time":0.6216787471858577,"velocity":3.0982716293541794,"position":0.9662111617564448,"holonomicRotation":0.0,"angularVelocity":1.4208130426820098,"angularAcceleration":1.0018370197677322,"curveRadius":2.187976656903051},{"acceleration":5.014823038634472,"curvature":0.4554050339448593,"pose":{"rotation":{"radians":0.5367712665143531},"translation":{"x":1.9272320000000007,"y":3.2744320000000005}},"time":0.6257037248561109,"velocity":3.1184561801049546,"position":0.9787628782470305,"holonomicRotation":0.0,"angularVelocity":1.424856763105661,"angularAcceleration":1.0046566105289205,"curveRadius":2.1958474884163897},{"acceleration":5.014646751628742,"curvature":0.45380274753675837,"pose":{"rotation":{"radians":0.5424890257816597},"translation":{"x":1.9379877760000008,"y":3.2809157760000005}},"time":0.6297052587371973,"velocity":3.1385224589832768,"position":0.9913217822032026,"holonomicRotation":0.0,"angularVelocity":1.4288918792696181,"angularAcceleration":1.0083923524999971,"curveRadius":2.2036005851176546},{"acceleration":5.0144758358124255,"curvature":0.45223646009204105,"pose":{"rotation":{"radians":0.5481899027524935},"translation":{"x":1.9487124480000007,"y":3.2874644480000006}},"time":0.6336837557902212,"velocity":3.158472536318516,"position":1.0038877558810027,"holonomicRotation":0.0,"angularVelocity":1.4329222555288237,"angularAcceleration":1.0130399006183073,"curveRadius":2.2112325923400244},{"acceleration":5.01431009678587,"curvature":0.45070621683540724,"pose":{"rotation":{"radians":0.5538742731727626},"translation":{"x":1.9594056320000008,"y":3.2940776320000005}},"time":0.6376396093841366,"velocity":3.1783084129358925,"position":1.0164606786388866,"holonomicRotation":0.0,"angularVelocity":1.436951668032524,"angularAcceleration":1.0185949525276017,"curveRadius":2.2187401962666704},{"acceleration":5.014149349022059,"curvature":0.44921205667481234,"pose":{"rotation":{"radians":0.5595425133851966},"translation":{"x":1.9700669440000007,"y":3.3007549440000004}},"time":0.6415731998801192,"velocity":3.198032023160643,"position":1.0290404270110394,"holonomicRotation":0.0,"angularVelocity":1.4409838081068465,"angularAcceleration":1.0250533395482873,"curveRadius":2.226120125542193},{"acceleration":5.013993415475468,"curvature":0.4477540124322439,"pose":{"rotation":{"radians":0.5651950002738984},"translation":{"x":1.980696000000001,"y":3.3074960000000004}},"time":0.6454848951850748,"velocity":3.217645237663037,"position":1.0416268747802186,"holonomicRotation":0.0,"angularVelocity":1.445022285232908,"angularAcceleration":1.0324109653799747,"curveRadius":2.233369154120812},{"acceleration":5.013842126937208,"curvature":0.44633211133455136,"pose":{"rotation":{"radians":0.5708321112125092},"translation":{"x":1.9912924160000007,"y":3.3143004160000005}},"time":0.6493750512762622,"velocity":3.2371498661533935,"position":1.0542198930501216,"holonomicRotation":0.0,"angularVelocity":1.4490706301942438,"angularAcceleration":1.0406638876282515,"curveRadius":2.2404841027681357},{"acceleration":5.013695321718138,"curvature":0.4449463754713489,"pose":{"rotation":{"radians":0.5764542240150154},"translation":{"x":2.0018558080000006,"y":3.3211678080000007}},"time":0.653244012698867,"velocity":3.2565476599378154,"position":1.0668193503172951,"holonomicRotation":0.0,"angularVelocity":1.453132297897418,"angularAcceleration":1.049808271398992,"curveRadius":2.247461840633405},{"acceleration":5.013552845175744,"curvature":0.44359682198548334,"pose":{"rotation":{"radians":0.5820617168896036},"translation":{"x":2.012385792000001,"y":3.3280977920000003}},"time":0.65709211303822,"velocity":3.2758403143427004,"position":1.0794251125425836,"holonomicRotation":0.0,"angularVelocity":1.457210670221497,"angularAcceleration":1.0598404314906338,"curveRadius":2.254299288088058},{"acceleration":5.013414549243218,"curvature":0.44228346357140413,"pose":{"rotation":{"radians":0.5876549683955372},"translation":{"x":2.022881984000001,"y":3.3350899840000006}},"time":0.6609196753682344,"velocity":3.2950294710161296,"position":1.092037043222132,"holonomicRotation":0.0,"angularVelocity":1.461309058790067,"angularAcceleration":1.0707568460562602,"curveRadius":2.2609934179430513},{"acceleration":5.013280292169202,"curvature":0.44100630878383207,"pose":{"rotation":{"radians":0.5932343574021122},"translation":{"x":2.0333440000000005,"y":3.3421440000000007}},"time":0.6647270126775175,"velocity":3.3141167201143995,"position":1.1046550034579428,"holonomicRotation":0.0,"angularVelocity":1.4654307074319632,"angularAcceleration":1.082554107261969,"curveRadius":2.267541257533732},{"acceleration":5.013149938105479,"curvature":0.43976536240568537,"pose":{"rotation":{"radians":0.598800263050939},"translation":{"x":2.043771456000001,"y":3.3492594560000004}},"time":0.668514428274515,"velocity":3.333103602380067,"position":1.1172788520280055,"holonomicRotation":0.0,"angularVelocity":1.4695787949015473,"angularAcceleration":1.0952290191951792,"curveRadius":2.2739398904216013},{"acceleration":5.013023356881918,"curvature":0.43856062556178693,"pose":{"rotation":{"radians":0.6043530647207653},"translation":{"x":2.0541639680000006,"y":3.356435968000001}},"time":0.672282216172938,"velocity":3.3519916111186387,"position":1.1299084454559938,"holonomicRotation":0.0,"angularVelocity":1.4737564373383063,"angularAcceleration":1.10877855903394,"curveRadius":2.2801864593270795},{"acceleration":5.012900423529287,"curvature":0.43739209639321713,"pose":{"rotation":{"radians":0.6098931419936862},"translation":{"x":2.0645211520000006,"y":3.3636731520000005}},"time":0.6760306614586505,"velocity":3.3707821940789633,"position":1.1425436380805527,"holonomicRotation":0.0,"angularVelocity":1.477966690360209,"angularAcceleration":1.1231998071174487,"curveRadius":2.2862781660805234},{"acceleration":3.212393326243053,"curvature":0.4362597700073285,"pose":{"rotation":{"radians":0.6154208746255811},"translation":{"x":2.074842624000001,"y":3.3709706240000004}},"time":0.6797674167804403,"velocity":3.382786121936484,"position":1.1551842821241753,"holonomicRotation":0.0,"angularVelocity":1.4792867490310944,"angularAcceleration":0.3532633413774656,"curveRadius":2.292212275230424},{"acceleration":1.275989144158481,"curvature":0.43516363895714666,"pose":{"rotation":{"radians":0.6209366425169791},"translation":{"x":2.085128000000001,"y":3.3783280000000007}},"time":0.683500482743354,"velocity":3.3875494735795892,"position":1.1678302277616814,"holonomicRotation":0.0,"angularVelocity":1.477543645409598,"angularAcceleration":-0.46693619636333,"curveRadius":2.2979861148244427},{"acceleration":1.1255901860971638,"curvature":0.4341036934661007,"pose":{"rotation":{"radians":0.626440825687208},"translation":{"x":2.0953768960000008,"y":3.3857448960000003}},"time":0.6872304461310189,"velocity":3.3917478837632467,"position":1.1804813231883085,"holonomicRotation":0.0,"angularVelocity":1.4756668090714642,"angularAcceleration":-0.5031782200170037,"curveRadius":2.3035970784203665},{"acceleration":1.092680274055794,"curvature":0.4330799216330578,"pose":{"rotation":{"radians":0.6319338042506204},"translation":{"x":2.105588928000001,"y":3.3932209280000003}},"time":0.6909574076678336,"velocity":3.3958202611166888,"position":1.1931374146874265,"holonomicRotation":0.0,"angularVelocity":1.4738490078722297,"angularAcceleration":-0.4877434825335127,"curveRadius":2.3090426271188003},{"acceleration":1.0593156094239868,"curvature":0.4320923098070697,"pose":{"rotation":{"radians":0.6374159583943286},"translation":{"x":2.1157637120000006,"y":3.4007557120000005}},"time":0.6946814683612349,"velocity":3.399765216739651,"position":1.2057983466978794,"holonomicRotation":0.0,"angularVelocity":1.4720904397240837,"angularAcceleration":-0.47221790752821435,"curveRadius":2.314320290602956},{"acceleration":1.0255094397449158,"curvature":0.4311408427216499,"pose":{"rotation":{"radians":0.6428876683582834},"translation":{"x":2.125900864000001,"y":3.4083488640000006}},"time":0.6984027294904411,"velocity":3.403581405155408,"position":1.2184639618809734,"holonomicRotation":0.0,"angularVelocity":1.4703912931586958,"angularAcceleration":-0.4566050342590125,"curveRadius":2.319427669360504},{"acceleration":0.9912752748440978,"curvature":0.4302255037988389,"pose":{"rotation":{"radians":0.6483493144174144},"translation":{"x":2.136000000000001,"y":3.4160000000000004}},"time":0.7021212925952892,"velocity":3.4072675248191913,"position":1.231134101187113,"holonomicRotation":0.0,"angularVelocity":1.4687517476872693,"angularAcceleration":-0.4409083361497504,"curveRadius":2.3243624359088932},{"acceleration":0.9566268744993093,"curvature":0.4293462752752821,"pose":{"rotation":{"radians":0.6538012768650252},"translation":{"x":2.146060736000001,"y":3.4237087360000005}},"time":0.705837259465187,"velocity":3.4108223185916846,"position":1.243808603922108,"holonomicRotation":0.0,"angularVelocity":1.4671719739419278,"angularAcceleration":-0.4251312782519523,"curveRadius":2.329122336880259},{"acceleration":0.9215782348819563,"curvature":0.4285031384986032,"pose":{"rotation":{"radians":0.6592439359982847},"translation":{"x":2.1560826880000006,"y":3.4314746880000007}},"time":0.7095507321282009,"velocity":3.4142445741737473,"position":1.2564873078131453,"holonomicRotation":0.0,"angularVelocity":1.465652134043794,"angularAcceleration":-0.4092772550263706,"curveRadius":2.3337051940945344},{"acceleration":0.8861435249567237,"curvature":0.42769607414071226,"pose":{"rotation":{"radians":0.6646776721054044},"translation":{"x":2.1660654720000005,"y":3.4392974720000007}},"time":0.7132618128405032,"velocity":3.4175331243175457,"position":1.2691700490744544,"holonomicRotation":0.0,"angularVelocity":1.46419238177892,"angularAcceleration":-0.3933496407218901,"curveRadius":2.338108905977471},{"acceleration":0.8503371916142228,"curvature":0.42692506226405785,"pose":{"rotation":{"radians":0.6701028654542673},"translation":{"x":2.176008704000001,"y":3.4471767040000008}},"time":0.7169706040757202,"velocity":3.4206868474407837,"position":1.281856662472665,"holonomicRotation":0.0,"angularVelocity":1.4627928629003633,"angularAcceleration":-0.3773517541962183,"curveRadius":2.3423314496853993},{"acceleration":0.8141738616047239,"curvature":0.4261900826856946,"pose":{"rotation":{"radians":0.6755198962825455},"translation":{"x":2.185912000000001,"y":3.4551120000000006}},"time":0.7206772085145398,"velocity":3.4237046678901786,"position":1.294546981391874,"holonomicRotation":0.0,"angularVelocity":1.4614537153048215,"angularAcceleration":-0.36128689145158766,"curveRadius":2.346370881505183},{"acceleration":0.7776683538438013,"curvature":0.42549111498766573,"pose":{"rotation":{"radians":0.680929144789296},"translation":{"x":2.195774976000001,"y":3.463102976000001}},"time":0.7243817290344938,"velocity":3.426585556264712,"position":1.3072408378984348,"holonomicRotation":0.0,"angularVelocity":1.4601750692469038,"angularAcceleration":-0.34515831428936833,"curveRadius":2.350225339086078},{"acceleration":0.7408357262675391,"curvature":0.42482813876175346,"pose":{"rotation":{"radians":0.6863309911277984},"translation":{"x":2.205597248000001,"y":3.4711492480000006}},"time":0.7280842686996895,"velocity":3.4293285299266114,"position":1.319938062805475,"holonomicRotation":0.0,"angularVelocity":1.4589570475855986,"angularAcceleration":-0.32896924042562026,"curveRadius":2.3538930422892888},{"acceleration":0.7036911937318191,"curvature":0.424201133738781,"pose":{"rotation":{"radians":0.6917258154001806},"translation":{"x":2.215378432000001,"y":3.4792504320000006}},"time":0.7317849307507818,"velocity":3.4319326532229426,"position":1.3326384857371618,"holonomicRotation":0.0,"angularVelocity":1.4577997660688489,"angularAcceleration":-0.31272283196142464,"curveRadius":2.3573722945676767},{"acceleration":0.6662501490872429,"curvature":0.42361007996169614,"pose":{"rotation":{"radians":0.697113997652353},"translation":{"x":2.225118144000001,"y":3.487406144000001}},"time":0.7354838185950632,"velocity":3.434397037800652,"position":1.3453419351927187,"holonomicRotation":0.0,"angularVelocity":1.4567033332742725,"angularAcceleration":-0.29642228711300445,"curveRadius":2.3606614840006226},{"acceleration":0.6285281495020896,"curvature":0.42305495790658737,"pose":{"rotation":{"radians":0.7024959178710106},"translation":{"x":2.234816000000001,"y":3.495616000000001}},"time":0.7391810357966859,"velocity":3.4367208428866953,"position":1.3580482386102148,"holonomicRotation":0.0,"angularVelocity":1.4556678510246552,"angularAcceleration":-0.2800707107937189,"curveRadius":2.363759084513093},{"acceleration":0.5905409558534574,"curvature":0.42253574855162407,"pose":{"rotation":{"radians":0.7078719559811373},"translation":{"x":2.244471616000001,"y":3.5038796160000008}},"time":0.7428766860668204,"velocity":3.4389032757297207,"position":1.3707572224301319,"holonomicRotation":0.0,"angularVelocity":1.4546934144639643,"angularAcceleration":-0.26367120519103987,"curveRadius":2.366663657283008},{"acceleration":0.5523044580278132,"curvature":0.4220524336016502,"pose":{"rotation":{"radians":0.7132424918449813},"translation":{"x":2.2540846080000008,"y":3.512196608000001}},"time":0.7465708732540071,"velocity":3.440943591781993,"position":1.3834687121587248,"holonomicRotation":0.0,"angularVelocity":1.4537801122996437,"angularAcceleration":-0.24722682366730897,"curveRadius":2.369373851173761},{"acceleration":0.5138346609636051,"curvature":0.4216049955488846,"pose":{"rotation":{"radians":0.7186079052611989},"translation":{"x":2.263654592000001,"y":3.5205665920000007}},"time":0.7502637013347144,"velocity":3.44284109484684,"position":1.3961825324311885,"holonomicRotation":0.0,"angularVelocity":1.4529280266927003,"angularAcceleration":-0.23074066496487664,"curveRadius":2.371888403974215},{"acceleration":0.47514774168560514,"curvature":0.4211934177613658,"pose":{"rotation":{"radians":0.7239685759661101},"translation":{"x":2.2731811840000007,"y":3.5289891840000007}},"time":0.7539552744038361,"velocity":3.444595137453901,"position":1.408898507074641,"holonomicRotation":0.0,"angularVelocity":1.452137233785431,"angularAcceleration":-0.21421569950324387,"curveRadius":2.374206143379398},{"acceleration":0.43626000059906606,"curvature":0.4208176845991983,"pose":{"rotation":{"radians":0.7293248836344008},"translation":{"x":2.282664000000001,"y":3.5374640000000004}},"time":0.7576456966652776,"velocity":3.446205121071888,"position":1.4216164591709382,"holonomicRotation":0.0,"angularVelocity":1.4514078034524505,"angularAcceleration":-0.1976549785648792,"curveRadius":2.3763259877075638},{"acceleration":0.3971878566696979,"curvature":0.4204777814786742,"pose":{"rotation":{"radians":0.7346772078818984},"translation":{"x":2.292102656000001,"y":3.5459906560000007}},"time":0.7613350724226088,"velocity":3.4476704963213916,"position":1.4343362111193323,"holonomicRotation":0.0,"angularVelocity":1.450739799778293,"angularAcceleration":-0.18106143643139072,"curveRadius":2.378246946802629},{"acceleration":0.3579478429199566,"curvature":0.42017369496416096,"pose":{"rotation":{"radians":0.7400259282677375},"translation":{"x":2.3014967680000007,"y":3.5545687680000007}},"time":0.7650235060697577,"velocity":3.448990763189142,"position":1.4470575846989848,"holonomicRotation":0.0,"angularVelocity":1.450133280823315,"angularAcceleration":-0.1644380821237813,"curveRadius":2.379968122671972},{"acceleration":0.31855655675985584,"curvature":0.4199054128880666,"pose":{"rotation":{"radians":0.7453714242984346},"translation":{"x":2.310845952000001,"y":3.563197952000001}},"time":0.7687111020818974,"velocity":3.4501654710774905,"position":1.4597804011313524,"holonomicRotation":0.0,"angularVelocity":1.4495882990163453,"angularAcceleration":-0.1477878284864977,"curveRadius":2.38148870985516},{"acceleration":0.27903069987780327,"curvature":0.4196729243382383,"pose":{"rotation":{"radians":0.7507140754316346},"translation":{"x":2.320149824000001,"y":3.571877824000001}},"time":0.7723979650063231,"velocity":3.4511942190196465,"position":1.4725044811424481,"holonomicRotation":0.0,"angularVelocity":1.4491049010270056,"angularAcceleration":-0.13111363217145416,"curveRadius":2.3828079964340114},{"acceleration":0.23938709166133332,"curvature":0.41947621972129306,"pose":{"rotation":{"radians":0.7560542610805632},"translation":{"x":2.329408000000001,"y":3.5806080000000007}},"time":0.7760841994532252,"velocity":3.4520766559630722,"position":1.4852296450250058,"holonomicRotation":0.0,"angularVelocity":1.4486831279590686,"angularAcceleration":-0.11441840556057481,"curveRadius":2.383925364504373},{"acceleration":0.19964255665393485,"curvature":0.419315290918276,"pose":{"rotation":{"radians":0.7613923606193054},"translation":{"x":2.338620096000001,"y":3.5893880960000004}},"time":0.7797699100867544,"velocity":3.4528124806570366,"position":1.497955712700546,"holonomicRotation":0.0,"angularVelocity":1.4483230154263753,"angularAcceleration":-0.09770504754695626,"curveRadius":2.384840290011982},{"acceleration":0.15981405462086992,"curvature":0.4191901310828717,"pose":{"rotation":{"radians":0.7667287533881022},"translation":{"x":2.3477857280000007,"y":3.598217728000001}},"time":0.7834552016158236,"velocity":3.453401442038757,"position":1.5106825037813667,"holonomicRotation":0.0,"angularVelocity":1.448024593632274,"angularAcceleration":-0.08097644155080176,"curveRadius":2.385552344509526},{"acceleration":0.119918540886243,"curvature":0.4191007350133541,"pose":{"rotation":{"radians":0.7720638186986672},"translation":{"x":2.3569045120000007,"y":3.607096512000001}},"time":0.7871401787851487,"velocity":3.4538433391241017,"position":1.5234098376324647,"holonomicRotation":0.0,"angularVelocity":1.4477878872563261,"angularAcceleration":-0.06423550678095766,"curveRadius":2.3860611935413005},{"acceleration":0.07997297966939967,"curvature":0.4190470988943057,"pose":{"rotation":{"radians":0.7773979358410195},"translation":{"x":2.3659760640000007,"y":3.616024064000001}},"time":0.7908249463664345,"velocity":3.4541380209669663,"position":1.5361375334334104,"holonomicRotation":0.0,"angularVelocity":1.4476129157896325,"angularAcceleration":-0.0474850754718692,"curveRadius":2.386366598500722},{"acceleration":0.039994446991610394,"curvature":0.41902922045158014,"pose":{"rotation":{"radians":0.7827314840887518},"translation":{"x":2.375000000000001,"y":3.625000000000001}},"time":0.7945096091492497,"velocity":3.4542853870173156,"position":1.5488654102401755,"holonomicRotation":0.0,"angularVelocity":1.4474996932167956,"angularAcceleration":-0.030728069164134356,"curveRadius":2.386468416026735},{"acceleration":-1.1811323079083375e-11,"curvature":0.4190470988943055,"pose":{"rotation":{"radians":0.7880648427061199},"translation":{"x":2.383975936000001,"y":3.634023936000001}},"time":0.798194271932065,"velocity":3.454285387017272,"position":1.561593287046941,"holonomicRotation":0.0,"angularVelocity":1.447448228435447,"angularAcceleration":-0.01396729752002437,"curveRadius":2.386366598500723},{"acceleration":-0.03999330948584792,"curvature":0.41910073501335415,"pose":{"rotation":{"radians":0.7933983909539015},"translation":{"x":2.392903488000001,"y":3.643095488000001}},"time":0.8018790395133507,"velocity":3.4541380209670103,"position":1.5743209828478864,"holonomicRotation":0.0,"angularVelocity":1.4474585248930965,"angularAcceleration":0.0027943302860342183,"curveRadius":2.3860611935413},{"acceleration":-0.07996843110594419,"curvature":0.4191901310828794,"pose":{"rotation":{"radians":0.798732508096204},"translation":{"x":2.401782272000001,"y":3.652214272000001}},"time":0.805564016682676,"velocity":3.453843339124118,"position":1.5870483166989848,"holonomicRotation":0.0,"angularVelocity":1.4475305808418861,"angularAcceleration":0.019553974279538675,"curveRadius":2.385552344509482},{"acceleration":-0.11990830274150725,"curvature":0.4193152909022269,"pose":{"rotation":{"radians":0.8040675734068445},"translation":{"x":2.410611904000001,"y":3.661379904000001}},"time":0.8092493082117097,"velocity":3.453401442071764,"position":1.5997751077798048,"holonomicRotation":0.0,"angularVelocity":1.4476643892645746,"angularAcceleration":0.03630877547524498,"curveRadius":2.3848402901032606},{"acceleration":-0.15979589100380767,"curvature":0.41947621973733923,"pose":{"rotation":{"radians":0.8094039661755654},"translation":{"x":2.419392000000001,"y":3.670592000000001}},"time":0.812935018845239,"velocity":3.452812480657097,"position":1.6125011754553453,"holonomicRotation":0.0,"angularVelocity":1.4478599378299444,"angularAcceleration":0.05305586488283025,"curveRadius":2.383925364413181},{"acceleration":-0.1996141964596313,"curvature":0.4196729243382304,"pose":{"rotation":{"radians":0.8147420657143334},"translation":{"x":2.428122176000001,"y":3.679850176000001}},"time":0.8166212532921764,"velocity":3.45207665593001,"position":1.625226339337903,"holonomicRotation":0.0,"angularVelocity":1.4481172089319991,"angularAcceleration":0.06979238726080052,"curveRadius":2.3828079964340563},{"acceleration":-0.23934628473342817,"curvature":0.4199054129041197,"pose":{"rotation":{"radians":0.8200822513632859},"translation":{"x":2.436802048000001,"y":3.689154048000001}},"time":0.8203081162166374,"velocity":3.4511942189867186,"position":1.637950419348999,"holonomicRotation":0.0,"angularVelocity":1.4484361795830294,"angularAcceleration":0.08651546248546631,"curveRadius":2.381488709764115},{"acceleration":-0.27897522907508504,"curvature":0.42017369496416906,"pose":{"rotation":{"radians":0.8254249024964637},"translation":{"x":2.4454312320000007,"y":3.698503232000001}},"time":0.8239957122288122,"velocity":3.450165471044486,"position":1.650673235781366,"holonomicRotation":0.0,"angularVelocity":1.4488168214573063,"angularAcceleration":0.10322222744036351,"curveRadius":2.3799681226719263},{"acceleration":-0.3184842043276212,"curvature":0.42047778147867415,"pose":{"rotation":{"radians":0.8307703985271329},"translation":{"x":2.454009344000001,"y":3.707897344000001}},"time":0.8276841458759612,"velocity":3.4489907631891583,"position":1.663394609361019,"holonomicRotation":0.0,"angularVelocity":1.449259100757035,"angularAcceleration":0.11990978882610386,"curveRadius":2.3782469468026295},{"acceleration":-0.35785643820631885,"curvature":0.4208176845991983,"pose":{"rotation":{"radians":0.8361191189130239},"translation":{"x":2.462536000000001,"y":3.717336000000001}},"time":0.8313735216332923,"velocity":3.447670496321435,"position":1.676114361309413,"holonomicRotation":0.0,"angularVelocity":1.4497629782661037,"angularAcceleration":0.13657527511731965,"curveRadius":2.3763259877075638},{"acceleration":-0.3970752249413738,"curvature":0.4211934177613584,"pose":{"rotation":{"radians":0.8414714431604695},"translation":{"x":2.471010816000001,"y":3.726818816000001}},"time":0.8350639438947338,"velocity":3.4462051210718445,"position":1.6888323134057104,"holonomicRotation":0.0,"angularVelocity":1.45032840912759,"angularAcceleration":0.15321576270395293,"curveRadius":2.37420614337944},{"acceleration":-0.4361240012856567,"curvature":0.42160499554888453,"pose":{"rotation":{"radians":0.846827750828786},"translation":{"x":2.479433408000001,"y":3.736345408000001}},"time":0.8387555169638555,"velocity":3.444595137453901,"position":1.7015482880491628,"holonomicRotation":0.0,"angularVelocity":1.4509553428914992,"angularAcceleration":0.1698283501830446,"curveRadius":2.3718884039742156},{"acceleration":-0.4749862533910909,"curvature":0.42205243358563704,"pose":{"rotation":{"radians":0.8521884215336977},"translation":{"x":2.487803392000001,"y":3.745915392000001}},"time":0.8424483450445279,"velocity":3.442841094879445,"position":1.7142621083216265,"holonomicRotation":0.0,"angularVelocity":1.451643723402245,"angularAcceleration":0.186410115961987,"curveRadius":2.3693738512636577},{"acceleration":-0.513645619084085,"curvature":0.4225357485516242,"pose":{"rotation":{"radians":0.8575538349499379},"translation":{"x":2.496120384000001,"y":3.755528384000001}},"time":0.8461425322316796,"velocity":3.440943591814688,"position":1.7269735980502199,"holonomicRotation":0.0,"angularVelocity":1.452393488586898,"angularAcceleration":0.20295809244879684,"curveRadius":2.366663657283007},{"acceleration":-0.5520858132633445,"curvature":0.4230549579065874,"pose":{"rotation":{"radians":0.8629243708137362},"translation":{"x":2.504384000000001,"y":3.765184000000001}},"time":0.849838182501814,"velocity":3.4389032757297637,"position":1.7396825818701367,"holonomicRotation":0.0,"angularVelocity":1.4532045705729064,"angularAcceleration":0.2194693563303064,"curveRadius":2.3637590845130925},{"acceleration":-0.5902906852585479,"curvature":0.42361007997767003,"pose":{"rotation":{"radians":0.8683004089239086},"translation":{"x":2.512593856000001,"y":3.7748818560000013}},"time":0.8535353997034717,"velocity":3.4367208428542475,"position":1.752388885287633,"holonomicRotation":0.0,"angularVelocity":1.4540768953909293,"angularAcceleration":0.2359409173017433,"curveRadius":2.3606614839116045},{"acceleration":-0.6282442679613746,"curvature":0.42420113373878826,"pose":{"rotation":{"radians":0.8736823291425702},"translation":{"x":2.5207495680000007,"y":3.7846215680000013}},"time":0.857234287547788,"velocity":3.434397037768224,"position":1.7650923347431897,"holonomicRotation":0.0,"angularVelocity":1.455010382899677,"angularAcceleration":0.25236977925190895,"curveRadius":2.3573722945676363},{"acceleration":-0.6659307290049119,"curvature":0.42482813877769865,"pose":{"rotation":{"radians":0.8790705113947155},"translation":{"x":2.5288507520000008,"y":3.794402752000001}},"time":0.860934949598915,"velocity":3.431932653190716,"position":1.7777927576748764,"holonomicRotation":0.0,"angularVelocity":1.4560049466025429,"angularAcceleration":0.2687529120804148,"curveRadius":2.3538930422009394},{"acceleration":-0.7033343412327394,"curvature":0.4254911149876656,"pose":{"rotation":{"radians":0.8844653356670706},"translation":{"x":2.536897024000001,"y":3.8042250240000013}},"time":0.8646374892641455,"velocity":3.429328529894383,"position":1.790489982581917,"holonomicRotation":0.0,"angularVelocity":1.4570604936434424,"angularAcceleration":0.285087301241319,"curveRadius":2.3502253390860783},{"acceleration":-0.7404395831670516,"curvature":0.42619008268569475,"pose":{"rotation":{"radians":0.8898671820056276},"translation":{"x":2.5448880000000007,"y":3.8140880000000013}},"time":0.8683420097840995,"velocity":3.4265855562647545,"position":1.8031838390884776,"holonomicRotation":0.0,"angularVelocity":1.4581769245063168,"angularAcceleration":0.3013698687484286,"curveRadius":2.346370881505182},{"acceleration":-0.7772311349025238,"curvature":0.4269250622640598,"pose":{"rotation":{"radians":0.8952764305123235},"translation":{"x":2.552823296000001,"y":3.8239912960000013}},"time":0.8720486142229191,"velocity":3.423704667890136,"position":1.8158741580076867,"holonomicRotation":0.0,"angularVelocity":1.4593541328673405,"angularAcceleration":0.31759751558454075,"curveRadius":2.3423314496853886},{"acceleration":-0.8136938042545481,"curvature":0.427696074140721,"pose":{"rotation":{"radians":0.900693461340607},"translation":{"x":2.560702528000001,"y":3.8339345280000012}},"time":0.8757574054581361,"velocity":3.4206868474407663,"position":1.828560771405897,"holonomicRotation":0.0,"angularVelocity":1.460592005515408,"angularAcceleration":0.3337671412489487,"curveRadius":2.338108905977423},{"acceleration":-0.8498125930993603,"curvature":0.42850313849861,"pose":{"rotation":{"radians":0.9061186546894917},"translation":{"x":2.568525312000001,"y":3.843917312000001}},"time":0.8794684861704385,"velocity":3.4175331243174436,"position":1.841243512667206,"holonomicRotation":0.0,"angularVelocity":1.4618904220810687,"angularAcceleration":0.34987559320829065,"curveRadius":2.3337051940944975},{"acceleration":-0.885572735301855,"curvature":0.42934627527527985,"pose":{"rotation":{"radians":0.9115523907966394},"translation":{"x":2.576291264000001,"y":3.853939264000001}},"time":0.8831819588334522,"velocity":3.41424457417379,"position":1.8539222165582432,"holonomicRotation":0.0,"angularVelocity":1.4632492548734464,"angularAcceleration":0.36591969719117984,"curveRadius":2.329122336880271},{"acceleration":-0.9209596592128576,"curvature":0.43022550379883,"pose":{"rotation":{"radians":0.9169950499298922},"translation":{"x":2.584000000000001,"y":3.864000000000001}},"time":0.8868979257033501,"velocity":3.4108223185916424,"position":1.8665967192932382,"holonomicRotation":0.0,"angularVelocity":1.4646683686397584,"angularAcceleration":0.3818962375062724,"curveRadius":2.324362435908941},{"acceleration":-0.9559589829239638,"curvature":0.43114084273749304,"pose":{"rotation":{"radians":0.9224470123774822},"translation":{"x":2.5916511360000007,"y":3.874099136000001}},"time":0.8906164888082323,"velocity":3.4072675247879607,"position":1.879266858599378,"holonomicRotation":0.0,"angularVelocity":1.4661476204160593,"angularAcceleration":0.39780198280319395,"curveRadius":2.3194276692752718},{"acceleration":-0.9905565709652241,"curvature":0.43209230980706964,"pose":{"rotation":{"radians":0.9279086584365919},"translation":{"x":2.599244288000001,"y":3.884236288000001}},"time":0.8943377499374726,"velocity":3.4035814051241142,"position":1.8919324737824714,"holonomicRotation":0.0,"angularVelocity":1.4676868592193317,"angularAcceleration":0.41363364456680246,"curveRadius":2.3143202906029563},{"acceleration":-1.0247384958809378,"curvature":0.4330799216172504,"pose":{"rotation":{"radians":0.9333803684005884},"translation":{"x":2.606779072000001,"y":3.8944110720000014}},"time":0.89806181063084,"velocity":3.3997652167706236,"position":1.9045934057929246,"holonomicRotation":0.0,"angularVelocity":1.4692859259092317,"angularAcceleration":0.42938792397984127,"curveRadius":2.3090426272030804},{"acceleration":-1.058491085113898,"curvature":0.4341036934345355,"pose":{"rotation":{"radians":0.9388625225442757},"translation":{"x":2.614255104000001,"y":3.9046231040000015}},"time":0.9017887721675529,"velocity":3.3958202612094506,"position":1.9172494972920426,"holonomicRotation":0.0,"angularVelocity":1.4709446528183014,"angularAcceleration":0.4450614509246354,"curveRadius":2.3035970785878694},{"acceleration":-1.0918009002453857,"curvature":0.43516363895714666,"pose":{"rotation":{"radians":0.9443555011076596},"translation":{"x":2.621672000000001,"y":3.9148720000000012}},"time":0.9055187355551501,"velocity":3.3917478838249897,"position":1.9299005927186699,"holonomicRotation":0.0,"angularVelocity":1.472662863568363,"angularAcceleration":0.4606508352802888,"curveRadius":2.2979861148244427},{"acceleration":-1.7019348670960293,"curvature":0.43625977000734745,"pose":{"rotation":{"radians":0.9498596842779459},"translation":{"x":2.629029376000001,"y":3.9251573760000014}},"time":0.9092541823295531,"velocity":3.3853903967154517,"position":1.9425465383561757,"holonomicRotation":0.0,"angularVelocity":1.4735006286271601,"angularAcceleration":0.22427439323668455,"curveRadius":2.2922122752303244},{"acceleration":-3.6441990002222524,"curvature":0.437392096408939,"pose":{"rotation":{"radians":0.9553754521692461},"translation":{"x":2.6363268480000013,"y":3.9354788480000007}},"time":0.913003192653033,"velocity":3.3717282570428035,"position":1.955187182399798,"holonomicRotation":0.0,"angularVelocity":1.4712597233342628,"angularAcceleration":-0.5977324945900157,"curveRadius":2.286278165998344},{"acceleration":-4.9871379711903385,"curvature":0.4385606255617841,"pose":{"rotation":{"radians":0.9609031848012304},"translation":{"x":2.643564032000001,"y":3.945836032000001}},"time":0.91677159067409,"velocity":3.3529347361814317,"position":1.9678223750243573,"holonomicRotation":0.0,"angularVelocity":1.4668653897747723,"angularAcceleration":-1.166101227878768,"curveRadius":2.280186459327094},{"acceleration":-4.987016553596181,"curvature":0.4397653623900097,"pose":{"rotation":{"radians":0.9664432620741601},"translation":{"x":2.650740544000001,"y":3.956228544000001}},"time":0.9205596615814072,"velocity":3.3340435638604444,"position":1.9804519684523454,"holonomicRotation":0.0,"angularVelocity":1.4625062224226537,"angularAcceleration":-1.1507618148589016,"curveRadius":2.2739398905026573},{"acceleration":-4.9868915492222605,"curvature":0.4410063087994853,"pose":{"rotation":{"radians":0.9719960637439282},"translation":{"x":2.657856000000001,"y":3.9666560000000013}},"time":0.9243676994796551,"velocity":3.315053291846554,"position":1.9930758170224085,"holonomicRotation":0.0,"angularVelocity":1.4581792036058758,"angularAcceleration":-1.1362856495647697,"curveRadius":2.267541257453247},{"acceleration":-4.9867628357422165,"curvature":0.4422834635714009,"pose":{"rotation":{"radians":0.9775619693928133},"translation":{"x":2.6649100160000008,"y":3.977118016000001}},"time":0.92819600775608,"velocity":3.295962426409914,"position":2.005693777258219,"holonomicRotation":0.0,"angularVelocity":1.4538812569406847,"angularAcceleration":-1.122675175261699,"curveRadius":2.2609934179430677},{"acceleration":-4.986630285645398,"curvature":0.4435968219542736,"pose":{"rotation":{"radians":0.9831413583993789},"translation":{"x":2.671902208000001,"y":3.9876142080000014}},"time":0.9320448994656294,"velocity":3.2767694264449054,"position":2.0183057079377678,"holonomicRotation":0.0,"angularVelocity":1.4496092453634772,"angularAcceleration":-1.1099329104553117,"curveRadius":2.2542992882466617},{"acceleration":-4.986493765855295,"curvature":0.4449463754713487,"pose":{"rotation":{"radians":0.9887346099052245},"translation":{"x":2.678832192000001,"y":3.9981441920000007}},"time":0.935914697735773,"velocity":3.257472701495717,"position":2.0309114701630557,"holonomicRotation":0.0,"angularVelocity":1.4453599685024867,"angularAcceleration":-1.098061595038362,"curveRadius":2.2474618406334064},{"acceleration":-4.986353137733651,"curvature":0.44633211131899053,"pose":{"rotation":{"radians":0.994342102779949},"translation":{"x":2.685699584000001,"y":4.0087075840000015}},"time":0.9398057361922885,"velocity":3.2380706096790286,"position":2.0435109274302294,"holonomicRotation":0.0,"angularVelocity":1.441130160339283,"angularAcceleration":-1.0870640859693788,"curveRadius":2.2404841028462474},{"acceleration":-4.986208256354179,"curvature":0.4477540124322387,"pose":{"rotation":{"radians":0.9999642155823683},"translation":{"x":2.692504000000001,"y":4.019304000000001}},"time":0.9437183594073533,"velocity":3.2185614555000694,"position":2.0561039457001318,"holonomicRotation":0.0,"angularVelocity":1.4369164863031878,"angularAcceleration":-1.0769434735936856,"curveRadius":2.2333691541208376},{"acceleration":-4.9860589704534055,"curvature":0.44921205667481756,"pose":{"rotation":{"radians":1.0056013265210262},"translation":{"x":2.699245056000001,"y":4.029933056000002}},"time":0.9476529233714108,"velocity":3.1989434875522575,"position":2.0686903934693115,"holonomicRotation":0.0,"angularVelocity":1.432715541074748,"angularAcceleration":-1.0677028679201994,"curveRadius":2.226120125542167},{"acceleration":-4.985905121868044,"curvature":0.4507062168508919,"pose":{"rotation":{"radians":1.0112538134096622},"translation":{"x":2.705922368000001,"y":4.040594368000001}},"time":0.9516097959903724,"velocity":3.1792148960947975,"position":2.081270141841464,"holonomicRotation":0.0,"angularVelocity":1.428523845207693,"angularAcceleration":-1.059345667830764,"curveRadius":2.2187401961904425},{"acceleration":-4.985746545290057,"curvature":0.45223646007658325,"pose":{"rotation":{"radians":1.0169220536221615},"translation":{"x":2.7125355520000007,"y":4.051287552000002}},"time":0.9555893576098631,"velocity":3.159373810498653,"position":2.093843064599348,"holonomicRotation":0.0,"angularVelocity":1.4243378428261966,"angularAcceleration":-1.0518752520364627,"curveRadius":2.211232592415606},{"acceleration":-4.985583067588838,"curvature":0.4538027475367534,"pose":{"rotation":{"radians":1.0226064240423844},"translation":{"x":2.719084224000001,"y":4.062012224000001}},"time":0.9595920015683295,"velocity":3.1394182965537363,"position":2.106409038277148,"holonomicRotation":0.0,"angularVelocity":1.4201538980751425,"angularAcceleration":-1.0452952584514108,"curveRadius":2.2036005851176785},{"acceleration":-4.985414507540619,"curvature":0.4554050339448751,"pose":{"rotation":{"radians":1.028307301013264},"translation":{"x":2.725568000000001,"y":4.072768000000002}},"time":0.9636181347810053,"velocity":3.119346353625971,"position":2.1189679422333207,"holonomicRotation":0.0,"angularVelocity":1.4159682925867647,"angularAcceleration":-1.0396092894293258,"curveRadius":2.1958474884163137},{"acceleration":-4.9852406753794085,"curvature":0.45704326729385686,"pose":{"rotation":{"radians":1.0340250602804888},"translation":{"x":2.731986496000001,"y":4.0835544960000005}},"time":0.9676681783568651,"velocity":3.0991559116545355,"position":2.131519658723905,"holonomicRotation":0.0,"angularVelocity":1.4117772216835929,"angularAcceleration":-1.0348211876416877,"curveRadius":2.187976656829403},{"acceleration":-4.985061371885896,"curvature":0.45871738815772506,"pose":{"rotation":{"radians":1.0397600769353796},"translation":{"x":2.738339328000001,"y":4.094371328000001}},"time":0.971742568250901,"velocity":3.078844827979775,"position":2.1440640729763305,"holonomicRotation":0.0,"angularVelocity":1.4075767916285662,"angularAcceleration":-1.0309347323817304,"curveRadius":2.1799914845524904},{"acceleration":-4.984876388265965,"curvature":0.4604273295453317,"pose":{"rotation":{"radians":1.045512725351935},"translation":{"x":2.7446261120000006,"y":4.105218112000001}},"time":0.9758417559542291,"velocity":3.058410883986385,"position":2.156601073263692,"holonomicRotation":0.0,"angularVelocity":1.403363015527401,"angularAcceleration":-1.0279539279804228,"curveRadius":2.1718954020116312},{"acceleration":-4.984685505226497,"curvature":0.4621730162746951,"pose":{"rotation":{"radians":1.0512833791230536},"translation":{"x":2.7508464640000008,"y":4.1160944640000015}},"time":0.9799662092247713,"velocity":3.037851781551729,"position":2.1691305509795358,"holonomicRotation":0.0,"angularVelocity":1.3991318103502188,"angularAcceleration":-1.0258826805973165,"curveRadius":2.1636918746585683},{"acceleration":-4.984488492370801,"curvature":0.4639543644847909,"pose":{"rotation":{"radians":1.0570724109913305},"translation":{"x":2.7570000000000006,"y":4.127000000000001}},"time":0.9841164128614743,"velocity":3.017165139283587,"position":2.181652400713124,"holonomicRotation":0.0,"angularVelocity":1.3948789927030683,"angularAcceleration":-1.0247250543419237,"curveRadius":2.155384401029342},{"acceleration":-4.984285107409487,"curvature":0.4657712811612695,"pose":{"rotation":{"radians":1.0628801927773655},"translation":{"x":2.7630863360000006,"y":4.137934336000002}},"time":0.9882928695253067,"velocity":2.9963484885323064,"position":2.194166520325219,"holonomicRotation":0.0,"angularVelocity":1.3906002751877273,"angularAcceleration":-1.024485074248254,"curveRadius":2.1469765106744703},{"acceleration":-4.9840750955398825,"curvature":0.46762366370596037,"pose":{"rotation":{"radians":1.068707095303676},"translation":{"x":2.7691050880000008,"y":4.148897088000001}},"time":0.992496100610544,"velocity":2.975399269159576,"position":2.206672811024343,"holonomicRotation":0.0,"angularVelocity":1.3862912621615784,"angularAcceleration":-1.025166815425192,"curveRadius":2.1384717618328133},{"acceleration":-4.983858188281258,"curvature":0.46951139935295344,"pose":{"rotation":{"radians":1.0745534883158845},"translation":{"x":2.775055872000001,"y":4.159887872000001}},"time":0.9967266471701949,"velocity":2.954314825047355,"position":2.2191711774435725,"holonomicRotation":0.0,"angularVelocity":1.381947445743538,"angularAcceleration":-1.0267742847862695,"curveRadius":2.129873739760371},{"acceleration":-4.983634102848808,"curvature":0.4714343645997839,"pose":{"rotation":{"radians":1.0804197403986842},"translation":{"x":2.7809383040000006,"y":4.170906304000001}},"time":1.0009850708997432,"velocity":2.9330923993243974,"position":2.2316615277178133,"holonomicRotation":0.0,"angularVelocity":1.3775642010669258,"angularAcceleration":-1.0293115375526583,"curveRadius":2.12118605492184},{"acceleration":-4.983402540976219,"curvature":0.4733924247442271,"pose":{"rotation":{"radians":1.0863062188890003},"translation":{"x":2.786752000000001,"y":4.181952000000002}},"time":1.0052719551838023,"velocity":2.911729129290346,"position":2.244143773561605,"holonomicRotation":0.0,"angularVelocity":1.3731367819292741,"angularAcceleration":-1.0327825162239948,"curveRadius":2.112412340650144},{"acceleration":-4.983163187785932,"curvature":0.47538543332938343,"pose":{"rotation":{"radians":1.092213289784437},"translation":{"x":2.792496576000001,"y":4.193024576000001}},"time":1.0095879062106774,"velocity":2.8902220410129353,"position":2.256617830347412,"holonomicRotation":0.0,"angularVelocity":1.3686603158038309,"angularAcceleration":-1.0371911306612762,"curveRadius":2.103556251180131},{"acceleration":-4.982915710613441,"curvature":0.4774132314234743,"pose":{"rotation":{"radians":1.0981413176481523},"translation":{"x":2.7981716480000007,"y":4.204123648000001}},"time":1.0139335541603467,"velocity":2.868568043571733,"position":2.2690836171844464,"holonomicRotation":0.0,"angularVelocity":1.3641297989098247,"angularAcceleration":-1.0425411691140236,"curveRadius":2.0946214603612057},{"acceleration":-4.982659757959761,"curvature":0.4794756472470108,"pose":{"rotation":{"radians":1.1040906655084468},"translation":{"x":2.8037768320000005,"y":4.215248832000001}},"time":1.0183095544718714,"velocity":2.8467639229186794,"position":2.281541056997976,"holonomicRotation":0.0,"angularVelocity":1.3595400906682304,"angularAcceleration":-1.0488363607988433,"curveRadius":2.085611658781142},{"acceleration":-4.982394957479981,"curvature":0.48157249539387187,"pose":{"rotation":{"radians":1.1100616947553323},"translation":{"x":2.809311744000001,"y":4.226399744000002}},"time":1.0227165891968681,"velocity":2.8248063353274167,"position":2.2939900766091545,"holonomicRotation":0.0,"angularVelocity":1.3548859084358569,"angularAcceleration":-1.056080226909728,"curveRadius":2.0765305526473496},{"acceleration":-4.9821209150847094,"curvature":0.4837035763394283,"pose":{"rotation":{"radians":1.1160547650316492},"translation":{"x":2.814776000000001,"y":4.237576000000001}},"time":1.0271553684463204,"velocity":2.8026918003912766,"position":2.3064306068153413,"holonomicRotation":0.0,"angularVelocity":1.3501618214189108,"angularAcceleration":-1.0642761785301693,"curveRadius":2.0673818613618686},{"acceleration":-4.981837212779629,"curvature":0.4858686756511655,"pose":{"rotation":{"radians":1.1220702341203208},"translation":{"x":2.820169216000001,"y":4.2487772160000015}},"time":1.031626631938766,"velocity":2.7804166935364685,"position":2.318862582470937,"holonomicRotation":0.0,"angularVelocity":1.3453622446619533,"angularAcceleration":-1.0734274025824462,"curveRadius":2.058169316348273},{"acceleration":-4.98154340695933,"curvature":0.48806756354488817,"pose":{"rotation":{"radians":1.1281084578259453},"translation":{"x":2.825491008000001,"y":4.260003008000001}},"time":1.0361311506587028,"velocity":2.757977238005642,"position":2.331285942568693,"holonomicRotation":0.0,"angularVelocity":1.3404814323225,"angularAcceleration":-1.083536919904661,"curveRadius":2.048896658357893},{"acceleration":-4.981239026570776,"curvature":0.49029999405552943,"pose":{"rotation":{"radians":1.1341697898535155},"translation":{"x":2.830740992000001,"y":4.271252992000002}},"time":1.040669728635021,"velocity":2.735369496264871,"position":2.3437006303215338,"holonomicRotation":0.0,"angularVelocity":1.335513471223242,"angularAcceleration":-1.0946074134189818,"curveRadius":2.03956763639435},{"acceleration":-4.980923570320437,"curvature":0.49256570453850973,"pose":{"rotation":{"radians":1.1402545816799603},"translation":{"x":2.835918784000001,"y":4.282526784000001}},"time":1.045243204850276,"velocity":2.7125893607860077,"position":2.356106593244842,"holonomicRotation":0.0,"angularVelocity":1.3304522730759718,"angularAcceleration":-1.1066414055873681,"curveRadius":2.030186005209013},{"acceleration":-4.980596504929129,"curvature":0.4948644147448579,"pose":{"rotation":{"radians":1.1463631824232712},"translation":{"x":2.841024000000001,"y":4.293824000000002}},"time":1.0498524552928343,"velocity":2.6896325441414586,"position":2.3685037832392455,"holonomicRotation":0.0,"angularVelocity":1.3252915673465424,"angularAcceleration":-1.1196409901660669,"curveRadius":2.0207555245522753},{"acceleration":-4.980257261807673,"curvature":0.49719582643303056,"pose":{"rotation":{"radians":1.1524959387042597},"translation":{"x":2.8460562560000007,"y":4.305144256000001}},"time":1.0544983951652132,"velocity":2.666494568354122,"position":2.3808921566738435,"holonomicRotation":0.0,"angularVelocity":1.3200248925839888,"angularAcceleration":-1.1336080335144219,"curveRadius":2.0112799561777783},{"acceleration":-4.979905234441006,"curvature":0.49955962237973184,"pose":{"rotation":{"radians":1.158653194505329},"translation":{"x":2.851015168000001,"y":4.316487168000002}},"time":1.0591819812634737,"velocity":2.643170753427439,"position":2.393271674469925,"holonomicRotation":0.0,"angularVelocity":1.3146455882077457,"angularAcceleration":-1.1485439283887442,"curveRadius":2.0017630633083208},{"acceleration":-4.979539774814845,"curvature":0.5019554658535155,"pose":{"rotation":{"radians":1.1648352910225657},"translation":{"x":2.855900352000001,"y":4.327852352000001}},"time":1.063904214544187,"velocity":2.619656204980173,"position":2.4056423021851097,"holonomicRotation":0.0,"angularVelocity":1.3091467849514489,"angularAcceleration":-1.1644497273684464,"curveRadius":1.9922086081872206},{"acceleration":-4.979160190172009,"curvature":0.5043829997560954,"pose":{"rotation":{"radians":1.1710425665137734},"translation":{"x":2.8607114240000007,"y":4.339239424000002}},"time":1.0686661428974595,"velocity":2.595945800895107,"position":2.4180040100979507,"holonomicRotation":0.0,"angularVelocity":1.3035213952645746,"angularAcceleration":-1.1813259817335207,"curveRadius":1.982620350970533},{"acceleration":-4.978765738320049,"curvature":0.5068418460483195,"pose":{"rotation":{"radians":1.1772753561398894},"translation":{"x":2.8654480000000007,"y":4.350648000000001}},"time":1.073468864146651,"velocity":2.572034176888931,"position":2.430356773292942,"holonomicRotation":0.0,"angularVelocity":1.297762102509148,"angularAcceleration":-1.1991728140366718,"curveRadius":1.973002047476296},{"acceleration":-4.978355623748659,"curvature":0.5093316047891755,"pose":{"rotation":{"radians":1.1835339918029282},"translation":{"x":2.870109696000001,"y":4.362077696000002}},"time":1.0783135292979649,"velocity":2.5479157108877084,"position":2.4427005717459647,"holonomicRotation":0.0,"angularVelocity":1.291861350075227,"angularAcceleration":-1.2179897370865098,"curveRadius":1.9633574484621346},{"acceleration":-4.977928992314462,"curvature":0.5118518535624833,"pose":{"rotation":{"radians":1.1898188019764262},"translation":{"x":2.874696128000001,"y":4.373528128000001}},"time":1.08320134606589,"velocity":2.523584506089533,"position":2.455035390410105,"holonomicRotation":0.0,"angularVelocity":1.285811328841175,"angularAcceleration":-1.2377757844265818,"curveRadius":1.9536902973780617},{"acceleration":-4.977484925572671,"curvature":0.5144021466205787,"pose":{"rotation":{"radians":1.196130111532029},"translation":{"x":2.879206912000001,"y":4.384998912000002}},"time":1.088133582703786,"velocity":2.499034372575049,"position":2.467361219301881,"holonomicRotation":0.0,"angularVelocity":1.2796039644795556,"angularAcceleration":-1.2585293077640105,"curveRadius":1.9440043292385336},{"acceleration":-4.977022434848794,"curvature":0.5169820141541447,"pose":{"rotation":{"radians":1.2024682415594241},"translation":{"x":2.8836416640000007,"y":4.3964896640000015}},"time":1.0931115721726106,"velocity":2.4742588073082676,"position":2.4796780535878082,"holonomicRotation":0.0,"angularVelocity":1.27323090317656,"angularAcceleration":-1.2802480485159113,"curveRadius":1.934303269014379},{"acceleration":-4.976540453923459,"curvature":0.5195909614569449,"pose":{"rotation":{"radians":1.2088335091818494},"translation":{"x":2.888000000000001,"y":4.408000000000002}},"time":1.0981367166851383,"velocity":2.4492509723548617,"position":2.4919858936713406,"holonomicRotation":0.0,"angularVelocity":1.2666834966748826,"angularAcceleration":-1.302928997435736,"curveRadius":1.9245908304408859},{"acceleration":-4.976037831352261,"curvature":0.5222284682600655,"pose":{"rotation":{"radians":1.2152262273646983},"translation":{"x":2.8922815360000005,"y":4.4195295360000015}},"time":1.1032104926679553,"velocity":2.424003671116558,"position":2.504284745280112,"holonomicRotation":0.0,"angularVelocity":1.2599527855582695,"angularAcceleration":-1.3265684451594792,"curveRadius":1.9148707142139332},{"acceleration":-4.975513321717014,"curvature":0.5248939878051837,"pose":{"rotation":{"radians":1.2216467047194628},"translation":{"x":2.896485888000001,"y":4.431077888000002}},"time":1.108334456189315,"velocity":2.398509322356041,"position":2.5165746195535053,"holonomicRotation":0.0,"angularVelocity":1.2530294815722824,"angularAcceleration":-1.3511618412439546,"curveRadius":1.9051466071871899},{"acceleration":-4.974965575458407,"curvature":0.527586946160825,"pose":{"rotation":{"radians":1.2280952453016536},"translation":{"x":2.9006126720000007,"y":4.442644672000001}},"time":1.1135102489075812,"velocity":2.372759931756958,"position":2.528855533130487,"holonomicRotation":0.0,"angularVelocity":1.2459039480914205,"angularAcceleration":-1.376703795674565,"curveRadius":1.8954221806980962},{"acceleration":-4.974393127904494,"curvature":0.5303067413665304,"pose":{"rotation":{"radians":1.2345721484028647},"translation":{"x":2.904661504000001,"y":4.454229504000002}},"time":1.1187396046027995,"velocity":2.346747060723296,"position":2.541127508237717,"holonomicRotation":0.0,"angularVelocity":1.2385661788379594,"angularAcceleration":-1.403188018013515,"curveRadius":1.8857010895677697},{"acceleration":-4.973794386442077,"curvature":0.533052742734141,"pose":{"rotation":{"radians":1.2410777083373046},"translation":{"x":2.9086320000000003,"y":4.465832000000002}},"time":1.1240243563629815,"velocity":2.320461792084763,"position":2.553390572777872,"holonomicRotation":0.0,"angularVelocity":1.2310057746621437,"angularAcceleration":-1.430607248722581,"curveRadius":1.8759869705777836},{"acceleration":-4.9731676159809,"curvature":0.5358242899805569,"pose":{"rotation":{"radians":1.2476122142228576},"translation":{"x":2.9125237760000005,"y":4.477451776000002}},"time":1.1293664445073663,"velocity":2.2938946923233927,"position":2.5656447604182,"holonomicRotation":0.0,"angularVelocity":1.2232119180627055,"angularAcceleration":-1.4589532012178488,"curveRadius":1.8662834416041245},{"acceleration":-4.972510922732632,"curvature":0.53862069246313,"pose":{"rotation":{"radians":1.2541759497559144},"translation":{"x":2.9163364480000005,"y":4.489088448000001}},"time":1.1347679253413834,"velocity":2.267035769877312,"position":2.5778901106792236,"holonomicRotation":0.0,"angularVelocity":1.2151733450057223,"angularAcceleration":-1.4882165287634594,"curveRadius":1.8565941004363706},{"acceleration":-4.971822235140322,"curvature":0.5414412283907459,"pose":{"rotation":{"radians":1.2607691929811071},"translation":{"x":2.9200696320000006,"y":4.500741632000002}},"time":1.1402309808528397,"velocity":2.2398744290136476,"position":2.5901266690236167,"holonomicRotation":0.0,"angularVelocity":1.2068783140435504,"angularAcceleration":-1.5183867242016413,"curveRadius":1.8469225237467926},{"acceleration":-4.971099282637377,"curvature":0.5442851441519826,"pose":{"rotation":{"radians":1.2673922160546647},"translation":{"x":2.9237229440000005,"y":4.512410944000001}},"time":1.1457579294762796,"velocity":2.2123994186764917,"position":2.60235448694517,"holonomicRotation":0.0,"angularVelocity":1.1983145718903792,"angularAcceleration":-1.549452100360074,"curveRadius":1.8372722657312996},{"acceleration":-4.970339570767143,"curvature":0.5471516533835759,"pose":{"rotation":{"radians":1.2740452850032347},"translation":{"x":2.9272960000000006,"y":4.524096000000002}},"time":1.1513512380732769,"velocity":2.1845987756253242,"position":2.614573622057865,"holonomicRotation":0.0,"angularVelocity":1.1894693155571043,"angularAcceleration":-1.5813996635235485,"curveRadius":1.8276468577148919},{"acceleration":-4.969540352570371,"curvature":0.5500399363964437,"pose":{"rotation":{"radians":1.2807286594758052},"translation":{"x":2.9307884160000004,"y":4.535796416000001}},"time":1.1570135353011541,"velocity":2.156459761063141,"position":2.6267841381849615,"holonomicRotation":0.0,"angularVelocity":1.180329149742646,"angularAcceleration":-1.6142151226993922,"curveRadius":1.8180498066221245},{"acceleration":-4.968698595823463,"curvature":0.5529491392614659,"pose":{"rotation":{"radians":1.2874425924915514},"translation":{"x":2.9341998080000002,"y":4.547511808000002}},"time":1.1627476265724006,"velocity":2.127968789815375,"position":2.6389861054481267,"holonomicRotation":0.0,"angularVelocity":1.1708800397742405,"angularAcceleration":-1.6478827283039572,"curveRadius":1.8084845946873658},{"acceleration":-4.967810944565119,"curvature":0.5558783732812413,"pose":{"rotation":{"radians":1.2941873301808833},"translation":{"x":2.9375297920000008,"y":4.559241792000002}},"time":1.1685565108427793,"velocity":2.0991113509612753,"position":2.651179600356499,"holonomicRotation":0.0,"angularVelocity":1.1611072583637778,"angularAcceleration":-1.6823852835727946,"curveRadius":1.798954677976039},{"acceleration":-4.9668736743972195,"curvature":0.5588267141256481,"pose":{"rotation":{"radians":1.3009631115227154},"translation":{"x":2.9407779840000003,"y":4.570985984000002}},"time":1.1744433995094674,"velocity":2.069871918618595,"position":2.663364705895711,"holonomicRotation":0.0,"angularVelocity":1.1509953263043637,"angularAcceleration":-1.7177039743649485,"curveRadius":1.7894634861266803},{"acceleration":-4.965882640323129,"curvature":0.5617932012303778,"pose":{"rotation":{"radians":1.3077701680745735},"translation":{"x":2.9439440000000006,"y":4.582744000000002}},"time":1.180411737753169,"velocity":2.04023385134262,"position":2.675541511616774,"holonomicRotation":0.0,"angularVelocity":1.1405279449504213,"angularAcceleration":-1.7538183873858901,"curveRadius":1.78001442133851},{"acceleration":-4.964833215210492,"curvature":0.5647768371119463,"pose":{"rotation":{"radians":1.314608723699815},"translation":{"x":2.9470274560000007,"y":4.594515456000002}},"time":1.1864652287225286,"velocity":2.0101792783099675,"position":2.6877101137248167,"holonomicRotation":0.0,"angularVelocity":1.1296879205496007,"angularAcceleration":-1.7907062975213537,"curveRadius":1.7706108577568784},{"acceleration":-4.963720217251391,"curvature":0.5677765867261405,"pose":{"rotation":{"radians":1.3214789942880618},"translation":{"x":2.9500279680000006,"y":4.606299968000002}},"time":1.1926078610382507,"velocity":1.979688970097276,"position":2.699870615167615,"holonomicRotation":0.0,"angularVelocity":1.118457077540253,"angularAcceleration":-1.8283436859149684,"curveRadius":1.7612561408460061},{"acceleration":-4.962537823897193,"curvature":0.5707913768706009,"pose":{"rotation":{"radians":1.3283811874717983},"translation":{"x":2.9529451520000003,"y":4.6180971520000025}},"time":1.1988439401921447,"velocity":1.94874219142326,"position":2.712023125723863,"holonomicRotation":0.0,"angularVelocity":1.1068161601872177,"angularAcceleration":-1.8667045535761377,"curveRadius":1.7519535867597755},{"acceleration":-4.961279469239047,"curvature":0.5738200956456002,"pose":{"rotation":{"radians":1.335315502338058},"translation":{"x":2.9557786240000006,"y":4.629906624000001}},"time":1.2051781245379847,"velocity":1.9173165326738688,"position":2.724167762091146,"holonomicRotation":0.0,"angularVelocity":1.0947447197071045,"angularAcceleration":-1.9057608400742556,"curveRadius":1.742706481680305},{"acceleration":-4.9599377209221185,"curvature":0.576861591813262,"pose":{"rotation":{"radians":1.3422821291361096},"translation":{"x":2.9585280000000007,"y":4.641728000000002}},"time":1.2116154667234638,"velocity":1.8853877163456279,"position":2.736304647973562,"holonomicRotation":0.0,"angularVelocity":1.082220984580612,"angularAcceleration":-1.945482276014872,"curveRadius":1.7335180816193316},{"acceleration":-4.958504132032011,"curvature":0.5799146744073892,"pose":{"rotation":{"radians":1.3492812489797497},"translation":{"x":2.9611928960000005,"y":4.653560896000002}},"time":1.2181614616046752,"velocity":1.8529293736788806,"position":2.7484339141689103,"holonomicRotation":0.0,"angularVelocity":1.0692217104735662,"angularAcceleration":-1.985836277439957,"curveRadius":1.7243916116140587},{"acceleration":-4.956969061035293,"curvature":0.5829781121894888,"pose":{"rotation":{"radians":1.3563130335470661},"translation":{"x":2.9637729280000005,"y":4.665404928000002}},"time":1.2248221019287682,"velocity":1.8199127856656676,"position":2.7605556986554474,"holonomicRotation":0.0,"angularVelocity":1.055722006468504,"angularAcceleration":-2.0267877183265455,"curveRadius":1.7153302655640084},{"acceleration":-4.95532145249921,"curvature":0.5860506332508155,"pose":{"rotation":{"radians":1.3633776447754746},"translation":{"x":2.9662677120000005,"y":4.6772597120000015}},"time":1.2316039433830896,"velocity":1.78630658121962,"position":2.77267014667809,"holonomicRotation":0.0,"angularVelocity":1.0416951319183152,"angularAcceleration":-2.068298801242352,"curveRadius":1.7063372058025303},{"acceleration":-4.9535485671640425,"curvature":0.5891309246386679,"pose":{"rotation":{"radians":1.3704752345535287},"translation":{"x":2.9686768640000007,"y":4.689124864000002}},"time":1.2385141810130922,"velocity":1.7520763835087578,"position":2.784777410834051,"holonomicRotation":0.0,"angularVelocity":1.0271122583741705,"angularAcceleration":-2.110328808495594,"curveRadius":1.6974155627856926},{"acceleration":-4.951635648030996,"curvature":0.5922176320623127,"pose":{"rotation":{"radians":1.3776059444095874},"translation":{"x":2.9710000000000005,"y":4.701000000000001}},"time":1.2455607395377533,"velocity":1.7171843931221094,"position":2.7968776511578204,"holonomicRotation":0.0,"angularVelocity":1.0119421886731093,"angularAcceleration":-2.15283384761087,"curveRadius":1.6885684347452539},{"acceleration":-4.949565503575213,"curvature":0.5953093595736683,"pose":{"rotation":{"radians":1.3847699051974123},"translation":{"x":2.9732367360000005,"y":4.712884736000002}},"time":1.2527523807843013,"velocity":1.6815888936941066,"position":2.808971035205448,"holonomicRotation":0.0,"angularVelocity":0.996151023420915,"angularAcceleration":-2.1957665449140666,"curveRadius":1.6797988876172745},{"acceleration":-4.9473179830773395,"curvature":0.5984046693700557,"pose":{"rotation":{"radians":1.3919672367794353},"translation":{"x":2.9753866880000004,"y":4.724778688000002}},"time":1.2600988323858988,"velocity":1.6452436615737158,"position":2.8210577381380344,"holonomicRotation":0.0,"angularVelocity":0.9797017624750936,"angularAcceleration":-2.239075656912306,"curveRadius":1.6711099548282373},{"acceleration":-4.94486931017707,"curvature":0.6015020816536214,"pose":{"rotation":{"radians":1.3991980477076629},"translation":{"x":2.9774494720000004,"y":4.736681472000003}},"time":1.2676109431263463,"velocity":1.6080972557186257,"position":2.8331379428044023,"holonomicRotation":0.0,"angularVelocity":0.9625538251579129,"angularAcceleration":-2.282705608272129,"curveRadius":1.6625046371424796},{"acceleration":-4.942191227827669,"curvature":0.60460007456127,"pose":{"rotation":{"radians":1.4064624349026047},"translation":{"x":2.9794247040000004,"y":4.748592704000002}},"time":1.2753008720054502,"velocity":1.5700921566696997,"position":2.845211839822831,"holonomicRotation":0.0,"angularVelocity":0.9446624681642469,"angularAcceleration":-2.3265958989923434,"curveRadius":1.653985902541698},{"acceleration":-4.93924988892279,"curvature":0.6076970841012796,"pose":{"rotation":{"radians":1.41376048333109},"translation":{"x":2.9813120000000004,"y":4.760512000000002}},"time":1.283182320431467,"velocity":1.5311637134069456,"position":2.8572796276618364,"holonomicRotation":0.0,"angularVelocity":0.9259780733188929,"angularAcceleration":-2.3706803414048245,"curveRadius":1.6455566863199538},{"acceleration":-4.936004400329307,"curvature":0.6107915042418585,"pose":{"rotation":{"radians":1.4210922656826717},"translation":{"x":2.9831109760000003,"y":4.772438976000002}},"time":1.291270820215119,"velocity":1.491238842882776,"position":2.8693415127198674,"holonomicRotation":0.0,"angularVelocity":0.9064452676873628,"angularAcceleration":-2.4148860918570376,"curveRadius":1.6372198910023223},{"acceleration":-4.932404886166336,"curvature":0.6138816870079442,"pose":{"rotation":{"radians":1.428457842045709},"translation":{"x":2.9848212480000003,"y":4.784373248000002}},"time":1.2995840946926274,"velocity":1.4502344072298723,"position":2.881397709403896,"holonomicRotation":0.0,"angularVelocity":0.8860018255099187,"angularAcceleration":-2.4591323470377624,"curveRadius":1.628978386493323},{"acceleration":-4.928389875023061,"curvature":0.6169659427695113,"pose":{"rotation":{"radians":1.4358572595831753},"translation":{"x":2.9864424320000005,"y":4.796314432000002}},"time":1.3081425170479217,"velocity":1.4080551651478685,"position":2.893448440206785,"holonomicRotation":0.0,"angularVelocity":0.864577281920298,"angularAcceleration":-2.5033286159764163,"curveRadius":1.6208350099700464},{"acceleration":-4.923882717948124,"curvature":0.6200425403987194,"pose":{"rotation":{"radians":1.4432905522090504},"translation":{"x":2.9879741440000003,"y":4.808262144000002}},"time":1.3169696998690328,"velocity":1.3645911522068312,"position":2.9054939357833853,"holonomicRotation":0.0,"angularVelocity":0.8420911605113327,"angularAcceleration":-2.5473723457032755,"curveRadius":1.6127925663889906},{"acceleration":-4.918786589982433,"curvature":0.623109707774154,"pose":{"rotation":{"radians":1.450757740264991},"translation":{"x":2.9894160000000003,"y":4.820216000000001}},"time":1.3260932650252866,"velocity":1.3197142822634191,"position":2.9175344350252543,"holonomicRotation":0.0,"angularVelocity":0.8184506744956023,"angularAcceleration":-2.5911456334069096,"curveRadius":1.6048538283445424},{"acceleration":-4.912977374927289,"curvature":0.6261656322069277,"pose":{"rotation":{"radians":1.4582588301993826},"translation":{"x":2.9907676160000003,"y":4.8321756160000024}},"time":1.3355458662504862,"velocity":1.2732738663098033,"position":2.929570185133949,"holonomicRotation":0.0,"angularVelocity":0.7935476971560562,"angularAcceleration":-2.6345105168678153,"curveRadius":1.5970215364191882},{"acceleration":-4.906293306643146,"curvature":0.6292084609699685,"pose":{"rotation":{"radians":1.4657938142472846},"translation":{"x":2.992028608,"y":4.844140608000002}},"time":1.3453665738914766,"velocity":1.2250905941443129,"position":2.9416014416927676,"holonomicRotation":0.0,"angularVelocity":0.7672546952168596,"angularAcceleration":-2.6773021762151714,"curveRadius":1.5892983995454075},{"acceleration":-4.898519497499279,"curvature":0.6322363020068372,"pose":{"rotation":{"radians":1.473362670113694},"translation":{"x":2.993198592,"y":4.856110592000002}},"time":1.3556027921619829,"velocity":1.1749482793655797,"position":2.9536284687369094,"holonomicRotation":0.0,"angularVelocity":0.7394191552379812,"angularAcceleration":-2.7193187213564363,"curveRadius":1.5816870951981268},{"acceleration":-4.8893641404678805,"curvature":0.6352472246674356,"pose":{"rotation":{"radians":1.4809653606596453},"translation":{"x":2.9942771840000004,"y":4.868085184000002}},"time":1.3663129828955178,"velocity":1.1225822568554624,"position":2.9656515388219136,"holonomicRotation":0.0,"angularVelocity":0.7098557565502948,"angularAcceleration":-2.7603055279977116,"curveRadius":1.5741902698174237},{"acceleration":-4.878420629606754,"curvature":0.6382392605344301,"pose":{"rotation":{"radians":1.488601833592083},"translation":{"x":2.995264,"y":4.880064000000003}},"time":1.377570653847638,"velocity":1.0676626026413147,"position":2.9776709330903337,"holonomicRotation":0.0,"angularVelocity":0.6783350628132772,"angularAcceleration":-2.799930276082666,"curveRadius":1.566810539299399},{"acceleration":-4.865104786542381,"curvature":0.6412104045156426,"pose":{"rotation":{"radians":1.49627202115791},"translation":{"x":2.996158656,"y":4.8920466560000015}},"time":1.3894704130212827,"velocity":1.0097690273269142,"position":2.9896869413365295,"holonomicRotation":0.0,"angularVelocity":0.6445666213829495,"angularAcceleration":-2.83774158262943,"curveRadius":1.5595504891337186},{"acceleration":-4.84854568657608,"curvature":0.6441586157880042,"pose":{"rotation":{"radians":1.5039758398437872},"translation":{"x":2.996960768,"y":4.904032768000002}},"time":1.4021375704473253,"velocity":0.948351735827695,"position":3.0016998620695197,"holonomicRotation":0.0,"angularVelocity":0.6081726489037638,"angularAcceleration":-2.8730970378849747,"curveRadius":1.5524126752177216},{"acceleration":-4.8273842463224925,"curvature":0.6470818190817547,"pose":{"rotation":{"radians":1.511713190080926},"translation":{"x":2.9976699520000003,"y":4.916021952000001}},"time":1.4157442164556688,"velocity":0.8826672272417309,"position":3.013710002573764,"holonomicRotation":0.0,"angularVelocity":0.5686449278091195,"angularAcceleration":-2.905030458674842,"curveRadius":1.5453996241449899},{"acceleration":-4.799373104427447,"curvature":0.6499779058913984,"pose":{"rotation":{"radians":1.5194839559568147},"translation":{"x":2.998285824,"y":4.928013824000002}},"time":1.4305380813379511,"velocity":0.8116659500151715,"position":3.0257176789678377,"holonomicRotation":0.0,"angularVelocity":0.5252694909492741,"angularAcceleration":-2.9319881724615087,"curveRadius":1.538513833987282},{"acceleration":-4.760501598426161,"curvature":0.6528447360474303,"pose":{"rotation":{"radians":1.527288004933617},"translation":{"x":2.998808,"y":4.9400080000000015}},"time":1.4468993447988883,"velocity":0.7337781291571087,"position":3.0377232162608507,"holonomicRotation":0.0,"angularVelocity":0.47698327182583705,"angularAcceleration":-2.9512524652342056,"curveRadius":1.5317577745274924},{"acceleration":-4.702814023698275,"curvature":0.6556801391027219,"pose":{"rotation":{"radians":1.5351251875753922},"translation":{"x":2.999236096,"y":4.952004096000002}},"time":1.465467938521416,"velocity":0.6464534861984496,"position":3.0497269484065814,"holonomicRotation":0.0,"angularVelocity":0.4220665689005264,"angularAcceleration":-2.9575046848423847,"curveRadius":1.5251338882529966},{"acceleration":-4.607805870089161,"curvature":0.6584819160890972,"pose":{"rotation":{"radians":1.5429953372829324},"translation":{"x":2.999569728,"y":4.964001728000001}},"time":1.4874915437144056,"velocity":0.5449729889096658,"position":3.0617292183551714,"holonomicRotation":0.0,"angularVelocity":0.357350653472727,"angularAcceleration":-2.93847963858339,"curveRadius":1.5186445907873543},{"acceleration":-4.418460750553726,"curvature":0.6612478412834537,"pose":{"rotation":{"radians":1.5508982700384952},"translation":{"x":2.999808512,"y":4.976000512000002}},"time":1.5161911212098473,"velocity":0.4181650321885816,"position":3.0737303781023515,"holonomicRotation":0.0,"angularVelocity":0.2753675644464824,"angularAcceleration":-2.8565956777330865,"curveRadius":1.512292271622457},{"acceleration":-3.5355890810330983,"curvature":0.6612478412834537,"pose":{"rotation":{"radians":1.5588337841609612},"translation":{"x":2.999952064,"y":4.988000064000001}},"time":1.5854743388998433,"velocity":0.17320804422499247,"position":3.08573078873605,"holonomicRotation":0.0,"angularVelocity":0.11453732068237628,"angularAcceleration":-2.3213448960141014,"curveRadius":1.512292271622457},{"acceleration":-0.0,"curvature":-0.663975664093471,"pose":{"rotation":{"radians":1.5747909935183229},"translation":{"x":3.0,"y":5.0}},"time":1.5854743388998433,"velocity":0,"position":-0.0,"holonomicRotation":0.0,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-1.5060792948869663},{"acceleration":-2.5,"curvature":-0.663975664093471,"pose":{"rotation":{"radians":1.5747909935183229},"translation":{"x":3.000047936,"y":4.988000064000001}},"time":1.654756462840433,"velocity":-0.1732053098514741,"position":-0.012000031744298058,"holonomicRotation":0.0,"angularVelocity":0.0,"angularAcceleration":0.0,"curveRadius":-1.5060792948869663},{"acceleration":-8.535371252575526,"curvature":-0.6612478412834536,"pose":{"rotation":{"radians":1.5827588694288295},"translation":{"x":3.000191488,"y":4.976000512}},"time":1.6834548316073188,"velocity":-0.4181565416201628,"position":-0.024000442377999136,"holonomicRotation":0.0,"angularVelocity":0.27764211879877,"angularAcceleration":9.674491294401816,"curveRadius":-1.5122922716224572},{"acceleration":-5.757894093817242,"curvature":-0.6584819160890969,"pose":{"rotation":{"radians":1.5906943835513019},"translation":{"x":3.000430272,"y":4.964001728000001}},"time":1.7054770090787634,"velocity":-0.5449579072159887,"position":-0.03600160212517667,"holonomicRotation":0.0,"angularVelocity":0.36034193860993596,"angularAcceleration":3.7552971280156133,"curveRadius":-1.518644590787355},{"acceleration":-5.4652336716017045,"curvature":-0.6556801391026855,"pose":{"rotation":{"radians":1.5985973163068543},"translation":{"x":3.000763904,"y":4.952004096}},"time":1.72404399224973,"velocity":-0.6464308088220165,"position":-0.04800387207376926,"holonomicRotation":0.0,"angularVelocity":0.4256444185240826,"angularAcceleration":3.5171292671962715,"curveRadius":-1.5251338882530814},{"acceleration":-5.337340132224197,"curvature":-0.6528447360474302,"pose":{"rotation":{"radians":1.606467466014406},"translation":{"x":3.001192,"y":4.940008000000001}},"time":1.7404034894422744,"velocity":-0.7337470097307943,"position":-0.06000760421949824,"holonomicRotation":0.0,"angularVelocity":0.48107528091623164,"angularAcceleration":3.3882986585559567,"curveRadius":-1.5317577745274926},{"acceleration":-5.264929926173049,"curvature":-0.6499779059037698,"pose":{"rotation":{"radians":1.6143046486561694},"translation":{"x":3.001714176,"y":4.928013824}},"time":1.7551954530990062,"velocity":-0.8116256618539851,"position":-0.07201314151251319,"holonomicRotation":0.0,"angularVelocity":0.5298270617502993,"angularAcceleration":3.2958288679867818,"curveRadius":-1.5385138339579985},{"acceleration":-5.2181863052484765,"curvature":-0.6470818190817534,"pose":{"rotation":{"radians":1.6221086976329895},"translation":{"x":3.0023300479999997,"y":4.916021952000001}},"time":1.7688000794891936,"velocity":-0.8826171369712825,"position":-0.08402081790658426,"holonomicRotation":0.0,"angularVelocity":0.5736319949549626,"angularAcceleration":3.2198556541221035,"curveRadius":-1.5453996241449928},{"acceleration":-5.185469967192308,"curvature":-0.6441586157755366,"pose":{"rotation":{"radians":1.6298794635088907},"translation":{"x":3.0030392320000003,"y":4.9040327679999995}},"time":1.7814651125712906,"velocity":-0.9482912856519945,"position":-0.09603095841083124,"holonomicRotation":0.0,"angularVelocity":0.6135606457187752,"angularAcceleration":3.1526684932433557,"curveRadius":-1.5524126752477683},{"acceleration":-5.161271006272823,"curvature":-0.6412104045031639,"pose":{"rotation":{"radians":1.6376168137459786},"translation":{"x":3.003841344,"y":4.892046656000001}},"time":1.7933626542461558,"velocity":-1.0096977225443982,"position":-0.10804387914381956,"holonomicRotation":0.0,"angularVelocity":0.6503318457319575,"angularAcceleration":3.090655281407054,"curveRadius":-1.5595504891640692},{"acceleration":-5.142636662349463,"curvature":-0.6382392605344286,"pose":{"rotation":{"radians":1.645320632431872},"translation":{"x":3.004736,"y":4.880064}},"time":1.8046180245401255,"velocity":-1.0675800024664868,"position":-0.12005988739001716,"holonomicRotation":0.0,"angularVelocity":0.6844571510917672,"angularAcceleration":3.031913163984707,"curveRadius":-1.5668105392994027},{"acceleration":-5.127839939713135,"curvature":-0.6352472246548937,"pose":{"rotation":{"radians":1.6529908199977594},"translation":{"x":3.005722816,"y":4.868085184000001}},"time":1.8153258402292327,"velocity":-1.122487967424177,"position":-0.1320792816584357,"holonomicRotation":0.0,"angularVelocity":0.7163167342981173,"angularAcceleration":2.975357825663771,"curveRadius":-1.5741902698485035},{"acceleration":-5.11580256887457,"curvature":-0.6322363020068388,"pose":{"rotation":{"radians":1.6606272929301413},"translation":{"x":3.0068014080000003,"y":4.856110592}},"time":1.8255596168686856,"velocity":-1.1748419482455787,"position":-0.14410235174344063,"holonomicRotation":0.0,"angularVelocity":0.7462028146033625,"angularAcceleration":2.9203373649987046,"curveRadius":-1.581687095198123},{"acceleration":-5.105816223076332,"curvature":-0.629208460982605,"pose":{"rotation":{"radians":1.6682299834760697},"translation":{"x":3.007971392,"y":4.844140608000001}},"time":1.8353778232993863,"velocity":-1.2249719059209627,"position":-0.1561293787875815,"holonomicRotation":0.0,"angularVelocity":0.7743461700046723,"angularAcceleration":2.866445679254409,"curveRadius":-1.5892983995134895},{"acceleration":-5.0973962491241345,"curvature":-0.6261656322196447,"pose":{"rotation":{"radians":1.67579883934253},"translation":{"x":3.009232384,"y":4.832175616}},"time":1.844827870085676,"velocity":-1.2731425389634436,"position":-0.16816063534640177,"holonomicRotation":0.0,"angularVelocity":0.8009331633618351,"angularAcceleration":2.813424521425176,"curveRadius":-1.5970215363867537},{"acceleration":-5.090199765560945,"curvature":-0.623109707774154,"pose":{"rotation":{"radians":1.6833338233904271},"translation":{"x":3.010584,"y":4.820216}},"time":1.8539488333719214,"velocity":-1.3195700641447794,"position":-0.18019638545509464,"holonomicRotation":0.0,"angularVelocity":0.8261171338404685,"angularAcceleration":2.761108633844812,"curveRadius":-1.6048538283445422},{"acceleration":-5.083977317704007,"curvature":-0.6200425403987191,"pose":{"rotation":{"radians":1.6908349133247844},"translation":{"x":3.012025856,"y":4.8082621439999995}},"time":1.8627733722172823,"velocity":-1.3644338194737926,"position":-0.1922368846969654,"holonomicRotation":0.0,"angularVelocity":0.8500262807841285,"angularAcceleration":2.7093933589774903,"curveRadius":-1.6127925663889913},{"acceleration":-5.078543064849826,"curvature":-0.6169659427566521,"pose":{"rotation":{"radians":1.6983021013807615},"translation":{"x":3.013557568,"y":4.796314432000001}},"time":1.8713291134085535,"velocity":-1.407884519565373,"position":-0.20428238027356396,"holonomicRotation":0.0,"angularVelocity":0.8727692772655782,"angularAcceleration":2.6582146389202004,"curveRadius":-1.6208350100038291},{"acceleration":-5.0737557049083,"curvature":-0.6138816870079441,"pose":{"rotation":{"radians":1.7057353940065614},"translation":{"x":3.0151787519999997,"y":4.784373248}},"time":1.879639674095175,"velocity":-1.4500502742601056,"position":-0.21633311107645473,"holonomicRotation":0.0,"angularVelocity":0.8944393652965064,"angularAcceleration":2.607536223857085,"curveRadius":-1.6289783864933232},{"acceleration":-5.069505878039998,"curvature":-0.6107915042418562,"pose":{"rotation":{"radians":1.7131348115441414},"translation":{"x":3.016889024,"y":4.772438976000001}},"time":1.8877254317087737,"velocity":-1.49104107001065,"position":-0.22838930776048144,"holonomicRotation":0.0,"angularVelocity":0.9151174065786669,"angularAcceleration":2.5573412251913745,"curveRadius":-1.6372198910023283},{"acceleration":-5.06570761830259,"curvature":-0.6076970841012463,"pose":{"rotation":{"radians":1.7205003879070997},"translation":{"x":3.018688,"y":4.760511999999999}},"time":1.8956041135545927,"velocity":-1.530952168659198,"position":-0.24045119281851401,"holonomicRotation":0.0,"angularVelocity":0.9348741968641555,"angularAcceleration":2.507626360870605,"curveRadius":-1.645556686320044},{"acceleration":-5.062292412183364,"curvature":-0.60460007456127,"pose":{"rotation":{"radians":1.727832170258715},"translation":{"x":3.020575296,"y":4.748592704}},"time":1.9032912551629764,"velocity":-1.5698667272946978,"position":-0.2525189806575182,"holonomicRotation":0.0,"angularVelocity":0.9537722504837324,"angularAcceleration":2.458398008300826,"curveRadius":-1.653985902541698},{"acceleration":-5.059204981040039,"curvature":-0.6015020816667189,"pose":{"rotation":{"radians":1.7351302186871767},"translation":{"x":3.022550528,"y":4.736681472}},"time":1.9108005614371286,"velocity":-1.607857847001044,"position":-0.2645928776759481,"holonomicRotation":0.0,"angularVelocity":0.9718671954534991,"angularAcceleration":2.4096693235234317,"curveRadius":-1.662504637106279},{"acceleration":-5.056400230611564,"curvature":-0.5984046693700557,"pose":{"rotation":{"radians":1.7423946058821427},"translation":{"x":3.024613312,"y":4.724778688}},"time":1.91814419466818,"velocity":-1.64499019576406,"position":-0.2766730823423151,"holonomicRotation":0.0,"angularVelocity":0.9892088788216608,"angularAcceleration":2.3614582622174876,"curveRadius":-1.6711099548282373},{"acceleration":-5.053841007339382,"curvature":-0.5953093595736652,"pose":{"rotation":{"radians":1.7496254168103444},"translation":{"x":3.026763264,"y":4.7128847359999995}},"time":1.925333006745701,"velocity":-1.681321309035491,"position":-0.2887597852749024,"holonomicRotation":0.0,"angularVelocity":1.0058422518530346,"angularAcceleration":2.313786040309213,"curveRadius":-1.6797988876172831},{"acceleration":-5.05149642297008,"curvature":-0.5922176320623417,"pose":{"rotation":{"radians":1.7568227483924304},"translation":{"x":3.0290000000000004,"y":4.701}},"time":1.9323767282387057,"velocity":-1.7169026429618017,"position":-0.30085316932252903,"holonomicRotation":0.0,"angularVelocity":1.021808086710096,"angularAcceleration":2.2666760565302844,"curveRadius":-1.6885684347451713},{"acceleration":-5.049340586274517,"curvature":-0.589130924651956,"pose":{"rotation":{"radians":1.7639867091802053},"translation":{"x":3.031323136,"y":4.689124864}},"time":1.9392841237539644,"velocity":-1.7517804354824487,"position":-0.31295340964629864,"holonomicRotation":0.0,"angularVelocity":1.0371435618460447,"angularAcceleration":2.2201530377219276,"curveRadius":-1.6974155627474066},{"acceleration":-5.047351630948116,"curvature":-0.586050633250819,"pose":{"rotation":{"radians":1.7711174190362282},"translation":{"x":3.033732288,"y":4.677259712}},"time":1.9460631206456207,"velocity":-1.785996416499742,"position":-0.32506067380225956,"holonomicRotation":0.0,"angularVelocity":1.0518827445989243,"angularAcceleration":2.1742424415359936,"curveRadius":-1.7063372058025204},{"acceleration":-5.045510961969076,"curvature":-0.5829781121894888,"pose":{"rotation":{"radians":1.7782150088143185},"translation":{"x":3.036227072,"y":4.665404928}},"time":1.9527209164604256,"velocity":-1.8195883982658922,"position":-0.3371751218249019,"holonomicRotation":0.0,"angularVelocity":1.0660569917610472,"angularAcceleration":2.128969940862946,"curveRadius":-1.7153302655640084},{"acceleration":-5.043802665249592,"curvature":-0.5799146744073547,"pose":{"rotation":{"radians":1.7852796200427274},"translation":{"x":3.038807104,"y":4.653560896}},"time":1.9592640692624839,"velocity":-1.8525907698080493,"position":-0.3492969063114388,"holonomicRotation":0.0,"angularVelocity":1.079695284845956,"angularAcceleration":2.084361086694869,"curveRadius":-1.7243916116141615},{"acceleration":-5.0422130406743735,"curvature":-0.5768615917997932,"pose":{"rotation":{"radians":1.7923114046100626},"translation":{"x":3.041472,"y":4.641728}},"time":1.9656985740594597,"velocity":-1.8850349138056426,"position":-0.3614261725067881,"holonomicRotation":0.0,"angularVelocity":1.092824512406922,"angularAcceleration":2.0404410246359075,"curveRadius":-1.7335180816598066},{"acceleration":-5.040730229483784,"curvature":-0.5738200956456038,"pose":{"rotation":{"radians":1.7993105244536647},"translation":{"x":3.044221376,"y":4.629906623999999}},"time":1.9720299278591562,"velocity":-1.916949560297329,"position":-0.37356305838920284,"holonomicRotation":0.0,"angularVelocity":1.1054697091699106,"angularAcceleration":1.9972342666421594,"curveRadius":-1.742706481680294},{"acceleration":-5.039343914482858,"curvature":-0.5707913768570366,"pose":{"rotation":{"radians":1.8062771512517184},"translation":{"x":3.047054848,"y":4.618097152}},"time":1.978263185358847,"velocity":-1.948361088545801,"position":-0.38570769475648686,"holonomicRotation":0.0,"angularVelocity":1.1176542599754922,"angularAcceleration":1.9547645522723545,"curveRadius":-1.751953586801409},{"acceleration":-5.038045076972435,"curvature":-0.5677765867125653,"pose":{"rotation":{"radians":1.813211466118048},"translation":{"x":3.0499720320000003,"y":4.606299968}},"time":1.9844030068658016,"velocity":-1.979293786062403,"position":-0.39786020531273436,"holonomicRotation":0.0,"angularVelocity":1.1294000743303645,"angularAcceleration":1.913054694109239,"curveRadius":-1.761256140888117},{"acceleration":-5.036825798293685,"curvature":-0.5647768371119459,"pose":{"rotation":{"radians":1.820113659301696},"translation":{"x":3.0529725439999997,"y":4.594515456}},"time":1.9904536997347049,"velocity":-2.009770072002046,"position":-0.4100207067555322,"holonomicRotation":0.0,"angularVelocity":1.1407277370036277,"angularAcceleration":1.872126534711486,"curveRadius":-1.7706108577568795},{"acceleration":-5.035679096669612,"curvature":-0.5617932012303779,"pose":{"rotation":{"radians":1.8269839298900132},"translation":{"x":3.0560560000000003,"y":4.582744}},"time":1.996419254363498,"velocity":-2.0398106907463003,"position":-0.4221893088635755,"holonomicRotation":0.0,"angularVelocity":1.1516566381200266,"angularAcceleration":1.8320008442550966,"curveRadius":-1.7800144213385096},{"acceleration":-5.0345987922755695,"curvature":-0.5588267141256478,"pose":{"rotation":{"radians":1.833822485515185},"translation":{"x":3.059222016,"y":4.570985984}},"time":2.002303375596971,"velocity":-2.0694348804019467,"position":-0.4343661145846383,"holonomicRotation":0.0,"angularVelocity":1.1622050861680477,"angularAcceleration":1.7926972659934512,"curveRadius":-1.7894634861266812},{"acceleration":-5.033579395008346,"curvature":-0.5558783732812124,"pose":{"rotation":{"radians":1.8406295420671128},"translation":{"x":3.062470208,"y":4.559241792}},"time":2.008109510235051,"velocity":-2.0986605200808293,"position":-0.4465512201238501,"holonomicRotation":0.0,"angularVelocity":1.1723904070848534,"angularAcceleration":1.754234366183112,"curveRadius":-1.7989546779761327},{"acceleration":-5.0326160105243085,"curvature":-0.5529491392614698,"pose":{"rotation":{"radians":1.8474053234088554},"translation":{"x":3.065800192,"y":4.547511807999999}},"time":2.013840871221043,"velocity":-2.1275042591410283,"position":-0.45874471503222336,"holonomicRotation":0.0,"angularVelocity":1.1822290304698975,"angularAcceleration":1.7166295072130613,"curveRadius":-1.808484594687353},{"acceleration":-5.0317042612959995,"curvature":-0.5500399363825702,"pose":{"rotation":{"radians":1.8541500610982622},"translation":{"x":3.069211584,"y":4.535796415999999}},"time":2.0195004589872814,"velocity":-2.155981631021588,"position":-0.47094668229538755,"holonomicRotation":0.0,"angularVelocity":1.1917365659813342,"angularAcceleration":1.6798989439041818,"curveRadius":-1.8180498066679804},{"acceleration":-5.030840219915563,"curvature":-0.5471516533975169,"pose":{"rotation":{"radians":1.8608639941139673},"translation":{"x":3.072704,"y":4.524095999999999}},"time":2.0250910803565287,"velocity":-2.1841071538603174,"position":-0.4831571984224852,"holonomicRotation":0.0,"angularVelocity":1.200927870493382,"angularAcceleration":1.6440577719333227,"curveRadius":-1.8276468576683245},{"acceleration":-5.030020352378899,"curvature":-0.5442851441519785,"pose":{"rotation":{"radians":1.867547368586635},"translation":{"x":3.0762770560000003,"y":4.512410944}},"time":2.0306153653331203,"velocity":-2.211894419724915,"position":-0.4953763335351787,"holonomicRotation":0.0,"angularVelocity":1.2098171077320357,"angularAcceleration":1.6091199632749673,"curveRadius":-1.8372722657313132},{"acceleration":-5.029241469862824,"curvature":-0.5414412284047262,"pose":{"rotation":{"radians":1.8742004375350847},"translation":{"x":3.0799303680000003,"y":4.5007416319999995}},"time":2.0360757820651902,"velocity":-2.2393561739965735,"position":-0.5076041514567335,"holonomicRotation":0.0,"angularVelocity":1.2184178012229603,"angularAcceleration":1.5750983693994312,"curveRadius":-1.846922523699104},{"acceleration":-5.028500687328672,"curvature":-0.538620692477182,"pose":{"rotation":{"radians":1.8808234606086733},"translation":{"x":3.083663552,"y":4.4890884479999995}},"time":2.04147465021602,"velocity":-2.2665043862038186,"position":-0.5198407098011256,"holonomicRotation":0.0,"angularVelocity":1.2267428817594963,"angularAcceleration":1.5420047876620777,"curveRadius":-1.8565941003879343},{"acceleration":-5.027795388007443,"curvature":-0.5358242899805565,"pose":{"rotation":{"radians":1.887416703833856},"translation":{"x":3.087476224,"y":4.477451776}},"time":2.0468141529467774,"velocity":-2.2933503134077737,"position":-0.5320860600621498,"holonomicRotation":0.0,"angularVelocity":1.2348047295122362,"angularAcceleration":1.5098499166038124,"curveRadius":-1.8662834416041256},{"acceleration":-5.027123192737607,"curvature":-0.5330527427341364,"pose":{"rotation":{"radians":1.8939804393669588},"translation":{"x":3.091368,"y":4.465832}},"time":2.052096347683174,"velocity":-2.319904557075669,"position":-0.544340247702477,"holonomicRotation":0.0,"angularVelocity":1.242615212172309,"angularAcceleration":1.4786434521725416,"curveRadius":-1.8759869705778003},{"acceleration":-5.026481933394539,"curvature":-0.5303067413665257,"pose":{"rotation":{"radians":1.9005149452524996},"translation":{"x":3.095338496,"y":4.454229504}},"time":2.0573231758137993,"velocity":-2.346177114243216,"position":-0.5566033122426332,"holonomicRotation":0.0,"angularVelocity":1.250185719184701,"angularAcceleration":1.448394097375074,"curveRadius":-1.8857010895677868},{"acceleration":-5.025869629875782,"curvature":-0.527586946146635,"pose":{"rotation":{"radians":1.9070205051869529},"translation":{"x":3.099387328,"y":4.442644671999999}},"time":2.0624964714471132,"velocity":-2.372177423653056,"position":-0.5688752873498626,"holonomicRotation":0.0,"angularVelocity":1.2575271926391536,"angularAcceleration":1.4191095918000391,"curveRadius":-1.8954221807490754},{"acceleration":-5.025284469967182,"curvature":-0.5248939878051837,"pose":{"rotation":{"radians":1.9134974082881397},"translation":{"x":3.103514112,"y":4.431077888}},"time":2.067617969336602,"velocity":-2.3979144074600742,"position":-0.5811562009268444,"holonomicRotation":0.0,"angularVelocity":1.2646501552758096,"angularAcceleration":1.3907967532847798,"curveRadius":-1.9051466071871899},{"acceleration":-5.024724791770228,"curvature":-0.5222284682600391,"pose":{"rotation":{"radians":1.91994594887033},"translation":{"x":3.1077184640000004,"y":4.419529536}},"time":2.07268931206887,"velocity":-2.4233965090144634,"position":-0.5934460752002377,"holonomicRotation":0.0,"angularVelocity":1.2715647359347109,"angularAcceleration":1.3634615177762577,"curveRadius":-1.91487071421403},{"acceleration":-5.024189068330523,"curvature":-0.5195909614569447,"pose":{"rotation":{"radians":1.9263664262250693},"translation":{"x":3.112,"y":4.4079999999999995}},"time":2.0777120565968965,"velocity":-2.448631727165193,"position":-0.6057449268090098,"holonomicRotation":0.0,"angularVelocity":1.2782806927393753,"angularAcceleration":1.3371089784060015,"curveRadius":-1.9245908304408867},{"acceleration":-5.023675894062114,"curvature":-0.5169820141397626,"pose":{"rotation":{"radians":1.932759144407969},"translation":{"x":3.1163583360000002,"y":4.396489664}},"time":2.0826876801900953,"velocity":-2.473627647468272,"position":-0.6180527668925414,"holonomicRotation":0.0,"angularVelocity":1.2848074343160134,"angularAcceleration":1.3117434336391052,"curveRadius":-1.9343032690681898},{"acceleration":-5.0231839727994005,"curvature":-0.5144021466205735,"pose":{"rotation":{"radians":1.9391244120303428},"translation":{"x":3.120793088,"y":4.3849989119999995}},"time":2.087617585863683,"velocity":-2.498391470635251,"position":-0.6303696011784695,"holonomicRotation":0.0,"angularVelocity":1.291154039006462,"angularAcceleration":1.2873683820059245,"curveRadius":-1.9440043292385534},{"acceleration":-5.022712107260546,"curvature":-0.5118518535624782,"pose":{"rotation":{"radians":1.9454625420578235},"translation":{"x":3.1253038720000004,"y":4.373528127999999}},"time":2.092503107342126,"velocity":-2.522930038515307,"position":-0.6426954300702445,"holonomicRotation":0.0,"angularVelocity":1.2973292729235841,"angularAcceleration":1.2639866479699629,"curveRadius":-1.953690297378081},{"acceleration":-5.022259189699773,"curvature":-0.5093316047891807,"pose":{"rotation":{"radians":1.95177385161334},"translation":{"x":3.1298903040000003,"y":4.362077695999999}},"time":2.097345513604724,"velocity":-2.5472498578678997,"position":-0.655030248734386,"holonomicRotation":0.0,"angularVelocity":1.3033416060655765,"angularAcceleration":1.2416003152049948,"curveRadius":-1.9633574484621148},{"acceleration":-5.021824193560564,"curvature":-0.506841846048325,"pose":{"rotation":{"radians":1.9580586617868585},"translation":{"x":3.1345520000000002,"y":4.350648}},"time":2.102146013055649,"velocity":-2.5713571221517295,"position":-0.6673740471874077,"holonomicRotation":0.0,"angularVelocity":1.3091992276568902,"angularAcceleration":1.2202108658058386,"curveRadius":-1.9730020474762744},{"acceleration":-5.021406166082636,"curvature":-0.5043829997561204,"pose":{"rotation":{"radians":1.9643172974498757},"translation":{"x":3.139288576,"y":4.339239424}},"time":2.1069057573557703,"velocity":-2.5952577315293346,"position":-0.6797268103823998,"holonomicRotation":0.0,"angularVelocity":1.3149100599496268,"angularAcceleration":1.1998191357866097,"curveRadius":-1.9826203509704343},{"acceleration":-5.021004221749742,"curvature":-0.5019554658388903,"pose":{"rotation":{"radians":1.9705500870760755},"translation":{"x":3.144099648,"y":4.327852352}},"time":2.111625844949285,"velocity":-2.6189573112634017,"position":-0.6920885182952394,"holonomicRotation":0.0,"angularVelocity":1.3204817713050865,"angularAcceleration":1.1804254147983964,"curveRadius":-1.9922086082452664},{"acceleration":-5.020617536340884,"curvature":-0.49955962237970714,"pose":{"rotation":{"radians":1.976757362567204},"translation":{"x":3.1489848320000005,"y":4.316487167999999}},"time":2.116307324314437,"velocity":-2.642461228660101,"position":-0.7044591460104255,"holonomicRotation":0.0,"angularVelocity":1.325921788171141,"angularAcceleration":1.1620294444847987,"curveRadius":-2.00176306330842},{"acceleration":-5.020245341603093,"curvature":-0.4971958264330603,"pose":{"rotation":{"radians":1.9829394590844593},"translation":{"x":3.153943744,"y":4.305144255999999}},"time":2.120951196964319,"velocity":-2.665774608697669,"position":-0.7168386638065064,"holonomicRotation":0.0,"angularVelocity":1.331237306305665,"angularAcceleration":1.1446304701441863,"curveRadius":-2.011279956177658},{"acceleration":-5.019886920612115,"curvature":-0.4948644147448579,"pose":{"rotation":{"radians":1.9890967148855339},"translation":{"x":3.158976,"y":4.293824}},"time":2.12555842022093,"velocity":-2.6889023484638694,"position":-0.7292270372411045,"holonomicRotation":0.0,"angularVelocity":1.3364353012933832,"angularAcceleration":1.128227285330627,"curveRadius":-2.0207555245522753},{"acceleration":-5.019541603416165,"curvature":-0.49256570452370857,"pose":{"rotation":{"radians":1.995229471166522},"translation":{"x":3.164081216,"y":4.282526783999999}},"time":2.130129909783134,"velocity":-2.7118491305109362,"position":-0.7416242272355078,"holonomicRotation":0.0,"angularVelocity":1.3415225382317364,"angularAcceleration":1.112818233341943,"curveRadius":-2.0301860052700182},{"acceleration":-5.019208763157145,"curvature":-0.49029999405552377,"pose":{"rotation":{"radians":2.001338071909835},"translation":{"x":3.1692590080000005,"y":4.271252991999999}},"time":2.1346665421069964,"velocity":-2.7346194352260893,"position":-0.7540301901588173,"holonomicRotation":0.0,"angularVelocity":1.3465055810632898,"angularAcceleration":1.0984012976636164,"curveRadius":-2.0395676363943736},{"acceleration":-5.018887812710113,"curvature":-0.4880675635449118,"pose":{"rotation":{"radians":2.0074228637363074},"translation":{"x":3.1745089920000003,"y":4.260003007999999}},"time":2.139169156615038,"velocity":-2.757217552305832,"position":-0.766444877911657,"holonomicRotation":0.0,"angularVelocity":1.351390800967919,"angularAcceleration":1.0849740513881583,"curveRadius":-2.0488966583577937},{"acceleration":-5.018578201452989,"curvature":-0.4858686756363079,"pose":{"rotation":{"radians":2.013484195763848},"translation":{"x":3.1798307840000004,"y":4.248777216}},"time":2.1436385577492474,"velocity":-2.7796475914115226,"position":-0.7788682380094131,"holonomicRotation":0.0,"angularVelocity":1.3561843847818247,"angularAcceleration":1.0725338070945085,"curveRadius":-2.0581693164112105},{"acceleration":-5.018279412368859,"curvature":-0.4837035763095772,"pose":{"rotation":{"radians":2.019522419469503},"translation":{"x":3.1852240000000003,"y":4.237576}},"time":2.148075516881194,"velocity":-2.8019134920768924,"position":-0.7913002136650081,"holonomicRotation":0.0,"angularVelocity":1.360892342275403,"angularAcceleration":1.0610774978025737,"curveRadius":-2.067381861489454},{"acceleration":-5.017990959647853,"curvature":-0.4815724954088063,"pose":{"rotation":{"radians":2.0255378885580493},"translation":{"x":3.190688256,"y":4.226399743999999}},"time":2.15248077409126,"velocity":-2.8240190329319295,"position":-0.8037407438711964,"holonomicRotation":0.0,"angularVelocity":1.3655205137171957,"angularAcceleration":1.050601865247958,"curveRadius":-2.0765305525829527},{"acceleration":-5.017712386117475,"curvature":-0.47947564724702796,"pose":{"rotation":{"radians":2.0315309588344928},"translation":{"x":3.1962231680000004,"y":4.2152488319999994}},"time":2.1568550398278235,"velocity":-2.8459678402984507,"position":-0.816189763482374,"holonomicRotation":0.0,"angularVelocity":1.370074576482512,"angularAcceleration":1.0411033621598245,"curveRadius":-2.0856116587810676},{"acceleration":-5.0174432613023185,"curvature":-0.47741323142346864,"pose":{"rotation":{"radians":2.0375019880813783},"translation":{"x":3.2018283520000006,"y":4.2041236479999995}},"time":2.1611989964561804,"velocity":-2.8677633962107905,"position":-0.8286472032959037,"holonomicRotation":0.0,"angularVelocity":1.3745600515223912,"angularAcceleration":1.0325782284745637,"curveRadius":-2.0946214603612305},{"acceleration":-5.017183179257472,"curvature":-0.4753854333143056,"pose":{"rotation":{"radians":2.043451335941641},"translation":{"x":3.2075034240000004,"y":4.193024575999999}},"time":2.1655132997060766,"velocity":-2.889409045906387,"position":-0.8411129901329378,"holonomicRotation":0.0,"angularVelocity":1.3789823096940073,"angularAcceleration":1.0250225622693876,"curveRadius":-2.1035562512468498},{"acceleration":-5.016931757062779,"curvature":-0.4733924247442328,"pose":{"rotation":{"radians":2.0493793638053237},"translation":{"x":3.2132480000000005,"y":4.181951999999999}},"time":2.1697985800258626,"velocity":-2.9109080048306364,"position":-0.8535870469187455,"holonomicRotation":0.0,"angularVelocity":1.3833465774251021,"angularAcceleration":1.0184322623993525,"curveRadius":-2.1124123406501187},{"acceleration":-5.0166886328995,"curvature":-0.47143436459980015,"pose":{"rotation":{"radians":2.055286434700795},"translation":{"x":3.2190616960000002,"y":4.170906303999999}},"time":2.174055443850567,"velocity":-2.9322633651918313,"position":-0.8660692927625362,"holonomicRotation":0.0,"angularVelocity":1.3876579422602928,"angularAcceleration":1.0128030899579494,"curveRadius":-2.121186054921767},{"acceleration":-5.016453464843795,"curvature":-0.46951139935295344,"pose":{"rotation":{"radians":2.0611729131911716},"translation":{"x":3.2249441280000006,"y":4.159887872}},"time":2.1782844747905106,"velocity":-2.9534781021034426,"position":-0.8785596430367774,"holonomicRotation":0.0,"angularVelocity":1.3919213583372567,"angularAcceleration":1.008130736688539,"curveRadius":-2.129873739760371},{"acceleration":-5.016225929287736,"curvature":-0.4676236637363229,"pose":{"rotation":{"radians":2.0670391652738456},"translation":{"x":3.230894912,"y":4.148897087999999}},"time":2.182486234746486,"velocity":-2.974555079343252,"position":-0.8910580094560067,"holonomicRotation":0.0,"angularVelocity":1.3961416511504283,"angularAcceleration":1.0044107367840718,"curveRadius":-2.1384717616939635},{"acceleration":-5.016005719793715,"curvature":-0.46577128117650907,"pose":{"rotation":{"radians":2.0728855582860835},"translation":{"x":3.2369136640000002,"y":4.137934335999999}},"time":2.186661264957,"velocity":-2.9954970547594986,"position":-0.9035643001551313,"holonomicRotation":0.0,"angularVelocity":1.400323522813269,"angularAcceleration":1.0016386593587288,"curveRadius":-2.1469765106042233},{"acceleration":-5.015792545910725,"curvature":-0.46395436448481275,"pose":{"rotation":{"radians":2.078712460812497},"translation":{"x":3.2430000000000003,"y":4.127}},"time":2.190810086982583,"velocity":-3.0163066853497296,"position":-0.9160784197672245,"holonomicRotation":0.0,"angularVelocity":1.4044715561386967,"angularAcceleration":0.9998098978093355,"curveRadius":-2.1553844010292402},{"acceleration":-5.015586132153029,"curvature":-0.4621730162899535,"pose":{"rotation":{"radians":2.084520242598428},"translation":{"x":3.249153536,"y":4.116094464}},"time":2.1949332036317677,"velocity":-3.0369865320366287,"position":-0.9286002695008139,"holonomicRotation":0.0,"angularVelocity":1.4085902195077777,"angularAcceleration":0.9989199238143465,"curveRadius":-2.163691874587135},{"acceleration":-5.0153862169819075,"curvature":-0.46042732956063537,"pose":{"rotation":{"radians":2.0903092744667395},"translation":{"x":3.2553738880000003,"y":4.105218111999999}},"time":2.1990310998328995,"velocity":-3.057539064162408,"position":-0.9411297472166573,"holonomicRotation":0.0,"angularVelocity":1.412683870985459,"angularAcceleration":0.9989641700906317,"curveRadius":-2.171895401939442},{"acceleration":-5.015192551928618,"curvature":-0.45871738814240054,"pose":{"rotation":{"radians":2.096079928237889},"translation":{"x":3.2616606720000005,"y":4.094371327999999}},"time":2.2031042434556447,"velocity":-3.077966663722135,"position":-0.9536667475040193,"holonomicRotation":0.0,"angularVelocity":1.4167567622523662,"angularAcceleration":0.9999380439627801,"curveRadius":-2.179991484625318},{"acceleration":-5.015004900722467,"curvature":-0.45704326726309885,"pose":{"rotation":{"radians":2.1018325766544494},"translation":{"x":3.2680135040000002,"y":4.083554496}},"time":2.2071530860857016,"velocity":-3.0982716293541244,"position":-0.9662111617564441,"holonomicRotation":0.0,"angularVelocity":1.4208130426842034,"angularAcceleration":1.0018370192323696,"curveRadius":-2.1879766569766486},{"acceleration":-5.014823038647243,"curvature":-0.4554050339602513,"pose":{"rotation":{"radians":2.1075675933092324},"translation":{"x":3.2744320000000005,"y":4.072767999999999}},"time":2.2111780637559546,"velocity":-3.1184561801049515,"position":-0.97876287824703,"holonomicRotation":0.0,"angularVelocity":1.4248567630990017,"angularAcceleration":1.0046566083293977,"curveRadius":-2.1958474883421735},{"acceleration":-5.014646751637538,"curvature":-0.4538027475367536,"pose":{"rotation":{"radians":2.1132853525765656},"translation":{"x":3.2809157760000005,"y":4.062012223999999}},"time":2.215179597637041,"velocity":-3.1385224589833083,"position":-0.9913217822032019,"holonomicRotation":0.0,"angularVelocity":1.4288918792763166,"angularAcceleration":1.0083923558381849,"curveRadius":-2.2036005851176776},{"acceleration":-5.014475835810277,"curvature":-0.45223646007658297,"pose":{"rotation":{"radians":2.118986229547372},"translation":{"x":3.2874644480000006,"y":4.051287551999999}},"time":2.219158094690065,"velocity":-3.1584725363185395,"position":-1.0038877558810024,"holonomicRotation":0.0,"angularVelocity":1.432922255521863,"angularAcceleration":1.0130398971850545,"curveRadius":-2.2112325924156075},{"acceleration":-5.01431009678848,"curvature":-0.4507062168354121,"pose":{"rotation":{"radians":2.1246705999676685},"translation":{"x":3.2940776320000005,"y":4.040594367999999}},"time":2.2231139482839803,"velocity":-3.178308412935926,"position":-1.0164606786388861,"holonomicRotation":0.0,"angularVelocity":1.4369516680395247,"angularAcceleration":1.0185949560569005,"curveRadius":-2.2187401962666464},{"acceleration":-5.014149349013592,"curvature":-0.4492120566748173,"pose":{"rotation":{"radians":2.1303388401800927},"translation":{"x":3.3007549440000004,"y":4.029933055999999}},"time":2.227047538779963,"velocity":-3.198032023160643,"position":-1.029040427011039,"holonomicRotation":0.0,"angularVelocity":1.4409838081043629,"angularAcceleration":1.0250533371372097,"curveRadius":-2.2261201255421685},{"acceleration":-5.013993415460937,"curvature":-0.44775401243225865,"pose":{"rotation":{"radians":2.1359913270688047},"translation":{"x":3.3074960000000004,"y":4.019303999999999}},"time":2.2309592340849185,"velocity":-3.21764523766298,"position":-1.041626874780218,"holonomicRotation":0.0,"angularVelocity":1.445022285235519,"angularAcceleration":1.0324109666823746,"curveRadius":-2.233369154120738},{"acceleration":-5.013842126946369,"curvature":-0.4463321113345515,"pose":{"rotation":{"radians":2.141628438007425},"translation":{"x":3.3143004160000005,"y":4.008707584}},"time":2.2348493901761057,"velocity":-3.2371498661533717,"position":-1.0542198930501205,"holonomicRotation":0.0,"angularVelocity":1.4490706301966823,"angularAcceleration":1.0406638875839311,"curveRadius":-2.2404841027681353},{"acceleration":-5.01369532171432,"curvature":-0.4449463754557567,"pose":{"rotation":{"radians":2.1472505508098934},"translation":{"x":3.3211678080000007,"y":3.9981441919999994}},"time":2.2387183515987106,"velocity":-3.2565476599377794,"position":-1.0668193503172942,"holonomicRotation":0.0,"angularVelocity":1.4531322978876198,"angularAcceleration":1.0498082682361864,"curveRadius":-2.2474618407121625},{"acceleration":-5.0135528451850915,"curvature":-0.44359682198548334,"pose":{"rotation":{"radians":2.1528580436844997},"translation":{"x":3.3280977920000003,"y":3.987614207999999}},"time":2.242566451938064,"velocity":-3.2758403143427004,"position":-1.0794251125425827,"holonomicRotation":0.0,"angularVelocity":1.4572106702262286,"angularAcceleration":1.0598404352664477,"curveRadius":-2.254299288088058},{"acceleration":-5.013414549243218,"curvature":-0.44228346357140413,"pose":{"rotation":{"radians":2.1584512951904333},"translation":{"x":3.3350899840000006,"y":3.977118015999999}},"time":2.2463940142680783,"velocity":-3.2950294710161296,"position":-1.0920370432221311,"holonomicRotation":0.0,"angularVelocity":1.461309058790067,"angularAcceleration":1.0707568448200822,"curveRadius":-2.2609934179430513},{"acceleration":-5.013280292169202,"curvature":-0.44100630878383207,"pose":{"rotation":{"radians":2.1640306841970087},"translation":{"x":3.3421440000000007,"y":3.9666559999999995}},"time":2.2502013515773616,"velocity":-3.3141167201143995,"position":-1.1046550034579419,"holonomicRotation":0.0,"angularVelocity":1.46543070743208,"angularAcceleration":1.0825541072926455,"curveRadius":-2.267541257533732},{"acceleration":-5.013149938105479,"curvature":-0.43976536240568537,"pose":{"rotation":{"radians":2.1695965898458365},"translation":{"x":3.3492594560000004,"y":3.956228543999999}},"time":2.253988767174359,"velocity":-3.333103602380067,"position":-1.1172788520280046,"holonomicRotation":0.0,"angularVelocity":1.469578794901782,"angularAcceleration":1.09522901922631,"curveRadius":-2.2739398904216013},{"acceleration":-5.013023356881918,"curvature":-0.43856062556178693,"pose":{"rotation":{"radians":2.175149391515662},"translation":{"x":3.356435968000001,"y":3.9458360319999994}},"time":2.257756555072782,"velocity":-3.3519916111186387,"position":-1.129908445455993,"holonomicRotation":0.0,"angularVelocity":1.4737564373380705,"angularAcceleration":1.1087785589090624,"curveRadius":-2.2801864593270795},{"acceleration":-5.012900423529287,"curvature":-0.43739209639321713,"pose":{"rotation":{"radians":2.180689468788583},"translation":{"x":3.3636731520000005,"y":3.9354788479999994}},"time":2.261505000358494,"velocity":-3.3707821940789633,"position":-1.1425436380805518,"holonomicRotation":0.0,"angularVelocity":1.4779666903603275,"angularAcceleration":1.12319980721199,"curveRadius":-2.2862781660805234},{"acceleration":-3.212393326243053,"curvature":-0.4362597700073285,"pose":{"rotation":{"radians":2.1862172014204777},"translation":{"x":3.3709706240000004,"y":3.925157375999999}},"time":2.265241755680284,"velocity":-3.382786121936484,"position":-1.1551842821241745,"holonomicRotation":0.0,"angularVelocity":1.4792867490309756,"angularAcceleration":0.35326334131394377,"curveRadius":-2.292212275230424},{"acceleration":-1.275989144158481,"curvature":-0.43516363895714666,"pose":{"rotation":{"radians":2.1917329693118752},"translation":{"x":3.3783280000000007,"y":3.914871999999999}},"time":2.268974821643198,"velocity":-3.3875494735795892,"position":-1.1678302277616806,"holonomicRotation":0.0,"angularVelocity":1.4775436454094792,"angularAcceleration":-0.46693619636333,"curveRadius":-2.2979861148244427},{"acceleration":-1.1255901860971638,"curvature":-0.4341036934661007,"pose":{"rotation":{"radians":2.1972371524821046},"translation":{"x":3.3857448960000003,"y":3.9046231039999992}},"time":2.2727047850308626,"velocity":-3.3917478837632467,"position":-1.1804813231883076,"holonomicRotation":0.0,"angularVelocity":1.4756668090715832,"angularAcceleration":-0.5031782199532472,"curveRadius":-2.3035970784203665},{"acceleration":-1.092680274055794,"curvature":-0.4330799216330578,"pose":{"rotation":{"radians":2.2027301310455174},"translation":{"x":3.3932209280000003,"y":3.894411071999999}},"time":2.2764317465676775,"velocity":-3.3958202611166888,"position":-1.1931374146874256,"holonomicRotation":0.0,"angularVelocity":1.473849007872349,"angularAcceleration":-0.4877434825334531,"curveRadius":-2.3090426271188003},{"acceleration":-1.0593156094239868,"curvature":-0.4320923098070697,"pose":{"rotation":{"radians":2.2082122851892256},"translation":{"x":3.4007557120000005,"y":3.8842362879999994}},"time":2.2801558072610786,"velocity":-3.399765216739651,"position":-1.2057983466978786,"holonomicRotation":0.0,"angularVelocity":1.4720904397240837,"angularAcceleration":-0.47221790756023263,"curveRadius":-2.314320290602956},{"acceleration":-1.0255094397449158,"curvature":-0.4311408427216499,"pose":{"rotation":{"radians":2.213683995153181},"translation":{"x":3.4083488640000006,"y":3.874099135999999}},"time":2.283877068390285,"velocity":-3.403581405155408,"position":-1.2184639618809725,"holonomicRotation":0.0,"angularVelocity":1.470391293158815,"angularAcceleration":-0.4566050342269702,"curveRadius":-2.319427669360504},{"acceleration":-0.9912752748440978,"curvature":-0.4302255037988389,"pose":{"rotation":{"radians":2.219145641212311},"translation":{"x":3.4160000000000004,"y":3.863999999999999}},"time":2.287595631495133,"velocity":-3.4072675248191913,"position":-1.2311341011871122,"holonomicRotation":0.0,"angularVelocity":1.4687517476870304,"angularAcceleration":-0.4409083362460666,"curveRadius":-2.3243624359088932},{"acceleration":-0.9566268744993093,"curvature":-0.4293462752752821,"pose":{"rotation":{"radians":2.224597603659922},"translation":{"x":3.4237087360000005,"y":3.853939263999999}},"time":2.2913115983650307,"velocity":-3.4108223185916846,"position":-1.243808603922107,"holonomicRotation":0.0,"angularVelocity":1.4671719739420475,"angularAcceleration":-0.42513127815544927,"curveRadius":-2.329122336880259},{"acceleration":-0.9215782348819563,"curvature":-0.4285031384986032,"pose":{"rotation":{"radians":2.2300402627931817},"translation":{"x":3.4314746880000007,"y":3.8439173119999994}},"time":2.2950250710280446,"velocity":-3.4142445741737473,"position":-1.2564873078131444,"holonomicRotation":0.0,"angularVelocity":1.465652134043794,"angularAcceleration":-0.4092772550585997,"curveRadius":-2.3337051940945344},{"acceleration":-0.8861435249567237,"curvature":-0.42769607414071226,"pose":{"rotation":{"radians":2.235473998900302},"translation":{"x":3.4392974720000007,"y":3.8339345279999995}},"time":2.298736151740347,"velocity":-3.4175331243175457,"position":-1.2691700490744535,"holonomicRotation":0.0,"angularVelocity":1.4641923817790397,"angularAcceleration":-0.3933496406896402,"curveRadius":-2.338108905977471},{"acceleration":-0.8503371916142228,"curvature":-0.42692506226405785,"pose":{"rotation":{"radians":2.240899192249165},"translation":{"x":3.4471767040000008,"y":3.823991295999999}},"time":2.302444942975564,"velocity":-3.4206868474407837,"position":-1.2818566624726642,"holonomicRotation":0.0,"angularVelocity":1.4627928629003633,"angularAcceleration":-0.37735175422848816,"curveRadius":-2.3423314496853993},{"acceleration":-0.8141738616047239,"curvature":-0.4261900826856946,"pose":{"rotation":{"radians":2.246316223077442},"translation":{"x":3.4551120000000006,"y":3.814087999999999}},"time":2.3061515474143834,"velocity":-3.4237046678901786,"position":-1.294546981391873,"holonomicRotation":0.0,"angularVelocity":1.461453715304582,"angularAcceleration":-0.3612868915162253,"curveRadius":-2.346370881505183},{"acceleration":-0.7776683538438013,"curvature":-0.42549111498766573,"pose":{"rotation":{"radians":2.2517254715841926},"translation":{"x":3.463102976000001,"y":3.804225023999999}},"time":2.3098560679343376,"velocity":-3.426585556264712,"position":-1.307240837898434,"holonomicRotation":0.0,"angularVelocity":1.4601750692469038,"angularAcceleration":-0.34515831422469434,"curveRadius":-2.350225339086078},{"acceleration":-0.7408357262675391,"curvature":-0.42482813876175346,"pose":{"rotation":{"radians":2.257127317922695},"translation":{"x":3.4711492480000006,"y":3.794402751999999}},"time":2.3135586075995334,"velocity":-3.4293285299266114,"position":-1.3199380628054742,"holonomicRotation":0.0,"angularVelocity":1.4589570475855986,"angularAcceleration":-0.32896924042562026,"curveRadius":-2.3538930422892888},{"acceleration":-0.7036911937318191,"curvature":-0.424201133738781,"pose":{"rotation":{"radians":2.2625221421950776},"translation":{"x":3.4792504320000006,"y":3.784621567999999}},"time":2.3172592696506253,"velocity":-3.4319326532229426,"position":-1.332638485737161,"holonomicRotation":0.0,"angularVelocity":1.457799766068969,"angularAcceleration":-0.31272283192896394,"curveRadius":-2.3573722945676767},{"acceleration":-0.6662501490872429,"curvature":-0.42361007996169614,"pose":{"rotation":{"radians":2.26791032444725},"translation":{"x":3.487406144000001,"y":3.774881855999999}},"time":2.320958157494907,"velocity":-3.434397037800652,"position":-1.3453419351927178,"holonomicRotation":0.0,"angularVelocity":1.4567033332742725,"angularAcceleration":-0.29642228714548075,"curveRadius":-2.3606614840006226},{"acceleration":-0.6285281495020896,"curvature":-0.42305495790658737,"pose":{"rotation":{"radians":2.2732922446659067},"translation":{"x":3.495616000000001,"y":3.765183999999999}},"time":2.3246553746965297,"velocity":-3.4367208428866953,"position":-1.358048238610214,"holonomicRotation":0.0,"angularVelocity":1.455667851024415,"angularAcceleration":-0.2800707108587009,"curveRadius":-2.363759084513093},{"acceleration":-0.5905409558534574,"curvature":-0.42253574855162407,"pose":{"rotation":{"radians":2.2786682827760343},"translation":{"x":3.5038796160000008,"y":3.755528383999999}},"time":2.3283510249666644,"velocity":-3.4389032757297207,"position":-1.370757222430131,"holonomicRotation":0.0,"angularVelocity":1.4546934144642045,"angularAcceleration":-0.26367120506102093,"curveRadius":-2.366663657283008},{"acceleration":-0.5523044580278132,"curvature":-0.4220524336016502,"pose":{"rotation":{"radians":2.2840388186398783},"translation":{"x":3.512196608000001,"y":3.7459153919999992}},"time":2.332045212153851,"velocity":-3.440943591781993,"position":-1.383468712158724,"holonomicRotation":0.0,"angularVelocity":1.4537801122996437,"angularAcceleration":-0.2472268237323442,"curveRadius":-2.369373851173761},{"acceleration":-0.5138346609636051,"curvature":-0.4216049955488846,"pose":{"rotation":{"radians":2.2894042320560954},"translation":{"x":3.5205665920000007,"y":3.736345407999999}},"time":2.335738040234558,"velocity":-3.44284109484684,"position":-1.3961825324311876,"holonomicRotation":0.0,"angularVelocity":1.4529280266925801,"angularAcceleration":-0.2307406649974062,"curveRadius":-2.371888403974215},{"acceleration":-0.47514774168560514,"curvature":-0.4211934177613658,"pose":{"rotation":{"radians":2.294764902761007},"translation":{"x":3.5289891840000007,"y":3.7268188159999993}},"time":2.33942961330368,"velocity":-3.444595137453901,"position":-1.40889850707464,"holonomicRotation":0.0,"angularVelocity":1.4521372337855514,"angularAcceleration":-0.21421569943810245,"curveRadius":-2.374206143379398},{"acceleration":-0.43626000059906606,"curvature":-0.4208176845991983,"pose":{"rotation":{"radians":2.300121210429298},"translation":{"x":3.5374640000000004,"y":3.717335999999999}},"time":2.3431200355651214,"velocity":-3.446205121071888,"position":-1.4216164591709373,"holonomicRotation":0.0,"angularVelocity":1.4514078034524505,"angularAcceleration":-0.19765497859749015,"curveRadius":-2.3763259877075638},{"acceleration":-0.3971878566696979,"curvature":-0.4204777814786742,"pose":{"rotation":{"radians":2.3054735346767954},"translation":{"x":3.5459906560000007,"y":3.707897343999999}},"time":2.3468094113224525,"velocity":-3.4476704963213916,"position":-1.4343362111193314,"holonomicRotation":0.0,"angularVelocity":1.450739799778293,"angularAcceleration":-0.18106143643139072,"curveRadius":-2.378246946802629},{"acceleration":-0.3579478429199566,"curvature":-0.42017369496416096,"pose":{"rotation":{"radians":2.310822255062634},"translation":{"x":3.5545687680000007,"y":3.6985032319999993}},"time":2.3504978449696017,"velocity":-3.448990763189142,"position":-1.447057584698984,"holonomicRotation":0.0,"angularVelocity":1.4501332808231946,"angularAcceleration":-0.16443808215640984,"curveRadius":-2.379968122671972},{"acceleration":-0.31855655675985584,"curvature":-0.4199054128880666,"pose":{"rotation":{"radians":2.3161677510933316},"translation":{"x":3.563197952000001,"y":3.689154047999999}},"time":2.354185440981741,"velocity":-3.4501654710774905,"position":-1.4597804011313515,"holonomicRotation":0.0,"angularVelocity":1.4495882990164657,"angularAcceleration":-0.14778782842122584,"curveRadius":-2.38148870985516},{"acceleration":-0.27903069987780327,"curvature":-0.4196729243382383,"pose":{"rotation":{"radians":2.321510402226531},"translation":{"x":3.571877824000001,"y":3.679850175999999}},"time":2.357872303906167,"velocity":-3.4511942190196465,"position":-1.4725044811424473,"holonomicRotation":0.0,"angularVelocity":1.449104901026885,"angularAcceleration":-0.13111363223679925,"curveRadius":-2.3828079964340114},{"acceleration":-0.23938709166133332,"curvature":-0.41947621972129306,"pose":{"rotation":{"radians":2.3268505878754597},"translation":{"x":3.5806080000000007,"y":3.670591999999999}},"time":2.361558538353069,"velocity":-3.4520766559630722,"position":-1.4852296450250049,"holonomicRotation":0.0,"angularVelocity":1.4486831279590686,"angularAcceleration":-0.11441840552786658,"curveRadius":-2.383925364504373},{"acceleration":-0.19964255665393485,"curvature":-0.419315290918276,"pose":{"rotation":{"radians":2.3321886874142024},"translation":{"x":3.5893880960000004,"y":3.661379903999999}},"time":2.365244248986598,"velocity":-3.4528124806570366,"position":-1.4979557127005452,"holonomicRotation":0.0,"angularVelocity":1.4483230154264959,"angularAcceleration":-0.09770504751424339,"curveRadius":-2.384840290011982},{"acceleration":-0.15981405462086992,"curvature":-0.4191901310828717,"pose":{"rotation":{"radians":2.337525080182999},"translation":{"x":3.598217728000001,"y":3.6522142719999993}},"time":2.3689295405156674,"velocity":-3.453401442038757,"position":-1.5106825037813658,"holonomicRotation":0.0,"angularVelocity":1.448024593632274,"angularAcceleration":-0.08097644158351835,"curveRadius":-2.385552344509526},{"acceleration":-0.119918540886243,"curvature":-0.4191007350133541,"pose":{"rotation":{"radians":2.342860145493564},"translation":{"x":3.607096512000001,"y":3.6430954879999993}},"time":2.3726145176849927,"velocity":-3.4538433391241017,"position":-1.5234098376324638,"holonomicRotation":0.0,"angularVelocity":1.4477878872562056,"angularAcceleration":-0.06423550681367704,"curveRadius":-2.3860611935413005},{"acceleration":-0.07997297966939967,"curvature":-0.4190470988943057,"pose":{"rotation":{"radians":2.348194262635916},"translation":{"x":3.616024064000001,"y":3.6340239359999993}},"time":2.3762992852662785,"velocity":-3.4541380209669663,"position":-1.5361375334334095,"holonomicRotation":0.0,"angularVelocity":1.4476129157896325,"angularAcceleration":-0.04748507543914794,"curveRadius":-2.386366598500722},{"acceleration":-0.039994446991610394,"curvature":-0.41902922045158014,"pose":{"rotation":{"radians":2.353527810883649},"translation":{"x":3.625000000000001,"y":3.624999999999999}},"time":2.3799839480490936,"velocity":-3.4542853870173156,"position":-1.5488654102401747,"holonomicRotation":0.0,"angularVelocity":1.447499693216916,"angularAcceleration":-0.03072806913147243,"curveRadius":-2.386468416026735},{"acceleration":1.1811323079083375e-11,"curvature":-0.4190470988943055,"pose":{"rotation":{"radians":2.358861169501017},"translation":{"x":3.634023936000001,"y":3.616024063999999}},"time":2.3836686108319087,"velocity":-3.454285387017272,"position":-1.56159328704694,"holonomicRotation":0.0,"angularVelocity":1.447448228435447,"angularAcceleration":-0.013967297552686296,"curveRadius":-2.386366598500723},{"acceleration":0.03999330948584792,"curvature":-0.41910073501335415,"pose":{"rotation":{"radians":2.3641947177487985},"translation":{"x":3.643095488000001,"y":3.607096511999999}},"time":2.3873533784131946,"velocity":-3.4541380209670103,"position":-1.5743209828478855,"holonomicRotation":0.0,"angularVelocity":1.4474585248930965,"angularAcceleration":0.0027943302860342183,"curveRadius":-2.3860611935413},{"acceleration":0.07996844008499467,"curvature":-0.4191901310989462,"pose":{"rotation":{"radians":2.369528834891101},"translation":{"x":3.652214272000001,"y":3.598217727999999}},"time":2.391038355582555,"velocity":-3.4538433390910277,"position":-1.587048316698984,"holonomicRotation":0.0,"angularVelocity":1.4475305808280177,"angularAcceleration":0.019553970515837665,"curveRadius":-2.385552344418048},{"acceleration":0.11990830272662478,"curvature":-0.4193152909022269,"pose":{"rotation":{"radians":2.374863900201767},"translation":{"x":3.661379904000001,"y":3.5893880959999995}},"time":2.3947236471116238,"velocity":-3.4534014420387242,"position":-1.5997751077798037,"holonomicRotation":0.0,"angularVelocity":1.4476643892576184,"angularAcceleration":0.03630877735052964,"curveRadius":-2.3848402901032606},{"acceleration":0.15979589100709177,"curvature":-0.4194762197533931,"pose":{"rotation":{"radians":2.3802002929704376},"translation":{"x":3.670592000000001,"y":3.580607999999999}},"time":2.3984093577451886,"velocity":-3.4528124806240394,"position":-1.6125011754553447,"holonomicRotation":0.0,"angularVelocity":1.4478599378024166,"angularAcceleration":0.05305585930088811,"curveRadius":-2.383925364321945},{"acceleration":0.19961419646350817,"curvature":-0.4196729243382305,"pose":{"rotation":{"radians":2.3855383925092557},"translation":{"x":3.679850176000001,"y":3.5718778239999995}},"time":2.402095592192161,"velocity":-3.452076655896931,"position":-1.6252263393379018,"holonomicRotation":0.0,"angularVelocity":1.4481172089317869,"angularAcceleration":0.06979239467026602,"curveRadius":-2.3828079964340554},{"acceleration":0.2393462668116446,"curvature":-0.4199054128880666,"pose":{"rotation":{"radians":2.3908785781581567},"translation":{"x":3.689154048000001,"y":3.563197951999999}},"time":2.405782455116587,"velocity":-3.4511942190197233,"position":-1.6379504193489982,"holonomicRotation":0.0,"angularVelocity":1.4484361795828835,"angularAcceleration":0.08651546250429971,"curveRadius":-2.38148870985516},{"acceleration":0.2789752290985816,"curvature":-0.42017369496416906,"pose":{"rotation":{"radians":2.3962212292913607},"translation":{"x":3.698503232000001,"y":3.5545687679999993}},"time":2.409470051128727,"velocity":-3.4501654710774137,"position":-1.6506732357813652,"holonomicRotation":0.0,"angularVelocity":1.4488168214782389,"angularAcceleration":0.1032222331573957,"curveRadius":-2.3799681226719263},{"acceleration":0.31848421325495613,"curvature":-0.42047778147868153,"pose":{"rotation":{"radians":2.40156672532203},"translation":{"x":3.707897344000001,"y":3.545990655999999}},"time":2.4131584847758756,"velocity":-3.4489907631891583,"position":-1.6633946093610181,"holonomicRotation":0.0,"angularVelocity":1.449259100757035,"angularAcceleration":0.11990978315090647,"curveRadius":-2.3782469468025877},{"acceleration":0.3578564293280104,"curvature":-0.4208176845831703,"pose":{"rotation":{"radians":2.4069154457079467},"translation":{"x":3.717336000000001,"y":3.5374639999999995}},"time":2.4168478605331716,"velocity":-3.447670496354203,"position":-1.6761143613094116,"holonomicRotation":0.0,"angularVelocity":1.4497629782869148,"angularAcceleration":0.13657528075944955,"curveRadius":-2.3763259877980727},{"acceleration":0.39707522491434266,"curvature":-0.4211934177613582,"pose":{"rotation":{"radians":2.4122677699553403},"translation":{"x":3.726818816000001,"y":3.528989183999999}},"time":2.420538282794578,"velocity":-3.446205121104726,"position":-1.6888323134057095,"holonomicRotation":0.0,"angularVelocity":1.4503284091272983,"angularAcceleration":0.1532157569871215,"curveRadius":-2.374206143379441},{"acceleration":0.4361240101811125,"curvature":-0.42160499554888453,"pose":{"rotation":{"radians":2.4176240776237092},"translation":{"x":3.736345408000001,"y":3.5205665919999993}},"time":2.4242298558636994,"velocity":-3.4445951374539443,"position":-1.7015482880491617,"holonomicRotation":0.0,"angularVelocity":1.450955342905738,"angularAcceleration":0.1698283541192034,"curveRadius":-2.3718884039742156},{"acceleration":0.4749862710639791,"curvature":-0.42205243361764627,"pose":{"rotation":{"radians":2.4229847483285685},"translation":{"x":3.745915392000001,"y":3.512196607999999}},"time":2.427922683944442,"velocity":-3.442841094814192,"position":-1.7142621083216256,"holonomicRotation":0.0,"angularVelocity":1.4516437233605162,"angularAcceleration":0.18641010080267476,"curveRadius":-2.36937385108396},{"acceleration":0.5136456191069221,"curvature":-0.4225357485516243,"pose":{"rotation":{"radians":2.428350161744861},"translation":{"x":3.755528384000001,"y":3.5038796159999994}},"time":2.4316168711316637,"velocity":-3.4409435917493147,"position":-1.7269735980502186,"holonomicRotation":0.0,"angularVelocity":1.4523934885735406,"angularAcceleration":0.20295810012493387,"curveRadius":-2.3666636572830066},{"acceleration":0.5520857955857992,"curvature":-0.4230549579065874,"pose":{"rotation":{"radians":2.4337206976086065},"translation":{"x":3.765184000000001,"y":3.495615999999999}},"time":2.4353125214017983,"velocity":-3.4389032757297207,"position":-1.7396825818701356,"holonomicRotation":0.0,"angularVelocity":1.453204570558563,"angularAcceleration":0.21946935606353266,"curveRadius":-2.3637590845130925},{"acceleration":0.5902906852352634,"curvature":-0.42361007997767014,"pose":{"rotation":{"radians":2.439096735718832},"translation":{"x":3.7748818560000013,"y":3.4874061439999995}},"time":2.439009738603456,"velocity":-3.4367208428542906,"position":-1.7523888852876317,"holonomicRotation":0.0,"angularVelocity":1.4540768954052667,"angularAcceleration":0.23594092505916195,"curveRadius":-2.360661483911604},{"acceleration":0.6282442679845273,"curvature":-0.42420113373878104,"pose":{"rotation":{"radians":2.4444786559374396},"translation":{"x":3.7846215680000013,"y":3.4792504319999993}},"time":2.4427086264477724,"velocity":-3.434397037768181,"position":-1.7650923347431886,"holonomicRotation":0.0,"angularVelocity":1.455010382885106,"angularAcceleration":0.25236977143646266,"curveRadius":-2.3573722945676763},{"acceleration":0.6659307289933916,"curvature":-0.42482813877769865,"pose":{"rotation":{"radians":2.449866838189612},"translation":{"x":3.794402752000001,"y":3.4711492479999992}},"time":2.4464092884988995,"velocity":-3.431932653190716,"position":-1.7777927576748753,"holonomicRotation":0.0,"angularVelocity":1.456004946609863,"angularAcceleration":0.26875291799588485,"curveRadius":-2.3538930422009394},{"acceleration":0.7033343412327394,"curvature":-0.4254911149876656,"pose":{"rotation":{"radians":2.455261662461968},"translation":{"x":3.8042250240000013,"y":3.463102975999999}},"time":2.45011182816413,"velocity":-3.429328529894383,"position":-1.7904899825819158,"holonomicRotation":0.0,"angularVelocity":1.4570604936436824,"angularAcceleration":0.2850872993290871,"curveRadius":-2.3502253390860783},{"acceleration":0.7404395831670516,"curvature":-0.42619008268569475,"pose":{"rotation":{"radians":2.4606635088005238},"translation":{"x":3.8140880000000013,"y":3.4551119999999993}},"time":2.453816348684084,"velocity":-3.4265855562647545,"position":-1.8031838390884765,"holonomicRotation":0.0,"angularVelocity":1.4581769245059573,"angularAcceleration":0.30136986858659376,"curveRadius":-2.346370881505182},{"acceleration":0.7772311349025238,"curvature":-0.4269250622640667,"pose":{"rotation":{"radians":2.46607275730722},"translation":{"x":3.8239912960000013,"y":3.447176703999999}},"time":2.4575229531229033,"velocity":-3.423704667890136,"position":-1.8158741580076856,"holonomicRotation":0.0,"angularVelocity":1.4593541328674604,"angularAcceleration":0.3175975157138759,"curveRadius":-2.342331449685351},{"acceleration":0.8136937956917609,"curvature":-0.4276960741248228,"pose":{"rotation":{"radians":2.471489788135531},"translation":{"x":3.8339345280000012,"y":3.4392974719999994}},"time":2.461231744358086,"velocity":-3.420686847472552,"position":-1.8285607714058956,"holonomicRotation":0.0,"angularVelocity":1.4605920055364296,"angularAcceleration":0.33376714688778025,"curveRadius":-2.3381089060643347},{"acceleration":0.8498126016207829,"curvature":-0.4285031385144863,"pose":{"rotation":{"radians":2.476914981484361},"translation":{"x":3.843917312000001,"y":3.431474687999999}},"time":2.464942825070388,"velocity":-3.4175331243176057,"position":-1.8412435126672049,"holonomicRotation":0.0,"angularVelocity":1.4618904220663935,"angularAcceleration":0.3498755835893298,"curveRadius":-2.3337051940080324},{"acceleration":0.8855727438587065,"curvature":-0.42934627527527985,"pose":{"rotation":{"radians":2.4823487175915364},"translation":{"x":3.853939264000001,"y":3.423708735999999}},"time":2.4686562977334363,"velocity":-3.414244574142146,"position":-1.853922216558242,"holonomicRotation":0.0,"angularVelocity":1.4632492548672993,"angularAcceleration":0.36591969948430925,"curveRadius":-2.329122336880271},{"acceleration":0.9209596506971679,"curvature":-0.43022550379883,"pose":{"rotation":{"radians":2.4877913767247897},"translation":{"x":3.864000000000001,"y":3.415999999999999}},"time":2.4723722646033344,"velocity":-3.4108223185916424,"position":-1.8665967192932371,"holonomicRotation":0.0,"angularVelocity":1.4646683686398778,"angularAcceleration":0.38189623919265525,"curveRadius":-2.324362435908941},{"acceleration":0.9559589829239638,"curvature":-0.43114084273749304,"pose":{"rotation":{"radians":2.4932433391723787},"translation":{"x":3.874099136000001,"y":3.4083488639999993}},"time":2.4760908277082163,"velocity":-3.4072675247879607,"position":-1.8792668585993768,"holonomicRotation":0.0,"angularVelocity":1.4661476204158206,"angularAcceleration":0.3978019827068777,"curveRadius":-2.3194276692752718},{"acceleration":0.9905565709652241,"curvature":-0.43209230980706964,"pose":{"rotation":{"radians":2.4987049852314884},"translation":{"x":3.884236288000001,"y":3.400755711999999}},"time":2.479812088837457,"velocity":-3.4035814051241142,"position":-1.8919324737824703,"holonomicRotation":0.0,"angularVelocity":1.4676868592193317,"angularAcceleration":0.4136336446309468,"curveRadius":-2.3143202906029563},{"acceleration":1.0247384958809378,"curvature":-0.4330799216172504,"pose":{"rotation":{"radians":2.5041766951954854},"translation":{"x":3.8944110720000014,"y":3.393220927999999}},"time":2.483536149530824,"velocity":-3.3997652167706236,"position":-1.9045934057929235,"holonomicRotation":0.0,"angularVelocity":1.469285925909351,"angularAcceleration":0.4293879240118595,"curveRadius":-2.3090426272030804},{"acceleration":1.058491101651367,"curvature":-0.4341036934661007,"pose":{"rotation":{"radians":2.509658849339173},"translation":{"x":3.9046231040000015,"y":3.385744895999999}},"time":2.487263111067605,"velocity":-3.3958202611477444,"position":-1.9172494972920415,"holonomicRotation":0.0,"angularVelocity":1.4709446527916916,"angularAcceleration":0.44506144374473716,"curveRadius":-2.3035970784203665},{"acceleration":1.0918009002354117,"curvature":-0.43516363895714666,"pose":{"rotation":{"radians":2.515151827902585},"translation":{"x":3.9148720000000012,"y":3.3783279999999993}},"time":2.49099307445527,"velocity":-3.3917478837632467,"position":-1.9299005927186685,"holonomicRotation":0.0,"angularVelocity":1.4726628635490813,"angularAcceleration":0.4606508372365788,"curveRadius":-2.2979861148244427},{"acceleration":1.7019348505511374,"curvature":-0.4362597700073408,"pose":{"rotation":{"radians":2.5206560110728145},"translation":{"x":3.9251573760000014,"y":3.370970623999999}},"time":2.494728521229673,"velocity":-3.3853903967155112,"position":-1.9425465383561746,"holonomicRotation":0.0,"angularVelocity":1.4735006286119428,"angularAcceleration":0.2242743943247216,"curveRadius":-2.2922122752303595},{"acceleration":3.6441990002381255,"curvature":-0.437392096408939,"pose":{"rotation":{"radians":2.5261717789641427},"translation":{"x":3.9354788480000007,"y":3.3636731519999987}},"time":2.498477531553153,"velocity":-3.3717282570428035,"position":-1.9551871823997968,"holonomicRotation":0.0,"angularVelocity":1.4712597233417255,"angularAcceleration":-0.5977324885403977,"curveRadius":-2.286278165998344},{"acceleration":4.9871379711903385,"curvature":-0.4385606255617841,"pose":{"rotation":{"radians":2.531699511596127},"translation":{"x":3.945836032000001,"y":3.356435967999999}},"time":2.50224592957421,"velocity":-3.3529347361814317,"position":-1.9678223750243562,"holonomicRotation":0.0,"angularVelocity":1.4668653897747723,"angularAcceleration":-1.1661012298591047,"curveRadius":-2.280186459327094},{"acceleration":4.987016553596181,"curvature":-0.4397653623900097,"pose":{"rotation":{"radians":2.537239588869056},"translation":{"x":3.956228544000001,"y":3.349259455999999}},"time":2.506034000481527,"velocity":-3.3340435638604444,"position":-1.9804519684523443,"holonomicRotation":0.0,"angularVelocity":1.4625062224225365,"angularAcceleration":-1.1507618148898513,"curveRadius":-2.2739398905026573},{"acceleration":4.986891549237538,"curvature":-0.4410063087994853,"pose":{"rotation":{"radians":2.5427923905388248},"translation":{"x":3.9666560000000013,"y":3.342143999999999}},"time":2.509842038379775,"velocity":-3.3150532918464957,"position":-1.9930758170224072,"holonomicRotation":0.0,"angularVelocity":1.4581792036059924,"angularAcceleration":-1.13628564950337,"curveRadius":-2.267541257453247},{"acceleration":4.986762835727021,"curvature":-0.4422834635714009,"pose":{"rotation":{"radians":2.5483582961877094},"translation":{"x":3.977118016000001,"y":3.3350899839999992}},"time":2.5136703466561996,"velocity":-3.295962426409914,"position":-2.0056937772582177,"holonomicRotation":0.0,"angularVelocity":1.4538812569405688,"angularAcceleration":-1.1226751753224258,"curveRadius":-2.2609934179430677},{"acceleration":4.986630285645398,"curvature":-0.4435968219542736,"pose":{"rotation":{"radians":2.553937685194276},"translation":{"x":3.9876142080000014,"y":3.328097791999999}},"time":2.517519238365749,"velocity":-3.2767694264449054,"position":-2.0183057079377664,"holonomicRotation":0.0,"angularVelocity":1.449609245363708,"angularAcceleration":-1.1099329103652567,"curveRadius":-2.2542992882466617},{"acceleration":4.986493765855295,"curvature":-0.4449463754713487,"pose":{"rotation":{"radians":2.5595309367001207},"translation":{"x":3.9981441920000007,"y":3.321167807999999}},"time":2.5213890366358926,"velocity":-3.257472701495717,"position":-2.0309114701630544,"holonomicRotation":0.0,"angularVelocity":1.4453599685022571,"angularAcceleration":-1.0980615951573085,"curveRadius":-2.2474618406334064},{"acceleration":4.986353137733651,"curvature":-0.44633211131899053,"pose":{"rotation":{"radians":2.565138429574846},"translation":{"x":4.0087075840000015,"y":3.314300415999999}},"time":2.5252800750924083,"velocity":-3.2380706096790286,"position":-2.043510927430228,"holonomicRotation":0.0,"angularVelocity":1.4411301603395112,"angularAcceleration":-1.0870640858517093,"curveRadius":-2.2404841028462474},{"acceleration":4.986208256354179,"curvature":-0.4477540124322387,"pose":{"rotation":{"radians":2.570760542377265},"translation":{"x":4.019304000000001,"y":3.307495999999999}},"time":2.529192698307473,"velocity":-3.2185614555000694,"position":-2.0561039457001304,"holonomicRotation":0.0,"angularVelocity":1.4369164863030743,"angularAcceleration":-1.076943473681025,"curveRadius":-2.2333691541208376},{"acceleration":4.9860589704534055,"curvature":-0.44921205667481756,"pose":{"rotation":{"radians":2.5763976533159223},"translation":{"x":4.029933056000002,"y":3.300754943999999}},"time":2.5331272622715306,"velocity":-3.1989434875522575,"position":-2.06869039346931,"holonomicRotation":0.0,"angularVelocity":1.4327155410746353,"angularAcceleration":-1.06770286792003,"curveRadius":-2.226120125542167},{"acceleration":4.985905121868044,"curvature":-0.4507062168508919,"pose":{"rotation":{"radians":2.5820501402045597},"translation":{"x":4.040594368000001,"y":3.294077631999999}},"time":2.5370841348904922,"velocity":-3.1792148960947975,"position":-2.0812701418414625,"holonomicRotation":0.0,"angularVelocity":1.4285238452080298,"angularAcceleration":-1.0593456677171287,"curveRadius":-2.2187401961904425},{"acceleration":4.985746545290057,"curvature":-0.45223646007658325,"pose":{"rotation":{"radians":2.5877183804170585},"translation":{"x":4.051287552000002,"y":3.2874644479999993}},"time":2.541063696509983,"velocity":-3.159373810498653,"position":-2.093843064599347,"holonomicRotation":0.0,"angularVelocity":1.4243378428260849,"angularAcceleration":-1.051875252149171,"curveRadius":-2.211232592415606},{"acceleration":4.985583067588838,"curvature":-0.4538027475367534,"pose":{"rotation":{"radians":2.5934027508372814},"translation":{"x":4.062012224000001,"y":3.280915775999999}},"time":2.5450663404684493,"velocity":-3.1394182965537363,"position":-2.1064090382771465,"holonomicRotation":0.0,"angularVelocity":1.4201538980751425,"angularAcceleration":-1.0452952584235071,"curveRadius":-2.2036005851176785},{"acceleration":4.985414507540619,"curvature":-0.4554050339448751,"pose":{"rotation":{"radians":2.5991036278081605},"translation":{"x":4.072768000000002,"y":3.274431999999999}},"time":2.549092473681125,"velocity":-3.119346353625971,"position":-2.1189679422333194,"holonomicRotation":0.0,"angularVelocity":1.4159682925866544,"angularAcceleration":-1.0396092894567357,"curveRadius":-2.1958474884163137},{"acceleration":4.9852406753794085,"curvature":-0.45704326729385686,"pose":{"rotation":{"radians":2.6048213870753862},"translation":{"x":4.0835544960000005,"y":3.268013503999999}},"time":2.553142517256985,"velocity":-3.0991559116545355,"position":-2.131519658723904,"holonomicRotation":0.0,"angularVelocity":1.411777221683812,"angularAcceleration":-1.0348211875603273,"curveRadius":-2.187976656829403},{"acceleration":4.985061371885896,"curvature":-0.45871738815772506,"pose":{"rotation":{"radians":2.6105564037302766},"translation":{"x":4.094371328000001,"y":3.261660671999999}},"time":2.5572169071510205,"velocity":-3.078844827979775,"position":-2.144064072976329,"holonomicRotation":0.0,"angularVelocity":1.4075767916284572,"angularAcceleration":-1.0309347324622777,"curveRadius":-2.1799914845524904},{"acceleration":4.984876388265965,"curvature":-0.4604273295453317,"pose":{"rotation":{"radians":2.616309052146832},"translation":{"x":4.105218112000001,"y":3.2553738879999994}},"time":2.561316094854349,"velocity":-3.058410883986385,"position":-2.156601073263691,"holonomicRotation":0.0,"angularVelocity":1.403363015527401,"angularAcceleration":-1.0279539279538263,"curveRadius":-2.1718954020116312},{"acceleration":4.984685505226497,"curvature":-0.4621730162746951,"pose":{"rotation":{"radians":2.622079705917951},"translation":{"x":4.1160944640000015,"y":3.2491535359999992}},"time":2.565440548124891,"velocity":-3.037851781551729,"position":-2.1691305509795344,"holonomicRotation":0.0,"angularVelocity":1.3991318103503265,"angularAcceleration":-1.0258826805712058,"curveRadius":-2.1636918746585683},{"acceleration":4.984488492370801,"curvature":-0.4639543644847909,"pose":{"rotation":{"radians":2.627868737786227},"translation":{"x":4.127000000000001,"y":3.2429999999999994}},"time":2.569590751761594,"velocity":-3.017165139283587,"position":-2.181652400713123,"holonomicRotation":0.0,"angularVelocity":1.3948789927028542,"angularAcceleration":-1.0247250544194484,"curveRadius":-2.155384401029342},{"acceleration":4.984285107409487,"curvature":-0.4657712811612695,"pose":{"rotation":{"radians":2.633676519572262},"translation":{"x":4.137934336000002,"y":3.2369136639999994}},"time":2.5737672084254264,"velocity":-2.9963484885323064,"position":-2.1941665203252176,"holonomicRotation":0.0,"angularVelocity":1.3906002751877273,"angularAcceleration":-1.0244850741970022,"curveRadius":-2.1469765106744703},{"acceleration":4.9840750955398825,"curvature":-0.46762366370596037,"pose":{"rotation":{"radians":2.6395034220985725},"translation":{"x":4.148897088000001,"y":3.2308949119999992}},"time":2.577970439510664,"velocity":-2.975399269159576,"position":-2.2066728110243417,"holonomicRotation":0.0,"angularVelocity":1.3862912621615784,"angularAcceleration":-1.025166815425192,"curveRadius":-2.1384717618328133},{"acceleration":4.983858188281258,"curvature":-0.46951139935295344,"pose":{"rotation":{"radians":2.645349815110781},"translation":{"x":4.159887872000001,"y":3.224944127999999}},"time":2.5822009860703146,"velocity":-2.954314825047355,"position":-2.219171177443571,"holonomicRotation":0.0,"angularVelocity":1.381947445743538,"angularAcceleration":-1.0267742847862695,"curveRadius":-2.129873739760371},{"acceleration":4.983634102866615,"curvature":-0.4714343645997839,"pose":{"rotation":{"radians":2.651216067193581},"translation":{"x":4.170906304000001,"y":3.2190616959999994}},"time":2.586459409799863,"velocity":-2.933092399324321,"position":-2.231661527717812,"holonomicRotation":0.0,"angularVelocity":1.3775642010669942,"angularAcceleration":-1.0293115375365713,"curveRadius":-2.12118605492184},{"acceleration":4.9834025409584015,"curvature":-0.4733924247442271,"pose":{"rotation":{"radians":2.6571025456838964},"translation":{"x":4.181952000000002,"y":3.213247999999999}},"time":2.590746294083922,"velocity":-2.911729129290346,"position":-2.244143773561604,"holonomicRotation":0.0,"angularVelocity":1.373136781929067,"angularAcceleration":-1.032782516288274,"curveRadius":-2.112412340650144},{"acceleration":4.983163187785932,"curvature":-0.47538543332938343,"pose":{"rotation":{"radians":2.663009616579334},"translation":{"x":4.193024576000001,"y":3.207503423999999}},"time":2.595062245110797,"velocity":-2.8902220410129353,"position":-2.2566178303474107,"holonomicRotation":0.0,"angularVelocity":1.3686603158040365,"angularAcceleration":-1.0371911305656356,"curveRadius":-2.103556251180131},{"acceleration":4.982915710613441,"curvature":-0.4774132314234743,"pose":{"rotation":{"radians":2.668937644443049},"translation":{"x":4.204123648000001,"y":3.2018283519999993}},"time":2.5994078930604667,"velocity":-2.868568043571733,"position":-2.269083617184445,"holonomicRotation":0.0,"angularVelocity":1.3641297989097225,"angularAcceleration":-1.0425411691848423,"curveRadius":-2.0946214603612057},{"acceleration":4.982659757959761,"curvature":-0.4794756472470108,"pose":{"rotation":{"radians":2.6748869923033434},"translation":{"x":4.215248832000001,"y":3.1962231679999995}},"time":2.6037838933719915,"velocity":-2.8467639229186794,"position":-2.2815410569979746,"holonomicRotation":0.0,"angularVelocity":1.3595400906682304,"angularAcceleration":-1.0488363607755022,"curveRadius":-2.085611658781142},{"acceleration":4.982394957479981,"curvature":-0.48157249539387187,"pose":{"rotation":{"radians":2.680858021550229},"translation":{"x":4.226399744000002,"y":3.190688255999999}},"time":2.608190928096988,"velocity":-2.8248063353274167,"position":-2.293990076609153,"holonomicRotation":0.0,"angularVelocity":1.3548859084358569,"angularAcceleration":-1.056080226909728,"curveRadius":-2.0765305526473496},{"acceleration":4.9821209150847094,"curvature":-0.4837035763394283,"pose":{"rotation":{"radians":2.6868510918265454},"translation":{"x":4.237576000000001,"y":3.185223999999999}},"time":2.61262970734644,"velocity":-2.8026918003912766,"position":-2.30643060681534,"holonomicRotation":0.0,"angularVelocity":1.350161821418811,"angularAcceleration":-1.06427617855268,"curveRadius":-2.0673818613618686},{"acceleration":4.981837212779629,"curvature":-0.4858686756511655,"pose":{"rotation":{"radians":2.692866560915218},"translation":{"x":4.2487772160000015,"y":3.179830783999999}},"time":2.6171009708388855,"velocity":-2.7804166935364685,"position":-2.3188625824709357,"holonomicRotation":0.0,"angularVelocity":1.345362244662152,"angularAcceleration":-1.073427402515653,"curveRadius":-2.058169316348273},{"acceleration":4.98154340695933,"curvature":-0.48806756354488817,"pose":{"rotation":{"radians":2.698904784620842},"translation":{"x":4.260003008000001,"y":3.174508991999999}},"time":2.6216054895588226,"velocity":-2.757977238005642,"position":-2.331285942568692,"holonomicRotation":0.0,"angularVelocity":1.3404814323224015,"angularAcceleration":-1.0835369199706653,"curveRadius":-2.048896658357893},{"acceleration":4.981239026570776,"curvature":-0.49029999405552943,"pose":{"rotation":{"radians":2.7049661166484125},"translation":{"x":4.271252992000002,"y":3.169259007999999}},"time":2.626144067535141,"velocity":-2.735369496264871,"position":-2.3437006303215324,"holonomicRotation":0.0,"angularVelocity":1.3355134712233396,"angularAcceleration":-1.094607413375733,"curveRadius":-2.03956763639435},{"acceleration":4.980923570320437,"curvature":-0.49256570453850973,"pose":{"rotation":{"radians":2.7110509084748564},"translation":{"x":4.282526784000001,"y":3.164081215999999}},"time":2.6307175437503956,"velocity":-2.7125893607860077,"position":-2.356106593244841,"holonomicRotation":0.0,"angularVelocity":1.3304522730757777,"angularAcceleration":-1.1066414056511635,"curveRadius":-2.030186005209013},{"acceleration":4.980596504929129,"curvature":-0.4948644147448579,"pose":{"rotation":{"radians":2.7171595092181677},"translation":{"x":4.293824000000002,"y":3.158975999999999}},"time":2.635326794192954,"velocity":-2.6896325441414586,"position":-2.368503783239244,"holonomicRotation":0.0,"angularVelocity":1.3252915673466388,"angularAcceleration":-1.1196409901030557,"curveRadius":-2.0207555245522753},{"acceleration":4.980257261807673,"curvature":-0.49719582643303056,"pose":{"rotation":{"radians":2.7232922654991567},"translation":{"x":4.305144256000001,"y":3.1539437439999993}},"time":2.639972734065333,"velocity":-2.666494568354122,"position":-2.380892156673842,"holonomicRotation":0.0,"angularVelocity":1.3200248925840843,"angularAcceleration":-1.133608033514613,"curveRadius":-2.0112799561777783},{"acceleration":4.979905234441006,"curvature":-0.49955962237973184,"pose":{"rotation":{"radians":2.729449521300226},"translation":{"x":4.316487168000002,"y":3.148984831999999}},"time":2.6446563201635938,"velocity":-2.643170753427439,"position":-2.393271674469924,"holonomicRotation":0.0,"angularVelocity":1.3146455882076982,"angularAcceleration":-1.1485439284192756,"curveRadius":-2.0017630633083208},{"acceleration":4.979539774814845,"curvature":-0.5019554658535155,"pose":{"rotation":{"radians":2.7356316178174627},"translation":{"x":4.327852352000001,"y":3.144099647999999}},"time":2.649378553444307,"velocity":-2.619656204980173,"position":-2.4056423021851083,"holonomicRotation":0.0,"angularVelocity":1.309146784951496,"angularAcceleration":-1.1644497273484156,"curveRadius":-1.9922086081872206},{"acceleration":4.979160190172009,"curvature":-0.5043829997560954,"pose":{"rotation":{"radians":2.74183889330867},"translation":{"x":4.339239424000002,"y":3.1392885759999993}},"time":2.6541404817975796,"velocity":-2.595945800895107,"position":-2.4180040100979494,"holonomicRotation":0.0,"angularVelocity":1.303521395264528,"angularAcceleration":-1.1813259817531983,"curveRadius":-1.982620350970533},{"acceleration":4.978765738320049,"curvature":-0.5068418460483195,"pose":{"rotation":{"radians":2.7480716829347855},"translation":{"x":4.350648000000001,"y":3.1345519999999993}},"time":2.658943203046771,"velocity":-2.572034176888931,"position":-2.4303567732929405,"holonomicRotation":0.0,"angularVelocity":1.2977621025090094,"angularAcceleration":-1.1991728140558124,"curveRadius":-1.973002047476296},{"acceleration":4.978355623748659,"curvature":-0.5093316047891755,"pose":{"rotation":{"radians":2.754330318597825},"translation":{"x":4.362077696000002,"y":3.129890303999999}},"time":2.6637878681980847,"velocity":-2.5479157108877084,"position":-2.4427005717459633,"holonomicRotation":0.0,"angularVelocity":1.2918613500753644,"angularAcceleration":-1.2179897370295396,"curveRadius":-1.9633574484621346},{"acceleration":4.977928992314462,"curvature":-0.5118518535624833,"pose":{"rotation":{"radians":2.760615128771323},"translation":{"x":4.373528128000001,"y":3.125303871999999}},"time":2.6686756849660096,"velocity":-2.523584506089533,"position":-2.455035390410104,"holonomicRotation":0.0,"angularVelocity":1.285811328841175,"angularAcceleration":-1.2377757844547017,"curveRadius":-1.9536902973780617},{"acceleration":4.977484925572671,"curvature":-0.5144021466205787,"pose":{"rotation":{"radians":2.7669264383269256},"translation":{"x":4.384998912000002,"y":3.120793087999999}},"time":2.6736079216039057,"velocity":-2.499034372575049,"position":-2.4673612193018797,"holonomicRotation":0.0,"angularVelocity":1.2796039644795105,"angularAcceleration":-1.2585293077731494,"curveRadius":-1.9440043292385336},{"acceleration":4.977022434848794,"curvature":-0.5169820141541447,"pose":{"rotation":{"radians":2.773264568354321},"translation":{"x":4.3964896640000015,"y":3.1163583359999993}},"time":2.67858591107273,"velocity":-2.4742588073082676,"position":-2.479678053587807,"holonomicRotation":0.0,"angularVelocity":1.273230903176649,"angularAcceleration":-1.2802480484889696,"curveRadius":-1.934303269014379},{"acceleration":4.976540453923459,"curvature":-0.5195909614569449,"pose":{"rotation":{"radians":2.7796298359767464},"translation":{"x":4.408000000000002,"y":3.111999999999999}},"time":2.683611055585258,"velocity":-2.4492509723548617,"position":-2.4919858936713393,"holonomicRotation":0.0,"angularVelocity":1.2666834966748826,"angularAcceleration":-1.302928997453455,"curveRadius":-1.9245908304408859},{"acceleration":4.976037831352261,"curvature":-0.5222284682600655,"pose":{"rotation":{"radians":2.7860225541595955},"translation":{"x":4.4195295360000015,"y":3.1077184639999995}},"time":2.688684831568075,"velocity":-2.424003671116558,"position":-2.5042847452801107,"holonomicRotation":0.0,"angularVelocity":1.2599527855583132,"angularAcceleration":-1.326568445150858,"curveRadius":-1.9148707142139332},{"acceleration":4.975513321717014,"curvature":-0.5248939878051837,"pose":{"rotation":{"radians":2.7924430315143596},"translation":{"x":4.431077888000002,"y":3.103514111999999}},"time":2.693808795089435,"velocity":-2.398509322356041,"position":-2.516574619553504,"holonomicRotation":0.0,"angularVelocity":1.2530294815721956,"angularAcceleration":-1.3511618412694353,"curveRadius":-1.9051466071871899},{"acceleration":4.974965575458407,"curvature":-0.527586946160825,"pose":{"rotation":{"radians":2.798891572096551},"translation":{"x":4.442644672000001,"y":3.0993873279999993}},"time":2.698984587807701,"velocity":-2.372759931756958,"position":-2.5288555331304856,"holonomicRotation":0.0,"angularVelocity":1.2459039480915062,"angularAcceleration":-1.3767037956412311,"curveRadius":-1.8954221806980962},{"acceleration":4.974393127904494,"curvature":-0.5303067413665304,"pose":{"rotation":{"radians":2.8053684751977617},"translation":{"x":4.454229504000002,"y":3.095338495999999}},"time":2.7042139435029195,"velocity":-2.346747060723296,"position":-2.541127508237716,"holonomicRotation":0.0,"angularVelocity":1.238566178837917,"angularAcceleration":-1.4031880180380152,"curveRadius":-1.8857010895677697},{"acceleration":4.973794386442077,"curvature":-0.533052742734141,"pose":{"rotation":{"radians":2.8118740351322016},"translation":{"x":4.465832000000002,"y":3.0913679999999997}},"time":2.7094986952631013,"velocity":-2.320461792084763,"position":-2.5533905727778707,"holonomicRotation":0.0,"angularVelocity":1.2310057746621437,"angularAcceleration":-1.430607248714556,"curveRadius":-1.8759869705777836},{"acceleration":4.9731676159809,"curvature":-0.5358242899805569,"pose":{"rotation":{"radians":2.818408541017755},"translation":{"x":4.477451776000002,"y":3.0874762239999995}},"time":2.714840783407486,"velocity":-2.2938946923233927,"position":-2.565644760418199,"holonomicRotation":0.0,"angularVelocity":1.223211918062747,"angularAcceleration":-1.458953201210076,"curveRadius":-1.8662834416041245},{"acceleration":4.972510922732632,"curvature":-0.53862069246313,"pose":{"rotation":{"radians":2.8249722765508114},"translation":{"x":4.489088448000001,"y":3.0836635519999995}},"time":2.720242264241503,"velocity":-2.267035769877312,"position":-2.5778901106792222,"holonomicRotation":0.0,"angularVelocity":1.2151733450056812,"angularAcceleration":-1.4882165287787517,"curveRadius":-1.8565941004363706},{"acceleration":4.971822235140322,"curvature":-0.5414412283907459,"pose":{"rotation":{"radians":2.831565519776004},"translation":{"x":4.500741632000002,"y":3.0799303679999994}},"time":2.7257053197529597,"velocity":-2.2398744290136476,"position":-2.5901266690236153,"holonomicRotation":0.0,"angularVelocity":1.2068783140435095,"angularAcceleration":-1.5183867242016007,"curveRadius":-1.8469225237467926},{"acceleration":4.971099282637377,"curvature":-0.5442851441519826,"pose":{"rotation":{"radians":2.8381885428495615},"translation":{"x":4.512410944000001,"y":3.0762770559999995}},"time":2.7312322683763997,"velocity":-2.2123994186764917,"position":-2.6023544869451687,"holonomicRotation":0.0,"angularVelocity":1.1983145718903792,"angularAcceleration":-1.549452100352682,"curveRadius":-1.8372722657312996},{"acceleration":4.970339570767143,"curvature":-0.5471516533835759,"pose":{"rotation":{"radians":2.844841611798131},"translation":{"x":4.524096000000002,"y":3.0727039999999994}},"time":2.7368255769733967,"velocity":-2.1845987756253242,"position":-2.6145736220578635,"holonomicRotation":0.0,"angularVelocity":1.1894693155570248,"angularAcceleration":-1.5813996635377605,"curveRadius":-1.8276468577148919},{"acceleration":4.969540352570371,"curvature":-0.5500399363964437,"pose":{"rotation":{"radians":2.851524986270702},"translation":{"x":4.535796416000001,"y":3.0692115839999996}},"time":2.7424878742012737,"velocity":-2.156459761063141,"position":-2.62678413818496,"holonomicRotation":0.0,"angularVelocity":1.1803291497427244,"angularAcceleration":-1.6142151226715107,"curveRadius":-1.8180498066221245},{"acceleration":4.968698595823463,"curvature":-0.5529491392614659,"pose":{"rotation":{"radians":2.858238919286448},"translation":{"x":4.547511808000002,"y":3.0658001919999998}},"time":2.7482219654725206,"velocity":-2.127968789815375,"position":-2.6389861054481254,"holonomicRotation":0.0,"angularVelocity":1.1708800397742016,"angularAcceleration":-1.6478827283244033,"curveRadius":-1.8084845946873658},{"acceleration":4.967810944565119,"curvature":-0.5558783732812413,"pose":{"rotation":{"radians":2.86498365697578},"translation":{"x":4.559241792000002,"y":3.0624702079999992}},"time":2.7540308497428994,"velocity":-2.0991113509612753,"position":-2.651179600356498,"holonomicRotation":0.0,"angularVelocity":1.161107258363816,"angularAcceleration":-1.6823852835595305,"curveRadius":-1.798954677976039},{"acceleration":4.9668736743972195,"curvature":-0.5588267141256481,"pose":{"rotation":{"radians":2.8717594383176124},"translation":{"x":4.570985984000002,"y":3.0592220159999997}},"time":2.7599177384095874,"velocity":-2.069871918618595,"position":-2.6633647058957095,"holonomicRotation":0.0,"angularVelocity":1.1509953263044015,"angularAcceleration":-1.717703974365024,"curveRadius":-1.7894634861266803},{"acceleration":4.965882640323129,"curvature":-0.5617932012303778,"pose":{"rotation":{"radians":2.87856649486947},"translation":{"x":4.582744000000002,"y":3.0560559999999994}},"time":2.765886076653289,"velocity":-2.04023385134262,"position":-2.6755415116167724,"holonomicRotation":0.0,"angularVelocity":1.140527944950347,"angularAcceleration":-1.753818387404678,"curveRadius":-1.78001442133851},{"acceleration":4.964833215210492,"curvature":-0.5647768371119463,"pose":{"rotation":{"radians":2.885405050494711},"translation":{"x":4.594515456000002,"y":3.0529725439999993}},"time":2.771939567622648,"velocity":-2.0101792783099675,"position":-2.6877101137248154,"holonomicRotation":0.0,"angularVelocity":1.1296879205495274,"angularAcceleration":-1.7907062975211703,"curveRadius":-1.7706108577568784},{"acceleration":4.963720217251391,"curvature":-0.5677765867261405,"pose":{"rotation":{"radians":2.892275321082959},"translation":{"x":4.606299968000002,"y":3.0499720319999994}},"time":2.7780821999383702,"velocity":-1.979688970097276,"position":-2.6998706151676135,"holonomicRotation":0.0,"angularVelocity":1.1184570775404337,"angularAcceleration":-1.8283436858736148,"curveRadius":-1.7612561408460061},{"acceleration":4.962537823897193,"curvature":-0.5707913768706009,"pose":{"rotation":{"radians":2.899177514266695},"translation":{"x":4.6180971520000025,"y":3.0470548479999997}},"time":2.7843182790922647,"velocity":-1.94874219142326,"position":-2.712023125723862,"holonomicRotation":0.0,"angularVelocity":1.106816160187111,"angularAcceleration":-1.8667045536222482,"curveRadius":-1.7519535867597755},{"acceleration":4.961279469239047,"curvature":-0.5738200956456002,"pose":{"rotation":{"radians":2.9061118291329553},"translation":{"x":4.629906624000001,"y":3.0442213759999994}},"time":2.7906524634381045,"velocity":-1.9173165326738688,"position":-2.724167762091145,"holonomicRotation":0.0,"angularVelocity":1.0947447197072098,"angularAcceleration":-1.9057608400407782,"curveRadius":-1.742706481680305},{"acceleration":4.9599377209221185,"curvature":-0.576861591813262,"pose":{"rotation":{"radians":2.9130784559310063},"translation":{"x":4.641728000000002,"y":3.0414719999999993}},"time":2.7970898056235836,"velocity":-1.8853877163456279,"position":-2.7363046479735607,"holonomicRotation":0.0,"angularVelocity":1.0822209845805433,"angularAcceleration":-1.9454822760419146,"curveRadius":-1.7335180816193316},{"acceleration":4.958504132032011,"curvature":-0.5799146744073892,"pose":{"rotation":{"radians":2.9200775757746467},"translation":{"x":4.653560896000002,"y":3.0388071039999995}},"time":2.8036358005047948,"velocity":-1.8529293736788806,"position":-2.748433914168909,"holonomicRotation":0.0,"angularVelocity":1.0692217104736,"angularAcceleration":-1.9858362774242857,"curveRadius":-1.7243916116140587},{"acceleration":4.956969061035293,"curvature":-0.5829781121894888,"pose":{"rotation":{"radians":2.9271093603419622},"translation":{"x":4.665404928000002,"y":3.0362270719999995}},"time":2.810296440828888,"velocity":-1.8199127856656676,"position":-2.760555698655446,"holonomicRotation":0.0,"angularVelocity":1.0557220064683706,"angularAcceleration":-2.026787718351648,"curveRadius":-1.7153302655640084},{"acceleration":4.95532145249921,"curvature":-0.5860506332508155,"pose":{"rotation":{"radians":2.934173971570372},"translation":{"x":4.6772597120000015,"y":3.0337322879999995}},"time":2.8170782822832097,"velocity":-1.78630658121962,"position":-2.7726701466780885,"holonomicRotation":0.0,"angularVelocity":1.0416951319185117,"angularAcceleration":-2.068298801193699,"curveRadius":-1.7063372058025303},{"acceleration":4.9535485671640425,"curvature":-0.5891309246386679,"pose":{"rotation":{"radians":2.941271561348426},"translation":{"x":4.689124864000002,"y":3.0313231359999993}},"time":2.823988519913212,"velocity":-1.7520763835087578,"position":-2.7847774108340495,"holonomicRotation":0.0,"angularVelocity":1.0271122583741386,"angularAcceleration":-2.1103288085286587,"curveRadius":-1.6974155627856926},{"acceleration":4.951635648030996,"curvature":-0.5922176320623127,"pose":{"rotation":{"radians":2.9484022712044844},"translation":{"x":4.701000000000001,"y":3.0289999999999995}},"time":2.831035078437873,"velocity":-1.7171843931221094,"position":-2.796877651157819,"holonomicRotation":0.0,"angularVelocity":1.0119421886730777,"angularAcceleration":-2.152833847610807,"curveRadius":-1.6885684347452539},{"acceleration":4.949565503575213,"curvature":-0.5953093595736683,"pose":{"rotation":{"radians":2.955566231992309},"translation":{"x":4.712884736000002,"y":3.0267632639999995}},"time":2.838226719684421,"velocity":-1.6815888936941066,"position":-2.8089710352054467,"holonomicRotation":0.0,"angularVelocity":0.9961510234208841,"angularAcceleration":-2.1957665449139743,"curveRadius":-1.6797988876172745},{"acceleration":4.9473179830773395,"curvature":-0.5984046693700557,"pose":{"rotation":{"radians":2.962763563574333},"translation":{"x":4.724778688000002,"y":3.0246133119999996}},"time":2.8455731712860186,"velocity":-1.6452436615737158,"position":-2.821057738138033,"holonomicRotation":0.0,"angularVelocity":0.9797017624751843,"angularAcceleration":-2.239075656895758,"curveRadius":-1.6711099548282373},{"acceleration":4.94486931017707,"curvature":-0.6015020816536214,"pose":{"rotation":{"radians":2.9699943745025603},"translation":{"x":4.736681472000003,"y":3.0225505279999996}},"time":2.8530852820264663,"velocity":-1.6080972557186257,"position":-2.833137942804401,"holonomicRotation":0.0,"angularVelocity":0.9625538251579129,"angularAcceleration":-2.282705608284204,"curveRadius":-1.6625046371424796},{"acceleration":4.942191227827669,"curvature":-0.60460007456127,"pose":{"rotation":{"radians":2.9772587616975015},"translation":{"x":4.748592704000002,"y":3.0205752959999996}},"time":2.8607752109055697,"velocity":-1.5700921566696997,"position":-2.84521183982283,"holonomicRotation":0.0,"angularVelocity":0.9446624681641603,"angularAcceleration":-2.3265958990036046,"curveRadius":-1.653985902541698},{"acceleration":4.93924988892279,"curvature":-0.6076970841012796,"pose":{"rotation":{"radians":2.984556810125987},"translation":{"x":4.760512000000002,"y":3.0186879999999996}},"time":2.8686566593315868,"velocity":-1.5311637134069456,"position":-2.857279627661835,"holonomicRotation":0.0,"angularVelocity":0.9259780733189492,"angularAcceleration":-2.370680341386695,"curveRadius":-1.6455566863199538},{"acceleration":4.936004400329307,"curvature":-0.6107915042418585,"pose":{"rotation":{"radians":2.9918885924775687},"translation":{"x":4.772438976000002,"y":3.0168890239999997}},"time":2.876745159115239,"velocity":-1.491238842882776,"position":-2.869341512719866,"holonomicRotation":0.0,"angularVelocity":0.9064452676873354,"angularAcceleration":-2.4148860918673867,"curveRadius":-1.6372198910023223},{"acceleration":4.932404886166336,"curvature":-0.6138816870079442,"pose":{"rotation":{"radians":2.999254168840606},"translation":{"x":4.784373248000002,"y":3.0151787519999997}},"time":2.8850584335927474,"velocity":-1.4502344072298723,"position":-2.8813977094038945,"holonomicRotation":0.0,"angularVelocity":0.8860018255099187,"angularAcceleration":-2.4591323470344637,"curveRadius":-1.628978386493323},{"acceleration":4.928389875023061,"curvature":-0.6169659427695113,"pose":{"rotation":{"radians":3.0066535863780723},"translation":{"x":4.796314432000002,"y":3.0135575679999995}},"time":2.8936168559480415,"velocity":-1.4080551651478685,"position":-2.8934484402067837,"holonomicRotation":0.0,"angularVelocity":0.864577281920298,"angularAcceleration":-2.5033286159764163,"curveRadius":-1.6208350099700464},{"acceleration":4.923882717948124,"curvature":-0.6200425403987194,"pose":{"rotation":{"radians":3.0140868790039477},"translation":{"x":4.808262144000002,"y":3.0120258559999997}},"time":2.9024440387691524,"velocity":-1.3645911522068312,"position":-2.905493935783384,"holonomicRotation":0.0,"angularVelocity":0.8420911605113579,"angularAcceleration":-2.5473723457004205,"curveRadius":-1.6127925663889906},{"acceleration":4.918786589982433,"curvature":-0.623109707774154,"pose":{"rotation":{"radians":3.0215540670598875},"translation":{"x":4.820216000000001,"y":3.0105839999999997}},"time":2.9115676039254064,"velocity":-1.3197142822634191,"position":-2.917534435025253,"holonomicRotation":0.0,"angularVelocity":0.8184506744955293,"angularAcceleration":-2.591145633417667,"curveRadius":-1.6048538283445424},{"acceleration":4.912977374927289,"curvature":-0.6261656322069277,"pose":{"rotation":{"radians":3.0290551569942794},"translation":{"x":4.8321756160000024,"y":3.0092323839999997}},"time":2.9210202051506062,"velocity":-1.2732738663098033,"position":-2.9295701851339477,"holonomicRotation":0.0,"angularVelocity":0.7935476971560798,"angularAcceleration":-2.634510516857609,"curveRadius":-1.5970215364191882},{"acceleration":4.906293306643146,"curvature":-0.6292084609699685,"pose":{"rotation":{"radians":3.036590141042181},"translation":{"x":4.844140608000002,"y":3.007971392}},"time":2.9308409127915964,"velocity":-1.2250905941443129,"position":-2.9416014416927663,"holonomicRotation":0.0,"angularVelocity":0.7672546952168144,"angularAcceleration":-2.6773021762221694,"curveRadius":-1.5892983995454075},{"acceleration":4.898519497499279,"curvature":-0.6322363020068372,"pose":{"rotation":{"radians":3.0441589969085907},"translation":{"x":4.856110592000002,"y":3.006801408}},"time":2.9410771310621024,"velocity":-1.1749482793655797,"position":-2.953628468736908,"holonomicRotation":0.0,"angularVelocity":0.7394191552380246,"angularAcceleration":-2.7193187213477814,"curveRadius":-1.5816870951981268},{"acceleration":4.8893641404678805,"curvature":-0.6352472246674356,"pose":{"rotation":{"radians":3.051761687454542},"translation":{"x":4.868085184000002,"y":3.0057228159999996}},"time":2.9517873217956376,"velocity":-1.1225822568554624,"position":-2.9656515388219122,"holonomicRotation":0.0,"angularVelocity":0.7098557565502948,"angularAcceleration":-2.7603055280017648,"curveRadius":-1.5741902698174237},{"acceleration":4.878420629606754,"curvature":-0.6382392605344301,"pose":{"rotation":{"radians":3.05939816038698},"translation":{"x":4.880064000000003,"y":3.004736}},"time":2.963044992747758,"velocity":-1.0676626026413147,"position":-2.9776709330903324,"holonomicRotation":0.0,"angularVelocity":0.6783350628132968,"angularAcceleration":-2.79993027608092,"curveRadius":-1.566810539299399},{"acceleration":4.865104786542381,"curvature":-0.6412104045156426,"pose":{"rotation":{"radians":3.067068347952807},"translation":{"x":4.8920466560000015,"y":3.003841344}},"time":2.9749447519214023,"velocity":-1.0097690273269142,"position":-2.989686941336528,"holonomicRotation":0.0,"angularVelocity":0.6445666213829495,"angularAcceleration":-2.8377415826310814,"curveRadius":-1.5595504891337186},{"acceleration":4.84854568657608,"curvature":-0.6441586157880042,"pose":{"rotation":{"radians":3.0747721666386845},"translation":{"x":4.904032768000002,"y":3.003039232}},"time":2.987611909347445,"velocity":-0.948351735827695,"position":-3.0016998620695183,"holonomicRotation":0.0,"angularVelocity":0.6081726489037813,"angularAcceleration":-2.87309703788359,"curveRadius":-1.5524126752177216},{"acceleration":4.8273842463224925,"curvature":-0.6470818190817547,"pose":{"rotation":{"radians":3.082509516875822},"translation":{"x":4.916021952000001,"y":3.0023300479999997}},"time":3.0012185553557886,"velocity":-0.8826672272417309,"position":-3.0137100025737626,"holonomicRotation":0.0,"angularVelocity":0.5686449278090379,"angularAcceleration":-2.9050304586821287,"curveRadius":-1.5453996241449899},{"acceleration":4.799373104427447,"curvature":-0.6499779058913984,"pose":{"rotation":{"radians":3.0902802827517117},"translation":{"x":4.928013824000002,"y":3.001714176}},"time":3.016012420238071,"velocity":-0.8116659500151715,"position":-3.0257176789678364,"holonomicRotation":0.0,"angularVelocity":0.5252694909493342,"angularAcceleration":-2.9319881724519328,"curveRadius":-1.538513833987282},{"acceleration":4.760501598426161,"curvature":-0.6528447360474303,"pose":{"rotation":{"radians":3.098084331728513},"translation":{"x":4.9400080000000015,"y":3.001192}},"time":3.0323736836990083,"velocity":-0.7337781291571087,"position":-3.0377232162608494,"holonomicRotation":0.0,"angularVelocity":0.47698327182578276,"angularAcceleration":-2.951252465241195,"curveRadius":-1.5317577745274924},{"acceleration":4.702814023698275,"curvature":-0.6556801391027219,"pose":{"rotation":{"radians":3.105921514370289},"translation":{"x":4.952004096000002,"y":3.000763904}},"time":3.0509422774215356,"velocity":-0.6464534861984496,"position":-3.04972694840658,"holonomicRotation":0.0,"angularVelocity":0.4220665689005623,"angularAcceleration":-2.957504684837527,"curveRadius":-1.5251338882529966},{"acceleration":4.607805870089161,"curvature":-0.6584819160890972,"pose":{"rotation":{"radians":3.113791664077829},"translation":{"x":4.964001728000001,"y":3.000430272}},"time":3.0729658826145254,"velocity":-0.5449729889096658,"position":-3.06172921835517,"holonomicRotation":0.0,"angularVelocity":0.357350653472727,"angularAcceleration":-2.9384796385850205,"curveRadius":-1.5186445907873543},{"acceleration":4.418460750553726,"curvature":-0.6612478412834537,"pose":{"rotation":{"radians":3.1216945968333922},"translation":{"x":4.976000512000002,"y":3.000191488}},"time":3.101665460109967,"velocity":-0.4181650321885816,"position":-3.07373037810235,"holonomicRotation":0.0,"angularVelocity":0.27536756444649013,"angularAcceleration":-2.8565956777328174,"curveRadius":-1.512292271622457},{"acceleration":3.5355890810330983,"curvature":-0.6612478412834537,"pose":{"rotation":{"radians":3.1296301109558584},"translation":{"x":4.988000064000001,"y":3.000047936}},"time":3.170948677799963,"velocity":-0.17320804422499247,"position":-3.085730788736049,"holonomicRotation":0.0,"angularVelocity":0.11453732068237948,"angularAcceleration":-2.3213448960141663,"curveRadius":-1.512292271622457}] \ No newline at end of file diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java new file mode 100644 index 0000000..af85a31 --- /dev/null +++ b/src/main/java/frc/robot/Constants.java @@ -0,0 +1,393 @@ +package frc.robot; + +import com.swervedrivespecialties.swervelib.SdsModuleConfigurations; +import edu.wpi.first.math.trajectory.TrapezoidProfile; +import edu.wpi.first.wpilibj.RobotBase; + +/** + * The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean + * constants. This class should not be used for any other purpose. All constants should be declared + * globally (i.e. public static). Do not put anything functional in this class. + * + *

It is advised to statically import this class (or one of its inner classes) wherever the + * constants are needed, to reduce verbosity. + */ +public final class Constants { + + public static final double LOOP_PERIOD_SECS = 0.02; + private static final String CONSTRUCTOR_EXCEPTION = "constant class"; + + public static Mode getMode() { + return RobotBase.isReal() ? Mode.REAL : Mode.REPLAY; + } + + /* DRIVETRAIN CONSTANTS */ + + public static final class DrivetrainConstants { + + private DrivetrainConstants() { + throw new IllegalStateException(CONSTRUCTOR_EXCEPTION); + } + + public static final int FRONT_LEFT_MODULE_DRIVE_MOTOR = 7; + public static final int FRONT_LEFT_MODULE_STEER_MOTOR = 6; + public static final int FRONT_LEFT_MODULE_STEER_ENCODER = 8; + public static final double FRONT_LEFT_MODULE_STEER_OFFSET = -Math.toRadians(118.0371); + + public static final int FRONT_RIGHT_MODULE_DRIVE_MOTOR = 13; + public static final int FRONT_RIGHT_MODULE_STEER_MOTOR = 12; + public static final int FRONT_RIGHT_MODULE_STEER_ENCODER = 14; + public static final double FRONT_RIGHT_MODULE_STEER_OFFSET = -Math.toRadians(102.9968); + + public static final int BACK_LEFT_MODULE_DRIVE_MOTOR = 10; + public static final int BACK_LEFT_MODULE_STEER_MOTOR = 9; + public static final int BACK_LEFT_MODULE_STEER_ENCODER = 11; + public static final double BACK_LEFT_MODULE_STEER_OFFSET = -Math.toRadians(172.7051); + + public static final int BACK_RIGHT_MODULE_DRIVE_MOTOR = 16; + public static final int BACK_RIGHT_MODULE_STEER_MOTOR = 15; + public static final int BACK_RIGHT_MODULE_STEER_ENCODER = 17; + public static final double BACK_RIGHT_MODULE_STEER_OFFSET = -Math.toRadians(40.3335); + + /** + * The left-to-right distance between the drivetrain wheels + * + *

Should be measured from center to center. + */ + public static final double TRACKWIDTH_METERS = 0.5715; // 22.5 inches + + /** + * The front-to-back distance between the drivetrain wheels. + * + *

Should be measured from center to center. + */ + public static final double WHEELBASE_METERS = 0.5969; // 23.5 inches + + public static final double ROBOT_WIDTH_WITH_BUMPERS = 0.89; // meters + public static final double ROBOT_LENGTH_WITH_BUMPERS = 0.91; // meters + public static final double EVASIVE_ROTATION_COG_SHIFT_MAGNITUDE = + 0.707; // a bit beyond the bumper permimeter (meters) + public static final double COG_OFFSET = 45; + + /** + * The maximum voltage that will be delivered to the drive motors. + * + *

This can be reduced to cap the robot's maximum speed. Typically, this is useful during + * initial testing of the robot. + */ + public static final double MAX_VOLTAGE = 13.0; + + // The formula for calculating the theoretical maximum velocity is: + // / 60 * * * pi + // By default this value is setup for a Mk3 standard module using Falcon500s to drive. + // An example of this constant for a Mk4 L2 module with NEOs to drive is: + // 5880.0 / 60.0 / SdsModuleConfigurations.MK4_L2.getDriveReduction() * + // SdsModuleConfigurations.MK4_L2.getWheelDiameter() * Math.PI + + /** + * The maximum velocity of the robot in meters per second. + * + *

This is a measure of how fast the robot should be able to drive in a straight line. + */ + public static final double MAX_VELOCITY_METERS_PER_SECOND = + 6380.0 + / 60.0 + * SdsModuleConfigurations.MK4_L2.getDriveReduction() + * SdsModuleConfigurations.MK4_L2.getWheelDiameter() + * Math.PI; + + /** + * The maximum angular velocity of the robot in radians per second. + * + *

This is a measure of how fast the robot can rotate in place. + */ + + // Here we calculate the theoretical maximum angular velocity. You can also + // replace this with a measured amount. + public static final double MAX_ANGULAR_VELOCITY_RADIANS_PER_SECOND = + MAX_VELOCITY_METERS_PER_SECOND + / Math.hypot(TRACKWIDTH_METERS / 2.0, WHEELBASE_METERS / 2.0); + + public static final int PIGEON_ID = 18; + public static final int TIMEOUT_MS = 30; + + /* Limelight */ + public static final String LIMELIGHT_NETWORK_TABLE_NAME = "limelight"; + public static final double LIMELIGHT_F = 0.1; + public static final double LIMELIGHT_P = 0.2; + public static final double LIMELIGHT_I = 0.50; + public static final double LIMELIGHT_ALIGNMENT_TOLERANCE = 1.0; + public static final double LIMELIGHT_LAUNCHPAD_ALIGNMENT_TOLERANCE = .6; + public static final double LIMELIGHT_AIM_TOLERANCE = 3; // inches + public static final int AIM_SETPOINT_COUNT = 2; + public static final double LIMELIGHT_SLOPE = 24; + public static final double LIMELIGHT_Y_COMPONENT = 4596.34; + + // FIXME: determine the latency by filming a phone timer and the camera video of same phone + // timer; check Pose Estimation document for details + public static final double LIMELIGHT_LATENCY = 0.05; + + /* Rev Hubs */ + public static final int POWER_DISTRIBUTION_HUB_ID = 21; + } + + public static final class PneumaticsConstants { + private PneumaticsConstants() { + throw new IllegalStateException(CONSTRUCTOR_EXCEPTION); + } + + public static final int PNEUMATICS_HUB_ID = 20; + public static final int FLOW_SENSOR_CHANNEL = 0; + public static final int PRESSURE_SENSOR_CHANNEL = 1; + } + + public static final class CollectorConstants { + + private CollectorConstants() { + throw new IllegalStateException(CONSTRUCTOR_EXCEPTION); + } + + public static final double OUTTAKE_POWER = -0.7; + public static final int COLLECTOR_MOTOR_ID = 5; + public static final int PEUNAMATICS_HUB_CAN_ID = 20; + public static final int COLLECTOR_SOLENOID_CHANNEL = 0; + public static final double COLLECTOR_DEFAULT_POWER = 0.9; + public static final int TIMEOUT_MS = 30; + } + + public static final class AutoConstants { + + private AutoConstants() { + throw new IllegalStateException(CONSTRUCTOR_EXCEPTION); + } + + // from sysId tool + public static final double S_VOLTS = 0.55493; + public static final double V_VOLT_SECONDS_PER_METER = 2.3014; + public static final double A_VOLT_SECONDS_SQUARED_PER_METER = 0.12872; + + public static final double MAX_SPEED_METERS_PER_SECOND = 3; + public static final double MAX_ACCELERATION_METERS_PER_SECOND_SQUARED = 3; + public static final double MAX_ANGULAR_SPEED_RADIANS_PER_SECOND = 2.0 * Math.PI; + public static final double MAX_ANGULAR_SPEED_RADIANS_PER_SECOND_SQUARED = 2.0 * Math.PI; + + public static final double PX_CONTROLLER = 2.2956; // from sysId tool + public static final double PY_CONTROLLER = 2.2956; // from sysId tool + public static final double P_THETA_CONTROLLER = 4.9; + + // Constraint for the motion profilied robot angle controller + public static final TrapezoidProfile.Constraints THETA_CONTROLLER_CONSTRAINTS = + new TrapezoidProfile.Constraints( + MAX_ANGULAR_SPEED_RADIANS_PER_SECOND, MAX_ANGULAR_SPEED_RADIANS_PER_SECOND_SQUARED); + } + + public static class FlywheelConstants { + + private FlywheelConstants() { + throw new IllegalStateException(CONSTRUCTOR_EXCEPTION); + } + + public static final int SLOT_INDEX = 0; + public static final int PID_LOOP_INDEX = 0; + public static final int TIMEOUT_MS = 30; + public static final int VELOCITY_TOLERANCE = 300; + public static final int LEFT_FLYWHEELMOTOR_CANID = 1; + public static final int RIGHT_FLYWHEELMOTOR_CANID = 2; + public static final double VELOCITY_PID_P = 0.18; + public static final double VELOCITY_PID_I = 0.0; + public static final double VELOCITY_PID_D = 0.0; + public static final double VELOCITY_PID_F = 0.0513; + public static final double VELOCITY_PID_I_ZONE = 0.0; + public static final double VELOCITY_PID_PEAK_OUTPUT = 1.0; + public static final int MAX_FLYWHEEL_VELOCITY = 18650; // ticks per 100 ms + public static final int NEAR_WALL_SHOT_VELOCITY = 7000; // ticks per 100 ms + public static final int WALL_SHOT_VELOCITY = 7682; // ticks per 100 ms + public static final int FENDER_SHOT_VELOCITY = 7799; // ticks per 100 ms + public static final int LAUNCH_PAD_VELOCITY = 8682; // ticks per 100 ms + public static final int SHOOT_SLOW_VELOCITY = 4000; // ticks per 100 ms + public static final int SHOOT_STEAL_VELOCITY = 5500; // ticks per 100 ms + public static final double REVERSE_POWER = -0.2; + public static final int SETPOINTCOUNT = 5; + } + + public static class LimelightConstants { + + private LimelightConstants() { + throw new IllegalStateException(CONSTRUCTOR_EXCEPTION); + } + + public static final double HUB_H = 104; // inches + public static final double ROBOT_H = 21.25; // inches + public static final double GRAV_CONST_FT = -32.17519788; + public static final double FLYWHEEL_RADIUS_INCHES = 2; // inches + public static final double VELOCITY_MULTIPLIER = 2; + public static final double TICKS_PER_ROTATION = 2048; + public static final int LIMELIGHT_ANGLE_OFFSET = -2; // degrees + public static final int LIMELIGHT_MOUNT_ANGLE = 45; // degrees + public static final int D2_D1_OFFSET_IN = 24; // inches + public static final int H2_H1_OFFSET_IN = -24; // inches + public static final int DISTANCE_TOLERANCE = 12; // inches + // 203" from center of hub to center of lauchpad + // 26" from edge of hub to center of hub + // 3" from center of launch pad to bumpers + // 18" from bumpers to center of robot + // 7.5" from center of robot to Limeligtht + public static final int HUB_LAUNCHPAD_DISTANCE = 149; // inches + public static final int EDGE_TO_CENTER_HUB_DISTANCE = 26 + 8; // inches + public static final int HUB_WALL_DISTANCE = 130; // inches + public static final int AUTO_SHOT_HUB_FAR_DISTANCE = 124; // inches + public static final int AUTO_SHOT_HUB_CLOSE_DISTANCE = 68; // inches + } + + public static class VisionBoxConstants { + + private VisionBoxConstants() { + throw new IllegalStateException(CONSTRUCTOR_EXCEPTION); + } + + public static final double CAMERA_HEIGHT_METERS = + .75184; // TODO: remeasure these at competition + public static final double CAMERA_ANGLE_DEGREES = 32.5; + public static final double X_KP = -0.8; // stolen from autoconstants, may be horribly wrong + public static final double X_KI = 0; + public static final double X_KD = 0; + public static final double X_MAX_ACCELERATION = 10; // TODO verify, adapted from AutoConstants + public static final double X_MAX_VELOCITY = 5; // TODO verify, adapted from AutoConstants + public static final double Y_KP = -0.8; + public static final double Y_KI = 0; + public static final double Y_KD = 0; + public static final double Y_MAX_ACCELERATION = 15; // TODO verify, adapted from AutoConstants + public static final double Y_MAX_VELOCITY = 3; // TODO verify, adapted from AutoConstants + public static final double ROTATIONAL_KP = + -6; // stolen from drivetrain constants limelight PID but converted from deg to rad, may be + // horribly wrong + public static final double ROTATIONAL_KI = 0; + public static final double ROTATIONAL_KD = 0; + public static final double ROTATIONAL_MAX_ACCELERATION = + 2.0 * Math.PI; // TODO verify, adapted from AutoConstants + public static final double ROTATIONAL_MAX_VELOCITY = + Math.PI; // TODO verify, adapted from DrivetrainSubsystem.aim() + public static final double AIM_TOLERANCE_DEGREES = 5; + public static final double AIM_TOLERANCE_METERS = .33; + public static final double MINIMUM_UNAIMED_DISTANCE_METERS = 1; // about 3ft + public static final double OVERSHOOT_DISTANCE_METERS = .6; // about 2ft + public static final double MAX_DISPLACEMENT_PER_TICK_METERS = + .036; // this is way too high. should be (relative max ball velocity * .02s) + public static final double AT_BALL_THRESHOLD_METERS = .1; + } + + public static final class StorageConstants { + + private StorageConstants() { + throw new IllegalStateException(CONSTRUCTOR_EXCEPTION); + } + + public static final double OUTTAKE_POWER = -.8; + public static final int SHOOTER_SENSOR = 1; + public static final int COLLECTOR_SENSOR = 0; + public static final int STORAGE_MOTOR_ID = 4; + public static final double STORAGE_DEFAULT_POWER = 0.7; + public static final int STORAGE_CAMERA_PORT = 0; + public static final int TIMEOUT_MS = 30; + public static final int WAIT_FOR_SHOT_DELAY = 10; + public static final int INDEXING_FORWARD_DELAY = 16; + public static final int INDEXING_BACKWARD_DURATION = 3; + } + + public static class ElevatorConstants { + + private ElevatorConstants() { + throw new IllegalStateException(CONSTRUCTOR_EXCEPTION); + } + + public static final double MIN_ELEVATOR_ENCODER_HEIGHT = 0; + public static final double TRANSFER_TO_SECONDARY_HEIGHT = 25150; + public static final double LOW_RUNG_HEIGHT = 150786; + public static final double REACH_JUST_BEFORE_NEXT_RUNG = 185227; + public static final double MID_RUNG_HEIGHT = 253338; + + public static final double NEXT_RUNG_HEIGHT = 227499; + public static final double LATCH_HIGH_RUNG_ENCODER_HEIGHT = 238151; + public static final double LATCH_TRAVERSE_RUNG_ENCODER_HEIGHT = 171592; + public static final double REACH_TO_NEXT_RUNG_HEIGHT = 265674; + public static final double MAX_ELEVATOR_HEIGHT = 272631; + public static final double TICKS_PER_INCH = 8874.266; + + public static final double RETRACT_DELAY_AFTER_EXTENSION_UNDER_RUNG = 0.040; + + public static final int ELEVATOR_POSITION_TOLERANCE = 1000; + public static final double ARBITRARY_FEED_FORWARD_EXTEND = .02; + public static final double ARBITRARY_FEED_FORWARD_RETRACT = -0.07; + public static final double DEFAULT_MOTOR_POWER = 0.5; + + public static final int SLOT_INDEX = 0; + public static final int PID_LOOP_INDEX = 0; + public static final int TIMEOUT_MS = 30; + public static final double POSITION_PID_P = 0.4; + public static final double POSITION_PID_I = 0.0; + public static final double POSITION_PID_D = 0.0; + public static final double POSITION_PID_F = 0.0; + public static final double POSITION_PID_I_ZONE = 0.0; + public static final double POSITION_PID_PEAK_OUTPUT = 1.0; + public static final double SLOW_PEAK_OUTPUT = 0.15; + public static final double MAX_ELEVATOR_VELOCITY = 20000; // theoretical maximum 21305 + public static final double ELEVATOR_ACCELERATION = MAX_ELEVATOR_VELOCITY * 10; + public static final int SCURVE_STRENGTH = 0; + + public static final int SAMPLE_WINDOW_WIDTH = 6; + public static final double EPSILON = 0.001; + + // CAN ID + public static final int PIGEON_ID = 18; + public static final int LEFT_ELEVATOR_MOTOR_CAN_ID = 22; + public static final int RIGHT_ELEVATOR_MOTOR_CAN_ID = 19; + public static final int CLIMBER_CAMERA_PORT = 0; + } + + public class SecondaryArmConstants { + + private SecondaryArmConstants() { + throw new IllegalStateException(CONSTRUCTOR_EXCEPTION); + } + + public static final int PNEUMATIC_HUB_CAN_ID = 20; + public static final int PNEUMATIC_CHANNEL = 1; + } + + public static final class JoystickConstants { + + private JoystickConstants() { + throw new IllegalStateException(CONSTRUCTOR_EXCEPTION); + } + + public static final int CLIMBER_UP = 2; + public static final int CLIMB_2 = 1; + public static final int CLIMB_3 = 7; + public static final int CLIMB_4 = 8; + public static final int LIMELIGHT_AIM_TOGGLE = 9; + public static final int FIELD_WALL = 6; + public static final int LAUNCHPAD = 5; + public static final int SECONDARY = 4; + public static final int AUTO_AIM_AND_SHOOT = 3; + public static final int SHOOT_SLOW = 10; + public static final int UNASSIGNED = 11; + public static final int CLIMB_CAM = 12; + + public static final int BUTTON_A = 1; + public static final int BUTTON_B = 2; + public static final int BUTTON_X = 3; + public static final int BUTTON_Y = 4; + public static final int BUTTON_LB = 5; + public static final int BUTTON_RB = 6; + public static final int BUTTON_BACK = 7; + public static final int BUTTON_START = 8; + public static final int LEFT_JOYSTICK_BUTTON = 9; + public static final int RIGHT_JOYSTICK_BUTTON = 10; + } + + public enum Mode { + REAL, + REPLAY, + SIM + } +} diff --git a/src/main/java/frc/robot/FieldConstants.java b/src/main/java/frc/robot/FieldConstants.java new file mode 100644 index 0000000..847e17b --- /dev/null +++ b/src/main/java/frc/robot/FieldConstants.java @@ -0,0 +1,148 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +// from https://github.com/Mechanical-Advantage/RobotCode2022 + +package frc.robot; + +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.geometry.Translation2d; +import edu.wpi.first.math.util.Units; +import frc.robot.util.GeomUtil; + +/** Contains various field dimensions and useful side points. All dimensions are in meters. */ +public final class FieldConstants { + + private FieldConstants() { + throw new IllegalStateException("constant class"); + } + + // Field dimensions + public static final double FIELD_LENGTH = Units.inchesToMeters(54.0 * 12.0); + public static final double FIELD_WIDTH = Units.inchesToMeters(27.0 * 12.0); + public static final double HANGAR_LENGTH = Units.inchesToMeters(128.75); + public static final double HANGAR_WIDTH = Units.inchesToMeters(116.0); + + // Vision target + public static final double VISION_TARGET_DIAMETER = Units.inchesToMeters(4.0 * 12.0 + 5.375); + public static final double VISION_TARGET_HEIGHT_LOWER = + Units.inchesToMeters(8.0 * 12.0 + 5.625); // Bottom of tape + public static final double VISION_TARGET_HEIGHT_UPPER = + VISION_TARGET_HEIGHT_LOWER + Units.inchesToMeters(2.0); // Top of tape + + // Dimensions of hub and tarmac + public static final Rotation2d CENTER_LINE_ANGLE = Rotation2d.fromDegrees(66.0); + public static final Translation2d HUB_CENTER = + new Translation2d(FIELD_LENGTH / 2.0, FIELD_WIDTH / 2.0); + public static final double TARMAC_INNER_DIAMETER = Units.inchesToMeters(219.25); + public static final double TARMAC_OUTER_DIAMETER = Units.inchesToMeters(237.31); + public static final double TARMAC_FENDER_TO_TIP = Units.inchesToMeters(84.75); + public static final double TARMAC_FULL_SIDE_LENGTH = + TARMAC_INNER_DIAMETER * (Math.sqrt(2.0) - 1.0); // If the tarmac formed a full octagon + public static final double TARMAC_MARKED_SIDE_LENGTH = + Units.inchesToMeters(82.83); // Length of tape marking outside of tarmac + public static final double TARMAC_MISSING_SIDE_LENGTH = + TARMAC_FULL_SIDE_LENGTH - TARMAC_MARKED_SIDE_LENGTH; // Length removed b/c of corner cutoff + public static final double HUB_SQUARE_LENGTH = + TARMAC_OUTER_DIAMETER - (TARMAC_FENDER_TO_TIP * 2.0); + + // Reference rotations (angle from hub to each reference point and fender side) + public static final Rotation2d REFERENCE_A_ROTATION = + Rotation2d.fromDegrees(180.0) + .minus(CENTER_LINE_ANGLE) + .plus(Rotation2d.fromDegrees(360.0 / 16.0)); + public static final Rotation2d REFERENCE_B_ROTATION = + REFERENCE_A_ROTATION.rotateBy(Rotation2d.fromDegrees(360.0 / 8.0)); + public static final Rotation2d REFERENCE_C_ROTATION = + REFERENCE_B_ROTATION.rotateBy(Rotation2d.fromDegrees(360.0 / 8.0)); + public static final Rotation2d REFERENCE_D_ROTATION = + REFERENCE_C_ROTATION.rotateBy(Rotation2d.fromDegrees(360.0 / 8.0)); + public static final Rotation2d FENDER_A_ROTATION = + REFERENCE_A_ROTATION.rotateBy(Rotation2d.fromDegrees(360.0 / 16.0)); + public static final Rotation2d FENDER_B_ROTATION = + FENDER_A_ROTATION.rotateBy(Rotation2d.fromDegrees(90.0)); + + // Reference points (centered of the sides of the tarmac if they formed a complete octagon, plus + // edges of fender) + public static final Pose2d REFERENCE_A = + new Pose2d(HUB_CENTER, REFERENCE_A_ROTATION) + .transformBy(GeomUtil.transformFromTranslation(TARMAC_INNER_DIAMETER / 2.0, 0.0)); + public static final Pose2d REFERENCE_B = + new Pose2d(HUB_CENTER, REFERENCE_B_ROTATION) + .transformBy(GeomUtil.transformFromTranslation(TARMAC_INNER_DIAMETER / 2.0, 0.0)); + public static final Pose2d REFERENCE_C = + new Pose2d(HUB_CENTER, REFERENCE_C_ROTATION) + .transformBy(GeomUtil.transformFromTranslation(TARMAC_INNER_DIAMETER / 2.0, 0.0)); + public static final Pose2d REFERENCE_D = + new Pose2d(HUB_CENTER, REFERENCE_D_ROTATION) + .transformBy(GeomUtil.transformFromTranslation(TARMAC_INNER_DIAMETER / 2.0, 0.0)); + public static final Pose2d FENDER_A = + new Pose2d(HUB_CENTER, FENDER_A_ROTATION) + .transformBy(GeomUtil.transformFromTranslation(HUB_SQUARE_LENGTH / 2.0, 0.0)); + public static final Pose2d FENDER_B = + new Pose2d(HUB_CENTER, FENDER_B_ROTATION) + .transformBy(GeomUtil.transformFromTranslation(HUB_SQUARE_LENGTH / 2.0, 0.0)); + + // Cargo points + public static final double CORNER_TO_CARGO_Y = Units.inchesToMeters(15.56); + public static final double REFERENCE_TO_CARGO_Y = + (TARMAC_FULL_SIDE_LENGTH / 2.0) - CORNER_TO_CARGO_Y; + public static final double REFERENCE_TO_CARGO_X = Units.inchesToMeters(40.44); + public static final Pose2d CARGO_A = + REFERENCE_A.transformBy( + GeomUtil.transformFromTranslation(REFERENCE_TO_CARGO_X, -REFERENCE_TO_CARGO_Y)); + public static final Pose2d CARGO_B = + REFERENCE_A.transformBy( + GeomUtil.transformFromTranslation(REFERENCE_TO_CARGO_X, REFERENCE_TO_CARGO_Y)); + public static final Pose2d CARGO_C = + REFERENCE_B.transformBy( + GeomUtil.transformFromTranslation(REFERENCE_TO_CARGO_X, REFERENCE_TO_CARGO_Y)); + public static final Pose2d CARGO_D = + REFERENCE_C.transformBy( + GeomUtil.transformFromTranslation(REFERENCE_TO_CARGO_X, -REFERENCE_TO_CARGO_Y)); + public static final Pose2d CARGO_E = + REFERENCE_D.transformBy( + GeomUtil.transformFromTranslation(REFERENCE_TO_CARGO_X, -REFERENCE_TO_CARGO_Y)); + public static final Pose2d CARGO_F = + REFERENCE_D.transformBy( + GeomUtil.transformFromTranslation(REFERENCE_TO_CARGO_X, REFERENCE_TO_CARGO_Y)); + + // Terminal cargo point + public static final Rotation2d TERMINAL_OUTER_ROTATION = Rotation2d.fromDegrees(133.75); + public static final double TERMINAL_LENGTH = Units.inchesToMeters(324.0 - 256.42); + public static final double TERMINAL_WIDTH = + Math.tan(Rotation2d.fromDegrees(180.0).minus(TERMINAL_OUTER_ROTATION).getRadians()) + * TERMINAL_LENGTH; + public static final Pose2d TERMINAL_CENTER = + new Pose2d( + new Translation2d(TERMINAL_LENGTH / 2.0, TERMINAL_WIDTH / 2.0), + TERMINAL_OUTER_ROTATION.minus(Rotation2d.fromDegrees(90.0))); + public static final double TERMINAL_CARGO_OFFSET = Units.inchesToMeters(10.43); + public static final Pose2d CARGO_G = + TERMINAL_CENTER.transformBy(GeomUtil.transformFromTranslation(TERMINAL_CARGO_OFFSET, 0.0)); + + // Opposite reference points + public static final Pose2d referenceAOpposite = opposite(REFERENCE_A); + public static final Pose2d referenceBOpposite = opposite(REFERENCE_B); + public static final Pose2d referenceCOpposite = opposite(REFERENCE_C); + public static final Pose2d referenceDOpposite = opposite(REFERENCE_D); + public static final Pose2d fenderAOpposite = opposite(FENDER_A); + public static final Pose2d fenderBOpposite = opposite(FENDER_B); + + // Opposite cargo points + public static final Pose2d cargoAOpposite = opposite(CARGO_A); + public static final Pose2d cargoBOpposite = opposite(CARGO_B); + public static final Pose2d cargoCOpposite = opposite(CARGO_C); + public static final Pose2d cargoDOpposite = opposite(CARGO_D); + public static final Pose2d cargoEOpposite = opposite(CARGO_E); + public static final Pose2d cargoFOpposite = opposite(CARGO_F); + public static final Pose2d cargoGOpposite = opposite(CARGO_G); + + // Calculate pose mirror on the opposite side of the field + private static Pose2d opposite(Pose2d pose) { + return new Pose2d(FIELD_LENGTH, FIELD_WIDTH, Rotation2d.fromDegrees(180.0)) + .transformBy(GeomUtil.poseToTransform(pose)); + } +} diff --git a/src/main/java/frc/robot/GVersion.java b/src/main/java/frc/robot/GVersion.java new file mode 100644 index 0000000..0a4342d --- /dev/null +++ b/src/main/java/frc/robot/GVersion.java @@ -0,0 +1,19 @@ +package frc.robot; + +/** + * Automatically generated file containing build version information. + */ +public final class GVersion { + public static final String MAVEN_GROUP = ""; + public static final String MAVEN_NAME = "2022-release"; + public static final String VERSION = "unspecified"; + public static final int GIT_REVISION = 1; + public static final String GIT_SHA = "2e4a428c59fe3c63d2cbee5c6873eb418b00e33a"; + public static final String GIT_DATE = "2022-12-26T16:17:21Z"; + public static final String GIT_BRANCH = "main"; + public static final String BUILD_DATE = "2022-12-26T16:28:10Z"; + public static final long BUILD_UNIX_TIME = 1672072090482L; + public static final int DIRTY = 1; + + private GVersion(){} +} diff --git a/src/main/java/frc/robot/Main.java b/src/main/java/frc/robot/Main.java new file mode 100644 index 0000000..d2ff510 --- /dev/null +++ b/src/main/java/frc/robot/Main.java @@ -0,0 +1,21 @@ +package frc.robot; + +import edu.wpi.first.wpilibj.RobotBase; + +/** + * Do NOT add any static variables to this class, or any initialization at all. Unless you know what + * you are doing, do not modify this file except to change the parameter class to the startRobot + * call. + */ +public final class Main { + private Main() {} + + /** + * Main initialization function. Do not perform any initialization here. + * + *

If you change your main robot class, change the parameter type. + */ + public static void main(String... args) { + RobotBase.startRobot(Robot::new); + } +} diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java new file mode 100644 index 0000000..048759d --- /dev/null +++ b/src/main/java/frc/robot/Robot.java @@ -0,0 +1,209 @@ +package frc.robot; + +import static frc.robot.Constants.*; + +import edu.wpi.first.cameraserver.CameraServer; +import edu.wpi.first.cscore.UsbCamera; +import edu.wpi.first.cscore.VideoMode.PixelFormat; +import edu.wpi.first.cscore.VideoSink; +import edu.wpi.first.cscore.VideoSource.ConnectionStrategy; +import edu.wpi.first.hal.FRCNetComm.tInstances; +import edu.wpi.first.hal.FRCNetComm.tResourceType; +import edu.wpi.first.hal.HAL; +import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.wpilibj.PowerDistribution.ModuleType; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.CommandScheduler; +import frc.robot.util.Alert; +import frc.robot.util.Alert.AlertType; +import org.littletonrobotics.junction.LoggedRobot; +import org.littletonrobotics.junction.Logger; +import org.littletonrobotics.junction.inputs.LoggedNetworkTables; +import org.littletonrobotics.junction.inputs.LoggedSystemStats; +import org.littletonrobotics.junction.io.ByteLogReceiver; +import org.littletonrobotics.junction.io.ByteLogReplay; +import org.littletonrobotics.junction.io.LogSocketServer; + +/** + * The VM is configured to automatically run this class, and to call the methods corresponding to + * each mode, as described in the TimedRobot documentation. If you change the name of this class or + * the package after creating this project, you must also update the build.properties file in the + * project. + */ +public class Robot extends LoggedRobot { + + private Command autonomousCommand; + private RobotContainer robotContainer; + private UsbCamera storageCam; + private VideoSink server; + private ByteLogReceiver logReceiver; + + private final Alert logReceiverQueueAlert = + new Alert("Logging queue exceeded capacity, data will NOT be logged.", AlertType.ERROR); + private final Alert logOpenFileAlert = + new Alert("Failed to open log file. Data will NOT be logged", AlertType.ERROR); + private final Alert logWriteAlert = + new Alert("Failed write to the log file. Data will NOT be logged", AlertType.ERROR); + + public Robot() { + super(Constants.LOOP_PERIOD_SECS); + } + /** + * This method is run when the robot is first started up and should be used for any initialization + * code. + */ + @Override + public void robotInit() { + final String GIT_DIRTY = "GitDirty"; + + // from AdvantageKit Robot Configuration docs + // (https://github.com/Mechanical-Advantage/AdvantageKit/blob/main/docs/START-LOGGING.md#robot-configuration) + + Logger logger = Logger.getInstance(); + + // Run as fast as possible during replay + setUseTiming(isReal()); + + // Log & replay "SmartDashboard" values (no tables are logged by default). + LoggedNetworkTables.getInstance().addTable("/SmartDashboard"); + + // Set a metadata value + logger.recordMetadata("RuntimeType", getRuntimeType().toString()); + logger.recordMetadata("ProjectName", GVersion.MAVEN_NAME); + logger.recordMetadata("BuildDate", GVersion.BUILD_DATE); + logger.recordMetadata("GitSHA", GVersion.GIT_SHA); + logger.recordMetadata("GitDate", GVersion.GIT_DATE); + logger.recordMetadata("GitBranch", GVersion.GIT_BRANCH); + switch (GVersion.DIRTY) { + case 0: + logger.recordMetadata(GIT_DIRTY, "All changes committed"); + break; + case 1: + logger.recordMetadata(GIT_DIRTY, "Uncomitted changes"); + break; + default: + logger.recordMetadata(GIT_DIRTY, "Unknown"); + break; + } + + if (isReal()) { + logReceiver = new ByteLogReceiver("/media/sda1"); + logger.addDataReceiver(logReceiver); + + // Provide log data over the network, viewable in Advantage Scope. + logger.addDataReceiver(new LogSocketServer(5800)); + + LoggedSystemStats.getInstance() + .setPowerDistributionConfig( + DrivetrainConstants.POWER_DISTRIBUTION_HUB_ID, ModuleType.kRev); + } else { + // Prompt the user for a file path on the command line + String path = ByteLogReplay.promptForPath(); + + // Read log file for replay + logger.setReplaySource(new ByteLogReplay(path)); + + // Save replay results to a new log with the "_sim" suffix + logger.addDataReceiver(new ByteLogReceiver(ByteLogReceiver.addPathSuffix(path, "_sim"))); + } + + // Start logging! No more data receivers, replay sources, or metadata values may be added. + logger.start(); + + // Alternative logging of scheduled commands + CommandScheduler.getInstance() + .onCommandInitialize( + command -> Logger.getInstance().recordOutput("Command initialized", command.getName())); + CommandScheduler.getInstance() + .onCommandInterrupt( + command -> Logger.getInstance().recordOutput("Command interrupted", command.getName())); + CommandScheduler.getInstance() + .onCommandFinish( + command -> Logger.getInstance().recordOutput("Command finished", command.getName())); + + // Instantiate our RobotContainer. This will perform all our button bindings, + // and put our autonomous chooser on the dashboard. + robotContainer = RobotContainer.getInstance(); + + storageCam = CameraServer.startAutomaticCapture(StorageConstants.STORAGE_CAMERA_PORT); + storageCam.setResolution(320, 240); + storageCam.setFPS(15); + storageCam.setPixelFormat(PixelFormat.kYUYV); + storageCam.setConnectionStrategy(ConnectionStrategy.kKeepOpen); + + server = CameraServer.getServer(); + + HAL.report(tResourceType.kResourceType_Framework, tInstances.kFramework_RobotBuilder); + } + + /** + * This method is called every robot packet, no matter the mode. Use this for items like + * diagnostics that you want ran during disabled, autonomous, teleoperated and test. + * + *

This runs after the mode specific periodic methods, but before LiveWindow and SmartDashboard + * integrated updating. + */ + @Override + public void robotPeriodic() { + // Runs the Scheduler. This is responsible for polling buttons, adding + // newly-scheduled commands, running already-scheduled commands, removing finished or + // interrupted commands, and running subsystem periodic() methods. This must be called from the + // robot's periodic block in order for anything in the Command-based framework to work. + CommandScheduler.getInstance().run(); + + // Log scheduled commands + Logger.getInstance() + .recordOutput( + "ActiveCommands/Scheduler", + NetworkTableInstance.getDefault() + .getEntry("/LiveWindow/Ungrouped/Scheduler/Names") + .getStringArray(new String[] {})); + + // Check logging faults + logReceiverQueueAlert.set(Logger.getInstance().getReceiverQueueFault()); + if (logReceiver != null) { + logOpenFileAlert.set(logReceiver.getOpenFault()); + logWriteAlert.set(logReceiver.getWriteFault()); + } + } + + @Override + public void disabledPeriodic() { + RobotContainer.getInstance().disabledPeriodic(); + } + + /** + * This autonomous schedules the autonomous command selected by your {@link RobotContainer} class. + */ + @Override + public void autonomousInit() { + autonomousCommand = robotContainer.getAutonomousCommand(); + + // schedule the autonomous command + if (autonomousCommand != null) { + autonomousCommand.schedule(); + } + } + + /** This method is called once each time the robot enters Teleop mode. */ + @Override + public void teleopInit() { + // This makes sure that the autonomous stops running when + // teleop starts running. If you want the autonomous to + // continue until interrupted by another command, remove + // this line or comment it out. + if (autonomousCommand != null) { + autonomousCommand.cancel(); + } + + server.setSource(storageCam); + robotContainer.teleopInit(); + } + + /** This method is called once each time the robot enters Test mode. */ + @Override + public void testInit() { + // Cancels all running commands at the start of test mode. + CommandScheduler.getInstance().cancelAll(); + } +} diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java new file mode 100644 index 0000000..bcf204c --- /dev/null +++ b/src/main/java/frc/robot/RobotContainer.java @@ -0,0 +1,716 @@ +package frc.robot; + +import static frc.robot.Constants.*; +import static frc.robot.Constants.JoystickConstants.*; + +import com.pathplanner.lib.PathPlanner; +import com.pathplanner.lib.PathPlannerTrajectory; +import edu.wpi.first.math.controller.ProfiledPIDController; +import edu.wpi.first.wpilibj.GenericHID; +import edu.wpi.first.wpilibj.Joystick; +import edu.wpi.first.wpilibj.XboxController; +import edu.wpi.first.wpilibj.livewindow.LiveWindow; +import edu.wpi.first.wpilibj.shuffleboard.EventImportance; +import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; +import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; +import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.CommandScheduler; +import edu.wpi.first.wpilibj2.command.ConditionalCommand; +import edu.wpi.first.wpilibj2.command.InstantCommand; +import edu.wpi.first.wpilibj2.command.ParallelCommandGroup; +import edu.wpi.first.wpilibj2.command.ParallelDeadlineGroup; +import edu.wpi.first.wpilibj2.command.ParallelRaceGroup; +import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; +import edu.wpi.first.wpilibj2.command.WaitCommand; +import edu.wpi.first.wpilibj2.command.button.JoystickButton; +import frc.robot.Constants.AutoConstants; +import frc.robot.Constants.CollectorConstants; +import frc.robot.Constants.StorageConstants; +import frc.robot.commands.*; +import frc.robot.subsystems.VisionBox; +import frc.robot.subsystems.collector.Collector; +import frc.robot.subsystems.collector.CollectorIO; +import frc.robot.subsystems.collector.CollectorIOTalonSRX; +import frc.robot.subsystems.drivetrain.Drivetrain; +import frc.robot.subsystems.drivetrain.DrivetrainIO; +import frc.robot.subsystems.drivetrain.DrivetrainIOTalonFX; +import frc.robot.subsystems.elevator.Elevator; +import frc.robot.subsystems.elevator.ElevatorIO; +import frc.robot.subsystems.elevator.ElevatorIOTalonFX; +import frc.robot.subsystems.flywheel.Flywheel; +import frc.robot.subsystems.flywheel.FlywheelIO; +import frc.robot.subsystems.flywheel.FlywheelIOTalonFX; +import frc.robot.subsystems.pneumatics.Pneumatics; +import frc.robot.subsystems.pneumatics.PneumaticsIO; +import frc.robot.subsystems.pneumatics.PneumaticsIORev; +import frc.robot.subsystems.secondary_arm.SecondaryArm; +import frc.robot.subsystems.secondary_arm.SecondaryArmIO; +import frc.robot.subsystems.secondary_arm.SecondaryArmSolenoid; +import frc.robot.subsystems.storage.Storage; +import frc.robot.subsystems.storage.StorageIO; +import frc.robot.subsystems.storage.StorageIOTalonSRX; + +/** + * 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. + */ +public class RobotContainer { + private final JoystickButton[] operatorButtons; + private final JoystickButton[] joystickButtons0; + private final JoystickButton[] joystickButtons1; + private final JoystickButton[] xboxButtons; + + private final Joystick joystick0 = new Joystick(0); + private final Joystick joystick1 = new Joystick(1); + private final Joystick operatorConsole = new Joystick(2); + private final XboxController xboxController = new XboxController(3); + + private static RobotContainer robotContainer = new RobotContainer(); + + private final Drivetrain drivetrain; + private final Storage storage; + private final Collector collector; + private final Flywheel flywheel; + private final SecondaryArm secondMechanism; + private final Elevator elevator; + private final Pneumatics pneumatics; + private final VisionBox visionBox; + + // A chooser for autonomous commands + SendableChooser chooser = new SendableChooser<>(); + + /** The container for the robot. Contains subsystems, IO devices, and commands. */ + private RobotContainer() { + + // create real or replay subsystems + if (Constants.getMode() != Mode.REPLAY) { + drivetrain = new Drivetrain(new DrivetrainIOTalonFX()); + storage = new Storage(new StorageIOTalonSRX()); + collector = new Collector(new CollectorIOTalonSRX()); + flywheel = new Flywheel(new FlywheelIOTalonFX()); + secondMechanism = new SecondaryArm(new SecondaryArmSolenoid()); + elevator = new Elevator(new ElevatorIOTalonFX()); + pneumatics = new Pneumatics(new PneumaticsIORev()); + } else { + drivetrain = new Drivetrain(new DrivetrainIO() {}); + storage = new Storage(new StorageIO() {}); + collector = new Collector(new CollectorIO() {}); + flywheel = new Flywheel(new FlywheelIO() {}); + secondMechanism = new SecondaryArm(new SecondaryArmIO() {}); + elevator = new Elevator(new ElevatorIO() {}); + pneumatics = new Pneumatics(new PneumaticsIO() {}); + } + + visionBox = new VisionBox(drivetrain); + + // disable all telemetry in the LiveWindow to reduce the processing during each iteration + LiveWindow.disableAllTelemetry(); + + // buttons use 1-based indexing such that the index matches the button number + this.joystickButtons0 = new JoystickButton[13]; + this.joystickButtons1 = new JoystickButton[13]; + this.operatorButtons = new JoystickButton[13]; + this.xboxButtons = new JoystickButton[11]; + + for (int i = 1; i < joystickButtons0.length; i++) { + joystickButtons0[i] = new JoystickButton(joystick0, i); + joystickButtons1[i] = new JoystickButton(joystick1, i); + operatorButtons[i] = new JoystickButton(operatorConsole, i); + } + + for (int i = 1; i < xboxButtons.length; i++) { + xboxButtons[i] = new JoystickButton(xboxController, i); + } + + // all subsystems must register with the Command Scheduler in order for their periodic methods + // to be invoked + drivetrain.register(); + storage.register(); + collector.register(); + flywheel.register(); + storage.register(); + elevator.register(); + secondMechanism.register(); + pneumatics.register(); + + // Set up the default command for the drivetrain. + // The joysticks' values map to percentage of the maximum velocities. + // The velocities may be specified from either the robot's frame of reference or the field's + // frame of reference. In the robot's frame of reference, the positive x direction is + // forward; the positive y direction, left; position rotation, CCW. In the field frame of + // reference, + // the origin of the field to the lower left corner (i.e., the corner of the field to the + // driver's right). Zero degrees is away from the driver and increases in the CCW direction. + // This is why the left joystick's y axis specifies the velocity in the x direction and the + // left joystick's x axis specifies the velocity in the y direction. + drivetrain.setDefaultCommand( + new DefaultDriveCommand( + drivetrain, + () -> + -modifyAxis(joystick0.getY()) * DrivetrainConstants.MAX_VELOCITY_METERS_PER_SECOND, + () -> + -modifyAxis(joystick0.getX()) * DrivetrainConstants.MAX_VELOCITY_METERS_PER_SECOND, + () -> + -modifyAxis(joystick1.getX()) + * DrivetrainConstants.MAX_ANGULAR_VELOCITY_RADIANS_PER_SECOND)); + + configureButtonBindings(); + configureAutoCommands(); + + CommandScheduler.getInstance() + .onCommandInitialize( + command -> + Shuffleboard.addEventMarker( + "Command initialized", + command + .getClass() + .getName() + .substring(command.getClass().getName().lastIndexOf('.') + 1), + EventImportance.kNormal)); + + CommandScheduler.getInstance() + .onCommandInterrupt( + command -> + Shuffleboard.addEventMarker( + "Command interrupted", + command + .getClass() + .getName() + .substring(command.getClass().getName().lastIndexOf('.') + 1), + EventImportance.kNormal)); + + CommandScheduler.getInstance() + .onCommandFinish( + command -> + Shuffleboard.addEventMarker( + "Command finished", + command + .getClass() + .getName() + .substring(command.getClass().getName().lastIndexOf('.') + 1), + EventImportance.kNormal)); + } + + /** + * Factory method to create the singleton robot container object. + * + * @return the singleton robot container object + */ + public static RobotContainer getInstance() { + return robotContainer; + } + + /** + * Use this method to define your button->command mappings. Buttons can be created by + * instantiating a {@link GenericHID} or one of its subclasses ({@link + * edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link + * edu.wpi.first.wpilibj2.command.button.JoystickButton}. + */ + private void configureButtonBindings() { + configureDrivetrainButtons(); + configureIntakeButtons(); + configureShooterButtons(); + configureClimberButtons(); + } + + private void configureDrivetrainButtons() { + // auto aim and shoot while moving + operatorButtons[JoystickConstants.AUTO_AIM_AND_SHOOT].whenPressed( + new SequentialCommandGroup( + new IndexSingleBallCommand(storage), + new LimelightAlignOnMoveCommand( + drivetrain, + flywheel, + collector, + () -> + -modifyAxis(joystick0.getY()) + * DrivetrainConstants.MAX_VELOCITY_METERS_PER_SECOND, + () -> + -modifyAxis(joystick0.getX()) + * DrivetrainConstants.MAX_VELOCITY_METERS_PER_SECOND, + () -> + -modifyAxis(joystick1.getX()) + * DrivetrainConstants.MAX_ANGULAR_VELOCITY_RADIANS_PER_SECOND), + new WaitCommand(0.300), + createLimelightShootCommandSequence(true /* use gyro */))); + + // field-relative toggle + joystickButtons0[3].toggleWhenPressed( + new ConditionalCommand( + new InstantCommand(() -> drivetrain.disableFieldRelative(), drivetrain), + new InstantCommand(() -> drivetrain.enableFieldRelative(), drivetrain), + drivetrain::getFieldRelative)); + + // rotate evasively around defending robot + joystickButtons1[4].whenPressed( + new InstantCommand( + () -> + drivetrain.rotateEvasively( + -modifyAxis(joystick0.getY()), + -modifyAxis(joystick0.getX()), + -modifyAxis(joystick1.getX())), + drivetrain)); + joystickButtons1[4].whenReleased( + new InstantCommand(() -> drivetrain.resetCenterGrav(), drivetrain)); + + // stop/disable/reset all subsystems + joystickButtons1[3].whenPressed( + new ParallelCommandGroup( + new InstantCommand(() -> flywheel.stopFlywheel(), flywheel), + new InstantCommand(() -> storage.disableStorage(), storage), + new InstantCommand(() -> collector.disableCollector(), collector), + new InstantCommand(() -> drivetrain.disableXstance(), drivetrain))); + + // reset gyro to 0 degrees + xboxButtons[BUTTON_Y].whenPressed( + new InstantCommand(() -> drivetrain.zeroGyroscope(), drivetrain)); + } + + private void configureIntakeButtons() { + // toggle collector + xboxButtons[JoystickConstants.LEFT_JOYSTICK_BUTTON].toggleWhenPressed( + new ConditionalCommand( + new InstantCommand(() -> collector.disableCollector(), collector), + new InstantCommand(() -> collector.enableCollector(), collector), + collector::isEnabled)); + + // toggle storage + xboxButtons[JoystickConstants.RIGHT_JOYSTICK_BUTTON].toggleWhenPressed( + new ConditionalCommand( + new InstantCommand(() -> storage.disableStorage(), storage), + new InstantCommand(() -> storage.enableStorage(), storage), + storage::isStorageEnabled)); + + // intake + joystickButtons1[1].toggleWhenPressed( + new ConditionalCommand( + new ParallelCommandGroup( + new InstantCommand(() -> collector.disableCollector(), collector), + new InstantCommand(() -> storage.disableStorage(), storage), + new InstantCommand(() -> flywheel.stopFlywheel(), flywheel)), + new SequentialCommandGroup( + new InstantCommand(() -> collector.enableCollector(), collector), + new SortStorageCommand(storage), + new InstantCommand(() -> collector.disableCollector(), collector), + new SetFlywheelVelocityCommand(flywheel, FlywheelConstants.WALL_SHOT_VELOCITY)), + collector::isEnabled)); + + // unjam all + xboxButtons[BUTTON_X].whenHeld( + new ParallelCommandGroup( + new InstantCommand( + () -> collector.setCollectorPower(CollectorConstants.OUTTAKE_POWER), collector), + new InstantCommand( + () -> storage.setStoragePower(StorageConstants.OUTTAKE_POWER), storage), + new InstantCommand(() -> flywheel.unjamFlywheel(), flywheel))); + xboxButtons[BUTTON_X].whenReleased( + new ParallelCommandGroup( + new InstantCommand(() -> collector.setCollectorPower(0), collector), + new InstantCommand(() -> storage.setStoragePower(0), storage), + new InstantCommand(() -> flywheel.stopFlywheel(), flywheel))); + + // unjam collector + xboxButtons[BUTTON_B].whenHeld( + new InstantCommand( + () -> collector.setCollectorPower(CollectorConstants.OUTTAKE_POWER), collector)); + xboxButtons[BUTTON_B].whenReleased( + new InstantCommand(() -> collector.setCollectorPower(0), collector)); + + joystickButtons0[2].whenPressed( + new ParallelRaceGroup( + new SortStorageCommand(storage), + new VisionBoxCollectBallCommand(visionBox, drivetrain, collector, storage))); + } + + private void configureShooterButtons() { + + // enable/disable limelight aiming + operatorButtons[JoystickConstants.LIMELIGHT_AIM_TOGGLE].toggleWhenPressed( + new ConditionalCommand( + new InstantCommand(() -> drivetrain.disableLimelightAim(), drivetrain), + new InstantCommand(() -> drivetrain.enableLimelightAim(), drivetrain), + drivetrain::isLimelightAimEnabled)); + + // preset field wall shot + operatorButtons[JoystickConstants.FIELD_WALL].whenPressed( + createShootCommandSequence(FlywheelConstants.WALL_SHOT_VELOCITY)); + + // preset launchpad shot + operatorButtons[JoystickConstants.LAUNCHPAD].whenPressed( + createShootCommandSequence(FlywheelConstants.LAUNCH_PAD_VELOCITY)); + + // shoot slow + operatorButtons[JoystickConstants.SHOOT_SLOW].whenPressed( + new SequentialCommandGroup( + new ParallelCommandGroup( + new InstantCommand(() -> collector.disableCollector(), collector), + new SetFlywheelVelocityCommand(flywheel, FlywheelConstants.SHOOT_SLOW_VELOCITY)), + new InstantCommand(() -> storage.enableStorage(), storage), + new WaitForShotCommand(storage, flywheel, drivetrain))); + + // limelight shot + joystickButtons0[1].whenPressed( + new SequentialCommandGroup( + new ParallelCommandGroup(new IndexSingleBallCommand(storage), new WaitCommand(0.300)), + createLimelightShootCommandSequence(true /* use gyro */))); + } + + private void configureClimberButtons() { + + // configure climb to 4 (traverse) rung climb sequence + operatorButtons[8].whenPressed( + new SequentialCommandGroup( + new RetractClimberFullCommand(elevator), + new InstantCommand(() -> secondMechanism.moveSecondaryArmOut(), secondMechanism), + new WaitCommand(0.5), // wait for secondary arm to be positioned + new ReachToNextRungWithPitchCommand(elevator, secondMechanism), + new WaitCommand( + ElevatorConstants + .RETRACT_DELAY_AFTER_EXTENSION_UNDER_RUNG), // wait for secondary arm to be + // positioned + new RetractClimberMinimumCommand( + ElevatorConstants.LATCH_TRAVERSE_RUNG_ENCODER_HEIGHT, elevator))); + + // configure climb to 3 (high) rung climb sequence + operatorButtons[7].whenPressed( + new SequentialCommandGroup( + new RetractClimberFullCommand(elevator), + new InstantCommand(() -> secondMechanism.moveSecondaryArmOut(), secondMechanism), + new WaitCommand(0.5), // wait for secondary arm to be positioned + new ReachToNextRungWithPitchCommand(elevator, secondMechanism), + new WaitCommand( + ElevatorConstants + .RETRACT_DELAY_AFTER_EXTENSION_UNDER_RUNG), // wait for secondary arm to be + // positioned + new RetractClimberMinimumCommand( + ElevatorConstants.LATCH_HIGH_RUNG_ENCODER_HEIGHT, elevator))); + + // configure climb to 1/2 (low/mid) rung climb sequence + operatorButtons[1].whenPressed( + new SequentialCommandGroup( + new RetractClimberFullCommand(elevator), + new InstantCommand(() -> secondMechanism.moveSecondaryArmOut(), secondMechanism))); + + // configure raise elevator before starting climb to 1 (low) rung + operatorButtons[11].whenPressed(new ExtendClimberToLowRungCommand(elevator)); + + // configure raise elevator before starting climb + operatorButtons[2].whenPressed(new ExtendClimberToMidRungCommand(elevator)); + + // retract climber + xboxButtons[BUTTON_A].whenPressed(new RetractClimberFullCommand(elevator)); + + // manually extend climber + xboxButtons[JoystickConstants.BUTTON_RB].whenPressed( + new InstantCommand( + () -> elevator.setElevatorMotorPower(ElevatorConstants.DEFAULT_MOTOR_POWER), elevator)); + xboxButtons[JoystickConstants.BUTTON_RB].whenReleased( + new InstantCommand(() -> elevator.setElevatorMotorPower(0), elevator)); + + // manually retract climber + xboxButtons[JoystickConstants.BUTTON_LB].whenPressed( + new InstantCommand( + () -> elevator.setElevatorMotorPower(-1 * ElevatorConstants.DEFAULT_MOTOR_POWER), + elevator)); + xboxButtons[JoystickConstants.BUTTON_LB].whenReleased( + new InstantCommand(() -> elevator.setElevatorMotorPower(0), elevator)); + + // pause elevator + xboxButtons[JoystickConstants.BUTTON_START].whenPressed( + new InstantCommand( + () -> elevator.elevatorPause(xboxButtons[JoystickConstants.BUTTON_BACK].get()), + elevator)); + + // enable elevator control + operatorButtons[12].toggleWhenPressed( + new ConditionalCommand( + new InstantCommand(() -> elevator.disableElevatorControl(), elevator), + new InstantCommand(() -> elevator.enableElevatorControl(), elevator), + elevator::isElevatorControlEnabled)); + + // manually toggle secondary arms + operatorButtons[JoystickConstants.SECONDARY].toggleWhenPressed( + new ConditionalCommand( + new InstantCommand(() -> secondMechanism.moveSecondaryArmOut()), + new InstantCommand(() -> secondMechanism.moveSecondaryArmIn()), + secondMechanism::isIn)); + } + + /** + * Use this to pass the autonomous command to the main {@link Robot} class. + * + * @return the command to run in autonomous + */ + public Command getAutonomousCommand() { + return chooser.getSelected(); + } + + /** Start teleop in a known state (i.e., storage, flywheel, collector stopped/disabled) */ + public void teleopInit() { + storage.disableStorage(); + flywheel.stopFlywheel(); + collector.disableCollector(); + visionBox.updateBallColorConstants(); + } + + public void disabledPeriodic() { + // By invoking the stop method, each swerve module's set method will be invoked when the robot + // is disabled. + // This is important since it provides an opportunity for the absolute angle to be properly + // read and the seed angle to be fixed before starting auto. As long as the robot is running for + // at most 10 seconds, the angles will be correct. + drivetrain.stop(); + } + + private void configureAutoCommands() { + ProfiledPIDController thetaController = + new ProfiledPIDController( + AutoConstants.P_THETA_CONTROLLER, + 0, + 0, + AutoConstants.THETA_CONTROLLER_CONSTRAINTS, + LOOP_PERIOD_SECS); + thetaController.enableContinuousInput(-Math.PI, Math.PI); + + PathPlannerTrajectory autoBlue01Path = + PathPlanner.loadPath( + "Blue0(1)", + AutoConstants.MAX_SPEED_METERS_PER_SECOND, + AutoConstants.MAX_ACCELERATION_METERS_PER_SECOND_SQUARED); + PathPlannerTrajectory autoBlue02Path = + PathPlanner.loadPath( + "Blue0(2)", + AutoConstants.MAX_SPEED_METERS_PER_SECOND, + AutoConstants.MAX_ACCELERATION_METERS_PER_SECOND_SQUARED); + Command autoOneBall = + new SequentialCommandGroup( + new FollowPath(autoBlue01Path, thetaController, drivetrain, true), + createAutoShootCommandSequence(FlywheelConstants.WALL_SHOT_VELOCITY, 2), + new FollowPath(autoBlue02Path, thetaController, drivetrain, false)); + + PathPlannerTrajectory autoBlue11Path = + PathPlanner.loadPath( + "Blue1(1)", + AutoConstants.MAX_SPEED_METERS_PER_SECOND, + AutoConstants.MAX_ACCELERATION_METERS_PER_SECOND_SQUARED); + PathPlannerTrajectory autoBlue12Path = + PathPlanner.loadPath( + "Blue1(2)", + AutoConstants.MAX_SPEED_METERS_PER_SECOND, + AutoConstants.MAX_ACCELERATION_METERS_PER_SECOND_SQUARED); + Command autoTwoBallSteal = + new SequentialCommandGroup( + new InstantCommand(() -> collector.enableCollector(), collector), + new FollowPath(autoBlue11Path, thetaController, drivetrain, true), + new WaitCommand(5.0), + createAutoShootCommandSequence(FlywheelConstants.WALL_SHOT_VELOCITY, 2), + new ParallelDeadlineGroup( + new FollowPath(autoBlue12Path, thetaController, drivetrain, false), + new SortStorageCommand(storage)), + new SequentialCommandGroup( + new ParallelCommandGroup( + new InstantCommand(() -> collector.disableCollector(), collector), + new SetFlywheelVelocityCommand( + flywheel, FlywheelConstants.SHOOT_STEAL_VELOCITY)), + new InstantCommand(() -> storage.enableStorage(), storage), + new WaitCommand(15))); + + Command autoTwoBall = + new SequentialCommandGroup( + new InstantCommand(() -> collector.enableCollector(), collector), + new FollowPath(autoBlue11Path, thetaController, drivetrain, true), + new WaitCommand(5.0), + createAutoShootCommandSequence(FlywheelConstants.WALL_SHOT_VELOCITY, 15)); + + PathPlannerTrajectory autoBlue2Path = + PathPlanner.loadPath( + "Blue2(1)", + AutoConstants.MAX_SPEED_METERS_PER_SECOND, + AutoConstants.MAX_ACCELERATION_METERS_PER_SECOND_SQUARED); + Command autoTwoBallAlt = + new SequentialCommandGroup( + new InstantCommand(() -> collector.enableCollector(), collector), + new FollowPath(autoBlue2Path, thetaController, drivetrain, true), + new InstantCommand(() -> collector.disableCollector(), collector), + createAutoShootCommandSequence(FlywheelConstants.WALL_SHOT_VELOCITY, 15)); + + // 5 ball auto (shoot 2; shoot 3 (with bowling)) + PathPlannerTrajectory autoBlue31Path = + PathPlanner.loadPath( + "Blue3(1)", + AutoConstants.MAX_SPEED_METERS_PER_SECOND, + AutoConstants.MAX_ACCELERATION_METERS_PER_SECOND_SQUARED); + PathPlannerTrajectory autoBlue32Path = + PathPlanner.loadPath( + "Blue3(2)", + AutoConstants.MAX_SPEED_METERS_PER_SECOND, + AutoConstants.MAX_ACCELERATION_METERS_PER_SECOND_SQUARED); + PathPlannerTrajectory autoBlue33Path = + PathPlanner.loadPath( + "Blue3(3)", + AutoConstants.MAX_SPEED_METERS_PER_SECOND, + AutoConstants.MAX_ACCELERATION_METERS_PER_SECOND_SQUARED); + Command autoFiveBall = + new SequentialCommandGroup( + new ParallelCommandGroup( + new InstantCommand(() -> collector.enableCollector(), collector), + new InstantCommand( + () -> flywheel.setVelocity(FlywheelConstants.NEAR_WALL_SHOT_VELOCITY), + flywheel)), + new WaitCommand(0.5), + new FollowPath(autoBlue31Path, thetaController, drivetrain, true), + createAutoShootNoAimCommandSequence(FlywheelConstants.NEAR_WALL_SHOT_VELOCITY, 2), + new ParallelDeadlineGroup( + new FollowPath(autoBlue32Path, thetaController, drivetrain, false), + new SortStorageCommand(storage)), + new ParallelCommandGroup( + new InstantCommand( + () -> flywheel.setVelocity(FlywheelConstants.LAUNCH_PAD_VELOCITY), flywheel), + new FollowPath(autoBlue33Path, thetaController, drivetrain, false)), + limelightCreateAutoShootCommandSequence(15)); + + // 5-ball auto (shoot 2, shoot 1, shoot 2 (no bowling)) + PathPlannerTrajectory autoBlue41Path = + PathPlanner.loadPath( + "Blue4(1)", + AutoConstants.MAX_SPEED_METERS_PER_SECOND, + AutoConstants.MAX_ACCELERATION_METERS_PER_SECOND_SQUARED); + PathPlannerTrajectory autoBlue42Path = + PathPlanner.loadPath( + "Blue4(2)", + AutoConstants.MAX_SPEED_METERS_PER_SECOND, + AutoConstants.MAX_ACCELERATION_METERS_PER_SECOND_SQUARED); + PathPlannerTrajectory autoBlue43Path = + PathPlanner.loadPath( + "Blue4(3)", + AutoConstants.MAX_SPEED_METERS_PER_SECOND, + AutoConstants.MAX_ACCELERATION_METERS_PER_SECOND_SQUARED); + PathPlannerTrajectory autoBlue44Path = + PathPlanner.loadPath( + "Blue4(4)", + AutoConstants.MAX_SPEED_METERS_PER_SECOND, + AutoConstants.MAX_ACCELERATION_METERS_PER_SECOND_SQUARED); + Command autoFiveBallAlt = + new SequentialCommandGroup( + new ParallelCommandGroup( + new InstantCommand(() -> collector.enableCollector(), collector), + new InstantCommand( + () -> flywheel.setVelocity(FlywheelConstants.WALL_SHOT_VELOCITY), flywheel)), + new WaitCommand(0.5), + new FollowPath(autoBlue41Path, thetaController, drivetrain, true), + limelightCreateAutoShootCommandSequence(2), + new ParallelDeadlineGroup( + new FollowPath(autoBlue42Path, thetaController, drivetrain, false), + new SortStorageCommand(storage)), + limelightCreateAutoShootCommandSequence(2), + new FollowPath(autoBlue43Path, thetaController, drivetrain, false), + new InstantCommand(() -> drivetrain.stop()), + new ParallelDeadlineGroup(new WaitCommand(2), new SortStorageCommand(storage)), + new ParallelCommandGroup( + new InstantCommand( + () -> flywheel.setVelocity(FlywheelConstants.LAUNCH_PAD_VELOCITY), flywheel), + new FollowPath(autoBlue44Path, thetaController, drivetrain, false)), + limelightCreateAutoShootCommandSequence(5)); + + ShuffleboardTab tab = Shuffleboard.getTab("MAIN"); + chooser.addOption("1 Ball", autoOneBall); + chooser.addOption("2 Ball & Steal", autoTwoBallSteal); + chooser.addOption("2 Ball", autoTwoBall); + chooser.addOption("Alt 2 Ball", autoTwoBallAlt); + chooser.addOption("Main 5 Ball", autoFiveBall); + chooser.addOption("Alt 5 Ball", autoFiveBallAlt); + tab.add("Auto Mode", chooser); + } + + private Command createShootCommandSequence(int shotVelocity) { + return new SequentialCommandGroup( + new ParallelCommandGroup( + new InstantCommand(() -> collector.disableCollector(), collector), + new SetFlywheelVelocityCommand(flywheel, shotVelocity), + new SequentialCommandGroup( + new LimelightAlignWithGyroCommand(drivetrain), + new InstantCommand(() -> drivetrain.enableXstance(), drivetrain))), + new InstantCommand(() -> storage.enableStorage(), storage), + new WaitForShotCommand(storage, flywheel, drivetrain)); + } + + private Command createLimelightShootCommandSequence(boolean useGyro) { + return new SequentialCommandGroup( + new ParallelCommandGroup( + new InstantCommand(() -> collector.disableCollector(), collector), + new LimelightSetFlywheelVelocityCommand(flywheel, drivetrain), + new SequentialCommandGroup( + (useGyro + ? new LimelightAlignWithGyroCommand(drivetrain) + : new LimelightAlignToTargetCommand(drivetrain)), + new InstantCommand(() -> drivetrain.enableXstance(), drivetrain))), + new InstantCommand(() -> storage.enableStorage(), storage), + new WaitForShotCommand(storage, flywheel, drivetrain)); + } + + private Command createAutoShootCommandSequence(int shotVelocity, double shotDelay) { + return new SequentialCommandGroup( + new ParallelCommandGroup( + new SetFlywheelVelocityCommand(flywheel, shotVelocity), + new LimelightAlignWithGyroCommand(drivetrain)), + new InstantCommand(() -> storage.enableStorage(), storage), + new WaitCommand(shotDelay), + new ParallelCommandGroup( + new InstantCommand(() -> flywheel.stopFlywheel(), flywheel), + new InstantCommand(() -> storage.disableStorage(), storage))); + } + + private Command createAutoShootNoAimCommandSequence(int shotVelocity, double shotDelay) { + return new SequentialCommandGroup( + new SetFlywheelVelocityCommand(flywheel, shotVelocity), + new InstantCommand(() -> storage.enableStorage(), storage), + new WaitCommand(shotDelay), + new ParallelCommandGroup( + new InstantCommand(() -> flywheel.stopFlywheel(), flywheel), + new InstantCommand(() -> storage.disableStorage(), storage))); + } + + private Command limelightCreateAutoShootCommandSequence(double shotDelay) { + return new SequentialCommandGroup( + new ParallelCommandGroup( + new LimelightSetFlywheelVelocityCommand(flywheel, drivetrain), + new LimelightAlignWithGyroCommand(drivetrain)), + new InstantCommand(() -> storage.enableStorage(), storage), + new WaitCommand(shotDelay), + new ParallelCommandGroup( + new InstantCommand(() -> flywheel.stopFlywheel(), flywheel), + new InstantCommand(() -> storage.disableStorage(), storage))); + } + + private static double deadband(double value, double deadband) { + if (Math.abs(value) > deadband) { + if (value > 0.0) { + return (value - deadband) / (1.0 - deadband); + } else { + return (value + deadband) / (1.0 - deadband); + } + } else { + return 0.0; + } + } + + /** + * Squares the specified value, while preserving the sign. This method is used on all joystick + * inputs. This is useful as a non-linear range is more natural for the driver. + * + * @param value + * @return + */ + public static double modifyAxis(double value) { + // Deadband + value = deadband(value, 0.1); + + // Square the axis + value = Math.copySign(value * value, value); + + return value; + } +} diff --git a/src/main/java/frc/robot/commands/DefaultDriveCommand.java b/src/main/java/frc/robot/commands/DefaultDriveCommand.java new file mode 100644 index 0000000..40ebfb4 --- /dev/null +++ b/src/main/java/frc/robot/commands/DefaultDriveCommand.java @@ -0,0 +1,66 @@ +package frc.robot.commands; + +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.subsystems.drivetrain.Drivetrain; +import java.util.function.DoubleSupplier; + +/** + * A single instance of this command should be created in the RobotContainer class and initialized + * with the joystick inputs as the suppliers. As a default command, this command will be scheduled + * whenever no other commands that require the drivetrain subsystem are scheduled. + * + *

Requires: the Drivetrain subsystem. + * + *

Finished When: never unless interrupted + * + *

At End: stops the drivetrain + */ +public class DefaultDriveCommand extends CommandBase { + private final Drivetrain drivetrain; + private final DoubleSupplier translationXSupplier; + private final DoubleSupplier translationYSupplier; + private final DoubleSupplier rotationSupplier; + + /** + * Construct a new DefaultDriveCommand object. + * + * @param drivetrain the Drivetrain subsystem required by this command + * @param translationXSupplier supplies the desired velocity in the x direction (m/s) + * @param translationYSupplier supplies the desired velocity in the y direction (m/s) + * @param rotationSupplier supplies the desried rotational velocity (m/s) + */ + public DefaultDriveCommand( + Drivetrain drivetrain, + DoubleSupplier translationXSupplier, + DoubleSupplier translationYSupplier, + DoubleSupplier rotationSupplier) { + this.drivetrain = drivetrain; + this.translationXSupplier = translationXSupplier; + this.translationYSupplier = translationYSupplier; + this.rotationSupplier = rotationSupplier; + + addRequirements(this.drivetrain); + } + + /** + * This method will be invoked every iteration of the Command Scheduler. This method should only + * invoke the drive method on the Drivetrain subsystem. Any other logic needs to be in the drive + * method as this method is only one of several methods that invoke the drive method. + */ + @Override + public void execute() { + drivetrain.drive( + translationXSupplier.getAsDouble(), + translationYSupplier.getAsDouble(), + rotationSupplier.getAsDouble()); + } + + /** + * This method will be invoked when this command is interrupted. The stop method of the Drivetrain + * subsystem needs to be invoked or else the robot will continue to move. + */ + @Override + public void end(boolean interrupted) { + drivetrain.stop(); + } +} diff --git a/src/main/java/frc/robot/commands/ExtendClimberToLowRungCommand.java b/src/main/java/frc/robot/commands/ExtendClimberToLowRungCommand.java new file mode 100644 index 0000000..1f474ba --- /dev/null +++ b/src/main/java/frc/robot/commands/ExtendClimberToLowRungCommand.java @@ -0,0 +1,60 @@ +package frc.robot.commands; + +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.Constants.ElevatorConstants; +import frc.robot.subsystems.elevator.Elevator; + +/** + * This command, when executed, extends the climber slightly above the low rung in preparation to + * climb the low rung. + * + *

Requires: the Elevator subsystem + * + *

Finished When: the climber is positioned slightly above the low rung + * + *

At End: stops the elevator + */ +public class ExtendClimberToLowRungCommand extends CommandBase { + private final Elevator elevator; + + /** + * Constructs a new ExtendClimberToLowRungCommand object. + * + * @param subsystem the elevator subsystem this command will control + */ + public ExtendClimberToLowRungCommand(Elevator subsystem) { + elevator = subsystem; + addRequirements(elevator); + } + + /** + * This method is invoked once when this command is scheduled. It sets the setpoint of the + * elevator position to slightly above the low rung. It is critical that this initialization + * occurs in this method and not the constructor as this command is constructed once when the + * RobotContainer is created, but this method is invoked each time this command is scheduled. + */ + @Override + public void initialize() { + elevator.setElevatorMotorPosition(ElevatorConstants.LOW_RUNG_HEIGHT, true); + } + + /** + * This method will be invoked when this command finishes or is interrupted. It stops the motion + * of the elevator. + * + * @param interrupted true if the command was interrupted by another command being scheduled + */ + @Override + public void end(boolean interrupted) { + elevator.stopElevator(); + } + + /** + * This method is invoked at the end of each Command Scheduler iteration. It returns true when the + * elevator has reached the specified setpoint, which is slightly above the low rung. + */ + @Override + public boolean isFinished() { + return elevator.atSetpoint(); + } +} diff --git a/src/main/java/frc/robot/commands/ExtendClimberToMidRungCommand.java b/src/main/java/frc/robot/commands/ExtendClimberToMidRungCommand.java new file mode 100644 index 0000000..dc75e64 --- /dev/null +++ b/src/main/java/frc/robot/commands/ExtendClimberToMidRungCommand.java @@ -0,0 +1,60 @@ +package frc.robot.commands; + +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.Constants.ElevatorConstants; +import frc.robot.subsystems.elevator.Elevator; + +/** + * This command, when executed, extends the climber slightly above the mid rung in preparation to + * climb the mid rung. + * + *

Requires: the Elevator subsystem + * + *

Finished When: the climber is positioned slightly above the mid rung + * + *

At End: stops the elevator + */ +public class ExtendClimberToMidRungCommand extends CommandBase { + private final Elevator elevator; + + /** + * Constructs a new ExtendClimberToMidRungCommand object. + * + * @param subsystem the elevator subsystem this command will control + */ + public ExtendClimberToMidRungCommand(Elevator subsystem) { + elevator = subsystem; + addRequirements(elevator); + } + + /** + * This method is invoked once when this command is scheduled. It sets the setpoint of the + * elevator position to slightly above the mid rung. It is critical that this initialization + * occurs in this method and not the constructor as this command is constructed once when the + * RobotContainer is created, but this method is invoked each time this command is scheduled. + */ + @Override + public void initialize() { + elevator.setElevatorMotorPosition(ElevatorConstants.MID_RUNG_HEIGHT, true); + } + + /** + * This method will be invoked when this command finishes or is interrupted. It stops the motion + * of the elevator. + * + * @param interrupted true if the command was interrupted by another command being scheduled + */ + @Override + public void end(boolean interrupted) { + elevator.stopElevator(); + } + + /** + * This method is invoked at the end of each Command Scheduler iteration. It returns true when the + * elevator has reached the specified setpoint, which is slightly above the mid rung. + */ + @Override + public boolean isFinished() { + return elevator.atSetpoint(); + } +} diff --git a/src/main/java/frc/robot/commands/FollowPath.java b/src/main/java/frc/robot/commands/FollowPath.java new file mode 100644 index 0000000..37b1210 --- /dev/null +++ b/src/main/java/frc/robot/commands/FollowPath.java @@ -0,0 +1,94 @@ +package frc.robot.commands; + +import static frc.robot.Constants.*; + +import com.pathplanner.lib.PathPlannerTrajectory; +import com.pathplanner.lib.commands.PPSwerveControllerCommand; +import edu.wpi.first.math.controller.PIDController; +import edu.wpi.first.math.controller.ProfiledPIDController; +import frc.robot.subsystems.drivetrain.Drivetrain; + +/** + * This command, when executed, instructs the drivetrain subsystem to follow the specified + * trajectory, persumably during the autonomous period. The superclass' execute method invokes the + * drivetrain subsystem's setSwerveModuleStates method to follow the trajectory. + * + *

Requires: the Drivetrain subsystem (handled by superclass) + * + *

Finished When: the time of the specified path has elapsed (handled by superclass) + * + *

At End: stops the drivetrain + */ +public class FollowPath extends PPSwerveControllerCommand { + private ProfiledPIDController thetaController; + private Drivetrain drivetrain; + private PathPlannerTrajectory trajectory; + private boolean initialPath; + + /** + * Constructs a new FollowPath object. + * + * @param trajectory the specified trajectory created by PathPlanner + * @param thetaController the PID controller for the drivetrain's rotation + * @param subsystem the drivetrain subsystem required by this command + * @param initialPath true, if this trajectory is the first in a sequence of trajectories or the + * only trajector, in which case the gyro and odometry will be initialized to match the start + * of trajectory; false, if this trajectory is a subsequent trajectory in which case the gyro + * and odometry will not be re-initialized in order to ensure a smooth transition between + * trajectories + */ + public FollowPath( + PathPlannerTrajectory trajectory, + ProfiledPIDController thetaController, + Drivetrain subsystem, + boolean initialPath) { + super( + trajectory, + subsystem::getPose, + subsystem.getKinematics(), + new PIDController(AutoConstants.PX_CONTROLLER, 0, 0, LOOP_PERIOD_SECS), + new PIDController(AutoConstants.PY_CONTROLLER, 0, 0, LOOP_PERIOD_SECS), + thetaController, + subsystem::setSwerveModuleStates, + subsystem); + + this.thetaController = thetaController; + this.drivetrain = subsystem; + this.trajectory = trajectory; + this.initialPath = initialPath; + } + + /** + * This method is invoked once when this command is scheduled. If the trajectory is the first in a + * sequence of trajectories or the only trajector, initialize the gyro and odometry to match the + * start of trajectory. PathPlanner sets the origin of the field to the lower left corner (i.e., + * the corner of the field to the driver's right). Zero degrees is away from the driver and + * increases in the CCW direction. It is critical that this initialization occurs in this method + * and not the constructor as this object is constructed well before the command is scheduled. + */ + @Override + public void initialize() { + super.initialize(); + + if (initialPath) { + // reset odometry to the starting pose of the trajectory + this.drivetrain.resetOdometry(this.trajectory.getInitialState()); + } + + // reset the theta controller such that old accumuldated ID values aren't used with the new path + // this doesn't matter if only the P value is non-zero, which is the current behavior + this.thetaController.reset(this.drivetrain.getPose().getRotation().getRadians()); + } + + /** + * This method will be invoked when this command finishes or is interrupted. It stops the motion + * of the drivetrain. + * + * @param interrupted true if the command was interrupted by another command being scheduled + */ + @Override + public void end(boolean interrupted) { + this.drivetrain.stop(); + super.end(interrupted); + } +} diff --git a/src/main/java/frc/robot/commands/IndexSingleBallCommand.java b/src/main/java/frc/robot/commands/IndexSingleBallCommand.java new file mode 100644 index 0000000..55a34e9 --- /dev/null +++ b/src/main/java/frc/robot/commands/IndexSingleBallCommand.java @@ -0,0 +1,74 @@ +package frc.robot.commands; + +import static frc.robot.Constants.*; + +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.subsystems.storage.Storage; + +/** + * This command, when executed, runs the storage in the reverse direction to ensure that the + * collected cargo is not in contact with the flywheel. + * + *

Requires: the storage subsystem + * + *

Finished When: the command has executed for the desired number of iterations to ensure the + * cargo is not in contact with the flywheel + * + *

At End: stops the storage + */ +public class IndexSingleBallCommand extends CommandBase { + private Storage storage; + private int indexingDelayCount; + + /** + * Constructs a new IndexSingleBallCommand object. + * + * @param storage the storage subsystem required by this command + */ + public IndexSingleBallCommand(Storage storage) { + this.storage = storage; + this.addRequirements(this.storage); + } + + /** + * This method is invoked once when this command is scheduled. It sets teh motor of the storage to + * the outtake power and initializes the indexing delay counter. It is critical that this + * initialization occurs in this method and not the constructor as this command is constructed + * once when the RobotContainer is created, but this method is invoked each time this command is + * scheduled. + */ + @Override + public void initialize() { + indexingDelayCount = 0; + storage.setStoragePower(StorageConstants.OUTTAKE_POWER); + } + + /** + * This method will be invoked every iteration of the Command Scheduler. It repeatedly increments + * the indexing delay counter. + */ + @Override + public void execute() { + indexingDelayCount++; + } + + /** + * This method will be invoked when this command finishes or is interrupted. It stops the motion + * of the storage. + * + * @param interrupted true if the command was interrupted by another command being scheduled + */ + @Override + public void end(boolean interrupted) { + storage.disableStorage(); + } + + /** + * This method is invoked at the end of each Command Scheduler iteration. It returns true when + * this command has executed for the desired number of iterations. + */ + @Override + public boolean isFinished() { + return indexingDelayCount > StorageConstants.INDEXING_BACKWARD_DURATION; + } +} diff --git a/src/main/java/frc/robot/commands/LimelightAlignOnMoveCommand.java b/src/main/java/frc/robot/commands/LimelightAlignOnMoveCommand.java new file mode 100644 index 0000000..18c3f5e --- /dev/null +++ b/src/main/java/frc/robot/commands/LimelightAlignOnMoveCommand.java @@ -0,0 +1,171 @@ +package frc.robot.commands; + +import static frc.robot.Constants.*; + +import edu.wpi.first.math.controller.PIDController; +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.subsystems.collector.Collector; +import frc.robot.subsystems.drivetrain.Drivetrain; +import frc.robot.subsystems.flywheel.Flywheel; +import java.util.function.DoubleSupplier; + +/** + * This command, when executed, instructs the drivetrain subsystem to move based on the joystick + * inputs. If the hub is visible, the drivetrain will rotate to stay aimed at the hub; if not, the + * joystick input will control the rotation of the drivetrain. + * + *

Requires: the drivetrain and flywheel subsystems (the collector subsystem is not a requirement + * as it is not controlled and only queried for its current state) + * + *

Finished When: the drivetrain is aimed, the flywheel is at the specified speed, and the robot + * is within optimal shooting distance + * + *

At End: stops the drivetrain + */ +public class LimelightAlignOnMoveCommand extends CommandBase { + + private final PIDController controller; + private final Drivetrain drivetrain; + private final Flywheel flywheel; + private final Collector collector; + private final DoubleSupplier translationXSupplier; + private final DoubleSupplier translationYSupplier; + private final DoubleSupplier rotationSupplier; + + /** + * Constructs a new LimelightAlignOnMoveCommand object. + * + * @param drivetrain the drivetrain subsystem this command will control + * @param flywheel the flywheel subsystem this command will control + * @param collector the collector subsystem to query for its current state (not a requirement) + * @param translationXSupplier supplies the desired velocity in the x direction (m/s) + * @param translationYSupplier supplies the desired velocity in the y direction (m/s) + * @param rotationSupplier supplies the desried rotational velocity (m/s) + */ + public LimelightAlignOnMoveCommand( + Drivetrain drivetrain, + Flywheel flywheel, + Collector collector, + DoubleSupplier translationXSupplier, + DoubleSupplier translationYSupplier, + DoubleSupplier rotationSupplier) { + this.controller = + new PIDController( + DrivetrainConstants.LIMELIGHT_P, DrivetrainConstants.LIMELIGHT_I, 0, LOOP_PERIOD_SECS); + this.drivetrain = drivetrain; + this.flywheel = flywheel; + this.collector = collector; + this.translationXSupplier = translationXSupplier; + this.translationYSupplier = translationYSupplier; + this.rotationSupplier = rotationSupplier; + + addRequirements(drivetrain); + addRequirements(flywheel); + // don't add the storage as a requirement as we are only determining if cargo is indexed + } + + /** + * This method is invoked once when this command is scheduled. It resets the PID controller for + * the drivetrain rotation. It is critical that this initialization occurs in this method and not + * the constructor as this command is constructed once when the RobotContainer is created, but + * this method is invoked each time this command is scheduled. + */ + @Override + public void initialize() { + // critical to reset the PID controller each time this command is initialized to reset any + // accumulated values due to non-zero I or D values + controller.reset(); + + // delete this method + drivetrain.enableAutoAimAndShoot(); + } + + /** + * This method will be invoked every iteration of the Command Scheduler. It repeatedly instructs + * the drivetrain subsytem to move translationally while keeping aligned to the hub, if visible. + * If the hub is not visible, the joystick input controls the rotation of the drivetrain. + */ + @Override + public void execute() { + // the input to the rotational PID controller is the number of degrees between the rotation + // of the drivetrain and the center of the hub target + double output = controller.calculate(drivetrain.getLimelightX(), 0); + + // if the target is visible, try to aim with PID + if (drivetrain.isLimelightTargetVisible()) { + + // refer to this document for a detailed explanation of this algorithm: + // https://docs.google.com/document/d/1WtUOrvnbNTLbmrZ3Far-ipM_e6wJMzDyVqbghETleNs/edit + + // limelight offset angle in rad, left of camera is negative angle + double tx = Math.toRadians(drivetrain.getLimelightX()); + + // positive limelight distance in meters; add the distance from the limelight to the center of + // the robot + // and the distance for the retroreflective tape to the center of the hub before converting + // to meters + double d = + (drivetrain.getLimelightDistanceIn() + LimelightConstants.EDGE_TO_CENTER_HUB_DISTANCE) + * 0.0254; + + // assuming robot v is forward/left positive and in the direction of the collector + double dhdt = drivetrain.getVelocityX(); + double dldt = drivetrain.getVelocityY(); + double h = d * Math.cos(tx); // h is always positive + double l = -d * Math.sin(tx); // positive if the target is to the left of the robot + + double w = -(l * dhdt - h * dldt) / (d * d); // negative dtheta/dt, assuming positive ccw + + drivetrain.aim( + translationXSupplier.getAsDouble(), + translationYSupplier.getAsDouble(), + output + w // PID output (rad/s) + ); + + // only turn on the flywheel if there is a cargo indexed + if (!collector.isEnabled()) { + flywheel.setVelocity(drivetrain.getVelocityFromLimelight()); + } + + } + // if we can't see the target, the joystick controls the rotation + else { + // if we don't see the target, reset the PID controller for any accumulated values due + // to non-zero I or D values + controller.reset(); + + drivetrain.drive( + translationXSupplier.getAsDouble(), + translationYSupplier.getAsDouble(), + rotationSupplier.getAsDouble()); + } + } + + /** + * This method will be invoked when this command finishes or is interrupted. It stops the motion + * of the drivetrain. It does not stop the motion of the flywheel. + * + * @param interrupted true if the command was interrupted by another command being scheduled + */ + @Override + public void end(boolean interrupted) { + drivetrain.stop(); + drivetrain.disableAutoAimAndShoot(); + } + + /** + * This method is invoked at the end of each Command Scheduler iteration. It returns true when the + * drivetrain is aimed, the flywheel is at the specified speed, and the robot is within optimal + * shooting distance. + */ + @Override + public boolean isFinished() { + // shooter is aimed AND flywheel is at speed AND robot is within optimal shooting distance + return drivetrain.isLimelightTargetVisible() + && drivetrain.isAimed() + && flywheel.isAtSetpoint() + && (drivetrain.getLimelightDistanceIn() < LimelightConstants.AUTO_SHOT_HUB_FAR_DISTANCE + && drivetrain.getLimelightDistanceIn() + > LimelightConstants.AUTO_SHOT_HUB_CLOSE_DISTANCE); + } +} diff --git a/src/main/java/frc/robot/commands/LimelightAlignToTargetCommand.java b/src/main/java/frc/robot/commands/LimelightAlignToTargetCommand.java new file mode 100644 index 0000000..aca374a --- /dev/null +++ b/src/main/java/frc/robot/commands/LimelightAlignToTargetCommand.java @@ -0,0 +1,63 @@ +package frc.robot.commands; + +import static frc.robot.Constants.*; + +import edu.wpi.first.math.controller.PIDController; +import edu.wpi.first.wpilibj2.command.PIDCommand; +import frc.robot.subsystems.drivetrain.Drivetrain; + +/** + * This command, when executed, instructs the drivetrain subsystem to rotate to aim at the hub. This + * command repeatedly uses the Limelight to aim. The superclass' execute method invokes the + * drivetrain subsystem's aim method to rotate the drivetrain. + * + *

Requires: the drivetrain subsystem (handled by the superclass) + * + *

Finished When: the shooter is aimed + * + *

At End: stops the drivetrain + */ +public class LimelightAlignToTargetCommand extends PIDCommand { + + private Drivetrain drivetrain; + + /** + * Constructs a new LimelightAlignToTargetCommand object. + * + * @param drivetrain the drivetrain subsystem this command will control + */ + public LimelightAlignToTargetCommand(Drivetrain drivetrain) { + // the input to the rotational PID controller is the number of degrees between the rotation + // of the drivetrain and the center of the hub target; the setpoint is 0 (aimed perfectly) + super( + new PIDController( + DrivetrainConstants.LIMELIGHT_P, DrivetrainConstants.LIMELIGHT_I, 0, LOOP_PERIOD_SECS), + drivetrain::getLimelightX, + 0, + output -> drivetrain.aim(0, 0, output), + drivetrain); + + this.drivetrain = drivetrain; + } + + /** + * This method will be invoked when this command finishes or is interrupted. It stops the motion + * of the drivetrain. + * + * @param interrupted true if the command was interrupted by another command being scheduled + */ + @Override + public void end(boolean interrupted) { + drivetrain.stop(); + super.end(interrupted); + } + + /** + * This method is invoked at the end of each Command Scheduler iteration. It returns true when the + * drivetrain is aimed based on the Limelight. + */ + @Override + public boolean isFinished() { + return drivetrain.isAimed(); + } +} diff --git a/src/main/java/frc/robot/commands/LimelightAlignWithGyroCommand.java b/src/main/java/frc/robot/commands/LimelightAlignWithGyroCommand.java new file mode 100644 index 0000000..b767669 --- /dev/null +++ b/src/main/java/frc/robot/commands/LimelightAlignWithGyroCommand.java @@ -0,0 +1,88 @@ +package frc.robot.commands; + +import static frc.robot.Constants.*; + +import edu.wpi.first.math.controller.PIDController; +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.subsystems.drivetrain.Drivetrain; + +/** + * This command, when executed, instructs the drivetrain subsystem to rotate to aim at the hub. This + * command initially uses the Limelight to determine the offset and then repeatedly uses the gyro to + * eliminate that initial offset. The advantage of this approach compared to using the Limelight + * repeatedly is that the Limelight has more noise than the gyro. + * + *

Requires: the drivetrain subsystem + * + *

Finished When: the shooter is aimed + * + *

At End: stops the drivetrain + */ +public class LimelightAlignWithGyroCommand extends CommandBase { + + private PIDController controller; + private Drivetrain drivetrain; + private double setpoint; + + /** + * Constructs a new LimelightAlignWithGyroCommand object. + * + * @param drivetrain the drivetrain subsystem this command will control + */ + public LimelightAlignWithGyroCommand(Drivetrain drivetrain) { + this.controller = + new PIDController( + DrivetrainConstants.LIMELIGHT_P, DrivetrainConstants.LIMELIGHT_I, 0, LOOP_PERIOD_SECS); + this.drivetrain = drivetrain; + + addRequirements(drivetrain); + } + + /** + * This method is invoked once when this command is scheduled. It resets the PID controller for + * the drivetrain rotation and determines the setpoint (in degrees) of the gyro based on the + * Limelight and the current gyro value. It is critical that this initialization occurs in this + * method and not the constructor as this command is constructed once when the RobotContainer is + * created, but this method is invoked each time this command is scheduled. + */ + @Override + public void initialize() { + controller.reset(); + double gyro = drivetrain.getGyroscopeRotation().getDegrees(); + double tx = drivetrain.getLimelightX(); + this.setpoint = gyro - tx; + drivetrain.setGyroSetpoint(this.setpoint); + } + + /** + * This method will be invoked every iteration of the Command Scheduler. It repeatedly obtains the + * rotational velocity from the PID controller and instructs the drivetrain subsytem to rotate to + * aligned to the hub. + */ + @Override + public void execute() { + double output = controller.calculate(drivetrain.getGyroscopeRotation().getDegrees(), setpoint); + + drivetrain.aim(0, 0, output); // PID output (rad/s) + } + + /** + * This method will be invoked when this command finishes or is interrupted. It stops the motion + * of the drivetrain. + * + * @param interrupted true if the command was interrupted by another command being scheduled + */ + @Override + public void end(boolean interrupted) { + drivetrain.stop(); + } + + /** + * This method is invoked at the end of each Command Scheduler iteration. It returns true when the + * drivetrain is aimed based on the gyro. + */ + @Override + public boolean isFinished() { + return drivetrain.isAimedWithGyro(); + } +} diff --git a/src/main/java/frc/robot/commands/LimelightSetFlywheelVelocityCommand.java b/src/main/java/frc/robot/commands/LimelightSetFlywheelVelocityCommand.java new file mode 100644 index 0000000..0ee32fa --- /dev/null +++ b/src/main/java/frc/robot/commands/LimelightSetFlywheelVelocityCommand.java @@ -0,0 +1,53 @@ +package frc.robot.commands; + +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.subsystems.drivetrain.Drivetrain; +import frc.robot.subsystems.flywheel.Flywheel; + +/** + * This command, when executed, instructs the flywheel subsystem to spin the flywheel at a velocity + * based on the distance from the robot to the hub as determined by the Limelight. It does not stop + * the flywheel when it ends as it is intended to be used as part of sequence of commands and will + * be followed by a command to shoot the cargo. + * + *

Requires: the flywheel subsystem (the drivetrain subsystem is not required as it is only + * queried to get the distance to the hub) + * + *

Finished When: the flywheel velocity is at the setpoint + * + *

At End: leaves the flywheel spinning + */ +public class LimelightSetFlywheelVelocityCommand extends CommandBase { + private Flywheel flywheel; + private Drivetrain drivetrain; + + /** + * Constructs a new LimelightAlignWithGyroCommand object. + * + * @param flywheel the flywheel subsystem this command will control + * @param drivetrainSubsystem the drivetrain subsystem used to get the distance to the hub + */ + public LimelightSetFlywheelVelocityCommand(Flywheel flywheel, Drivetrain drivetrainSubsystem) { + this.flywheel = flywheel; + this.drivetrain = drivetrainSubsystem; + addRequirements(this.flywheel); + } + + /** + * This method will be invoked every iteration of the Command Scheduler. It repeatedly sets the + * setpoint of the flywheel velocity to the desired velocity. + */ + @Override + public void execute() { + flywheel.setVelocity(this.drivetrain.getVelocityFromLimelight()); + } + + /** + * This method is invoked at the end of each Command Scheduler iteration. It returns true when the + * velocity of the flywheel has reached the specified setpoint. + */ + @Override + public boolean isFinished() { + return flywheel.isAtSetpoint(); + } +} diff --git a/src/main/java/frc/robot/commands/ReachToNextRungWithPitchCommand.java b/src/main/java/frc/robot/commands/ReachToNextRungWithPitchCommand.java new file mode 100644 index 0000000..7e91fa4 --- /dev/null +++ b/src/main/java/frc/robot/commands/ReachToNextRungWithPitchCommand.java @@ -0,0 +1,100 @@ +package frc.robot.commands; + +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.Constants.ElevatorConstants; +import frc.robot.subsystems.elevator.Elevator; +import frc.robot.subsystems.secondary_arm.SecondaryArm; + +/** + * This command, when executed, extends the climber below and slightly beyond the next rung (high or + * traverse). It uses the pitch of the robot to determine when the robot's swing is at a local + * minimum such that the climber will clear under the rung and not into or over it. This is + * essential such that the hooks are positioned properly to grab the rung. It is intended to be + * invoked when the climber is fully retracted and after the secondary arms are moved outward and + * before the climber is retracted the minimum amount to transfer to the next rung. + * + *

Requires: the elevator and secondary arm subsystems + * + *

Finished When: the climber is positioned slightly beyond the next rung + * + *

At End: stops the elevator + */ +public class ReachToNextRungWithPitchCommand extends CommandBase { + private final Elevator elevator; + private final SecondaryArm secondaryArm; + private boolean startedFinalExtension; + + /** + * Constructs a new ReachToNextRungWithPitchCommand object. + * + * @param elevator the elevator subsystem this command will control + * @param secondaryArm the secondary arm subsystem this command will control + */ + public ReachToNextRungWithPitchCommand(Elevator elevator, SecondaryArm secondaryArm) { + this.elevator = elevator; + this.secondaryArm = secondaryArm; + addRequirements(elevator); + addRequirements(secondaryArm); + } + + /** + * This method is invoked once when this command is scheduled. It initializes the state variable + * that tracks if cimber has started moving under the rung. It is critical that this + * initialization occurs in this method and not the constructor as this command is constructed + * once when the RobotContainer is created, but this method is invoked each time this command is + * scheduled. + */ + @Override + public void initialize() { + this.startedFinalExtension = false; + } + + /** + * This method will be invoked every iteration of the Command Scheduler. It repeatedly checks if + * the climber is near the next rung. If it is, and if the robot's swing is at a local minimum, it + * extends under and slightly beyond the rung. If the climber is near the next rung, but not at a + * local minimum, it stops the climber until it is. + */ + @Override + public void execute() { + // it may be more efficient to only invoke setElevatorMotorPosition in the initialize + // method instead of repeatedly in this method as well as the following line of code + elevator.setElevatorMotorPosition(ElevatorConstants.REACH_TO_NEXT_RUNG_HEIGHT, true); + + // if the robot has been transferred from the elevator to secondary arms, move the + // secondary arms in to dampen the swing + secondaryArm.moveSecondaryArmIn(); + + if (elevator.isApproachingNextRung()) { + if (elevator.isNearLocalMinimum()) { + this.startedFinalExtension = true; + elevator.setElevatorMotorPosition(ElevatorConstants.REACH_TO_NEXT_RUNG_HEIGHT, true); + } + // once the elevator has started extending under the next rung, don't stop it based on + // the robot's swing + else if (!this.startedFinalExtension) { + elevator.stopElevator(); + } + } + } + + /** + * This method will be invoked when this command finishes or is interrupted. It stops the motion + * of the elevator. + * + * @param interrupted true if the command was interrupted by another command being scheduled + */ + @Override + public void end(boolean interrupted) { + elevator.stopElevator(); + } + + /** + * This method is invoked at the end of each Command Scheduler iteration. It returns true when the + * elevator has reached the specified setpoint, which is slightly beyond the next rung. + */ + @Override + public boolean isFinished() { + return elevator.atSetpoint(); + } +} diff --git a/src/main/java/frc/robot/commands/RetractClimberFullCommand.java b/src/main/java/frc/robot/commands/RetractClimberFullCommand.java new file mode 100644 index 0000000..1c2ff2b --- /dev/null +++ b/src/main/java/frc/robot/commands/RetractClimberFullCommand.java @@ -0,0 +1,59 @@ +package frc.robot.commands; + +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.Constants.ElevatorConstants; +import frc.robot.subsystems.elevator.Elevator; + +/** + * This command, when executed, retracts the climber completely. + * + *

Requires: the elevator subsystem + * + *

Finished When: the climber is fully retracted + * + *

At End: stops the elevator + */ +public class RetractClimberFullCommand extends CommandBase { + private final Elevator elevator; + + /** + * Constructs a new RetractClimberFullCommand object. + * + * @param elevator the elevator subsystem this command will control + */ + public RetractClimberFullCommand(Elevator elevator) { + this.elevator = elevator; + addRequirements(elevator); + } + + /** + * This method is invoked once when this command is scheduled. It sets the setpoint of the + * elevator position to the fully retracted position. It is critical that this initialization + * occurs in this method and not the constructor as this command is constructed once when the + * RobotContainer is created, but this method is invoked each time this command is scheduled. + */ + @Override + public void initialize() { + elevator.setElevatorMotorPosition(ElevatorConstants.MIN_ELEVATOR_ENCODER_HEIGHT, true); + } + + /** + * This method will be invoked when this command finishes or is interrupted. It stops the motion + * of the elevator. + * + * @param interrupted true if the command was interrupted by another command being scheduled + */ + @Override + public void end(boolean interrupted) { + elevator.stopElevator(); + } + + /** + * This method is invoked at the end of each Command Scheduler iteration. It returns true when the + * elevator has reached the specified setpoint, which is fully retracted. + */ + @Override + public boolean isFinished() { + return elevator.atSetpoint(); + } +} diff --git a/src/main/java/frc/robot/commands/RetractClimberMinimumCommand.java b/src/main/java/frc/robot/commands/RetractClimberMinimumCommand.java new file mode 100644 index 0000000..b27b1f7 --- /dev/null +++ b/src/main/java/frc/robot/commands/RetractClimberMinimumCommand.java @@ -0,0 +1,62 @@ +package frc.robot.commands; + +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.subsystems.elevator.Elevator; + +/** + * This command, when executed, retracts the climber just enough to pull the secondary arms off of + * the previous rung such that the robot is transferred to the next rung. + * + *

Requires: the elevator subsystem + * + *

Finished When: the climber reaches the specified position + * + *

At End: stops the elevator + */ +public class RetractClimberMinimumCommand extends CommandBase { + private final Elevator elevator; + private double encoderSetpoint; + + /** + * Constructs a new RetractClimberMinimumCommand object. + * + * @param setpoint the desired position of the elevator in units of encoder ticks + * @param elevator the elevator subsystem this command will control + */ + public RetractClimberMinimumCommand(double setpoint, Elevator elevator) { + this.elevator = elevator; + this.encoderSetpoint = setpoint; + addRequirements(elevator); + } + + /** + * This method is invoked once when this command is scheduled. It sets the setpoint of the + * elevator position to specified value. It is critical that this initialization occurs in this + * method and not the constructor as this command is constructed once when the RobotContainer is + * created, but this method is invoked each time this command is scheduled. + */ + @Override + public void initialize() { + elevator.setElevatorMotorPosition(encoderSetpoint, true); + } + + /** + * This method will be invoked when this command finishes or is interrupted. It stops the motion + * of the elevator. + * + * @param interrupted true if the command was interrupted by another command being scheduled + */ + @Override + public void end(boolean interrupted) { + elevator.stopElevator(); + } + + /** + * This method is invoked at the end of each Command Scheduler iteration. It returns true when the + * elevator has reached the specified setpoint. + */ + @Override + public boolean isFinished() { + return elevator.atSetpoint(); + } +} diff --git a/src/main/java/frc/robot/commands/SetFlywheelVelocityCommand.java b/src/main/java/frc/robot/commands/SetFlywheelVelocityCommand.java new file mode 100644 index 0000000..df7e949 --- /dev/null +++ b/src/main/java/frc/robot/commands/SetFlywheelVelocityCommand.java @@ -0,0 +1,52 @@ +package frc.robot.commands; + +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.subsystems.flywheel.Flywheel; + +/** + * This command, when executed, instructs the flywheel subsystem to spin the flywheel at the + * specified velocity. It does not stop the flywheel when it ends as it is intended to be used as + * part of sequence of commands and will be followed by a command to shoot the cargo. + * + *

Requires: the flywheel subsystem + * + *

Finished When: the flywheel velocity is at the setpoint + * + *

At End: leaves the flywheel spinning + */ +public class SetFlywheelVelocityCommand extends CommandBase { + private Flywheel flywheel; + private double velocity; + + /** + * Constructs a new SetFlywheelVelocityCommand object. + * + * @param flywheel the flywheel subsystem this command will control + * @param velocity the velocity setpoint in units of encoder ticks per 100 ms + */ + public SetFlywheelVelocityCommand(Flywheel flywheel, double velocity) { + this.flywheel = flywheel; + this.velocity = velocity; + addRequirements(this.flywheel); + } + + /** + * This method is invoked once when this command is scheduled. It sets the setpoint of the + * flywheel velocity to the desired velocity. It is critical that this initialization occurs in + * this method and not the constructor as this command is constructed once when the RobotContainer + * is created, but this method is invoked each time this command is scheduled. + */ + @Override + public void initialize() { + flywheel.setVelocity(this.velocity); + } + + /** + * This method is invoked at the end of each Command Scheduler iteration. It returns true when the + * velocity of the flywheel has reached the specified setpoint. + */ + @Override + public boolean isFinished() { + return flywheel.isAtSetpoint(); + } +} diff --git a/src/main/java/frc/robot/commands/SortStorageCommand.java b/src/main/java/frc/robot/commands/SortStorageCommand.java new file mode 100644 index 0000000..03a8783 --- /dev/null +++ b/src/main/java/frc/robot/commands/SortStorageCommand.java @@ -0,0 +1,102 @@ +package frc.robot.commands; + +import static frc.robot.Constants.*; + +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.subsystems.storage.Storage; + +/** + * This command, when executed, instructs the storage subsystem to run its belt until cargo is + * detected at the shooter-end of the storage at which point it continues to run the belt for a + * period of time in the intake direction to ensure the cargo is positioned against the flywheel. + * After that it runs the belt in the outtake direction in order to move it away from the flywheel + * such that when the flywheel begins spinning the cargo will not be inadvertantly shot. + * + *

Requires: the storage subsystem + * + *

Finished When: the flywheel velocity is at the setpoint + * + *

At End: leaves the flywheel spinning + */ +public class SortStorageCommand extends CommandBase { + private Storage storage; + private int indexingDelayCount; + + /** + * Constructs a new SortStorageCommand object. + * + * @param storage the storage subsystem this command will control + */ + public SortStorageCommand(Storage storage) { + this.storage = storage; + this.addRequirements(this.storage); + } + + /** + * This method is invoked once when this command is scheduled. It initializes the indexing delay + * counter. It is critical that this initialization occurs in this method and not the constructor + * as this command is constructed once when the RobotContainer is created, but this method is + * invoked each time this command is scheduled. + */ + @Override + public void initialize() { + indexingDelayCount = 0; + } + + /** + * This method will be invoked every iteration of the Command Scheduler. + * + *

If cargo is detected at the collector end of the storage and not at the shooter end, it runs + * the storage belt in the intake direction. + * + *

If cargo is detected at the shooter end of the storage, it continues to run the storage in + * the intake direction for the desired number of iterations. After that, it reverses the + * direction of the storage belt for the desired number of iterations. After that, it stops the + * storage belt. + */ + @Override + public void execute() { + if (!this.storage.isShooterSensorUnblocked()) { + indexingDelayCount++; + if (indexingDelayCount == 1) { + this.storage.enableStorage(); + } + if (indexingDelayCount == StorageConstants.INDEXING_FORWARD_DELAY) { + this.storage.setStoragePower(StorageConstants.OUTTAKE_POWER); + } else if (indexingDelayCount + > StorageConstants.INDEXING_FORWARD_DELAY + StorageConstants.INDEXING_BACKWARD_DURATION) { + this.storage.disableStorage(); + } + } else if (!this.storage.isCollectorSensorUnblocked() + && this.storage.isShooterSensorUnblocked()) { + this.storage.enableStorage(); + indexingDelayCount = 0; + } + } + + /** + * This method will be invoked when this command finishes or is interrupted. It stops the motion + * of the storage. + * + * @param interrupted true if the command was interrupted by another command being scheduled + */ + @Override + public void end(boolean interrupted) { + this.storage.disableStorage(); + } + + /** + * This method is invoked at the end of each Command Scheduler iteration. It returns true when + * cargo is detected at both the shooter and collector end of the storage and the indexing of the + * cargo at the shooter end has completed. It is critical that this command doesn't finish until + * the indexing is compelte or else the cargo may still be touching the flywheel and then + * inadvertantly shot. + */ + @Override + public boolean isFinished() { + return !this.storage.isCollectorSensorUnblocked() + && !this.storage.isShooterSensorUnblocked() + && indexingDelayCount + > StorageConstants.INDEXING_FORWARD_DELAY + StorageConstants.INDEXING_BACKWARD_DURATION; + } +} diff --git a/src/main/java/frc/robot/commands/VisionBoxCollectBallCommand.java b/src/main/java/frc/robot/commands/VisionBoxCollectBallCommand.java new file mode 100644 index 0000000..a697f83 --- /dev/null +++ b/src/main/java/frc/robot/commands/VisionBoxCollectBallCommand.java @@ -0,0 +1,261 @@ +package frc.robot.commands; + +import edu.wpi.first.math.controller.ProfiledPIDController; +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.geometry.Transform2d; +import edu.wpi.first.math.geometry.Translation2d; +import edu.wpi.first.math.trajectory.TrapezoidProfile; +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.Constants.*; +import frc.robot.subsystems.VisionBox; +import frc.robot.subsystems.collector.Collector; +import frc.robot.subsystems.drivetrain.Drivetrain; +import frc.robot.subsystems.storage.Storage; + +/** + * This command, when executed, instructs the drivetrain subsystem to move based on the vision box's + * outputs. It utilises 3 PID controllers, two for vertical and horizontal translation and one for + * rotational, to align the robot to a cargo and collect it. + * + *

Requires: the drivetrain and collector subsystems Finished When: the robot intakes a cargo At + * End: stops the drivetrain and retracts the intake + */ +public class VisionBoxCollectBallCommand extends CommandBase { + + private ProfiledPIDController xTranslationController; + private ProfiledPIDController yTranslationController; + private ProfiledPIDController rotationalController; + private Drivetrain drivetrainSubsystem; + private Collector collectorSubsystem; + private Storage storageSubsystem; + private VisionBox visionBoxSubsystem; + private Pose2d ballPose; + private boolean initializationFailed; + private int ticksWithoutBall; + private int startingCargoCount; + private boolean initialFieldRelativeState; + + public VisionBoxCollectBallCommand( + VisionBox visionBox, Drivetrain drivetrain, Collector collector, Storage storage) { + // X,Y and angle are all in robot-relative coordinate system (x is forwards and backwards, y is + // side to side, +angle is counterclockwise) + xTranslationController = + new ProfiledPIDController( + VisionBoxConstants.X_KP, + VisionBoxConstants.X_KI, + VisionBoxConstants.X_KD, + new TrapezoidProfile.Constraints( + VisionBoxConstants.X_MAX_VELOCITY, VisionBoxConstants.X_MAX_ACCELERATION)); + yTranslationController = + new ProfiledPIDController( + VisionBoxConstants.Y_KP, + VisionBoxConstants.Y_KI, + VisionBoxConstants.Y_KD, + new TrapezoidProfile.Constraints( + VisionBoxConstants.Y_MAX_VELOCITY, VisionBoxConstants.Y_MAX_ACCELERATION)); + rotationalController = + new ProfiledPIDController( + VisionBoxConstants.ROTATIONAL_KP, + VisionBoxConstants.ROTATIONAL_KI, + 0, + new TrapezoidProfile.Constraints( + VisionBoxConstants.ROTATIONAL_MAX_VELOCITY, + VisionBoxConstants.ROTATIONAL_MAX_ACCELERATION)); + + drivetrainSubsystem = drivetrain; + collectorSubsystem = collector; + storageSubsystem = storage; + visionBoxSubsystem = visionBox; + + addRequirements(drivetrainSubsystem); + addRequirements(collectorSubsystem); + } + + /** + * This method is invoked once when this command is scheduled. It resets the PID controller for + * the drivetrain rotation. It is critical that this initialization occurs in this method and not + * the constructor as this command is constructed once when the RobotContainer is created, but + * this method is invoked each time this command is scheduled. + */ + @Override + public void initialize() { + visionBoxSubsystem.updateBallColorConstants(); + + // critical to reset the PID controllers each time this command is initialized to reset any + // accumulated values due to non-zero I or D values + xTranslationController.reset(new TrapezoidProfile.State(0, drivetrainSubsystem.getVelocityX())); + yTranslationController.reset(new TrapezoidProfile.State(0, drivetrainSubsystem.getVelocityY())); + rotationalController.reset( + new TrapezoidProfile.State(0, drivetrainSubsystem.getVelocityRotational())); + + // reset ticksWithoutBall + ticksWithoutBall = 0; + + // disable field relative drive + initialFieldRelativeState = drivetrainSubsystem.getFieldRelative(); + drivetrainSubsystem.disableFieldRelative(); + + // get first ball pose + Transform2d ballTransform = visionBoxSubsystem.getFirstBallTransform2d(); + initializationFailed = + ballTransform == null; // if the the first ball doesn't exist, fail starting the command + + if (initializationFailed) return; + // get the first ball Pose2d relative to the field + ballPose = drivetrainSubsystem.getPose().plus(ballTransform); + + // find the number of balls in the storage + startingCargoCount = storageSubsystem.getNumberOfCargoInStorage(); + } + + /** + * This method will be invoked every iteration of the Command Scheduler. It repeatedly instructs + * the drivetrain subsytem to move to the ideal location. Notably, it doesn't rely on visionBox to + * continue funcitoning, as a ball may blink out of view if it is covered by the intake + */ + @Override + public void execute() { + if (initializationFailed) return; + // calculate the ideal location to PID to, either the ball if the robot is aimed at it, or + // MINIMUM_UNAIMED_DISTANCE_METERS meters from the ball if it isn't. + Pose2d idealPose; + + // get the angle from the robot to the ball + Translation2d robotToBallTranslation = + (new Transform2d(drivetrainSubsystem.getPose(), ballPose)) + .getTranslation(); // the translation from the robot to the ball + double robotToBallAngle = + Math.atan2( + robotToBallTranslation.getY(), robotToBallTranslation.getX()); // TODO: verify this math + if (this.isAimed()) { + // the robot is aimed, so the ideal location is the furthest point from the robot on a circle + // OVERSHOOT_DISTANCE_METERS from the ball + Transform2d ballToIdealPoseTransform = + new Transform2d( + new Translation2d( + VisionBoxConstants.OVERSHOOT_DISTANCE_METERS, new Rotation2d(robotToBallAngle)), + new Rotation2d(0)); + idealPose = ballPose.plus(ballToIdealPoseTransform); + + // deploy the collector once we're aimed to the target + collectorSubsystem.enableCollector(); + } else { + // the robot isn't aimed, so the ideal location is the nearest point along a circle + // MINIMUM_UNAIMED_DISTANCE_METERS from the ball + // using the angle from the robot to the ball, create a new transform from the ball position + // translated -MINIMUM_UNAIMED_DISTANCE_METERS meters backwards towards the robot + Transform2d ballToIdealPoseTransform = + new Transform2d( + new Translation2d( + -VisionBoxConstants.MINIMUM_UNAIMED_DISTANCE_METERS, + new Rotation2d(robotToBallAngle)), + new Rotation2d(0)); + idealPose = ballPose.plus(ballToIdealPoseTransform); + } + + // find translation between the robot and the ideal pose relative to the robot + Transform2d distance = new Transform2d(drivetrainSubsystem.getPose(), idealPose); + + // calculate PIDs + double xOutput = + xTranslationController.calculate( + distance.getX(), + new TrapezoidProfile.State( + 0, + VisionBoxConstants + .X_MAX_VELOCITY)); // end moving at max velocity in the x direction + double yOutput = + yTranslationController.calculate( + distance.getY(), new TrapezoidProfile.State(0, 0)); // end without strafing + double rotationalOutput = + rotationalController.calculate( + robotToBallAngle, new TrapezoidProfile.State(0, 0)); // end without rotating + + // UNCOMMENT THIS IF THE ROBOT IS MOVING TOO QUICKLY WHEN "AIMING" + // final double UNAIMED_MOVEMENT_MULTIPLIER = .66; + // if (!isAimed()) { //if the robot isn't aimed, make it move really slowly as we don't trust + // horzontial angles too far from 0 deg + // xOutput *= UNAIMED_MOVEMENT_MULTIPLIER; + // yOutput *= UNAIMED_MOVEMENT_MULTIPLIER; + // } + + // drive the robot + drivetrainSubsystem.aim(xOutput, yOutput, rotationalOutput); + + // update the ball pose + Transform2d ballTransform = visionBoxSubsystem.getFirstBallTransform2d(); + + if (ballTransform != null) { // if a ball is found, check if it's the same ball + Pose2d newPose = drivetrainSubsystem.getPose().plus(ballTransform); + // find the distance between the new and old ball pose + double ballDisplacement = (new Transform2d(ballPose, newPose)).getTranslation().getNorm(); + + if (ballDisplacement + < ticksWithoutBall + * VisionBoxConstants + .MAX_DISPLACEMENT_PER_TICK_METERS) { // ensure the ball didn't move more than + // acceptable + ballPose = newPose; + ticksWithoutBall = 0; + } else { + ticksWithoutBall++; + } + + } else { + ticksWithoutBall++; + } + } + + /** + * This method will be invoked when this command finishes or is interrupted. It stops the motion + * of the drivetrain. It does not stop the motion of the flywheel. + * + * @param interrupted true if the command was interrupted by another command being scheduled + */ + @Override + public void end(boolean interrupted) { + // reenable field relative drive + if (initialFieldRelativeState) { + drivetrainSubsystem.enableFieldRelative(); + } + collectorSubsystem.disableCollector(); + drivetrainSubsystem.stop(); + // if (storageSubsystem.getNumberOfCargoInStorage() == 2) { //bring in the collector + // collectorSubsystem.disableCollector(); + // } + + } + + public boolean + isAimed() { // dont use visionbox for isaimed, instead use stored pose (as that is what we are + // tracking) + Translation2d robotToBallTranslation = + (new Transform2d(drivetrainSubsystem.getPose(), ballPose)) + .getTranslation(); // the translation from the robot to the ball + + return robotToBallTranslation.getY() + < VisionBoxConstants + .AIM_TOLERANCE_METERS; // translational error approach (require to be within a certain + // horizontal distance) + + // double robotToBallAngle = Math.atan2(robotToBallTranslation.getY(), + // robotToBallTranslation.getX()); //rotational error approach (require to be within a certain + // degree range) + // return robotToBallAngle < Math.toRadians(VisionBoxConstants.AIM_TOLERANCE_DEGREES); + } + + public boolean isAtBall() { + double robotToBallDistance = + (new Transform2d(drivetrainSubsystem.getPose(), ballPose)).getTranslation().getNorm(); + return robotToBallDistance < VisionBoxConstants.AT_BALL_THRESHOLD_METERS; + } + + @Override + public boolean isFinished() { + return initializationFailed + || storageSubsystem.getNumberOfCargoInStorage() > startingCargoCount + || storageSubsystem.getNumberOfCargoInStorage() == 2 + || isAtBall(); + } +} diff --git a/src/main/java/frc/robot/commands/WaitForShotCommand.java b/src/main/java/frc/robot/commands/WaitForShotCommand.java new file mode 100644 index 0000000..0530f91 --- /dev/null +++ b/src/main/java/frc/robot/commands/WaitForShotCommand.java @@ -0,0 +1,90 @@ +package frc.robot.commands; + +import static frc.robot.Constants.*; + +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.subsystems.drivetrain.Drivetrain; +import frc.robot.subsystems.flywheel.Flywheel; +import frc.robot.subsystems.storage.Storage; + +/** + * This command, when executed, waits for all cargo to be shot and then stops the motion of the + * storage and flywheel and disables the drivetrain's x-stance. + * + *

Requires: the storage, flywheel, and drivetrain subsystems + * + *

Finished When: all cargo has been shot + * + *

At End: stops the motion of the storage and flywheel and disables the drivetrain's x-stance + */ +public class WaitForShotCommand extends CommandBase { + private final Storage storage; + private final Flywheel flywheel; + private final Drivetrain drivetrain; + private int iterationDelayCount; + + /** + * Constructs a new WaitForShotCommand object. + * + * @param storage the storage subsystem this command will control + * @param flywheel the flywheel subsystem this command will control + * @param drivetrain the drivetrain subsystem this command will control + */ + public WaitForShotCommand(Storage storage, Flywheel flywheel, Drivetrain drivetrain) { + this.storage = storage; + this.flywheel = flywheel; + this.drivetrain = drivetrain; + addRequirements(storage); + addRequirements(flywheel); + addRequirements(drivetrain); + } + + /** + * This method is invoked once when this command is scheduled. It initializes the + * iterationDelayCount delay counter. It is critical that this initialization occurs in this + * method and not the constructor as this command is constructed once when the RobotContainer is + * created, but this method is invoked each time this command is scheduled. + */ + @Override + public void initialize() { + iterationDelayCount = 0; + } + + /** + * This method will be invoked when this command finishes or is interrupted. It stops the stops + * the motion of the storage and flywheel and disables the drivetrain's x-stance. + * + * @param interrupted true if the command was interrupted by another command being scheduled + */ + @Override + public void end(boolean interrupted) { + this.flywheel.stopFlywheel(); + this.storage.disableStorage(); + this.drivetrain.disableXstance(); + } + + /** + * This method is invoked at the end of each Command Scheduler iteration. It returns true when + * cargo is detected at neither the shooter end of the storage nor the collector end, and the + * desired number of additional iterationDelayCount have occurred to ensure the cargo has + * completely exited the shooter before the flywheel and storage are stopped. + */ + @Override + public boolean isFinished() { + if (storage.isCollectorSensorUnblocked() && storage.isShooterSensorUnblocked()) { + if (iterationDelayCount > StorageConstants.WAIT_FOR_SHOT_DELAY) { + return true; + } + + iterationDelayCount++; + } + // if cargo is detected at either end of the storage system, reset the iterationDelayCount delay + // counter. This is critical as there is a brief period of time where cargo can be between + // the sensors and the iteration counter can be incremented prematurely. + else { + iterationDelayCount = 0; + } + + return false; + } +} diff --git a/src/main/java/frc/robot/subsystems/VisionBox.java b/src/main/java/frc/robot/subsystems/VisionBox.java new file mode 100644 index 0000000..34d2081 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/VisionBox.java @@ -0,0 +1,169 @@ +package frc.robot.subsystems; + +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.geometry.Transform2d; +import edu.wpi.first.math.geometry.Translation2d; +import edu.wpi.first.networktables.NetworkTable; +import edu.wpi.first.networktables.NetworkTableEntry; +import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.smartdashboard.Field2d; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.Constants.VisionBoxConstants; +import frc.robot.subsystems.drivetrain.Drivetrain; + +public class VisionBox extends SubsystemBase { + + private NetworkTableEntry txListNT; + private NetworkTableEntry tyListNT; + private NetworkTable configNT; + private Drivetrain drivetrain; + private final Field2d ballField = new Field2d(); + + public VisionBox(Drivetrain drivetrain) { + /* + tx and ty and camera-relative measures of angle (where x is to the left and right of the camera and y is up and down). + In the robot relative coordinate system, tx is a rotation about the z axis from +x to +y. ty is a rotation about the y axis from +x to +z. + This leads to some counter-intuitive logic where tx is used to find a y coordinate and ty is used to find the x. + */ + this.drivetrain = drivetrain; // need the drivetrain to get pose + this.txListNT = + NetworkTableInstance.getDefault() + .getTable("VisionBox") + .getSubTable("output") + .getEntry("tx_list"); + this.tyListNT = + NetworkTableInstance.getDefault() + .getTable("VisionBox") + .getSubTable("output") + .getEntry("ty_list"); + this.configNT = NetworkTableInstance.getDefault().getTable("VisionBox").getSubTable("config"); + + // put field data on SmartDashboard (COMMENT THIS OUT WHEN DONE TESTING) + SmartDashboard.putData("Field", ballField); + } + + @Override + public void periodic() { + // This method will be called once per scheduler run + + // show ball and robot pose on map (COMMENT THIS OUT WHEN DONE WITH TESTING) + // if (drivetrain.getPose() != null && getFirstBallTransform2d() != null) { + // ballField.setRobotPose(drivetrain.getPose()); + // + // ballField.getObject("ball").setPose(drivetrain.getPose().plus(getFirstBallTransform2d())); + // } + + } + /** + * returns a list, with each entry being a ball's angle relative to the camera in the horizontal + * direction in radians + * + * @param defaultList a default list to be returned + * @return the list + */ + public double[] getTxList(double[] defaultList) { + return this.txListNT.getDoubleArray(defaultList); + } + + public double[] getTxList() { + return getTxList(new double[0]); + } + + /** + * returns a list, with each entry being a ball's angle relative to the camera in the vertical + * direction in radians + * + * @param defaultList a default list to be returned + * @return the list + */ + public double[] getTyList(double[] defaultList) { + return this.tyListNT.getDoubleArray(defaultList); + } + + public double[] getTyList() { + return getTyList(new double[0]); + } + + /** + * get the first ball's angle relative to the camera in the horizontal direction (positive theta + * is to the left of the image) in radians + * + * @return the angle relative to the robot or null if no balls are detected + */ + public Double getFirstBallTx() { + double[] txList = getTxList(); + if (txList.length == 0) { + return null; + } else { + return txList[0]; + } + } + + /** + * get the first ball's angle relative to the camera in the vertical direction (positive theta is + * to the top of the image) in radians + * + * @return the angle relative to the robot or null if no balls are detected + */ + public Double getFirstBallTy() { + double[] tyList = getTyList(); + if (tyList.length == 0) { + return null; + } else { + return tyList[0]; + } + } + + /** + * Get the transform from the robot to the first ball. This includes rotational and translational + * position data. + * + * @return the translation or null if no balls are detected + */ + public Transform2d getFirstBallTransform2d() { + + Double tx = getFirstBallTx(); + Double ty = getFirstBallTy(); + + // check if the first ball exists, if not return null + if (tx == null) return null; + + // determine the ball's distance from the robot in the x direction + double x = + VisionBoxConstants.CAMERA_HEIGHT_METERS + / Math.abs(Math.tan(Math.toRadians(VisionBoxConstants.CAMERA_ANGLE_DEGREES) - ty)); + + // using the direction in the radial direction and tx, calculate the distance in the y direction + double y = x * Math.tan(tx); + + Rotation2d rotation = new Rotation2d(0); // we dont care which way the ball is rotated + Translation2d translation = new Translation2d(x, y); + + return new Transform2d(translation, rotation); + } + + /** Set constants for visionBox based on alliance color in FMS */ + public void updateBallColorConstants() { + configNT.getEntry("debugMode").setBoolean(false); + + if (DriverStation.getAlliance() == DriverStation.Alliance.Red) { + // RED BALL CONSTANTS + configNT.getEntry("lowerHue").setDouble(159); + configNT.getEntry("lowerSaturation").setDouble(109); + configNT.getEntry("lowerValue").setDouble(120); + configNT.getEntry("upperHue").setDouble(9); + configNT.getEntry("upperSaturation").setDouble(255); + configNT.getEntry("upperValue").setDouble(255); + } else { + // BLUE BALL CONSTANTS + configNT.getEntry("lowerHue").setDouble(84); + configNT.getEntry("lowerSaturation").setDouble(57); + configNT.getEntry("lowerValue").setDouble(115); + configNT.getEntry("upperHue").setDouble(128); + configNT.getEntry("upperSaturation").setDouble(255); + configNT.getEntry("upperValue").setDouble(255); + } + } +} diff --git a/src/main/java/frc/robot/subsystems/collector/Collector.java b/src/main/java/frc/robot/subsystems/collector/Collector.java new file mode 100644 index 0000000..e4a077b --- /dev/null +++ b/src/main/java/frc/robot/subsystems/collector/Collector.java @@ -0,0 +1,99 @@ +package frc.robot.subsystems.collector; + +import static frc.robot.Constants.*; + +import edu.wpi.first.networktables.EntryListenerFlags; +import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets; +import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; +import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; +import edu.wpi.first.wpilibj2.command.InstantCommand; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.subsystems.collector.CollectorIO.CollectorIOInputs; +import org.littletonrobotics.junction.Logger; + +/** + * This subsystem models the robot's collector mechanism. It consists of a single motor, which + * rotates the collector's intake wheels in an intake or outtake direction, and a solenoid which, + * when enabled, deploys the collector; and, when disabled, retracts the collector. + */ +public class Collector extends SubsystemBase { + private final CollectorIO io; + private final CollectorIOInputs inputs = new CollectorIOInputs(); + + private static final String SUBSYSTEM_NAME = "Collector"; + private static final boolean TESTING = false; + private static final boolean DEBUGGING = false; + + /** Constructs a new Collector object. */ + public Collector(CollectorIO io) { + this.io = io; + ShuffleboardTab tab = Shuffleboard.getTab(SUBSYSTEM_NAME); + + if (DEBUGGING) { + tab.add(SUBSYSTEM_NAME, this); + tab.addBoolean("Enabled?", this::isEnabled); + } + + if (TESTING) { + tab.add("Collector Speed", 0.0) + .withWidget(BuiltInWidgets.kNumberSlider) + .getEntry() + .addListener( + event -> io.setMotorPercentage(event.getEntry().getValue().getDouble()), + EntryListenerFlags.kNew | EntryListenerFlags.kUpdate); + tab.add("Deploy Collector", new InstantCommand(() -> io.setExtended(true), this)); + tab.add("Retract Collector", new InstantCommand(() -> io.setExtended(false), this)); + } + } + + /** + * For each iteration, the subsystem's periodic method is invoked before any commands are + * executed. + */ + @Override + public void periodic() { + io.updateInputs(inputs); + Logger.getInstance().processInputs(SUBSYSTEM_NAME, inputs); + } + + /** + * Sets the power of the collector's motor, which rotates the collector's intake wheels, to the + * specified value. + * + * @param power the specified power of the collector's motor as a percentage of full power [-1.0, + * 1.0]; positive values rotate the wheels in the intake direction + */ + public void setCollectorPower(double power) { + io.setMotorPercentage(power); + } + + /** + * Disables the collector subsystem. This results in stopping the collector's intake wheels and + * retracting the collector back inside the robot frame. + */ + public void disableCollector() { + io.setEnabled(false); + io.setMotorPercentage(0.0); + io.setExtended(false); + } + + /** + * Enables the collector subsystem. This results in spinning the collector's intake wheels in the + * intake direcion and extending the collector outside the robot frame to position it to collect + * cargo. + */ + public void enableCollector() { + io.setEnabled(true); + io.setMotorPercentage(CollectorConstants.COLLECTOR_DEFAULT_POWER); + io.setExtended(true); + } + + /** + * Returns true if the collector is enabled (i.e., intake wheels spinning and collector deployed). + * + * @return true if the collector is enabled (i.e., intake wheels spinning and collector deployed) + */ + public boolean isEnabled() { + return inputs.isEnabled; + } +} diff --git a/src/main/java/frc/robot/subsystems/collector/CollectorIO.java b/src/main/java/frc/robot/subsystems/collector/CollectorIO.java new file mode 100644 index 0000000..94bf13d --- /dev/null +++ b/src/main/java/frc/robot/subsystems/collector/CollectorIO.java @@ -0,0 +1,45 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems.collector; + +import org.littletonrobotics.junction.LogTable; +import org.littletonrobotics.junction.inputs.LoggableInputs; + +/** Intake subsystem hardware interface. */ +public interface CollectorIO { + /** Contains all of the input data received from hardware. */ + public static class CollectorIOInputs implements LoggableInputs { + boolean isEnabled = false; + double appliedVolts = 0.0; + double[] currentAmps = new double[] {}; + double[] tempCelcius = new double[] {}; + + public void toLog(LogTable table) { + table.put("Enabled", isEnabled); + table.put("AppliedVolts", appliedVolts); + table.put("CurrentAmps", currentAmps); + table.put("TempCelcius", tempCelcius); + } + + public void fromLog(LogTable table) { + isEnabled = table.getBoolean("Extended", isEnabled); + appliedVolts = table.getDouble("AppliedVolts", appliedVolts); + currentAmps = table.getDoubleArray("CurrentAmps", currentAmps); + tempCelcius = table.getDoubleArray("TempCelcius", tempCelcius); + } + } + + /** Updates the set of loggable inputs. */ + public default void updateInputs(CollectorIOInputs inputs) {} + + /** Enable/Disable collector. */ + public default void setEnabled(boolean enabled) {} + + /** Run the roller open loop at the specified voltage. */ + public default void setMotorPercentage(double percentage) {} + + /** Set solenoid state. */ + public default void setExtended(boolean extended) {} +} diff --git a/src/main/java/frc/robot/subsystems/collector/CollectorIOTalonSRX.java b/src/main/java/frc/robot/subsystems/collector/CollectorIOTalonSRX.java new file mode 100644 index 0000000..89069c3 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/collector/CollectorIOTalonSRX.java @@ -0,0 +1,71 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems.collector; + +import static frc.robot.Constants.*; +import static frc.robot.Constants.CollectorConstants.*; + +import com.ctre.phoenix.motorcontrol.ControlMode; +import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced; +import com.ctre.phoenix.motorcontrol.SupplyCurrentLimitConfiguration; +import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; +import edu.wpi.first.wpilibj.PneumaticsModuleType; +import edu.wpi.first.wpilibj.Solenoid; +import frc.robot.util.CANDeviceFinder; +import frc.robot.util.CANDeviceId.CANDeviceType; +import frc.robot.util.TalonUtil; + +public class CollectorIOTalonSRX implements CollectorIO { + private final WPI_TalonSRX collectorMotor; + private final Solenoid collectorPiston; + private boolean isEnabled; + + public CollectorIOTalonSRX() { + CANDeviceFinder can = new CANDeviceFinder(); + + can.isDevicePresent( + CANDeviceType.TALON, CollectorConstants.COLLECTOR_MOTOR_ID, "Collector Motor"); + collectorMotor = new WPI_TalonSRX(CollectorConstants.COLLECTOR_MOTOR_ID); + collectorMotor.setInverted(true); + + collectorMotor.configSupplyCurrentLimit(new SupplyCurrentLimitConfiguration(true, 0, 40, .2)); + + // no data is read from the Talon SRX; so, set these CAN frame periods to the maximum value + // to reduce traffic on the bus + collectorMotor.setStatusFramePeriod(StatusFrameEnhanced.Status_1_General, 255, TIMEOUT_MS); + collectorMotor.setStatusFramePeriod(StatusFrameEnhanced.Status_2_Feedback0, 255, TIMEOUT_MS); + + collectorPiston = + new Solenoid( + CollectorConstants.PEUNAMATICS_HUB_CAN_ID, + PneumaticsModuleType.REVPH, + CollectorConstants.COLLECTOR_SOLENOID_CHANNEL); + } + + @Override + public void updateInputs(CollectorIOInputs inputs) { + inputs.isEnabled = isEnabled; + + inputs.appliedVolts = collectorMotor.getMotorOutputVoltage(); + inputs.currentAmps = new double[] {collectorMotor.getStatorCurrent()}; + inputs.tempCelcius = new double[] {collectorMotor.getTemperature()}; + } + + @Override + public void setEnabled(boolean enabled) { + isEnabled = enabled; + } + + @Override + public void setMotorPercentage(double percentage) { + collectorMotor.set(ControlMode.PercentOutput, percentage); + TalonUtil.checkError(collectorMotor.getLastError(), "Collector Motor Error"); + } + + @Override + public void setExtended(boolean extended) { + collectorPiston.set(extended); + } +} diff --git a/src/main/java/frc/robot/subsystems/drivetrain/Drivetrain.java b/src/main/java/frc/robot/subsystems/drivetrain/Drivetrain.java new file mode 100644 index 0000000..a6c9ff0 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/drivetrain/Drivetrain.java @@ -0,0 +1,791 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems.drivetrain; + +import static frc.robot.Constants.*; +import static frc.robot.Constants.DrivetrainConstants.*; + +import com.pathplanner.lib.PathPlannerTrajectory.PathPlannerState; +import edu.wpi.first.math.VecBuilder; +import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator; +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.geometry.Transform2d; +import edu.wpi.first.math.geometry.Translation2d; +import edu.wpi.first.math.kinematics.ChassisSpeeds; +import edu.wpi.first.math.kinematics.SwerveDriveKinematics; +import edu.wpi.first.math.kinematics.SwerveDriveOdometry; +import edu.wpi.first.math.kinematics.SwerveModuleState; +import edu.wpi.first.math.util.Units; +import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; +import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; +import edu.wpi.first.wpilibj2.command.InstantCommand; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.FieldConstants; +import frc.robot.commands.LimelightAlignToTargetCommand; +import frc.robot.commands.LimelightAlignWithGyroCommand; +import frc.robot.subsystems.drivetrain.DrivetrainIO.DrivetrainIOInputs; +import org.littletonrobotics.junction.Logger; + +/** + * This subsystem models the robot's drivetrain mechanism. It consists of a four MK4 swerve modules, + * each with two motors and an encoder. It also consists of a Pigeon which is used to measure the + * robot's rotation. + */ +public class Drivetrain extends SubsystemBase { + private final DrivetrainIO io; + private final DrivetrainIOInputs inputs = new DrivetrainIOInputs(); + + // some of this code is from the SDS example code + + // When aiming, rotate the robot much slower to avoid overshooting the setpoint + public static final double MAX_AIM_ANGULAR_VELOCITY_RADIANS_PER_SECOND = 1.0; + + private Translation2d centerGravity; + + /* The geometry and coordinate systems can be confusing. Refer to this document + for a detailed explanation: !!! + */ + private final SwerveDriveKinematics kinematics = + new SwerveDriveKinematics( + // Front left + new Translation2d(WHEELBASE_METERS / 2.0, TRACKWIDTH_METERS / 2.0), + // Front right + new Translation2d(WHEELBASE_METERS / 2.0, -TRACKWIDTH_METERS / 2.0), + // Back left + new Translation2d(-WHEELBASE_METERS / 2.0, TRACKWIDTH_METERS / 2.0), + // Back right + new Translation2d(-WHEELBASE_METERS / 2.0, -TRACKWIDTH_METERS / 2.0)); + + private boolean isFieldRelative; + private boolean isXstance; + + private final SwerveDriveOdometry odometry; + private double gyroOffset; + + private ChassisSpeeds chassisSpeeds; + + private int aimSetpointCount; + private int gyroAimSetpointCount; + private double lastLimelightDistance; + private boolean limelightAimEnabled; + private boolean autoAimAndShootEnabled; + private double gyroSetpoint; + + private static final String SUBSYSTEM_NAME = "Drivetrain"; + private static final boolean TESTING = false; + private static final boolean DEBUGGING = false; + + private final SwerveDrivePoseEstimator poseEstimator; + private Timer timer; + + /** Constructs a new DrivetrainSubsystem object. */ + public Drivetrain(DrivetrainIO io) { + this.io = io; + + this.centerGravity = new Translation2d(); // default to (0,0) + + this.zeroGyroscope(); + + ShuffleboardTab tab = Shuffleboard.getTab(SUBSYSTEM_NAME); + ShuffleboardTab tabMain = Shuffleboard.getTab("MAIN"); + + this.isFieldRelative = false; + this.isXstance = false; + + this.odometry = new SwerveDriveOdometry(kinematics, Rotation2d.fromDegrees(inputs.yaw)); + this.gyroOffset = 0; + + this.chassisSpeeds = new ChassisSpeeds(0.0, 0.0, 0.0); + + this.aimSetpointCount = 0; + this.gyroAimSetpointCount = 0; + this.lastLimelightDistance = 0.0; + this.limelightAimEnabled = true; + this.autoAimAndShootEnabled = false; + this.gyroSetpoint = 0.0; + this.timer = new Timer(); + this.startTimer(); + + this.poseEstimator = // FIXME tune standard deviations(current are from example), maybe + // add time + new SwerveDrivePoseEstimator( + new Rotation2d(inputs.yaw), // Current Rotation + new Pose2d(), // Starting Pose new SwerveDrivePoseEstimator( + kinematics, // kinematiucs object for drivetrains + VecBuilder.fill(0.05, 0.05, Units.degreesToRadians(5)), // state standard deveiation + VecBuilder.fill(Units.degreesToRadians(0.01)), // local measourement standard Deviations + VecBuilder.fill( + 0.5, 0.5, Units.degreesToRadians(30)), // vision measurement standard deviation + 0.02); // time in seconds between each robot loop + + tabMain.addNumber("Limelight Dist", () -> getLimelightDistanceIn()); + tabMain.addBoolean("Target Visible?", () -> isLimelightTargetVisible()); + tabMain.addNumber("Limelight Vel", () -> getVelocityFromLimelight()); + tabMain.addBoolean("At Launchpad Dist?", () -> isAtLaunchpadDistance()); + tabMain.addBoolean("At Wall Dist?", () -> isAtWallDistance()); + tabMain.addBoolean("Is Aimed?", () -> isAimed()); + tabMain.addBoolean("Is Aimed Gryo?", () -> isAimedWithGyro()); + tabMain.addNumber("Gyroscope Angle", () -> getGyroscopeRotation().getDegrees()); + tabMain.addBoolean("X-Stance On?", this::isXstance); + tabMain.addBoolean("Limelight Aim Enabled?", this::isLimelightAimEnabled); + tabMain.addBoolean("Aim & Shoot Enabled?", () -> this.autoAimAndShootEnabled); + tabMain.addBoolean("Field-Relative Enabled?", () -> this.isFieldRelative); + + if (DEBUGGING) { + tab.add(SUBSYSTEM_NAME, this); + tab.addNumber("vx", () -> getVelocityX()); + tab.addNumber("vy", () -> getVelocityY()); + tab.addNumber("Limelight x", () -> getLimelightX()); + tab.addNumber("Limelight y", () -> getLimelightY()); + tab.addNumber("Pose Est X", () -> poseEstimator.getEstimatedPosition().getX()); + tab.addNumber("Pose Est Y", () -> poseEstimator.getEstimatedPosition().getY()); + tab.addNumber( + "Pose Est Rot", () -> poseEstimator.getEstimatedPosition().getRotation().getDegrees()); + tab.addNumber("Odometry X", () -> odometry.getPoseMeters().getX()); + tab.addNumber("Odometry Y", () -> odometry.getPoseMeters().getY()); + tab.addNumber("Odometry Rot", () -> odometry.getPoseMeters().getRotation().getDegrees()); + tab.addNumber("CoG X", () -> this.centerGravity.getX()); + tab.addNumber("CoG Y", () -> this.centerGravity.getY()); + tab.addNumber("gyro setpoint", () -> this.gyroSetpoint); + } + + if (TESTING) { + tab.add("Enable XStance", new InstantCommand(() -> this.enableXstance())); + tab.add("Disable XStance", new InstantCommand(() -> this.disableXstance())); + tab.add("Align with Gyro", new LimelightAlignWithGyroCommand(this)); + tab.add("Align to Target", new LimelightAlignToTargetCommand(this)); + } + } + + /** + * Zeroes the gyroscope. This sets the current rotation of the robot to zero degrees. This method + * is intended to be invoked only when the alignment beteween the robot's rotation and the gyro is + * sufficiently different to make field-relative driving difficult. The robot needs to be + * positioned facing away from the driver, ideally aligned to a field wall before this method is + * invoked. + */ + public void zeroGyroscope() { + // There is a delay between setting the yaw on the Pigeon and that change + // taking effect. As a result, it is recommended to never set the yaw and + // adjust the local offset instead. + setGyroOffset(0.0); + } + + /** + * Returns the rotation of the robot. Zero degrees is facing away from the driver station; CCW is + * positive. This method should always be invoked instead of obtaining the yaw directly from the + * Pigeon as the local offset needs to be added. + * + * @return the rotation of the robot + */ + public Rotation2d getGyroscopeRotation() { + return Rotation2d.fromDegrees(inputs.yaw + this.gyroOffset); + } + + /** + * Sets the rotation of the robot to the specified value. This method should only be invoked when + * the rotation of the robot is known (e.g., at the start of an autonomous path). Zero degrees is + * facing away from the driver station; CCW is positive. + * + * @param expectedYaw the rotation of the robot (in degrees) + */ + public void setGyroOffset(double expectedYaw) { + // There is a delay between setting the yaw on the Pigeon and that change + // taking effect. As a result, it is recommended to never set the yaw and + // adjust the local offset instead. + this.gyroOffset = expectedYaw - inputs.yaw; + } + + /** + * Returns the pose of the robot (e.g., x and y position of the robot on the field and the robot's + * rotation). The origin of the field to the lower left corner (i.e., the corner of the field to + * the driver's right). Zero degrees is away from the driver and increases in the CCW direction. + * + * @return the pose of the robot + */ + public Pose2d getPose() { + // return poseEstimator.getEstimatedPosition(); + return odometry.getPoseMeters(); + } + + /** + * Sets the odometry of the robot to the specified PathPlanner state. This method should only be + * invoked when the rotation of the robot is known (e.g., at the start of an autonomous path). The + * origin of the field to the lower left corner (i.e., the corner of the field to the driver's + * right). Zero degrees is away from the driver and increases in the CCW direction. + * + * @param state the specified PathPlanner state to which is set the odometry + */ + public void resetOdometry(PathPlannerState state) { + setGyroOffset(state.holonomicRotation.getDegrees()); + odometry.resetPosition( + new Pose2d(state.poseMeters.getTranslation(), state.holonomicRotation), + this.getGyroscopeRotation()); + poseEstimator.resetPosition( + new Pose2d(state.poseMeters.getTranslation(), state.holonomicRotation), + this.getGyroscopeRotation()); + } + + /** + * Controls the drivetrain to move the robot with the desired velocities in the x, y, and + * rotational directions. The velocities may be specified from either the robot's frame of + * reference of the field's frame of reference. In the robot's frame of reference, the positive x + * direction is forward; the positive y direction, left; position rotation, CCW. In the field + * frame of reference, the origin of the field to the lower left corner (i.e., the corner of the + * field to the driver's right). Zero degrees is away from the driver and increases in the CCW + * direction. + * + * @param translationXSupplier the desired velocity in the x direction (m/s) + * @param translationYSupplier the desired velocity in the y direction (m/s) + * @param rotationSupplier the desired rotational velcoity (rad/s) + */ + public void drive( + double translationXSupplier, double translationYSupplier, double rotationSupplier) { + if (isXstance) { + this.setXStance(); + } else { + if (isFieldRelative) { + chassisSpeeds = + ChassisSpeeds.fromFieldRelativeSpeeds( + translationXSupplier, + translationYSupplier, + rotationSupplier, + getGyroscopeRotation()); + + } else { + chassisSpeeds = + new ChassisSpeeds(translationXSupplier, translationYSupplier, rotationSupplier); + } + + SwerveModuleState[] states = kinematics.toSwerveModuleStates(chassisSpeeds, centerGravity); + + io.setSwerveModules(states); + } + } + + /** + * Stops the motion of the robot. Since the motors are in break mode, the robot will stop soon + * after this method is invoked. + */ + public void stop() { + chassisSpeeds = new ChassisSpeeds(0.0, 0.0, 0.0); + SwerveModuleState[] states = kinematics.toSwerveModuleStates(chassisSpeeds, centerGravity); + setSwerveModuleStates(states); + } + + /** + * This method is invoked each iteration of the scheduler. Typically, when using a command-based + * model, subsystems don't override the periodic method. However, the drivetrain needs to + * continually update the odometry of the robot. + */ + @Override + public void periodic() { + io.updateInputs(inputs); + Logger.getInstance().processInputs(SUBSYSTEM_NAME, inputs); + + odometry.update( + this.getGyroscopeRotation(), + new SwerveModuleState( + inputs.frontLeftDriveVelocity, new Rotation2d(inputs.frontLeftSteerAngle)), + new SwerveModuleState( + inputs.frontRightDriveVelocity, new Rotation2d(inputs.frontRightSteerAngle)), + new SwerveModuleState( + inputs.backLeftDriveVelocity, new Rotation2d(inputs.backLeftSteerAngle)), + new SwerveModuleState( + inputs.backRightDriveVelocity, new Rotation2d(inputs.backRightSteerAngle))); + + // Log poses + Pose2d pose = odometry.getPoseMeters(); + Pose2d poseEstimatorPose = poseEstimator.getEstimatedPosition(); + Logger.getInstance() + .recordOutput( + "Odometry/Robot", + new double[] {pose.getX(), pose.getY(), pose.getRotation().getRadians()}); + Logger.getInstance() + .recordOutput( + "Odometry/Pose Estimator", + new double[] { + poseEstimatorPose.getX(), + poseEstimatorPose.getY(), + poseEstimatorPose.getRotation().getRadians() + }); + Logger.getInstance() + .recordOutput( + "Odometry/VisionTarget", + new double[] {FieldConstants.HUB_CENTER.getX(), FieldConstants.HUB_CENTER.getY()}); + if (isLimelightTargetVisible()) { + Logger.getInstance().recordOutput("Vision/DistanceInches", getLimelightDistanceIn()); + } + + poseEstimator.updateWithTime( + this.timer.get(), + this.getGyroscopeRotation(), + new SwerveModuleState( + inputs.frontLeftDriveVelocity, new Rotation2d(inputs.frontLeftSteerAngle)), + new SwerveModuleState( + inputs.frontRightDriveVelocity, new Rotation2d(inputs.frontRightSteerAngle)), + new SwerveModuleState( + inputs.backLeftDriveVelocity, new Rotation2d(inputs.backLeftSteerAngle)), + new SwerveModuleState( + inputs.backRightDriveVelocity, new Rotation2d(inputs.backRightSteerAngle))); + + if (this.isLimelightTargetVisible()) { + poseEstimator.addVisionMeasurement( + this.getVisionPose2d(), this.timer.get() - LIMELIGHT_LATENCY); + } + Logger.getInstance().recordOutput("SUBSYSTEM_NAME/gyroOffset", this.gyroOffset); + } + + /** + * Sets each of the swerve modules based on the specified corresponding swerve module state. + * Incorporates the configured feedforward when setting each swerve module. The order of the + * states in the array must be front left, front right, back left, back right. + * + * @param states the specified swerve module state for each swerve module + */ + public void setSwerveModuleStates(SwerveModuleState[] states) { + io.setSwerveModulesWithFeedForward(states); + } + + /** + * Returns the kinematics for the drivetrain + * + * @return the kinematics for the drivetrain + */ + public SwerveDriveKinematics getKinematics() { + return kinematics; + } + + /** + * Returns true if field relative mode is enabled + * + * @return true if field relative mode is enabled + */ + public boolean getFieldRelative() { + return isFieldRelative; + } + + /** + * Enables field-relative mode. When enabled, the joystick inputs specify the velocity of the + * robot in the frame of reference of the field. + */ + public void enableFieldRelative() { + this.isFieldRelative = true; + } + + /** + * Disables field-relative mode. When disabled, the joystick inputs specify the velocity of the + * robot in the frame of reference of the robot. + */ + public void disableFieldRelative() { + this.isFieldRelative = false; + } + + /** + * Sets the swerve modules in the x-stance orientation. In this orientation the wheels are aligned + * to make an 'X'. This makes it more difficult for other robots to push the robot, which is + * useful when shooting. + */ + public void setXStance() { + chassisSpeeds = new ChassisSpeeds(0.0, 0.0, 0.0); + SwerveModuleState[] states = kinematics.toSwerveModuleStates(chassisSpeeds, centerGravity); + states[0].angle = new Rotation2d(Math.PI / 2 - Math.atan(TRACKWIDTH_METERS / WHEELBASE_METERS)); + states[1].angle = new Rotation2d(Math.PI / 2 + Math.atan(TRACKWIDTH_METERS / WHEELBASE_METERS)); + states[2].angle = new Rotation2d(Math.PI / 2 + Math.atan(TRACKWIDTH_METERS / WHEELBASE_METERS)); + states[3].angle = + new Rotation2d(3.0 / 2.0 * Math.PI - Math.atan(TRACKWIDTH_METERS / WHEELBASE_METERS)); + io.setSwerveModules(states); + } + + /** + * Sets the robot's center of gravity about which it will rotate. The origin is at the center of + * the robot. The positive x direction is forward; the positive y direction, left. + * + * @param x the x coordinate of the robot's center of gravity (in meters) + * @param y the y coordinate of the robot's center of gravity (in meters) + */ + public void setCenterGrav(double x, double y) { + this.centerGravity = new Translation2d(x, y); + } + + /** Resets the robot's center of gravity about which it will rotate to the center of the robot. */ + public void resetCenterGrav() { + setCenterGrav(0.0, 0.0); + } + + /** + * Controls the drivetrain to move the robot with the desired velocities in the x, y, and + * rotational directions. Instead of rotating about the robot's center of gravity, the robot will + * rotate about the point on the robot's frame perimeter in the direction of the velocity. This + * will result in a "spin move" to evade a defending robot. The velocities must be specified from + * reference of the field's frame of reference: the origin of the field to the lower left corner + * (i.e., the corner of the field to the driver's right). Zero degrees is away from the driver and + * increases in the CCW direction. + * + *

This method needs to be debugged. + * + * @param translationX the desired velocity in the x direction (m/s) + * @param translationY the desired velocity in the y direction (m/s) + * @param rotation the desired rotational velcoity (rad/s) + */ + public void rotateEvasively(double translationX, double translationY, double rotation) { + + double gyro = getGyroscopeRotation().getDegrees(); + + /* + Assumptions: + * positive x is moving joystick 0 right (no it's positive when left) + * positive y is moving joystick 0 forward (correct) + * positive z is moving joystick 1 left (correct) + * gyro values increase when rotation counter clockwise + */ + + double x = -translationX; + double y = translationY; + double z = rotation; + + double worldFrameAngle = Math.toDegrees(Math.atan(y / x)); + if (x < 0) { + worldFrameAngle += 180.0; + } + double robotFrameAngle = worldFrameAngle - gyro; + double robotFrameCOGAngle; + + if (z < 0) { + robotFrameCOGAngle = robotFrameAngle + COG_OFFSET; + } else { + robotFrameCOGAngle = robotFrameAngle - COG_OFFSET; + } + + double cogX = + Math.cos(Math.toRadians(robotFrameCOGAngle)) * EVASIVE_ROTATION_COG_SHIFT_MAGNITUDE; + double cogY = + Math.sin(Math.toRadians(robotFrameCOGAngle)) * EVASIVE_ROTATION_COG_SHIFT_MAGNITUDE; + + setCenterGrav(cogX, cogY); + } + + /** + * Returns the horizontal offset between the rotation of the robot and the center of the hub's + * vision target (in degrees). A positive value indicates the hub's vision target is to the left + * of the robot rotation. + * + * @return the horizontal offset between the rotation of the robot and the center of the hub's + * vision target (in degrees) + */ + public double getLimelightX() { + return inputs.limelightTX; + } + + /** + * Returns the vertical offset between the center of the Limelight image and the the hub's vision + * target (in degrees). A positive value indicates the vision target is above the center of the + * Limelight image. + * + * @return the vertical offset between the center of the Limelight image and the the hub's vision + * target (in degrees) + */ + private double getLimelightY() { + return inputs.limelightTY; + } + + /** + * Returns true if the hub's vision target is visible. + * + * @return true if the hub's vision target is visible + */ + public boolean isLimelightTargetVisible() { + return inputs.limelightTV == 1; + } + + /** + * Returns the distance from the Limelight mounted on the robot to the hub's vision target (in + * inches). + * + * @return the distance from the Limelight mounted on the robot to the hub's vision target (in + * inches). + */ + public double getLimelightDistanceIn() { + // refer to the following page for the algorithm to calculate the distance: + // https://docs.limelightvision.io/en/latest/cs_estimating_distance.html + + double ty = inputs.limelightTY; + + this.lastLimelightDistance = + (LimelightConstants.HUB_H - LimelightConstants.ROBOT_H) + / (Math.tan( + Math.toRadians( + LimelightConstants.LIMELIGHT_MOUNT_ANGLE + + LimelightConstants.LIMELIGHT_ANGLE_OFFSET + + ty))); + + return this.lastLimelightDistance; + } + + /** + * Returns the desired flywheel velocity (in ticks / 100 ms) based on the distance to the hub. The + * line of best fit was determined empirically. + * + * @return the desired flywheel velocity (in ticks / 100 ms) based on the distance to the hub + */ + public double getVelocityFromLimelight() { + return LIMELIGHT_SLOPE * this.getLimelightDistanceIn() + LIMELIGHT_Y_COMPONENT; + } + + private boolean isAtLaunchpadDistance() { + return Math.abs(LimelightConstants.HUB_LAUNCHPAD_DISTANCE - this.lastLimelightDistance) + <= LimelightConstants.DISTANCE_TOLERANCE; + } + + private boolean isAtWallDistance() { + return Math.abs(LimelightConstants.HUB_WALL_DISTANCE - this.lastLimelightDistance) + <= LimelightConstants.DISTANCE_TOLERANCE; + } + + /** + * Controls the drivetrain to move the robot with the desired velocities in the x, y, and + * rotational directions. This method is designed to be invoked from commands that use joystick + * inputs for the x and y velocities and a PID for the rotational velocity (to align the robot + * with the hub). + * + *

The velocities may be specified from either the robot's frame of reference of the field's + * frame of reference. In the robot's frame of reference, the positive x direction is forward; the + * positive y direction, left; position rotation, CCW. In the field frame of reference, the origin + * of the field to the lower left corner (i.e., the corner of the field to the driver's right). + * Zero degrees is away from the driver and increases in the CCW direction. + * + * @param translationXSupplier the desired velocity in the x direction (m/s) + * @param translationYSupplier the desired velocity in the y direction (m/s) + * @param rotationSupplier the desired rotational velcoity (rad/s) + */ + public void aim( + double translationXSupplier, double translationYSupplier, double rotationSupplier) { + + // incorporate a feedforward for the rotation to make the PID more responsive + + // LIMELIGHT_F is specified as a fraction of MAX_AIM_ANGULAR_VELOCITY_RADIANS_PER_SECOND + if (rotationSupplier > 0) { // clockwise + rotationSupplier += LIMELIGHT_F * MAX_AIM_ANGULAR_VELOCITY_RADIANS_PER_SECOND; + } else if (rotationSupplier < 0) { // counterclockwise + rotationSupplier -= LIMELIGHT_F * MAX_AIM_ANGULAR_VELOCITY_RADIANS_PER_SECOND; + } + + // clamp the rotation to MAX_AIM_ANGULAR_VELOCITY_RADIANS_PER_SECOND + if (rotationSupplier > MAX_AIM_ANGULAR_VELOCITY_RADIANS_PER_SECOND) { + rotationSupplier = MAX_AIM_ANGULAR_VELOCITY_RADIANS_PER_SECOND; + } else if (rotationSupplier < -MAX_AIM_ANGULAR_VELOCITY_RADIANS_PER_SECOND) { + rotationSupplier = -MAX_AIM_ANGULAR_VELOCITY_RADIANS_PER_SECOND; + } + + drive(translationXSupplier, translationYSupplier, rotationSupplier); + } + + /** + * Returns true if the robot is aimed at the center of the hub's vision traget (within the desired + * tolerance) based on the Limelight's reported horizontal offset. If Limelight aiming is + * disabled, this method returns true. + * + * @return true if the robot is aimed at the center of the hub's vision traget (within the desired + * tolerance) based on the Limelight's reported horizontal offset. If Limelight aiming is + * disabled, this method returns true + */ + public boolean isAimed() { + + // check if limelight aiming is enabled + if (!this.limelightAimEnabled) { + return true; + } + + // Calculate the horizontal offset (in inches) from the center of the hub and + // ensure we are within the specified tolerance. It is critical to use the + // offset in inches instead of degrees as the same degree offset when close + // to the hub or far from the hub results in significantly different offsets + // in inches, which can result in missed shots. The tolerance is critical + // since it is highly unlikely that the robot will be aligned perfectly. + // Waiting the specified number of iterations is critical since the PID may + // overshoot the setpoint and need additional time to settle. The robot is + // only considered aimed if it remains aligned continuously for the desired + // number of iterations. Without waiting, it would be reported that the + // robot was aimed but then, when the cargo is shot, the robot would + // overrotate and miss. + + double distanceToHub = + getLimelightDistanceIn() + LimelightConstants.EDGE_TO_CENTER_HUB_DISTANCE; + if (Math.abs(distanceToHub * Math.sin(Math.toRadians(getLimelightX()))) + < LIMELIGHT_AIM_TOLERANCE) { + aimSetpointCount++; + if (aimSetpointCount >= AIM_SETPOINT_COUNT) { + return true; + } + } else { + + aimSetpointCount = 0; + } + return false; + } + + /** + * Sets the setpoint for the robot's rotation to the specified value (in degrees). Zero degrees is + * away from the driver and increases in the CCW direction. + * + * @param setpoint the specified setpoint for the robot's rotation (in degrees) + */ + public void setGyroSetpoint(double setpoint) { + this.gyroSetpoint = setpoint; + } + + /** + * Returns true if the robot is aimed at the center of the hub's vision traget (within the desired + * tolerance) based on the gyro. If Limelight aiming is disabled, this method returns true. + * + * @return true if the robot is aimed at the center of the hub's vision traget (within the desired + * tolerance) based on the gyro. If Limelight aiming is disabled, this method returns true. + */ + public boolean isAimedWithGyro() { + + // check if limelight aiming is enabled + if (!this.limelightAimEnabled) { + return true; + } + + // Calculate the horizontal offset (in inches) from the center of the hub and + // ensure we are within the specified tolerance. It is critical to use the + // offset in inches instead of degrees as the same degree offset when close + // to the hub or far from the hub results in significantly different offsets + // in inches, which can result in missed shots. The tolerance is critical + // since it is highly unlikely that the robot will be aligned perfectly. + // Waiting the specified number of iterations is critical since the PID may + // overshoot the setpoint and need additional time to settle. The robot is + // only considered aimed if it remains aligned continuously for the desired + // number of iterations. Without waiting, it would be reported that the + // robot was aimed but then, when the cargo is shot, the robot would + // overrotate and miss. + + double distanceToHub = + getLimelightDistanceIn() + LimelightConstants.EDGE_TO_CENTER_HUB_DISTANCE; + double setPointDisplacement = distanceToHub * Math.sin(Math.toRadians(this.gyroSetpoint)); + double currentDisplacement = distanceToHub * Math.sin(getGyroscopeRotation().getRadians()); + if (Math.abs(setPointDisplacement - currentDisplacement) < LIMELIGHT_AIM_TOLERANCE) { + gyroAimSetpointCount++; + if (gyroAimSetpointCount >= AIM_SETPOINT_COUNT) { + return true; + } + } else { + + gyroAimSetpointCount = 0; + } + return false; + } + + /** + * Returns the desired velocity of the drivetrain in the x direction (units of m/s) + * + * @return the desired velocity of the drivetrain in the x direction (units of m/s) + */ + public double getVelocityX() { + return chassisSpeeds.vxMetersPerSecond; + } + + /** + * Returns the desired velocity of the drivetrain in the y direction (units of m/s) + * + * @return the desired velocity of the drivetrain in the y direction (units of m/s) + */ + public double getVelocityY() { + return chassisSpeeds.vyMetersPerSecond; + } + + /** + * Returns the desired velocity of the drivetrain (units of rad/s) + * + * @return the desired velocity of the drivetrain (units of rad/s) + */ + public double getVelocityRotational() { + return chassisSpeeds.omegaRadiansPerSecond; + } + + /** + * Enable the auto aim and shoot mode. In this mode, the robot moves based on the joystick inputs. + * If the hub is visible, the drivetrain will rotate to stay aimed at the hub; if not, the + * joystick input will control the rotation of the drivetrain. + */ + public void enableAutoAimAndShoot() { + this.autoAimAndShootEnabled = true; + } + + /** Disables the auto aim and shoot mode. */ + public void disableAutoAimAndShoot() { + this.autoAimAndShootEnabled = false; + } + + /** Enables aiming based on the Limelight. */ + public void enableLimelightAim() { + this.limelightAimEnabled = true; + } + + /** + * Disables aiming based on the Limelight. This method is only invoked when the operator has + * determined that the Limelight is not functioning and the driver will aim the robot manually. + * This is critical since, without disabling this feature, the driver would be fighting the code + * that tries to aim based on the malfunctioning Limelight. + */ + public void disableLimelightAim() { + this.limelightAimEnabled = false; + } + + /** + * Returns true if the limelight aim feature is enabled. + * + * @return + */ + public boolean isLimelightAimEnabled() { + return this.limelightAimEnabled; + } + + /** + * Puts the drivetrain into the x-stance orientation. In this orientation the wheels are aligned + * to make an 'X'. This makes it more difficult for other robots to push the robot, which is + * useful when shooting. The robot cannot be driven until x-stance is disabled. + */ + public void enableXstance() { + this.isXstance = true; + this.setXStance(); + } + + /** Disables the x-stance, allowing the robot to be driven. */ + public void disableXstance() { + this.isXstance = false; + } + + /** + * Returns true if the robot is in the x-stance orientation. + * + * @return true if the robot is in the x-stance orientation + */ + public boolean isXstance() { + return isXstance; + } + + public void startTimer() { + this.timer.reset(); + this.timer.start(); + } + + public Pose2d getVisionPose2d() { + double r = this.getLimelightDistanceIn(); + double theta = this.inputs.yaw - this.getLimelightX(); + double x = Math.sin(theta) * r; + double y = Math.cos(theta) * r; + Translation2d translation = new Translation2d(x, y); + + Transform2d cameraToVisionTarget = new Transform2d(translation, new Rotation2d(0)); + Translation2d hubLocation = FieldConstants.HUB_CENTER; + + return new Pose2d(hubLocation, new Rotation2d(this.inputs.yaw)) + .plus(cameraToVisionTarget.inverse()); + } +} diff --git a/src/main/java/frc/robot/subsystems/drivetrain/DrivetrainIO.java b/src/main/java/frc/robot/subsystems/drivetrain/DrivetrainIO.java new file mode 100644 index 0000000..1d25bb1 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/drivetrain/DrivetrainIO.java @@ -0,0 +1,74 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems.drivetrain; + +import edu.wpi.first.math.kinematics.SwerveModuleState; +import org.littletonrobotics.junction.LogTable; +import org.littletonrobotics.junction.inputs.LoggableInputs; + +/** Intake subsystem hardware interface. */ +public interface DrivetrainIO { + /** + * Contains all of the input data received from hardware. More can be logged when we have our own + * swerve library code with access to the motors and encoders + */ + public static class DrivetrainIOInputs implements LoggableInputs { + double frontLeftDriveVelocity = 0.0; + double frontLeftSteerAngle = 0.0; + + double frontRightDriveVelocity = 0.0; + double frontRightSteerAngle = 0.0; + + double backLeftDriveVelocity = 0.0; + double backLeftSteerAngle = 0.0; + + double backRightDriveVelocity = 0.0; + double backRightSteerAngle = 0.0; + + double yaw = 0.0; + + double limelightTX = 0.0; + double limelightTY = 0.0; + double limelightTV = 0.0; + + public void toLog(LogTable table) { + table.put("FrontLeftDriveVelocity", frontLeftDriveVelocity); + table.put("FrontLeftSteerAngle", frontLeftSteerAngle); + table.put("FrontRightDriveVelocity", frontRightDriveVelocity); + table.put("FrontRightSteerAngle", frontRightSteerAngle); + table.put("BackLeftDriveVelocity", backLeftDriveVelocity); + table.put("BackLeftSteerAngle", backLeftSteerAngle); + table.put("BackRightDriveVelocity", backRightDriveVelocity); + table.put("BackRightSteerAngle", backRightSteerAngle); + table.put("Yaw", yaw); + table.put("LimelightTX", limelightTX); + table.put("LimelightTY", limelightTY); + table.put("LimelightTV", limelightTV); + } + + public void fromLog(LogTable table) { + frontLeftDriveVelocity = table.getDouble("FrontLeftDriveVelocity", frontLeftDriveVelocity); + frontLeftSteerAngle = table.getDouble("FrontLeftSteerAngle", frontLeftSteerAngle); + frontRightDriveVelocity = table.getDouble("FrontRightDriveVelocity", frontRightDriveVelocity); + frontRightSteerAngle = table.getDouble("FrontRightSteerAngle", frontRightSteerAngle); + backLeftDriveVelocity = table.getDouble("BackLeftDriveVelocity", backLeftDriveVelocity); + backLeftSteerAngle = table.getDouble("BackLeftSteerAngle", backLeftSteerAngle); + backRightDriveVelocity = table.getDouble("BackRightDriveVelocity", backRightDriveVelocity); + backRightSteerAngle = table.getDouble("BackRightSteerAngle", backRightSteerAngle); + } + } + + /** Updates the set of loggable inputs. */ + public default void updateInputs(DrivetrainIOInputs inputs) {} + + /** Set the swerve modules to the specified states. */ + public default void setSwerveModules(SwerveModuleState[] states) {} + + /** Set the swerve modules to the specified states with feed forward. */ + public default void setSwerveModulesWithFeedForward(SwerveModuleState[] states) {} + + /** Run the flywheel closed loop at the specified velocity. */ + public default void setVelocity(double velocity) {} +} diff --git a/src/main/java/frc/robot/subsystems/drivetrain/DrivetrainIOTalonFX.java b/src/main/java/frc/robot/subsystems/drivetrain/DrivetrainIOTalonFX.java new file mode 100644 index 0000000..dbd75a2 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/drivetrain/DrivetrainIOTalonFX.java @@ -0,0 +1,185 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems.drivetrain; + +import static frc.robot.Constants.DrivetrainConstants.*; + +import com.ctre.phoenix.sensors.Pigeon2; +import com.swervedrivespecialties.swervelib.Mk4SwerveModuleHelper; +import com.swervedrivespecialties.swervelib.SwerveModule; +import edu.wpi.first.math.controller.SimpleMotorFeedforward; +import edu.wpi.first.math.kinematics.SwerveModuleState; +import edu.wpi.first.networktables.NetworkTableInstance; +import frc.robot.Constants.AutoConstants; +import frc.robot.util.CANDeviceFinder; +import frc.robot.util.CANDeviceId.CANDeviceType; + +public class DrivetrainIOTalonFX implements DrivetrainIO { + private final Pigeon2 pigeon; + + // These are our modules. We initialize them in the constructor. + private final SwerveModule frontLeftModule; + private final SwerveModule frontRightModule; + private final SwerveModule backLeftModule; + private final SwerveModule backRightModule; + + private SimpleMotorFeedforward feedForward; + + public DrivetrainIOTalonFX() { + this.pigeon = new Pigeon2(PIGEON_ID); + CANDeviceFinder can = new CANDeviceFinder(); + + // There are 4 methods you can call to create your swerve modules. + // The method you use depends on what motors you are using. + // + // Mk3SwerveModuleHelper.createFalcon500(...) + // Your module has two Falcon 500s on it. One for steering and one for driving. + // + // Mk3SwerveModuleHelper.createNeo(...) + // Your module has two NEOs on it. One for steering and one for driving. + // + // Mk3SwerveModuleHelper.createFalcon500Neo(...) + // Your module has a Falcon 500 and a NEO on it. The Falcon 500 is for driving + // and the NEO is for steering. + // + // Mk3SwerveModuleHelper.createNeoFalcon500(...) + // Your module has a NEO and a Falcon 500 on it. The NEO is for driving and the + // Falcon 500 is for steering. + // + // Similar helpers also exist for Mk4 modules using the Mk4SwerveModuleHelper + // class. + + // By default we will use Falcon 500s in standard configuration. But if you use + // a different configuration or motors + // you MUST change it. If you do not, your code will crash on startup. + + can.isDevicePresent(CANDeviceType.TALON, FRONT_LEFT_MODULE_DRIVE_MOTOR, "Front Left Drive"); + can.isDevicePresent(CANDeviceType.TALON, FRONT_LEFT_MODULE_STEER_MOTOR, "Front Left Steer"); + + frontLeftModule = + Mk4SwerveModuleHelper.createFalcon500( + // This can either be STANDARD or FAST depending on your gear configuration + Mk4SwerveModuleHelper.GearRatio.L2, + // This is the ID of the drive motor + FRONT_LEFT_MODULE_DRIVE_MOTOR, + // This is the ID of the steer motor + FRONT_LEFT_MODULE_STEER_MOTOR, + // This is the ID of the steer encoder + FRONT_LEFT_MODULE_STEER_ENCODER, + // This is how much the steer encoder is offset from true zero (In our case, + // zero is facing straight forward) + FRONT_LEFT_MODULE_STEER_OFFSET); + + // We will do the same for the other modules + can.isDevicePresent(CANDeviceType.TALON, FRONT_RIGHT_MODULE_DRIVE_MOTOR, "Front Right Drive"); + can.isDevicePresent(CANDeviceType.TALON, FRONT_RIGHT_MODULE_STEER_MOTOR, "Front Right Steer"); + frontRightModule = + Mk4SwerveModuleHelper.createFalcon500( + Mk4SwerveModuleHelper.GearRatio.L2, + FRONT_RIGHT_MODULE_DRIVE_MOTOR, + FRONT_RIGHT_MODULE_STEER_MOTOR, + FRONT_RIGHT_MODULE_STEER_ENCODER, + FRONT_RIGHT_MODULE_STEER_OFFSET); + + can.isDevicePresent(CANDeviceType.TALON, BACK_LEFT_MODULE_DRIVE_MOTOR, "Back Left Drive"); + can.isDevicePresent(CANDeviceType.TALON, BACK_LEFT_MODULE_STEER_MOTOR, "Back Left Steer"); + backLeftModule = + Mk4SwerveModuleHelper.createFalcon500( + Mk4SwerveModuleHelper.GearRatio.L2, + BACK_LEFT_MODULE_DRIVE_MOTOR, + BACK_LEFT_MODULE_STEER_MOTOR, + BACK_LEFT_MODULE_STEER_ENCODER, + BACK_LEFT_MODULE_STEER_OFFSET); + + can.isDevicePresent(CANDeviceType.TALON, BACK_RIGHT_MODULE_DRIVE_MOTOR, "Back Right Drive"); + can.isDevicePresent(CANDeviceType.TALON, BACK_RIGHT_MODULE_STEER_MOTOR, "Back Right Steer"); + backRightModule = + Mk4SwerveModuleHelper.createFalcon500( + Mk4SwerveModuleHelper.GearRatio.L2, + BACK_RIGHT_MODULE_DRIVE_MOTOR, + BACK_RIGHT_MODULE_STEER_MOTOR, + BACK_RIGHT_MODULE_STEER_ENCODER, + BACK_RIGHT_MODULE_STEER_OFFSET); + + this.feedForward = + new SimpleMotorFeedforward( + AutoConstants.S_VOLTS, + AutoConstants.V_VOLT_SECONDS_PER_METER, + AutoConstants.A_VOLT_SECONDS_SQUARED_PER_METER); + } + + @Override + public void updateInputs(DrivetrainIOInputs inputs) { + + inputs.frontLeftDriveVelocity = frontLeftModule.getDriveVelocity(); + inputs.frontLeftSteerAngle = frontLeftModule.getSteerAngle(); + inputs.frontRightDriveVelocity = frontRightModule.getDriveVelocity(); + inputs.frontRightSteerAngle = frontRightModule.getSteerAngle(); + inputs.backLeftDriveVelocity = backLeftModule.getDriveVelocity(); + inputs.backLeftSteerAngle = backLeftModule.getSteerAngle(); + inputs.backRightDriveVelocity = backRightModule.getDriveVelocity(); + inputs.backRightSteerAngle = backRightModule.getSteerAngle(); + inputs.yaw = pigeon.getYaw(); + inputs.limelightTX = + NetworkTableInstance.getDefault() + .getTable(LIMELIGHT_NETWORK_TABLE_NAME) + .getEntry("tx") + .getDouble(0); + inputs.limelightTY = + NetworkTableInstance.getDefault() + .getTable(LIMELIGHT_NETWORK_TABLE_NAME) + .getEntry("ty") + .getDouble(0); + inputs.limelightTV = + NetworkTableInstance.getDefault() + .getTable(LIMELIGHT_NETWORK_TABLE_NAME) + .getEntry("tv") + .getDouble(0); + } + + @Override + public void setSwerveModules(SwerveModuleState[] states) { + + // the set method of the swerve modules take a voltage, not a velocity + frontLeftModule.set( + states[0].speedMetersPerSecond / MAX_VELOCITY_METERS_PER_SECOND * MAX_VOLTAGE, + states[0].angle.getRadians()); + frontRightModule.set( + states[1].speedMetersPerSecond / MAX_VELOCITY_METERS_PER_SECOND * MAX_VOLTAGE, + states[1].angle.getRadians()); + backLeftModule.set( + states[2].speedMetersPerSecond / MAX_VELOCITY_METERS_PER_SECOND * MAX_VOLTAGE, + states[2].angle.getRadians()); + backRightModule.set( + states[3].speedMetersPerSecond / MAX_VELOCITY_METERS_PER_SECOND * MAX_VOLTAGE, + states[3].angle.getRadians()); + } + + @Override + public void setSwerveModulesWithFeedForward(SwerveModuleState[] states) { + // the set method of the swerve modules take a voltage, not a velocity + frontLeftModule.set( + this.calculateFeedforwardVoltage(states[0].speedMetersPerSecond), + states[0].angle.getRadians()); + frontRightModule.set( + this.calculateFeedforwardVoltage(states[1].speedMetersPerSecond), + states[1].angle.getRadians()); + backLeftModule.set( + this.calculateFeedforwardVoltage(states[2].speedMetersPerSecond), + states[2].angle.getRadians()); + backRightModule.set( + this.calculateFeedforwardVoltage(states[3].speedMetersPerSecond), + states[3].angle.getRadians()); + } + + private double calculateFeedforwardVoltage(double velocity) { + double voltage = this.feedForward.calculate(velocity); + // clamp the voltage to the maximum voltage + if (voltage > MAX_VOLTAGE) { + return MAX_VOLTAGE; + } + return voltage; + } +} diff --git a/src/main/java/frc/robot/subsystems/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/elevator/Elevator.java new file mode 100644 index 0000000..caa1d06 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/elevator/Elevator.java @@ -0,0 +1,382 @@ +package frc.robot.subsystems.elevator; + +import static frc.robot.Constants.*; +import static frc.robot.Constants.ElevatorConstants.*; + +import edu.wpi.first.networktables.EntryListenerFlags; +import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets; +import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; +import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.commands.ExtendClimberToMidRungCommand; +import frc.robot.commands.RetractClimberFullCommand; +import frc.robot.commands.RetractClimberMinimumCommand; +import frc.robot.subsystems.elevator.ElevatorIO.ElevatorIOInputs; +import java.util.Map; +import org.littletonrobotics.junction.Logger; + +/** + * This subsystem models the robot's elevator mechanism. It consists of two motors, which both + * control the elevator. The right motor is controlled by a PID running on its motor controller to + * position the elevator at the specified setpoint. The left motor follows the right. It also + * consists of a Pigeon, which is used to measure the pitch of the robot and determine when to + * extend and retract the elevator around a rung. + */ +public class Elevator extends SubsystemBase { + private final ElevatorIO io; + private final ElevatorIOInputs inputs = new ElevatorIOInputs(); + + private double encoderPositionSetpoint; + + private double prevPitch; + private double[] latestPitches; + private int latestPitchesIndex; + + private static final String SUBSYSTEM_NAME = "Elevator"; + private static final boolean TESTING = false; + private static final boolean DEBUGGING = false; + private static final boolean TUNING = false; + + /** Constructs a new Elevator object. */ + public Elevator(ElevatorIO io) { + this.io = io; + + this.encoderPositionSetpoint = 0.0; + + this.prevPitch = 0.0; + this.latestPitches = new double[100]; + this.latestPitchesIndex = 0; + + ShuffleboardTab tab = Shuffleboard.getTab(SUBSYSTEM_NAME); + + if (DEBUGGING) { + tab.add("elevator", this); + tab.addNumber("Encoder", this::getElevatorEncoderHeight); + tab.addBoolean("Near Local Min?", this::isNearLocalMinimum); + tab.addBoolean("Near Local Max?", this::isNearLocalMaximum); + tab.addNumber("Pitch", () -> inputs.pitch); + tab.addBoolean("At Setpoint?", this::atSetpoint); + tab.addBoolean("Approaching Next Rung?", this::isApproachingNextRung); + tab.addBoolean("Control Enabled?", this::isElevatorControlEnabled); + } + + if (TESTING) { + tab.add("Extend Climber to Mid", new ExtendClimberToMidRungCommand(this)); + tab.add("Retract Climber Full", new RetractClimberFullCommand(this)); + tab.add( + "Retract Climber Minimum", + new RetractClimberMinimumCommand(ElevatorConstants.LATCH_HIGH_RUNG_ENCODER_HEIGHT, this)); + } + + if (TUNING) { + io.setControlEnabled(true); + + tab.addNumber("Closed Loop Target", this::getSetpoint); + tab.addNumber("Closed Loop Error", () -> inputs.rightClosedLoopError); + tab.addNumber("Velocity", () -> inputs.rightVelocity); + tab.addNumber("Left Motor Volts", () -> inputs.leftAppliedVolts); + tab.addNumber("Right Motor Volts", () -> inputs.rightAppliedVolts); + + tab.add("Elevator Motors", 0.0) + .withWidget(BuiltInWidgets.kNumberSlider) + .withProperties(Map.of("min", -1, "max", 1)) + .getEntry() + .addListener( + event -> this.setElevatorMotorPower(event.getEntry().getValue().getDouble()), + EntryListenerFlags.kNew | EntryListenerFlags.kUpdate); + + tab.add("Position Setpoint", 0.0) + .withWidget(BuiltInWidgets.kNumberSlider) + .withProperties(Map.of("min", 0, "max", MAX_ELEVATOR_HEIGHT)) + .getEntry() + .addListener( + event -> this.setElevatorMotorPosition(event.getEntry().getValue().getDouble(), true), + EntryListenerFlags.kNew | EntryListenerFlags.kUpdate); + + tab.add("Flywheel F", POSITION_PID_F) + .withWidget(BuiltInWidgets.kNumberSlider) + .withProperties(Map.of("min", 0, "max", 1.0)) // specify widget properties here + .getEntry() + .addListener( + event -> io.configureKF(event.getEntry().getValue().getDouble()), + EntryListenerFlags.kNew | EntryListenerFlags.kUpdate); + + tab.add("Flywheel P", POSITION_PID_P) + .withWidget(BuiltInWidgets.kNumberSlider) + .withProperties(Map.of("min", 0, "max", 1.0)) // specify widget properties here + .getEntry() + .addListener( + event -> io.configureKP(event.getEntry().getValue().getDouble()), + EntryListenerFlags.kNew | EntryListenerFlags.kUpdate); + + tab.add("Flywheel I", POSITION_PID_I) + .withWidget(BuiltInWidgets.kNumberSlider) + .withProperties(Map.of("min", 0, "max", 1.0)) // specify widget properties here + .getEntry() + .addListener( + event -> io.configureKI(event.getEntry().getValue().getDouble()), + EntryListenerFlags.kNew | EntryListenerFlags.kUpdate); + + tab.add("Flywheel D", POSITION_PID_D) + .withWidget(BuiltInWidgets.kNumberSlider) + .withProperties(Map.of("min", 0, "max", 1.0)) // specify widget properties here + .getEntry() + .addListener( + event -> io.configureKD(event.getEntry().getValue().getDouble()), + EntryListenerFlags.kNew | EntryListenerFlags.kUpdate); + } + } + + /** + * This method is invoked each iteration of the scheduler. Typically, when using a command-based + * model, subsystems don't override the periodic method. However, the elevator needs to + * continually record the robot's pitch in order to identify local maxima and minima. + */ + @Override + public void periodic() { + io.updateInputs(inputs); + Logger.getInstance().processInputs(SUBSYSTEM_NAME, inputs); + + double pitch = inputs.pitch; + + // keep the last 100 unique pitches (2 seconds of data) + if (pitch != this.prevPitch) { + this.prevPitch = pitch; + this.latestPitches[this.latestPitchesIndex] = pitch; + this.latestPitchesIndex++; + this.latestPitchesIndex %= this.latestPitches.length; + } + } + + /** + * Sets the power of the motors the raise and lower the elevator. This method is intended to only + * be invoked for manual control of the elevator. Typically, the setElevatorMotorPosition method + * is invoked to move the elevator to a specified position. + * + * @param power the specified power of the elevator's motors as a percentage of full power [-1.0, + * 1.0]; positive values raise the elevator + */ + public void setElevatorMotorPower(double power) { + // since this method is intended for manual control, ensure that the elevator isn't driven + // into the hardstops at the top or bottom + if (isElevatorControlEnabled()) { + if ((power > 0 && this.getElevatorEncoderHeight() > MAX_ELEVATOR_HEIGHT - 5000) + || (power < 0 && this.getElevatorEncoderHeight() < MIN_ELEVATOR_ENCODER_HEIGHT + 5000)) { + this.stopElevator(); + } else { + io.setMotorPercentage(power); + } + } + } + + /** + * Sets the setpoint of the elevator to the specified position and moves the elevator towards that + * position with the power capped at the specified value. + * + * @param desiredEncoderPosition the specified position of the elevator (in ticks); ticks are 0 + * when the elevator is fully retracted + * @param isFast if true, move the elevator at maximum power; if false, move the elevator slowly + */ + public void setElevatorMotorPosition(double desiredEncoderPosition, boolean isFast) { + // Control of the elevator is locked out until enabled with the press of a climb-enable + // button on the operator console. This is critical because, if the elevator is + // inadvertently extended when not in the hanger, it may violate the height limit and + // result in a penalty. + if (isElevatorControlEnabled()) { + + if (isFast) { + io.configClosedLoopPeakOutput(POSITION_PID_PEAK_OUTPUT); + } else { + io.configClosedLoopPeakOutput(SLOW_PEAK_OUTPUT); + } + + // the feedforward term will be different depending if the elevator is going up + // or down and if it under load or not; use the desiredEncoderPosition to determine the + // corresponding feed forward term + if (desiredEncoderPosition > this.getElevatorEncoderHeight()) { // extending unloaded + // as long as the setpoints are correct, this check is not required as the elevator + // will not hit the hardstops + if (this.getElevatorEncoderHeight() > MAX_ELEVATOR_HEIGHT - 2500) { + this.stopElevator(); + } else { + io.setPosition(desiredEncoderPosition, ARBITRARY_FEED_FORWARD_EXTEND); + } + } else { // retracting loaded + // as long as the setpoints are correct, this check is not required as the elevator + // will not hit the hardstops + if (this.getElevatorEncoderHeight() < MIN_ELEVATOR_ENCODER_HEIGHT + 2500) { + this.stopElevator(); + } else { + io.setPosition(desiredEncoderPosition, ARBITRARY_FEED_FORWARD_RETRACT); + } + } + + this.encoderPositionSetpoint = desiredEncoderPosition; + } + } + + /** + * Returns true if the elevator's position is at the specified setpoint (i.e., within the desired + * tolerance) or if elevator control is not enabled. The tolerance is critical since it is highly + * unlikely that the position of the elevator will match the setpoint exactly. Based on impirical + * observations, there is little to no overshoot of the setpoint. Therefore, there is no need to + * wait additional iterations and provide time to settle. + * + * @return true if the elevator's position is at the specified setpoint (i.e., within the desired + * tolerance) or if elevator control is not enabled. + */ + public boolean atSetpoint() { + if (!isElevatorControlEnabled()) { + return true; + } + + return Math.abs(this.getElevatorEncoderHeight() - this.encoderPositionSetpoint) + < ELEVATOR_POSITION_TOLERANCE; + } + + /** + * Stops the elevator. Since the elevator's motors are in brake mode, the elevator will stop + * moving almost immediately after this method is executed. + */ + public void stopElevator() { + io.setMotorPercentage(0.0); + } + + /** + * Returns true if the robot's swing is just beyond a local minimum. This is useful for + * determining when it is time to extend the elevator below a rung. + * + * @return true if the robot's swing is just beyond a local minimum + */ + public boolean isNearLocalMinimum() { + // check for a local minimum 2/3 through the sample window + // (latestPitchesIndex is the index where the *next* pitch will be stored) + int potentialLocalMinIndex = (this.latestPitchesIndex - 1) - (SAMPLE_WINDOW_WIDTH / 3); + + // there is a potential to end up with a negative index; wrap around as necessary + potentialLocalMinIndex = + (potentialLocalMinIndex + this.latestPitches.length) % this.latestPitches.length; + + // check if all of the samples before and after the potential local min are greater than the + // potential local min + + double potentialLocalMin = this.latestPitches[potentialLocalMinIndex]; + + int minIndex = this.latestPitchesIndex - SAMPLE_WINDOW_WIDTH; + minIndex = + (minIndex + this.latestPitches.length) % this.latestPitches.length; // handle wrap around + + boolean isLocalMin = true; + for (int i = 0; i < SAMPLE_WINDOW_WIDTH; i++) { + int index = minIndex + i; + index = (index + this.latestPitches.length) % this.latestPitches.length; // handle wrap around + + if (this.latestPitches[index] + EPSILON < potentialLocalMin) { + isLocalMin = false; + } + } + + return isLocalMin; + } + + /** + * Returns true if the robot's swing is just beyond a local maximum. This is useful for + * determining when it is time to extend the elevator above a rung. + * + * @return true if the robot's swing is just beyond a local maximum + */ + public boolean isNearLocalMaximum() { + // check for a local minimum 2/3 through the sample window + // (latestPitchesIndex is the index where the *next* pitch will be stored) + int potentialLocalMaxIndex = (this.latestPitchesIndex - 1) - (SAMPLE_WINDOW_WIDTH / 3); + + // there is a potential to end up with a negative index; wrap around as necessary + potentialLocalMaxIndex = + (potentialLocalMaxIndex + this.latestPitches.length) % this.latestPitches.length; + + // check if all of the samples before and after the potential local min are greater than the + // potential local min + + double potentialLocalMax = this.latestPitches[potentialLocalMaxIndex]; + + int minIndex = this.latestPitchesIndex - SAMPLE_WINDOW_WIDTH; + minIndex = + (minIndex + this.latestPitches.length) % this.latestPitches.length; // handle wrap around + + boolean isLocalMax = true; + for (int i = 0; i < SAMPLE_WINDOW_WIDTH; i++) { + int index = minIndex + i; + index = (index + this.latestPitches.length) % this.latestPitches.length; // handle wrap around + + if (this.latestPitches[index] - EPSILON > potentialLocalMax) { + isLocalMax = false; + } + } + + return isLocalMax; + } + + /** + * Returns true if the elevator is approaching the next rung. This is used to determine when it is + * time to ensure that the elevator passes below the next rung. + * + * @return true if the elevator is approaching the next rung + */ + public boolean isApproachingNextRung() { + return this.getElevatorEncoderHeight() > REACH_JUST_BEFORE_NEXT_RUNG; + } + + /** + * Stops the elevator. This method is intended to only be invoked for manual control of the + * elevator. To prevent inadvertent operation, this method requires that two buttons are pressed + * simultaneously to stop the elevator. + * + * @param isStartPressed true if the second button is also pressed, which is required to stop the + * elevator + */ + public void elevatorPause(boolean isStartPressed) { + if (isStartPressed) { + this.stopElevator(); + } + } + + /** + * Enables operation of the elevator. Control of the elevator is locked out until enabled with the + * press of a climb-enable button on the operator console, which invokes this method. This is + * critical because, if the elevator is inadvertently extended when not in the hanger, it may + * violate the height limit and result in a penalty. + */ + public void enableElevatorControl() { + io.setControlEnabled(true); + } + + /** + * Disables operation of the elevator. Control of the elevator is locked out until enabled with + * the press of a climb-enable button on the operator console. This is critical because, if the + * elevator is inadvertently extended when not in the hanger, it may violate the height limit and + * result in a penalty. + */ + public void disableElevatorControl() { + io.setControlEnabled(false); + } + + /** + * Returns true if control of the elevator is enabled. Control of the elevator is locked out until + * enabled with the press of a climb-enable button on the operator console. This is critical + * because, if the elevator is inadvertently extended when not in the hanger, it may violate the + * height limit and result in a penalty. + * + * @return true if control of the elevator is enabled + */ + public boolean isElevatorControlEnabled() { + return inputs.isControlEnabled; + } + + private double getElevatorEncoderHeight() { + return inputs.rightPosition; + } + + private double getSetpoint() { + return encoderPositionSetpoint; + } +} diff --git a/src/main/java/frc/robot/subsystems/elevator/ElevatorIO.java b/src/main/java/frc/robot/subsystems/elevator/ElevatorIO.java new file mode 100644 index 0000000..f349253 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/elevator/ElevatorIO.java @@ -0,0 +1,99 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems.elevator; + +import org.littletonrobotics.junction.LogTable; +import org.littletonrobotics.junction.inputs.LoggableInputs; + +/** Intake subsystem hardware interface. */ +public interface ElevatorIO { + /** Contains all of the input data received from hardware. */ + public static class ElevatorIOInputs implements LoggableInputs { + boolean isControlEnabled = false; + + double leftPosition = 0.0; + double leftVelocity = 0.0; + double leftClosedLoopError = 0.0; + double leftAppliedVolts = 0.0; + double[] leftCurrentAmps = new double[] {}; + double[] leftTempCelcius = new double[] {}; + + double rightPosition = 0.0; + double rightVelocity = 0.0; + double rightClosedLoopError = 0.0; + double rightAppliedVolts = 0.0; + double[] rightCurrentAmps = new double[] {}; + double[] rightTempCelcius = new double[] {}; + + double pitch = 0.0; + + public void toLog(LogTable table) { + table.put("ControlEnabled", isControlEnabled); + + table.put("LeftPosition", leftPosition); + table.put("LeftVelocity", leftVelocity); + table.put("LeftClosedLoopError", leftClosedLoopError); + table.put("LeftAppliedVolts", leftAppliedVolts); + table.put("LeftCurrentAmps", leftCurrentAmps); + table.put("LeftTempCelcius", leftTempCelcius); + + table.put("RightPosition", rightPosition); + table.put("RightVelocity", rightVelocity); + table.put("RightClosedLoopError", rightClosedLoopError); + table.put("RightAppliedVolts", rightAppliedVolts); + table.put("RightCurrentAmps", rightCurrentAmps); + table.put("RightTempCelcius", rightTempCelcius); + + table.put("Pitch", pitch); + } + + public void fromLog(LogTable table) { + isControlEnabled = table.getBoolean("ControlEnabled", isControlEnabled); + + leftPosition = table.getDouble("LeftPosition", leftPosition); + leftVelocity = table.getDouble("LeftVelocity", leftVelocity); + leftClosedLoopError = table.getDouble("LeftClosedLoopError", leftClosedLoopError); + leftAppliedVolts = table.getDouble("LeftAppliedVolts", leftAppliedVolts); + leftCurrentAmps = table.getDoubleArray("LeftCurrentAmps", leftCurrentAmps); + leftTempCelcius = table.getDoubleArray("LeftTempCelcius", leftTempCelcius); + + rightPosition = table.getDouble("RightPosition", rightPosition); + rightVelocity = table.getDouble("RightVelocity", rightVelocity); + rightClosedLoopError = table.getDouble("RightClosedLoopError", rightClosedLoopError); + rightAppliedVolts = table.getDouble("RightAppliedVolts", rightAppliedVolts); + rightCurrentAmps = table.getDoubleArray("RightCurrentAmps", rightCurrentAmps); + rightTempCelcius = table.getDoubleArray("RightTempCelcius", rightTempCelcius); + + pitch = table.getDouble("Pitch", pitch); + } + } + + /** Updates the set of loggable inputs. */ + public default void updateInputs(ElevatorIOInputs inputs) {} + + /** Enable/Disable collector. */ + public default void setControlEnabled(boolean controlEnabled) {} + + /** Run the climber open loop at the specified voltage. */ + public default void setMotorPercentage(double percentage) {} + + /** Run the climber closed loop to the specified position. */ + public default void setPosition(double position, double arbitraryFeedForward) {} + + /** Set position feed forward constant. */ + public default void configureKF(double kF) {} + + /** Set position proportional constant. */ + public default void configureKP(double kP) {} + + /** Set position integrative constant. */ + public default void configureKI(double kI) {} + + /** Set position derivative constant. */ + public default void configureKD(double kD) {} + + /** Set closed loop peak output. */ + public default void configClosedLoopPeakOutput(double peakOutput) {} +} diff --git a/src/main/java/frc/robot/subsystems/elevator/ElevatorIOTalonFX.java b/src/main/java/frc/robot/subsystems/elevator/ElevatorIOTalonFX.java new file mode 100644 index 0000000..caba10b --- /dev/null +++ b/src/main/java/frc/robot/subsystems/elevator/ElevatorIOTalonFX.java @@ -0,0 +1,196 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems.elevator; + +import static frc.robot.Constants.ElevatorConstants.*; + +import com.ctre.phoenix.motorcontrol.ControlMode; +import com.ctre.phoenix.motorcontrol.DemandType; +import com.ctre.phoenix.motorcontrol.NeutralMode; +import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced; +import com.ctre.phoenix.motorcontrol.TalonFXControlMode; +import com.ctre.phoenix.motorcontrol.TalonFXFeedbackDevice; +import com.ctre.phoenix.motorcontrol.TalonFXInvertType; +import com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration; +import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX; +import com.ctre.phoenix.sensors.Pigeon2; +import frc.robot.util.CANDeviceFinder; +import frc.robot.util.CANDeviceId.CANDeviceType; + +public class ElevatorIOTalonFX implements ElevatorIO { + private boolean isControlEnabled; + + private final WPI_TalonFX leftElevatorMotor; + private final WPI_TalonFX rightElevatorMotor; + private final Pigeon2 pigeon; + + public ElevatorIOTalonFX() { + CANDeviceFinder can = new CANDeviceFinder(); + + this.isControlEnabled = false; + + can.isDevicePresent(CANDeviceType.TALON, LEFT_ELEVATOR_MOTOR_CAN_ID, "Left Elevator Motor"); + can.isDevicePresent(CANDeviceType.TALON, RIGHT_ELEVATOR_MOTOR_CAN_ID, "Right Elevator Motor"); + this.leftElevatorMotor = new WPI_TalonFX(LEFT_ELEVATOR_MOTOR_CAN_ID); + this.rightElevatorMotor = new WPI_TalonFX(RIGHT_ELEVATOR_MOTOR_CAN_ID); + + // the following configuration is based on the CTRE example code + + /* Factory Default all hardware to prevent unexpected behaviour */ + this.rightElevatorMotor.configFactoryDefault(); + this.leftElevatorMotor.configFactoryDefault(); + + /** Config Objects for motor controllers */ + TalonFXConfiguration rightConfig = new TalonFXConfiguration(); + + /* Disable all motors */ + this.rightElevatorMotor.set(TalonFXControlMode.PercentOutput, 0); + this.leftElevatorMotor.set(TalonFXControlMode.PercentOutput, 0); + + /* Set neutral modes */ + this.leftElevatorMotor.setNeutralMode(NeutralMode.Brake); + this.rightElevatorMotor.setNeutralMode(NeutralMode.Brake); + + this.leftElevatorMotor.follow(this.rightElevatorMotor); + + /* Configure output */ + this.rightElevatorMotor.setInverted(TalonFXInvertType.Clockwise); + this.leftElevatorMotor.setInverted(TalonFXInvertType.FollowMaster); + + /* + * Talon FX does not need sensor phase set for its integrated sensor + * This is because it will always be correct if the selected feedback device is + * integrated sensor (default value) + * and the user calls getSelectedSensor* to get the sensor's position/velocity. + * + * https://phoenix-documentation.readthedocs.io/en/latest/ch14_MCSensor.html# + * sensor-phase + * + * this.leftElevatorMotor.setSensorPhase(true) + * this.rightElevatorMotor.setSensorPhase(true) + */ + + /** Feedback Sensor Configuration */ + + /** Distance Configs */ + + /* Configure the left Talon's selected sensor as integrated sensor */ + rightConfig.primaryPID.selectedFeedbackSensor = + TalonFXFeedbackDevice.IntegratedSensor.toFeedbackDevice(); // Local + // Feedback + // Source + + /* FPID for Distance */ + rightConfig.slot0.kF = POSITION_PID_F; + rightConfig.slot0.kP = POSITION_PID_P; + rightConfig.slot0.kI = POSITION_PID_I; + rightConfig.slot0.kD = POSITION_PID_D; + rightConfig.slot0.integralZone = POSITION_PID_I_ZONE; + rightConfig.slot0.closedLoopPeakOutput = POSITION_PID_PEAK_OUTPUT; + + /* Config the neutral deadband. */ + rightConfig.neutralDeadband = 0.001; + + /** + * 1ms per loop. PID loop can be slowed down if need be. For example, - if sensor updates are + * too slow - sensor deltas are very small per update, so derivative error never gets large + * enough to be useful. - sensor movement is very slow causing the derivative error to be near + * zero. + */ + int closedLoopTimeMs = 1; + rightConfig.slot0.closedLoopPeriod = closedLoopTimeMs; + rightConfig.slot1.closedLoopPeriod = closedLoopTimeMs; + rightConfig.slot2.closedLoopPeriod = closedLoopTimeMs; + rightConfig.slot3.closedLoopPeriod = closedLoopTimeMs; + + /* Motion Magic Configs */ + rightConfig.motionAcceleration = + ELEVATOR_ACCELERATION; // (distance units per 100 ms) per second + rightConfig.motionCruiseVelocity = MAX_ELEVATOR_VELOCITY; // distance units per 100 ms + rightConfig.motionCurveStrength = SCURVE_STRENGTH; + + /* APPLY the config settings */ + this.rightElevatorMotor.configAllSettings(rightConfig); + + /* Initialize */ + this.rightElevatorMotor.getSensorCollection().setIntegratedSensorPosition(0, TIMEOUT_MS); + + // these status frames aren't read; so, set these CAN frame periods to the maximum value + // to reduce traffic on the bus + this.leftElevatorMotor.setStatusFramePeriod( + StatusFrameEnhanced.Status_1_General, 255, TIMEOUT_MS); + this.leftElevatorMotor.setStatusFramePeriod( + StatusFrameEnhanced.Status_2_Feedback0, 255, TIMEOUT_MS); + + this.pigeon = new Pigeon2(PIGEON_ID); + } + + @Override + public void updateInputs(ElevatorIOInputs inputs) { + inputs.isControlEnabled = isControlEnabled; + + inputs.leftPosition = leftElevatorMotor.getSelectedSensorPosition(SLOT_INDEX); + inputs.leftVelocity = leftElevatorMotor.getSelectedSensorVelocity(SLOT_INDEX); + inputs.leftClosedLoopError = leftElevatorMotor.getClosedLoopError(SLOT_INDEX); + inputs.leftAppliedVolts = leftElevatorMotor.getMotorOutputVoltage(); + inputs.leftCurrentAmps = new double[] {leftElevatorMotor.getStatorCurrent()}; + inputs.leftTempCelcius = new double[] {leftElevatorMotor.getTemperature()}; + + inputs.rightPosition = rightElevatorMotor.getSelectedSensorPosition(SLOT_INDEX); + inputs.rightVelocity = rightElevatorMotor.getSelectedSensorVelocity(SLOT_INDEX); + inputs.rightClosedLoopError = rightElevatorMotor.getClosedLoopError(SLOT_INDEX); + inputs.rightAppliedVolts = rightElevatorMotor.getMotorOutputVoltage(); + inputs.rightCurrentAmps = new double[] {rightElevatorMotor.getStatorCurrent()}; + inputs.rightTempCelcius = new double[] {rightElevatorMotor.getTemperature()}; + + inputs.pitch = pigeon.getPitch(); + } + + @Override + public void setControlEnabled(boolean controlEnabled) { + isControlEnabled = controlEnabled; + } + + @Override + public void setMotorPercentage(double percentage) { + leftElevatorMotor.set(ControlMode.PercentOutput, percentage); + rightElevatorMotor.set(ControlMode.PercentOutput, percentage); + } + + @Override + public void setPosition(double position, double arbitraryFeedForward) { + leftElevatorMotor.follow(rightElevatorMotor); + rightElevatorMotor.set( + TalonFXControlMode.Position, + position, + DemandType.ArbitraryFeedForward, + arbitraryFeedForward); + } + + @Override + public void configureKF(double kF) { + rightElevatorMotor.config_kF(SLOT_INDEX, kF, TIMEOUT_MS); + } + + @Override + public void configureKP(double kP) { + rightElevatorMotor.config_kP(SLOT_INDEX, kP, TIMEOUT_MS); + } + + @Override + public void configureKI(double kI) { + rightElevatorMotor.config_kI(SLOT_INDEX, kI, TIMEOUT_MS); + } + + @Override + public void configureKD(double kD) { + rightElevatorMotor.config_kD(SLOT_INDEX, kD, TIMEOUT_MS); + } + + @Override + public void configClosedLoopPeakOutput(double peakOutput) { + rightElevatorMotor.configClosedLoopPeakOutput(SLOT_INDEX, peakOutput); + } +} diff --git a/src/main/java/frc/robot/subsystems/flywheel/Flywheel.java b/src/main/java/frc/robot/subsystems/flywheel/Flywheel.java new file mode 100644 index 0000000..cd2601a --- /dev/null +++ b/src/main/java/frc/robot/subsystems/flywheel/Flywheel.java @@ -0,0 +1,176 @@ +package frc.robot.subsystems.flywheel; + +import static frc.robot.Constants.FlywheelConstants.*; + +import edu.wpi.first.networktables.EntryListenerFlags; +import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets; +import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; +import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; +import edu.wpi.first.wpilibj2.command.InstantCommand; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.commands.SetFlywheelVelocityCommand; +import frc.robot.subsystems.flywheel.FlywheelIO.FlywheelIOInputs; +import java.util.Map; +import org.littletonrobotics.junction.Logger; + +/** + * This subsystem models the robot's flywheel mechanism. It consists of two motors, which both + * rotate the flywheel. The right motor is controlled by a PID running on its motor controller to + * keep the flywheel's velocity at the specified setpoint. The left motor follows the right. + */ +public class Flywheel extends SubsystemBase { + private final FlywheelIO io; + private final FlywheelIOInputs inputs = new FlywheelIOInputs(); + + private double velocitySetPoint; + private int atSetpointIterationCount; + + private static final String SUBSYSTEM_NAME = "Shooter"; + private static final boolean TESTING = false; + private static final boolean DEBUGGING = false; + private static final boolean TUNING = false; + + /** Constructs a new Flywheel object. */ + public Flywheel(FlywheelIO io) { + this.io = io; + + this.velocitySetPoint = 0.0; + + ShuffleboardTab tab = Shuffleboard.getTab(SUBSYSTEM_NAME); + + if (DEBUGGING) { + tab.add(SUBSYSTEM_NAME, this); + + tab.addBoolean("At Setpoint?", this::isAtSetpoint); + tab.addNumber("Velocity", this::getVelocity); + tab.addNumber("Right Velocity", () -> inputs.rightVelocity); + tab.addNumber("Left Velocity", () -> inputs.leftVelocity); + tab.addNumber("Right Closed Loop Error", () -> inputs.rightClosedLoopError); + tab.addNumber("Left Voltage", () -> inputs.leftAppliedVolts); + tab.addNumber("Right Voltage", () -> inputs.rightAppliedVolts); + } + + if (TESTING) { + tab.add("Wall Shot", new SetFlywheelVelocityCommand(this, WALL_SHOT_VELOCITY)); + tab.add("Launchpad Shot", new SetFlywheelVelocityCommand(this, LAUNCH_PAD_VELOCITY)); + tab.add("Stop Flywheel", new InstantCommand(this::stopFlywheel, this)); + } + + if (TUNING) { + tab.add("Velocity Setpoint", 0.0) + .withWidget(BuiltInWidgets.kNumberSlider) + .withProperties(Map.of("min", 0, "max", 25000)) // specify widget properties here + .getEntry() + .addListener( + event -> this.setVelocity(event.getEntry().getValue().getDouble()), + EntryListenerFlags.kNew | EntryListenerFlags.kUpdate); + + tab.add("Flywheel Power", 0.0) + .withWidget(BuiltInWidgets.kNumberSlider) + .withProperties(Map.of("min", 0, "max", 1.0)) // specify widget properties here + .getEntry() + .addListener( + event -> io.setMotorPercentage(event.getEntry().getValue().getDouble()), + EntryListenerFlags.kNew | EntryListenerFlags.kUpdate); + + tab.add("Flywheel F", VELOCITY_PID_F) + .withWidget(BuiltInWidgets.kNumberSlider) + .withProperties(Map.of("min", 0, "max", 1.0)) // specify widget properties here + .getEntry() + .addListener( + event -> io.configureKF(event.getEntry().getValue().getDouble()), + EntryListenerFlags.kNew | EntryListenerFlags.kUpdate); + + tab.add("Flywheel P", VELOCITY_PID_P) + .withWidget(BuiltInWidgets.kNumberSlider) + .withProperties(Map.of("min", 0, "max", 2.0)) // specify widget properties here + .getEntry() + .addListener( + event -> io.configureKP(event.getEntry().getValue().getDouble()), + EntryListenerFlags.kNew | EntryListenerFlags.kUpdate); + + tab.add("Flywheel I", VELOCITY_PID_I) + .withWidget(BuiltInWidgets.kNumberSlider) + .withProperties(Map.of("min", 0, "max", 1.0)) // specify widget properties here + .getEntry() + .addListener( + event -> io.configureKI(event.getEntry().getValue().getDouble()), + EntryListenerFlags.kNew | EntryListenerFlags.kUpdate); + + tab.add("Flywheel D", VELOCITY_PID_D) + .withWidget(BuiltInWidgets.kNumberSlider) + .withProperties(Map.of("min", 0, "max", 1.0)) // specify widget properties here + .getEntry() + .addListener( + event -> io.configureKD(event.getEntry().getValue().getDouble()), + EntryListenerFlags.kNew | EntryListenerFlags.kUpdate); + } + } + + /** + * For each iteration, the subsystem's periodic method is invoked before any commands are + * executed. + */ + @Override + public void periodic() { + io.updateInputs(inputs); + Logger.getInstance().processInputs(SUBSYSTEM_NAME, inputs); + } + + private double getVelocity() { + return inputs.rightVelocity; + } + + /** + * Sets the velocity of the flywheel to the specified value. + * + * @param velocitySetPoint the desired velocity of the flywheel in units of ticks per 100 ms + */ + public void setVelocity(double velocitySetPoint) { + this.velocitySetPoint = velocitySetPoint; + + io.setVelocity(velocitySetPoint); + } + + /** + * Returns true if the flywheel's velocity is at the specified setpoint (i.e., within the desired + * tolerance for the specified number of iterations). The tolerance is critical since it is highly + * unlikely that the velocity of the flywheel will match the setpoint exactly. Waiting the + * specified number of iterations is critical since the PID may overshoot the setpoint and need + * additional time to settle. The flywheel is only considered at the specified velocity if it + * remains at that velocity continuously for the desired number of iterations. Without waiting, it + * would be reported that the flywheel had reached the specified velocity but then, when the cargo + * is shot, the velocity would be too great. + * + * @return true if the flywheel's velocity is at the specified setpoint (i.e., within the desired + * tolerance for the specified number of iterations) + */ + public boolean isAtSetpoint() { + if (Math.abs(this.getVelocity() - this.velocitySetPoint) < VELOCITY_TOLERANCE) { + atSetpointIterationCount++; + if (atSetpointIterationCount >= SETPOINTCOUNT) { + return true; + } + } else { + atSetpointIterationCount = 0; + } + + return false; + } + + /** + * Stops the flywheel. Since the flywheel's motors are in brake mode, the flywheel will stop + * spinning shortly after this method is executed. + */ + public void stopFlywheel() { + io.setMotorPercentage(0.0); + } + + /** + * Reverses the normal direction of the flywheel at the desired power. This method is invoked if + * cargo has jammed in the flywheel or storage. + */ + public void unjamFlywheel() { + io.setMotorPercentage(REVERSE_POWER); + } +} diff --git a/src/main/java/frc/robot/subsystems/flywheel/FlywheelIO.java b/src/main/java/frc/robot/subsystems/flywheel/FlywheelIO.java new file mode 100644 index 0000000..97836bd --- /dev/null +++ b/src/main/java/frc/robot/subsystems/flywheel/FlywheelIO.java @@ -0,0 +1,75 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems.flywheel; + +import org.littletonrobotics.junction.LogTable; +import org.littletonrobotics.junction.inputs.LoggableInputs; + +/** Intake subsystem hardware interface. */ +public interface FlywheelIO { + /** Contains all of the input data received from hardware. */ + public static class FlywheelIOInputs implements LoggableInputs { + double leftVelocity = 0.0; + double leftClosedLoopError = 0.0; + double leftAppliedVolts = 0.0; + double[] leftCurrentAmps = new double[] {}; + double[] leftTempCelcius = new double[] {}; + + double rightVelocity = 0.0; + double rightClosedLoopError = 0.0; + double rightAppliedVolts = 0.0; + double[] rightCurrentAmps = new double[] {}; + double[] rightTempCelcius = new double[] {}; + + public void toLog(LogTable table) { + table.put("LeftVelocity", leftVelocity); + table.put("LeftClosedLoopError", leftClosedLoopError); + table.put("LeftAppliedVolts", leftAppliedVolts); + table.put("LeftCurrentAmps", leftCurrentAmps); + table.put("LeftTempCelcius", leftTempCelcius); + + table.put("RightVelocity", rightVelocity); + table.put("RightClosedLoopError", rightClosedLoopError); + table.put("RightAppliedVolts", rightAppliedVolts); + table.put("RightCurrentAmps", rightCurrentAmps); + table.put("RightTempCelcius", rightTempCelcius); + } + + public void fromLog(LogTable table) { + leftVelocity = table.getDouble("LeftVelocity", leftVelocity); + leftClosedLoopError = table.getDouble("LeftClosedLoopError", leftClosedLoopError); + leftAppliedVolts = table.getDouble("LeftAppliedVolts", leftAppliedVolts); + leftCurrentAmps = table.getDoubleArray("LeftCurrentAmps", leftCurrentAmps); + leftTempCelcius = table.getDoubleArray("LeftTempCelcius", leftTempCelcius); + + rightVelocity = table.getDouble("RightVelocity", rightVelocity); + rightClosedLoopError = table.getDouble("RightClosedLoopError", rightClosedLoopError); + rightAppliedVolts = table.getDouble("RightAppliedVolts", rightAppliedVolts); + rightCurrentAmps = table.getDoubleArray("RightCurrentAmps", rightCurrentAmps); + rightTempCelcius = table.getDoubleArray("RightTempCelcius", rightTempCelcius); + } + } + + /** Updates the set of loggable inputs. */ + public default void updateInputs(FlywheelIOInputs inputs) {} + + /** Run the flywheel open loop at the specified voltage. */ + public default void setMotorPercentage(double percentage) {} + + /** Run the flywheel closed loop at the specified velocity. */ + public default void setVelocity(double velocity) {} + + /** Set velocity feed forward constant. */ + public default void configureKF(double kF) {} + + /** Set velocity proportional constant. */ + public default void configureKP(double kP) {} + + /** Set velocity integrative constant. */ + public default void configureKI(double kI) {} + + /** Set velocity derivative constant. */ + public default void configureKD(double kD) {} +} diff --git a/src/main/java/frc/robot/subsystems/flywheel/FlywheelIOTalonFX.java b/src/main/java/frc/robot/subsystems/flywheel/FlywheelIOTalonFX.java new file mode 100644 index 0000000..13591e8 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/flywheel/FlywheelIOTalonFX.java @@ -0,0 +1,157 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems.flywheel; + +import static frc.robot.Constants.FlywheelConstants.*; + +import com.ctre.phoenix.motorcontrol.ControlMode; +import com.ctre.phoenix.motorcontrol.NeutralMode; +import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced; +import com.ctre.phoenix.motorcontrol.TalonFXControlMode; +import com.ctre.phoenix.motorcontrol.TalonFXFeedbackDevice; +import com.ctre.phoenix.motorcontrol.TalonFXInvertType; +import com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration; +import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX; +import frc.robot.util.CANDeviceFinder; +import frc.robot.util.CANDeviceId.CANDeviceType; + +public class FlywheelIOTalonFX implements FlywheelIO { + private final WPI_TalonFX leftFlywheelMotor; + private final WPI_TalonFX rightFlywheelMotor; + + public FlywheelIOTalonFX() { + CANDeviceFinder can = new CANDeviceFinder(); + + can.isDevicePresent(CANDeviceType.TALON, LEFT_FLYWHEELMOTOR_CANID, "Left Flywheel Motor"); + can.isDevicePresent(CANDeviceType.TALON, RIGHT_FLYWHEELMOTOR_CANID, "Right Flywheel Motor"); + leftFlywheelMotor = new WPI_TalonFX(LEFT_FLYWHEELMOTOR_CANID); + rightFlywheelMotor = new WPI_TalonFX(RIGHT_FLYWHEELMOTOR_CANID); + + // the following configuration is based on the CTRE example code + + /* Factory Default all hardware to prevent unexpected behaviour */ + rightFlywheelMotor.configFactoryDefault(); + leftFlywheelMotor.configFactoryDefault(); + + /* Config sensor used for Primary PID [Velocity] */ + TalonFXConfiguration rightConfig = new TalonFXConfiguration(); + + /* Disable all motors */ + this.rightFlywheelMotor.set(TalonFXControlMode.PercentOutput, 0); + this.leftFlywheelMotor.set(TalonFXControlMode.PercentOutput, 0); + + /* Set neutral modes */ + this.leftFlywheelMotor.setNeutralMode(NeutralMode.Brake); + this.rightFlywheelMotor.setNeutralMode(NeutralMode.Brake); + + this.leftFlywheelMotor.follow(this.rightFlywheelMotor); + + /* Configure output */ + this.rightFlywheelMotor.setInverted(TalonFXInvertType.CounterClockwise); + this.leftFlywheelMotor.setInverted(TalonFXInvertType.Clockwise); + + /* + * Talon FX does not need sensor phase set for its integrated sensor + * This is because it will always be correct if the selected feedback device is + * integrated sensor (default value) + * and the user calls getSelectedSensor* to get the sensor's position/velocity. + * + * https://phoenix-documentation.readthedocs.io/en/latest/ch14_MCSensor.html# + * sensor-phase + * + * this.rightFlywheelMotor.setSensorPhase(true) + */ + + /** Feedback Sensor Configuration */ + + /** Distance Configs */ + + /* Configure the left Talon's selected sensor as integrated sensor */ + rightConfig.primaryPID.selectedFeedbackSensor = + TalonFXFeedbackDevice.IntegratedSensor.toFeedbackDevice(); // Local + // Feedback + // Source + + /* FPID for velocity */ + rightConfig.slot0.kF = VELOCITY_PID_F; + rightConfig.slot0.kP = VELOCITY_PID_P; + rightConfig.slot0.kI = VELOCITY_PID_I; + rightConfig.slot0.kD = VELOCITY_PID_D; + rightConfig.slot0.integralZone = VELOCITY_PID_I_ZONE; + rightConfig.slot0.closedLoopPeakOutput = VELOCITY_PID_PEAK_OUTPUT; + + /* Config the neutral deadband. */ + rightConfig.neutralDeadband = 0.001; + + /** + * 1ms per loop. PID loop can be slowed down if need be. For example, - if sensor updates are + * too slow - sensor deltas are very small per update, so derivative error never gets large + * enough to be useful. - sensor movement is very slow causing the derivative error to be near + * zero. + */ + int closedLoopTimeMs = 1; + rightConfig.slot0.closedLoopPeriod = closedLoopTimeMs; + rightConfig.slot1.closedLoopPeriod = closedLoopTimeMs; + rightConfig.slot2.closedLoopPeriod = closedLoopTimeMs; + rightConfig.slot3.closedLoopPeriod = closedLoopTimeMs; + + /* APPLY the config settings */ + this.rightFlywheelMotor.configAllSettings(rightConfig); + + // these status frames aren't read; so, set these CAN frame periods to the maximum value + // to reduce traffic on the bus + this.leftFlywheelMotor.setStatusFramePeriod( + StatusFrameEnhanced.Status_1_General, 255, TIMEOUT_MS); + this.leftFlywheelMotor.setStatusFramePeriod( + StatusFrameEnhanced.Status_2_Feedback0, 255, TIMEOUT_MS); + } + + @Override + public void updateInputs(FlywheelIOInputs inputs) { + inputs.leftVelocity = leftFlywheelMotor.getSelectedSensorVelocity(SLOT_INDEX); + inputs.leftClosedLoopError = leftFlywheelMotor.getClosedLoopError(SLOT_INDEX); + inputs.leftAppliedVolts = leftFlywheelMotor.getMotorOutputVoltage(); + inputs.leftCurrentAmps = new double[] {leftFlywheelMotor.getStatorCurrent()}; + inputs.leftTempCelcius = new double[] {leftFlywheelMotor.getTemperature()}; + + inputs.rightVelocity = rightFlywheelMotor.getSelectedSensorVelocity(SLOT_INDEX); + inputs.rightClosedLoopError = rightFlywheelMotor.getClosedLoopError(SLOT_INDEX); + inputs.rightAppliedVolts = rightFlywheelMotor.getMotorOutputVoltage(); + inputs.rightCurrentAmps = new double[] {rightFlywheelMotor.getStatorCurrent()}; + inputs.rightTempCelcius = new double[] {rightFlywheelMotor.getTemperature()}; + } + + @Override + public void setMotorPercentage(double percentage) { + leftFlywheelMotor.set(ControlMode.PercentOutput, percentage); + rightFlywheelMotor.set(ControlMode.PercentOutput, percentage); + } + + @Override + public void setVelocity(double velocity) { + leftFlywheelMotor.follow(this.rightFlywheelMotor); + rightFlywheelMotor.set(TalonFXControlMode.Velocity, velocity); + } + + @Override + public void configureKF(double kF) { + rightFlywheelMotor.config_kF(SLOT_INDEX, kF, TIMEOUT_MS); + } + + @Override + public void configureKP(double kP) { + rightFlywheelMotor.config_kP(SLOT_INDEX, kP, TIMEOUT_MS); + } + + @Override + public void configureKI(double kI) { + rightFlywheelMotor.config_kI(SLOT_INDEX, kI, TIMEOUT_MS); + } + + @Override + public void configureKD(double kD) { + rightFlywheelMotor.config_kD(SLOT_INDEX, kD, TIMEOUT_MS); + } +} diff --git a/src/main/java/frc/robot/subsystems/pneumatics/Pneumatics.java b/src/main/java/frc/robot/subsystems/pneumatics/Pneumatics.java new file mode 100644 index 0000000..892b728 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/pneumatics/Pneumatics.java @@ -0,0 +1,127 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +// from https://github.com/Mechanical-Advantage/RobotCode2022 + +package frc.robot.subsystems.pneumatics; + +import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.Constants; +import frc.robot.subsystems.pneumatics.PneumaticsIO.PneumaticsIOInputs; +import frc.robot.util.Alert; +import frc.robot.util.Alert.AlertType; +import java.util.ArrayList; +import java.util.List; +import org.littletonrobotics.junction.Logger; + +public class Pneumatics extends SubsystemBase { + private static final int NORMAL_AVERAGING_TAPS = 25; + private static final int COMPRESSOR_AVERAGING_TAPS = 50; + private static final double COMPRESSOR_RATE_PSI_PER_SEC = 1.5; + + private final PneumaticsIO io; + private final PneumaticsIOInputs inputs = new PneumaticsIOInputs(); + + private final List filterData = new ArrayList<>(); + private double pressureSmoothedPsi = 0.0; + + private double lastPressurePsi = 0.0; + private boolean lastPressureIncreasing = false; + private double compressorMaxPoint = 0.0; + private double compressorMinPoint = 0.0; + + private Timer noPressureTimer = new Timer(); + private Timer compressorEnabledTimer = new Timer(); + private Alert dumpValveAlert = + new Alert("Cannot build pressure. Is the dump value open?", AlertType.WARNING); + + /** Creates a new Pneumatics. */ + public Pneumatics(PneumaticsIO io) { + this.io = io; + noPressureTimer.start(); + compressorEnabledTimer.start(); + + Shuffleboard.getTab("MAIN").addNumber("Pressure", () -> getPressure()); + } + + public double getPressure() { + return pressureSmoothedPsi; + } + + @Override + public void periodic() { + io.updateInputs(inputs); + Logger.getInstance().processInputs("Pneumatics", inputs); + + calculateAveragePressure(); + + // Log pressure + Logger.getInstance().recordOutput("PressurePsi", pressureSmoothedPsi); + + // Detect if dump value is open + if (inputs.pressurePsi > 3) { + noPressureTimer.reset(); + } + if (!inputs.compressorActive) { + compressorEnabledTimer.reset(); + } + dumpValveAlert.set(noPressureTimer.hasElapsed(5) && compressorEnabledTimer.hasElapsed(5)); + } + + private void calculateAveragePressure() { + // Calculate input pressure for averaging filter + double limitedPressure = inputs.pressurePsi < 0.0 ? 0.0 : inputs.pressurePsi; + double processedPressure; + if (inputs.compressorActive) { + // When compressor is active, average the most recent min and max points + processedPressure = averagePressures(limitedPressure); + } else { + // When compressor is inactive, reset min/max status and use normal pressure + processedPressure = resetPressures(limitedPressure); + } + + // Run averaging filter + filterData.add(processedPressure); + while (filterData.size() + > (inputs.compressorActive ? COMPRESSOR_AVERAGING_TAPS : NORMAL_AVERAGING_TAPS)) { + filterData.remove(0); + } + pressureSmoothedPsi = filterData.stream().mapToDouble(a -> a).summaryStatistics().getAverage(); + } + + private double averagePressures(double limitedPressure) { + if (limitedPressure != lastPressurePsi) { + boolean increasing = limitedPressure > lastPressurePsi; + if (increasing != lastPressureIncreasing) { + if (increasing) { + compressorMinPoint = lastPressurePsi; + } else { + compressorMaxPoint = lastPressurePsi; + } + } + lastPressurePsi = limitedPressure; + lastPressureIncreasing = increasing; + } + double processedPressure = (compressorMinPoint + compressorMaxPoint) / 2.0; + + // Apply latency compensation + processedPressure += + (COMPRESSOR_AVERAGING_TAPS / 2.0) + * Constants.LOOP_PERIOD_SECS + * COMPRESSOR_RATE_PSI_PER_SEC; + + return processedPressure; + } + + private double resetPressures(double limitedPressure) { + + lastPressurePsi = limitedPressure; + lastPressureIncreasing = false; + compressorMaxPoint = limitedPressure; + compressorMinPoint = limitedPressure; + return limitedPressure; + } +} diff --git a/src/main/java/frc/robot/subsystems/pneumatics/PneumaticsIO.java b/src/main/java/frc/robot/subsystems/pneumatics/PneumaticsIO.java new file mode 100644 index 0000000..14dd8af --- /dev/null +++ b/src/main/java/frc/robot/subsystems/pneumatics/PneumaticsIO.java @@ -0,0 +1,44 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +// from https://github.com/Mechanical-Advantage/RobotCode2022 + +package frc.robot.subsystems.pneumatics; + +import org.littletonrobotics.junction.LogTable; +import org.littletonrobotics.junction.inputs.LoggableInputs; + +/** Pneumatics subsystem hardware interface. */ +public interface PneumaticsIO { + /** Contains all of the input data received from hardware. */ + public static class PneumaticsIOInputs implements LoggableInputs { + double revPressurePsi = 0.0; + boolean compressorActive = false; + double compressorCurrentAmps = 0.0; + double pressurePsi = 0.0; + double flow = 0.0; + + public void toLog(LogTable table) { + table.put("RevPressurePsi", revPressurePsi); + table.put("CompressorActive", compressorActive); + table.put("CompressorCurrentAmps", compressorCurrentAmps); + table.put("PressurePsi", pressurePsi); + table.put("Flow", flow); + } + + public void fromLog(LogTable table) { + revPressurePsi = table.getDouble("RevPressurePsi", revPressurePsi); + compressorActive = table.getBoolean("CompressorActive", compressorActive); + compressorCurrentAmps = table.getDouble("CompressorCurrentAmps", compressorCurrentAmps); + pressurePsi = table.getDouble("PressurePsi", pressurePsi); + flow = table.getDouble("Flow", flow); + } + } + + /** Updates the set of loggable inputs. */ + public default void updateInputs(PneumaticsIOInputs inputs) {} + + /** Updates the compressor threshold */ + public default void useLowClosedLoopThresholds(boolean useLow) {} +} diff --git a/src/main/java/frc/robot/subsystems/pneumatics/PneumaticsIORev.java b/src/main/java/frc/robot/subsystems/pneumatics/PneumaticsIORev.java new file mode 100644 index 0000000..cdcef6b --- /dev/null +++ b/src/main/java/frc/robot/subsystems/pneumatics/PneumaticsIORev.java @@ -0,0 +1,48 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +// from https://github.com/Mechanical-Advantage/RobotCode2022 + +package frc.robot.subsystems.pneumatics; + +import static frc.robot.Constants.PneumaticsConstants.*; + +import edu.wpi.first.wpilibj.AnalogInput; +import edu.wpi.first.wpilibj.PneumaticHub; + +public class PneumaticsIORev implements PneumaticsIO { + private static final double PRESSURE_SUPPLY_NORMALIZED = 4.5868055556; // FIX_ME + private static final double FLOW_SUPPLY_NORMALIZED = 4.5868055556; // FIX_ME + + private final PneumaticHub pneumatics; + private final AnalogInput pressureSensor; + private final AnalogInput flowSensor; + + public PneumaticsIORev() { + pneumatics = new PneumaticHub(PNEUMATICS_HUB_ID); + pressureSensor = new AnalogInput(PRESSURE_SENSOR_CHANNEL); + flowSensor = new AnalogInput(FLOW_SENSOR_CHANNEL); + pneumatics.enableCompressorDigital(); + // useLowClosedLoopThresholds(false); + } + + @Override + public void updateInputs(PneumaticsIOInputs inputs) { + inputs.revPressurePsi = pneumatics.getPressure(0); + inputs.compressorActive = pneumatics.getCompressor(); + inputs.compressorCurrentAmps = pneumatics.getCompressorCurrent(); + inputs.pressurePsi = + ((pressureSensor.getAverageVoltage() / PRESSURE_SUPPLY_NORMALIZED) * 250) - 25; // FIX_ME + inputs.flow = ((flowSensor.getAverageVoltage() / FLOW_SUPPLY_NORMALIZED) * 250) - 25; // FIX_ME + } + + @Override + public void useLowClosedLoopThresholds(boolean useLow) { + if (useLow) { + pneumatics.enableCompressorAnalog(50, 60); + } else { + pneumatics.enableCompressorAnalog(80, 120); + } + } +} diff --git a/src/main/java/frc/robot/subsystems/secondary_arm/SecondaryArm.java b/src/main/java/frc/robot/subsystems/secondary_arm/SecondaryArm.java new file mode 100644 index 0000000..dc9ae9e --- /dev/null +++ b/src/main/java/frc/robot/subsystems/secondary_arm/SecondaryArm.java @@ -0,0 +1,68 @@ +package frc.robot.subsystems.secondary_arm; + +import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; +import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; +import edu.wpi.first.wpilibj2.command.InstantCommand; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.subsystems.secondary_arm.SecondaryArmIO.SecondaryArmIOInputs; +import org.littletonrobotics.junction.Logger; + +/** + * This subsystem models the robot's secondary arms which hold the robot on a rung. It consists of a + * solenoid which, when enabled, deploys the arms to engage with a rung; and, when disabled, + * retracts the arms to remain clear of the rungs. + */ +public class SecondaryArm extends SubsystemBase { + private final SecondaryArmIO io; + private final SecondaryArmIOInputs inputs = new SecondaryArmIOInputs(); + + private static final String SUBSYSTEM_NAME = "SecondaryArm"; + private static final boolean TESTING = false; + private static final boolean DEBUGGING = false; + + /** Constructs a new SecondaryArm object. */ + public SecondaryArm(SecondaryArmIO io) { + this.io = io; + + ShuffleboardTab tab = Shuffleboard.getTab("Elevator"); + + if (DEBUGGING) { + tab.add(SUBSYSTEM_NAME, this); + tab.addBoolean("Secondary Arms In?", this::isIn); + } + + if (TESTING) { + tab.add("Second Arm Out", new InstantCommand(() -> this.moveSecondaryArmOut(), this)); + tab.add("Second Arm In", new InstantCommand(() -> this.moveSecondaryArmIn(), this)); + } + } + + /** + * For each iteration, the subsystem's periodic method is invoked before any commands are + * executed. + */ + @Override + public void periodic() { + io.updateInputs(inputs); + Logger.getInstance().processInputs(SUBSYSTEM_NAME, inputs); + } + + /** + * Returns true if the secondary arms are retracted (i.e., within the robot's frame) + * + * @return true if the secondary arms are retracted (i.e., within the robot's frame) + */ + public boolean isIn() { + return inputs.isIn; + } + + /** Move the secondary arms within the robot's frame, which keeps them clear of rungs. */ + public void moveSecondaryArmIn() { + io.setExtended(false); + } + + /** Move the secondary arms out such that they can engage with a rung and support the robot. */ + public void moveSecondaryArmOut() { + io.setExtended(true); + } +} diff --git a/src/main/java/frc/robot/subsystems/secondary_arm/SecondaryArmIO.java b/src/main/java/frc/robot/subsystems/secondary_arm/SecondaryArmIO.java new file mode 100644 index 0000000..92b47fa --- /dev/null +++ b/src/main/java/frc/robot/subsystems/secondary_arm/SecondaryArmIO.java @@ -0,0 +1,30 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems.secondary_arm; + +import org.littletonrobotics.junction.LogTable; +import org.littletonrobotics.junction.inputs.LoggableInputs; + +/** Intake subsystem hardware interface. */ +public interface SecondaryArmIO { + /** Contains all of the input data received from hardware. */ + public static class SecondaryArmIOInputs implements LoggableInputs { + boolean isIn = false; + + public void toLog(LogTable table) { + table.put("isIn", isIn); + } + + public void fromLog(LogTable table) { + isIn = table.getBoolean("Extended", isIn); + } + } + + /** Updates the set of loggable inputs. */ + public default void updateInputs(SecondaryArmIOInputs inputs) {} + + /** Set solenoid state. */ + public default void setExtended(boolean extended) {} +} diff --git a/src/main/java/frc/robot/subsystems/secondary_arm/SecondaryArmSolenoid.java b/src/main/java/frc/robot/subsystems/secondary_arm/SecondaryArmSolenoid.java new file mode 100644 index 0000000..0c445da --- /dev/null +++ b/src/main/java/frc/robot/subsystems/secondary_arm/SecondaryArmSolenoid.java @@ -0,0 +1,29 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems.secondary_arm; + +import static frc.robot.Constants.SecondaryArmConstants.*; + +import edu.wpi.first.wpilibj.PneumaticsModuleType; +import edu.wpi.first.wpilibj.Solenoid; + +public class SecondaryArmSolenoid implements SecondaryArmIO { + private final Solenoid solenoid; + + public SecondaryArmSolenoid() { + + solenoid = new Solenoid(PNEUMATIC_HUB_CAN_ID, PneumaticsModuleType.REVPH, PNEUMATIC_CHANNEL); + } + + @Override + public void updateInputs(SecondaryArmIOInputs inputs) { + inputs.isIn = !solenoid.get(); + } + + @Override + public void setExtended(boolean extended) { + solenoid.set(extended); + } +} diff --git a/src/main/java/frc/robot/subsystems/storage/Storage.java b/src/main/java/frc/robot/subsystems/storage/Storage.java new file mode 100644 index 0000000..78b8f7d --- /dev/null +++ b/src/main/java/frc/robot/subsystems/storage/Storage.java @@ -0,0 +1,131 @@ +package frc.robot.subsystems.storage; + +import static frc.robot.Constants.*; + +import edu.wpi.first.networktables.EntryListenerFlags; +import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets; +import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; +import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.commands.SortStorageCommand; +import frc.robot.subsystems.storage.StorageIO.StorageIOInputs; +import java.util.Map; +import org.littletonrobotics.junction.Logger; + +/** + * This subsystem models the robot's storage mechanism. Is consists of a single motor, which moves + * the storage's belt in an intake or outtake direction, and two sensors which detect cargo at the + * collector end and the shooter end of the storage. + */ +public class Storage extends SubsystemBase { + private final StorageIO io; + private final StorageIOInputs inputs = new StorageIOInputs(); + + private static final String SUBSYSTEM_NAME = "Storage"; + private static final boolean TESTING = false; + private static final boolean DEBUGGING = false; + + /** Constructs a new Storage object. */ + public Storage(StorageIO io) { + this.io = io; + + ShuffleboardTab tab = Shuffleboard.getTab(SUBSYSTEM_NAME); + + if (DEBUGGING) { + tab.add(SUBSYSTEM_NAME, this); + tab.addBoolean("Collector Unblocked?", this::isCollectorSensorUnblocked); + tab.addBoolean("Shooter Unblocked?", this::isShooterSensorUnblocked); + } + + if (TESTING) { + tab.add("Sort Storage", new SortStorageCommand(this)); + tab.add("Belt Power", 0.0) + .withWidget(BuiltInWidgets.kNumberSlider) + .withProperties(Map.of("min", -1.0, "max", 1.0)) // specify widget properties here + .getEntry() + .addListener( + event -> this.setStoragePower(event.getEntry().getValue().getDouble()), + EntryListenerFlags.kNew | EntryListenerFlags.kUpdate); + } + } + + /** + * For each iteration, the subsystem's periodic method is invoked before any commands are + * executed. + */ + @Override + public void periodic() { + io.updateInputs(inputs); + Logger.getInstance().processInputs(SUBSYSTEM_NAME, inputs); + } + + /** + * Sets the storage's motor, which moves the belt, to the specified value + * + * @param power the specified power of the storage's motor as a percentage of full power [-1.0, + * 1.0]; positive values rotate the belt in the intake direction + */ + public void setStoragePower(double power) { + io.setMotorPercentage(power); + } + + /** + * Enable the storage subsystem. This results in the storage's belt moving in the intake direction + * at the default power. + */ + public void enableStorage() { + io.setEnabled(true); + io.setMotorPercentage(StorageConstants.STORAGE_DEFAULT_POWER); + } + + /** + * Returns true if the storage subsystem is enabled (i.e., belt is moving in the intake direction + * at the default power). + * + * @return true if the storage subsystem is enabled (i.e., belt is moving in the intake direction + * at the default power) + */ + public boolean isStorageEnabled() { + return inputs.isEnabled; + } + + /** Disable the storage subsystem. This results in the storage's belt stopping. */ + public void disableStorage() { + io.setEnabled(false); + io.setMotorPercentage(0.0); + } + + /** + * Returns true if the sensor at the shooter end of the storage detects cargo. + * + * @return true if the sensor at the shooter end of the storage detects cargo + */ + public boolean isShooterSensorUnblocked() { + return inputs.isShooterSensorUnblocked; + } + + /** + * Returns true if the sensor at the collector end of the storage detects cargo. + * + * @return true if the sensor at the collector end of the storage detects cargo + */ + public boolean isCollectorSensorUnblocked() { + return inputs.isCollectorSensorUnblocked; + } + + /** + * Returns the number of cargo currently in the storage (0, 1, or 2) + * + * @return the number of cargo currently in the storage (0, 1, or 2) + */ + public int getNumberOfCargoInStorage() { + if (!isCollectorSensorUnblocked() && !isShooterSensorUnblocked()) { // both sensors are blocked + return 2; + } else if (isCollectorSensorUnblocked() + && !isShooterSensorUnblocked()) { // one sensor or the other is blocked + return 1; + } else { // no sensors are blocked + return 0; + } + } +} diff --git a/src/main/java/frc/robot/subsystems/storage/StorageIO.java b/src/main/java/frc/robot/subsystems/storage/StorageIO.java new file mode 100644 index 0000000..0041681 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/storage/StorageIO.java @@ -0,0 +1,52 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems.storage; + +import org.littletonrobotics.junction.LogTable; +import org.littletonrobotics.junction.inputs.LoggableInputs; + +/** Intake subsystem hardware interface. */ +public interface StorageIO { + /** Contains all of the input data received from hardware. */ + public static class StorageIOInputs implements LoggableInputs { + boolean isEnabled = false; + + double appliedVolts = 0.0; + double[] currentAmps = new double[] {}; + double[] tempCelcius = new double[] {}; + + boolean isShooterSensorUnblocked = true; + boolean isCollectorSensorUnblocked = true; + + public void toLog(LogTable table) { + table.put("Enabled", isEnabled); + table.put("AppliedVolts", appliedVolts); + table.put("CurrentAmps", currentAmps); + table.put("TempCelcius", tempCelcius); + table.put("ShooterSensorUnblocked", isShooterSensorUnblocked); + table.put("CollectorSensorUnblocked", isCollectorSensorUnblocked); + } + + public void fromLog(LogTable table) { + isEnabled = table.getBoolean("Extended", isEnabled); + appliedVolts = table.getDouble("AppliedVolts", appliedVolts); + currentAmps = table.getDoubleArray("CurrentAmps", currentAmps); + tempCelcius = table.getDoubleArray("TempCelcius", tempCelcius); + isShooterSensorUnblocked = + table.getBoolean("ShooterSensorUnblocked", isShooterSensorUnblocked); + isCollectorSensorUnblocked = + table.getBoolean("CollectorSensorUnblocked", isCollectorSensorUnblocked); + } + } + + /** Updates the set of loggable inputs. */ + public default void updateInputs(StorageIOInputs inputs) {} + + /** Enable/Disable collector. */ + public default void setEnabled(boolean enabled) {} + + /** Run the roller open loop at the specified voltage. */ + public default void setMotorPercentage(double percentage) {} +} diff --git a/src/main/java/frc/robot/subsystems/storage/StorageIOTalonSRX.java b/src/main/java/frc/robot/subsystems/storage/StorageIOTalonSRX.java new file mode 100644 index 0000000..1045f73 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/storage/StorageIOTalonSRX.java @@ -0,0 +1,65 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems.storage; + +import static frc.robot.Constants.*; +import static frc.robot.Constants.CollectorConstants.*; + +import com.ctre.phoenix.motorcontrol.ControlMode; +import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced; +import com.ctre.phoenix.motorcontrol.SupplyCurrentLimitConfiguration; +import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; +import edu.wpi.first.wpilibj.DigitalInput; +import frc.robot.util.CANDeviceFinder; +import frc.robot.util.CANDeviceId.CANDeviceType; + +public class StorageIOTalonSRX implements StorageIO { + private final WPI_TalonSRX beltMotor; + private final DigitalInput collectorSensor; + private final DigitalInput shooterSensor; + private boolean isEnabled; + + public StorageIOTalonSRX() { + + CANDeviceFinder can = new CANDeviceFinder(); + + this.isEnabled = false; + can.isDevicePresent(CANDeviceType.TALON, StorageConstants.STORAGE_MOTOR_ID); + this.beltMotor = new WPI_TalonSRX(StorageConstants.STORAGE_MOTOR_ID); + + // no data is read from the Talon SRX; so, set these CAN frame periods to the maximum value + // to reduce traffic on the bus + this.beltMotor.setStatusFramePeriod(StatusFrameEnhanced.Status_1_General, 255, TIMEOUT_MS); + this.beltMotor.setStatusFramePeriod(StatusFrameEnhanced.Status_2_Feedback0, 255, TIMEOUT_MS); + + this.beltMotor.configSupplyCurrentLimit(new SupplyCurrentLimitConfiguration(true, 0, 30, .2)); + + this.collectorSensor = new DigitalInput(StorageConstants.COLLECTOR_SENSOR); + + this.shooterSensor = new DigitalInput(StorageConstants.SHOOTER_SENSOR); + } + + @Override + public void updateInputs(StorageIOInputs inputs) { + inputs.isEnabled = isEnabled; + + inputs.appliedVolts = beltMotor.getMotorOutputVoltage(); + inputs.currentAmps = new double[] {beltMotor.getStatorCurrent()}; + inputs.tempCelcius = new double[] {beltMotor.getTemperature()}; + + inputs.isShooterSensorUnblocked = this.shooterSensor.get(); + inputs.isCollectorSensorUnblocked = this.collectorSensor.get(); + } + + @Override + public void setEnabled(boolean enabled) { + isEnabled = enabled; + } + + @Override + public void setMotorPercentage(double percentage) { + beltMotor.set(ControlMode.PercentOutput, percentage); + } +} diff --git a/src/main/java/frc/robot/util/Alert.java b/src/main/java/frc/robot/util/Alert.java new file mode 100644 index 0000000..16ba02d --- /dev/null +++ b/src/main/java/frc/robot/util/Alert.java @@ -0,0 +1,133 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +// from https://github.com/Mechanical-Advantage/RobotCode2022 + +package frc.robot.util; + +import edu.wpi.first.util.sendable.Sendable; +import edu.wpi.first.util.sendable.SendableBuilder; +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import java.util.ArrayList; +import java.util.Comparator; +import java.util.HashMap; +import java.util.List; +import java.util.Map; +import java.util.function.Predicate; + +/** Class for managing persistent alerts to be sent over NetworkTables. */ +public class Alert { + private static Map groups = new HashMap<>(); + + private final AlertType type; + private boolean active = false; + private double activeStartTime = 0.0; + private String text; + + /** + * Creates a new Alert in the default group - "Alerts". If this is the first to be instantiated, + * the appropriate entries will be added to NetworkTables. + * + * @param text Text to be displayed when the alert is active. + * @param type Alert level specifying urgency. + */ + public Alert(String text, AlertType type) { + this("Alerts", text, type); + } + + /** + * Creates a new Alert. If this is the first to be instantiated in its group, the appropriate + * entries will be added to NetworkTables. + * + * @param group Group identifier, also used as NetworkTables title + * @param text Text to be displayed when the alert is active. + * @param type Alert level specifying urgency. + */ + public Alert(String group, String text, AlertType type) { + if (!groups.containsKey(group)) { + groups.put(group, new SendableAlerts()); + SmartDashboard.putData(group, groups.get(group)); + } + + this.text = text; + this.type = type; + groups.get(group).alerts.add(this); + } + + /** + * Sets whether the alert should currently be displayed. When activated, the alert text will also + * be sent to the console. + */ + public void set(boolean active) { + if (active && !this.active) { + activeStartTime = Timer.getFPGATimestamp(); + switch (type) { + case ERROR: + DriverStation.reportError(text, false); + break; + case WARNING: + DriverStation.reportWarning(text, false); + break; + case INFO: + System.out.println(text); + break; + } + } + this.active = active; + } + + /** Updates current alert text. */ + public void setText(String text) { + this.text = text; + } + + private static class SendableAlerts implements Sendable { + public final List alerts = new ArrayList<>(); + + public String[] getStrings(AlertType type) { + Predicate activeFilter = (Alert x) -> x.type == type && x.active; + Comparator timeSorter = + (Alert a1, Alert a2) -> (int) (a2.activeStartTime - a1.activeStartTime); + return alerts.stream() + .filter(activeFilter) + .sorted(timeSorter) + .map((Alert a) -> a.text) + .toArray(String[]::new); + } + + @Override + public void initSendable(SendableBuilder builder) { + builder.setSmartDashboardType("Alerts"); + builder.addStringArrayProperty("errors", () -> getStrings(AlertType.ERROR), null); + builder.addStringArrayProperty("warnings", () -> getStrings(AlertType.WARNING), null); + builder.addStringArrayProperty("infos", () -> getStrings(AlertType.INFO), null); + } + } + + /** Represents an alert's level of urgency. */ + public enum AlertType { + /** + * High priority alert - displayed first on the dashboard with a red "X" symbol. Use this type + * for problems which will seriously affect the robot's functionality and thus require immediate + * attention. + */ + ERROR, + + /** + * Medium priority alert - displayed second on the dashboard with a yellow "!" symbol. Use this + * type for problems which could affect the robot's functionality but do not necessarily require + * immediate attention. + */ + WARNING, + + /** + * Low priority alert - displayed last on the dashboard with a green "i" symbol. Use this type + * for problems which are unlikely to affect the robot's functionality, or any other alerts + * which do not fall under "ERROR" or "WARNING". + */ + INFO + } +} diff --git a/src/main/java/frc/robot/util/CANDeviceFinder.java b/src/main/java/frc/robot/util/CANDeviceFinder.java new file mode 100644 index 0000000..d581fe4 --- /dev/null +++ b/src/main/java/frc/robot/util/CANDeviceFinder.java @@ -0,0 +1,309 @@ +package frc.robot.util; + +import edu.wpi.first.hal.can.CANJNI; +import frc.robot.util.Alert.AlertType; +import frc.robot.util.CANDeviceId.CANDeviceType; +import java.nio.ByteBuffer; +import java.nio.ByteOrder; +import java.util.*; + +public class CANDeviceFinder { + // Logger logger = EventLogging.getLogger(getClass(), Level.INFO); + + Set deviceSet = new TreeSet<>(); + + /* + * this is a map, keyed by CANDeviceType, whose values are sets contained + * the device numbers for all the present devices of that type. + */ + Map> byDeviceType = new TreeMap<>(); + + public CANDeviceFinder() { + super(); + find(); + } + + public boolean isDevicePresent(CANDeviceType deviceType, int id) { + return isDevicePresent(deviceType, id, null); + } + + public boolean isDevicePresent(CANDeviceType deviceType, int id, String whatItIs) { + boolean rv = false; + Set deviceTypeSet = byDeviceType.get(deviceType); + if (deviceTypeSet != null) { + rv = deviceTypeSet.contains(id); + } + if (!rv) { + if (whatItIs == null) { + Alert motor = + new Alert( + " " + deviceType + "(" + id + ")" + " is missing From the CAN bus", + AlertType.WARNING); + motor.set(true); + // logger.warn("{} {} is missing from the CAN bus!!!", deviceType, id); + } else { + Alert motor = + new Alert( + " " + deviceType + "(" + id + ")" + whatItIs + " is missing From the CAN bus", + AlertType.WARNING); + motor.set(true); + // logger.warn("{} {} ({}) is missing from the CAN bus!!!", deviceType, id, whatItIs); + } + } + return rv; + } + + /** @return ArrayList of strings holding the names of devices we've found. */ + public Set getDeviceSet() { + return deviceSet; + } + + abstract class CanFinder { + int[] ids; + long[] ts0; + Set idsPresent = new TreeSet<>(); + + void pass1() { + ts0 = new long[ids.length]; + for (int i = 0; i < ids.length; ++i) { + ts0[i] = checkMessage(ids[i]); + // logger.info ("pass1 looking for {} got {}", String.format("%08x", ids[i]), ts0[i]); + } + } + + void pass2() { + long[] ts1 = new long[ids.length]; + for (int i = 0; i < ids.length; ++i) { + ts1[i] = checkMessage(ids[i]); + // logger.info ("pass2 looking for {} got {}", String.format("%08x", ids[i]), ts1[i]); + } + for (int i = 0; i < ids.length; ++i) { + if (ts0[i] >= 0 && ts1[i] >= 0 && ts0[i] != ts1[i]) { + // logger.info ("found {}", String.format("%08x", ids[i])); + idsPresent.add(ids[i]); + } + } + } + + abstract void report(); + } + + class DeviceFinder extends CanFinder { + Set deviceSet; + CANDeviceType canDeviceType; + + DeviceFinder( + int devType, + int mfg, + int apiId, + int maxDevices, + Set deviceSet, + CANDeviceType canDeviceType) { + super(); + + this.deviceSet = deviceSet; + this.canDeviceType = canDeviceType; + + ids = new int[maxDevices]; + for (int i = 0; i < maxDevices; i++) { + ids[i] = canBusId(devType, mfg, apiId, i); + } + } + + @Override + void report() { + for (int id : idsPresent) { + int deviceId = extractDeviceId(id); + deviceSet.add(new CANDeviceId(canDeviceType, deviceId)); // NOPMD + } + } + } + + class APIFinder extends CanFinder { + CANDeviceType canDeviceType; + + APIFinder(int devType, int mfg, int deviceId, CANDeviceType canDeviceType) { + super(); + this.canDeviceType = canDeviceType; + + ids = new int[1024]; + for (int i = 0; i < 1024; i++) { + ids[i] = canBusId(devType, mfg, i, deviceId); + } + } + + @Override + void report() { + for (int id : idsPresent) { + int apiId = extractApiId(id); + // logger.info ("{}: API {} {} = msg {}", canDeviceType, String.format("%2d", apiId), + // String.format("0x%03X", apiId), String.format("%08X", id)); + } + } + } + + /** + * polls for received framing to determine if a device is deviceSet. This is meant to be used once + * initially (and not periodically) since this steals cached messages from the robot API. + */ + public void find() { + // logger.info ("calling find()"); + List finders = new ArrayList<>(); + + /* + * PDPs used to be 0x08041400. + * 2019.02.09: PDPs respond to APIs 0x50 0x51 0x52 0x59 0x5d + */ + finders.add(new DeviceFinder(8, 4, extractApiId(0x08041400), 1, deviceSet, CANDeviceType.PDP)); + + /* + * SRX used to be 0x02041400. + + As of 2019.02.08: (SRX @ devid 1) + 7 0x007 = 020401C1 + 81 0x051 = 02041441 ** using this? + 82 0x052 = 02041481 + 83 0x053 = 020414C1 + 87 0x057 = 020415C1 + 91 0x05B = 020416C1 + 92 0x05C = 02041701 + 93 0x05D = 02041741 + 94 0x05E = 02041781 + + 2020.01.20 Device id is 0x0204 (https://github.com/CrossTheRoadElec/Phoenix-api/blob/master/src/main/java/com/ctre/phoenix/motorcontrol/can/TalonSRX.java) + + Talon FX and SRX are the same. + */ + finders.add( + new DeviceFinder(2, 4, extractApiId(0x02041441), 64, deviceSet, CANDeviceType.TALON)); + + /* + SPX used to be 0x01041400. + + As of 2019.02.08: (SPX @ devid 2) + 7 0x007 = 010401C2 + 81 0x051 = 01041442 ** using this + 83 0x053 = 010414C2 + 91 0x05B = 010416C2 + 92 0x05C = 01041702 + 93 0x05D = 01041742 + 94 0x05E = 01041782 + + 2020.01.20 Device id is 0x0104 (https://github.com/CrossTheRoadElec/Phoenix-api/blob/master/src/main/java/com/ctre/phoenix/motorcontrol/can/VictorSPX.java) + */ + finders.add( + new DeviceFinder(1, 4, extractApiId(0x01041442), 64, deviceSet, CANDeviceType.VICTOR_SPX)); + + /* we always used 0x09041400 for PCMs */ + finders.add(new DeviceFinder(9, 4, extractApiId(0x09041400), 64, deviceSet, CANDeviceType.PCM)); + + // per REV (0x02051800) + finders.add( + new DeviceFinder(2, 5, extractApiId(0x02051800), 64, deviceSet, CANDeviceType.SPARK_MAX)); + + findDetails(finders); + } + + public void research() { + // logger.info ("calling research()"); + List finders = new ArrayList<>(); + + finders.add(new APIFinder(9, 4, 0, CANDeviceType.PCM)); // PCM + finders.add(new APIFinder(8, 4, 0, CANDeviceType.PDP)); // PDP + finders.add(new APIFinder(2, 4, 1, CANDeviceType.TALON)); // SRX #1 + finders.add(new APIFinder(1, 4, 2, CANDeviceType.VICTOR_SPX)); // SPX #2 + + findDetails(finders); + } + + void findDetails(List finders) { + deviceSet.clear(); + byDeviceType.clear(); + + for (CanFinder finder : finders) { + finder.pass1(); + } + + /* wait 200ms */ + try { + Thread.sleep(200); + } catch (InterruptedException e) { + e.printStackTrace(); // NOPMD + } + + for (CanFinder finder : finders) { + finder.pass2(); + } + + for (CanFinder finder : finders) { + finder.report(); + } + + /* + fill in the byDeviceType map. + */ + for (CANDeviceId canDeviceId : deviceSet) { + CANDeviceType canDeviceType = canDeviceId.getDeviceType(); + Set deviceNumberSet = byDeviceType.get(canDeviceType); + if (deviceNumberSet == null) { + deviceNumberSet = new TreeSet<>(); // NOPMD + byDeviceType.put(canDeviceType, deviceNumberSet); + } + deviceNumberSet.add(canDeviceId.getDeviceNumber()); + } + } + + /* help to calculate the CAN bus ID for a devType|mfg|api|dev. + total of 32 bits: 8 bit devType, 8 bit mfg, 10 bit API, 6 bit device id. + */ + boolean logCanBusIds = false; + + private int canBusId(int devType, int mfg, int apiId, int devId) { + // TODO bounds check parameters + int rv = + ((devType & 0xff) << 24) | ((mfg & 0xff) << 16) | ((apiId & 0x3ff) << 6) | (devId & 0x3f); + if (logCanBusIds) { + // logger.info("devType {}, mfg {}, api {}, devId {} -> {}", + // String.format ("0x%02X", devType), + // String.format ("0x%02X", mfg), + // String.format ("0x%03X", apiId), + // String.format ("0x%02X", devId), + // String.format ("0x%08X", rv) + // ); + } + return rv; + } + + private int extractDeviceId(int canId) { + return canId & 0x3f; + } + + private int extractApiId(int canId) { + return (canId & 0xffc0) >> 6; + } + + /** helper routine to get last received message for a given ID */ + private ByteBuffer targetID = ByteBuffer.allocateDirect(4); + + private ByteBuffer timeStamp = ByteBuffer.allocateDirect(4); + + private long checkMessage(int id) { + try { + targetID.clear(); + targetID.order(ByteOrder.LITTLE_ENDIAN); + targetID.asIntBuffer().put(0, id); + + timeStamp.clear(); + timeStamp.order(ByteOrder.LITTLE_ENDIAN); + timeStamp.asIntBuffer().put(0, 0x00000000); + + CANJNI.FRCNetCommCANSessionMuxReceiveMessage(targetID.asIntBuffer(), 0x1fffffff, timeStamp); + + long retval = timeStamp.getInt(); + retval &= 0xFFFFFFFF; /* undo sign-extension */ + return retval; + } catch (Exception e) { + return -1; + } + } +} diff --git a/src/main/java/frc/robot/util/CANDeviceId.java b/src/main/java/frc/robot/util/CANDeviceId.java new file mode 100644 index 0000000..73c6a1c --- /dev/null +++ b/src/main/java/frc/robot/util/CANDeviceId.java @@ -0,0 +1,67 @@ +package frc.robot.util; + +/** + * An object representing a CAN device on the bus. These can be put in Collections, are Hashable, + * and are Comparable. + */ +public class CANDeviceId implements Comparable { + + public enum CANDeviceType { + PDP, + PCM, + TALON, + VICTOR_SPX, + SPARK_MAX + } + + private CANDeviceType deviceType; + private int deviceNumber; + + public CANDeviceType getDeviceType() { + return deviceType; + } + + public int getDeviceNumber() { + return deviceNumber; + } + + private String toString; + + public CANDeviceId(CANDeviceType deviceType, int deviceNumber) { + this.deviceType = deviceType; + this.deviceNumber = deviceNumber; + this.toString = deviceType.toString() + " " + Integer.toString(deviceNumber); + } + + @Override + public boolean equals(Object object) { + if (this == object) return true; + if (object == null || getClass() != object.getClass()) return false; + if (!super.equals(object)) return false; + + CANDeviceId that = (CANDeviceId) object; + + if (deviceNumber != that.deviceNumber) return false; + return deviceType == that.deviceType; + } + + @Override + public int hashCode() { + int result = super.hashCode(); + result = 31 * result + deviceType.hashCode(); + result = 31 * result + deviceNumber; + return result; + } + + @Override + public java.lang.String toString() { + return this.toString; + } + + @Override + public int compareTo(CANDeviceId canDeviceId) { + int rv = Integer.compare(this.deviceType.ordinal(), canDeviceId.deviceType.ordinal()); + if (rv == 0) rv = Integer.compare(this.deviceNumber, canDeviceId.deviceNumber); + return rv; + } +} diff --git a/src/main/java/frc/robot/util/GeomUtil.java b/src/main/java/frc/robot/util/GeomUtil.java new file mode 100644 index 0000000..fe3ec69 --- /dev/null +++ b/src/main/java/frc/robot/util/GeomUtil.java @@ -0,0 +1,125 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +// from https://github.com/Mechanical-Advantage/RobotCode2022 + +package frc.robot.util; + +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.geometry.Transform2d; +import edu.wpi.first.math.geometry.Translation2d; +import edu.wpi.first.math.geometry.Twist2d; + +/** Geometry utilities for working with translations, rotations, transforms, and poses. */ +public class GeomUtil { + + private GeomUtil() { + throw new IllegalStateException("static class"); + } + /** + * Creates a pure translating transform + * + * @param translation The translation to create the transform with + * @return The resulting transform + */ + public static Transform2d transformFromTranslation(Translation2d translation) { + return new Transform2d(translation, new Rotation2d()); + } + + /** + * Creates a pure translating transform + * + * @param x The x componenet of the translation + * @param y The y componenet of the translation + * @return The resulting transform + */ + public static Transform2d transformFromTranslation(double x, double y) { + return new Transform2d(new Translation2d(x, y), new Rotation2d()); + } + + /** + * Creates a pure rotating transform + * + * @param rotation The rotation to create the transform with + * @return The resulting transform + */ + public static Transform2d transformFromRotation(Rotation2d rotation) { + return new Transform2d(new Translation2d(), rotation); + } + + /** + * Creates a pure translated pose + * + * @param translation The translation to create the pose with + * @return The resulting pose + */ + public static Pose2d poseFromTranslation(Translation2d translation) { + return new Pose2d(translation, new Rotation2d()); + } + + /** + * Creates a pure rotated pose + * + * @param rotation The rotation to create the pose with + * @return The resulting pose + */ + public static Pose2d poseFromRotation(Rotation2d rotation) { + return new Pose2d(new Translation2d(), rotation); + } + + /** + * Converts a Pose2d to a Transform2d to be used in a kinematic chain + * + * @param pose The pose that will represent the transform + * @return The resulting transform + */ + public static Transform2d poseToTransform(Pose2d pose) { + return new Transform2d(pose.getTranslation(), pose.getRotation()); + } + + /** + * Converts a Transform2d to a Pose2d to be used as a position or as the start of a kinematic + * chain + * + * @param transform The transform that will represent the pose + * @return The resulting pose + */ + public static Pose2d transformToPose(Transform2d transform) { + return new Pose2d(transform.getTranslation(), transform.getRotation()); + } + + /** + * Interpolates between two poses based on the scale factor t. For example, t=0 would result in + * the first pose, t=1 would result in the last pose, and t=0.5 would result in a pose which is + * exactly halfway between the two poses. Values of t less than zero return the first pose, and + * values of t greater than 1 return the last pose. + * + * @param lhs The left hand side, or first pose to use for interpolation + * @param rhs The right hand side, or last pose to use for interpolation + * @param t The scale factor, 0 <= t <= 1 + * @return The pose which represents the interpolation. For t <= 0, the "lhs" parameter is + * returned directly. For t >= 1, the "rhs" parameter is returned directly. + */ + public static Pose2d interpolate(Pose2d lhs, Pose2d rhs, double t) { + if (t <= 0) { + return lhs; + } else if (t >= 1) { + return rhs; + } + Twist2d twist = lhs.log(rhs); + Twist2d scaled = new Twist2d(twist.dx * t, twist.dy * t, twist.dtheta * t); + return lhs.exp(scaled); + } + + /** + * Returns the direction that this translation makes with the origin as a Rotation2d + * + * @param translation The translation + * @return The direction of the translation + */ + public static Rotation2d direction(Translation2d translation) { + return new Rotation2d(translation.getX(), translation.getY()); + } +} diff --git a/src/main/java/frc/robot/util/TalonUtil.java b/src/main/java/frc/robot/util/TalonUtil.java new file mode 100644 index 0000000..c93a8aa --- /dev/null +++ b/src/main/java/frc/robot/util/TalonUtil.java @@ -0,0 +1,22 @@ +package frc.robot.util; + +import com.ctre.phoenix.ErrorCode; +import frc.robot.util.Alert.AlertType; + +public class TalonUtil { + + private TalonUtil() {} + + /* + * checks the specified error code for issues + * + * @param errorCode error code + * @param message message to print if error happens + */ + public static void checkError(ErrorCode errorCode, String message) { + if (errorCode != ErrorCode.OK) { + Alert talonAlert = new Alert(message + errorCode, AlertType.ERROR); + talonAlert.set(true); + } + } +} diff --git a/sysid_data20220216-170203.json b/sysid_data20220216-170203.json new file mode 100644 index 0000000..cfebbf2 --- /dev/null +++ b/sysid_data20220216-170203.json @@ -0,0 +1,7 @@ +{ + "slow-forward": [], + "sysid": true, + "test": "Drivetrain", + "units": "Meters", + "unitsPerRotation": 12.56 +} \ No newline at end of file diff --git a/vendordeps/AdvantageKit.json b/vendordeps/AdvantageKit.json new file mode 100644 index 0000000..9047505 --- /dev/null +++ b/vendordeps/AdvantageKit.json @@ -0,0 +1,41 @@ +{ + "fileName": "AdvantageKit.json", + "name": "AdvantageKit", + "version": "1.7.3", + "uuid": "d820cc26-74e3-11ec-90d6-0242ac120003", + "mavenUrls": [], + "jsonUrl": "https://github.com/Mechanical-Advantage/AdvantageKit/releases/latest/download/AdvantageKit.json", + "javaDependencies": [ + { + "groupId": "org.littletonrobotics.akit.junction", + "artifactId": "wpilib-shim", + "version": "1.7.3" + }, + { + "groupId": "org.littletonrobotics.akit.junction", + "artifactId": "junction-core", + "version": "1.7.3" + }, + { + "groupId": "org.littletonrobotics.akit.conduit", + "artifactId": "conduit-api", + "version": "1.7.3" + } + ], + "jniDependencies": [ + { + "groupId": "org.littletonrobotics.akit.conduit", + "artifactId": "conduit-wpilibio", + "version": "1.7.3", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "linuxathena", + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + } + ], + "cppDependencies": [] +} \ No newline at end of file diff --git a/vendordeps/PathplannerLib.json b/vendordeps/PathplannerLib.json new file mode 100644 index 0000000..400f8e7 --- /dev/null +++ b/vendordeps/PathplannerLib.json @@ -0,0 +1,33 @@ +{ + "fileName": "PathplannerLib.json", + "name": "PathplannerLib", + "version": "2022.2.0", + "uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786", + "mavenUrls": [ + "https://3015rangerrobotics.github.io/pathplannerlib/repo" + ], + "jsonUrl": "https://3015rangerrobotics.github.io/pathplannerlib/PathplannerLib.json", + "javaDependencies": [ + { + "groupId": "com.pathplanner.lib", + "artifactId": "PathplannerLib-java", + "version": "2022.2.0" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "com.pathplanner.lib", + "artifactId": "PathplannerLib-cpp", + "version": "2022.2.0", + "libName": "PathplannerLib", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "osxx86-64", + "linuxathena" + ] + } + ] +} \ No newline at end of file diff --git a/vendordeps/Phoenix.json b/vendordeps/Phoenix.json new file mode 100644 index 0000000..02f7200 --- /dev/null +++ b/vendordeps/Phoenix.json @@ -0,0 +1,257 @@ +{ + "fileName": "Phoenix.json", + "name": "CTRE-Phoenix", + "version": "5.21.1", + "frcYear": 2022, + "uuid": "ab676553-b602-441f-a38d-f1296eff6537", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix-frc2022-latest.json", + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-java", + "version": "5.21.1" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-java", + "version": "5.21.1" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.21.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "linuxathena" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.21.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simTalonSRX", + "version": "5.21.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simTalonFX", + "version": "5.21.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simVictorSPX", + "version": "5.21.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simPigeonIMU", + "version": "5.21.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simCANCoder", + "version": "5.21.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-cpp", + "version": "5.21.1", + "libName": "CTRE_Phoenix_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena" + ] + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-cpp", + "version": "5.21.1", + "libName": "CTRE_Phoenix", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena" + ] + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.21.1", + "libName": "CTRE_PhoenixCCI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "5.21.1", + "libName": "CTRE_Phoenix_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "api-cpp-sim", + "version": "5.21.1", + "libName": "CTRE_PhoenixSim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.21.1", + "libName": "CTRE_PhoenixCCISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simTalonSRX", + "version": "5.21.1", + "libName": "CTRE_SimTalonSRX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simTalonFX", + "version": "5.21.1", + "libName": "CTRE_SimTalonFX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simVictorSPX", + "version": "5.21.1", + "libName": "CTRE_SimVictorSPX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simPigeonIMU", + "version": "5.21.1", + "libName": "CTRE_SimPigeonIMU", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "simCANCoder", + "version": "5.21.1", + "libName": "CTRE_SimCANCoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxx86-64" + ] + } + ] +} \ No newline at end of file diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json new file mode 100644 index 0000000..997e2a4 --- /dev/null +++ b/vendordeps/REVLib.json @@ -0,0 +1,73 @@ +{ + "fileName": "REVLib.json", + "name": "REVLib", + "version": "2022.1.1", + "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", + "mavenUrls": [ + "https://maven.revrobotics.com/" + ], + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib.json", + "javaDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-java", + "version": "2022.1.1" + } + ], + "jniDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2022.1.1", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxaarch64bionic", + "linuxx86-64", + "linuxathena", + "linuxraspbian", + "osxx86-64" + ] + } + ], + "cppDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-cpp", + "version": "2022.1.1", + "libName": "REVLib", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxaarch64bionic", + "linuxx86-64", + "linuxathena", + "linuxraspbian", + "osxx86-64" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2022.1.1", + "libName": "REVLibDriver", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxaarch64bionic", + "linuxx86-64", + "linuxathena", + "linuxraspbian", + "osxx86-64" + ] + } + ] +} \ No newline at end of file diff --git a/vendordeps/SdsSwerveLib.json b/vendordeps/SdsSwerveLib.json new file mode 100644 index 0000000..41ea607 --- /dev/null +++ b/vendordeps/SdsSwerveLib.json @@ -0,0 +1,19 @@ +{ + "fileName": "SdsSwerveLib.json", + "name": "swerve-lib", + "version": "1.1.0", + "uuid": "9619F7EA-7F96-4236-9D94-02338DFED592", + "mavenUrls": [ + "https://jitpack.io" + ], + "jsonUrl": "https://raw.githubusercontent.com/SwerveDriveSpecialties/swerve-lib/master/SdsSwerveLib.json", + "javaDependencies": [ + { + "groupId": "com.github.SwerveDriveSpecialties", + "artifactId": "swerve-lib", + "version": "1.1.0" + } + ], + "jniDependencies": [], + "cppDependencies": [] +} \ No newline at end of file diff --git a/vendordeps/WPILibNewCommands.json b/vendordeps/WPILibNewCommands.json new file mode 100644 index 0000000..b608513 --- /dev/null +++ b/vendordeps/WPILibNewCommands.json @@ -0,0 +1,37 @@ +{ + "fileName": "WPILibNewCommands.json", + "name": "WPILib-New-Commands", + "version": "1.0.0", + "uuid": "111e20f7-815e-48f8-9dd6-e675ce75b266", + "mavenUrls": [], + "jsonUrl": "", + "javaDependencies": [ + { + "groupId": "edu.wpi.first.wpilibNewCommands", + "artifactId": "wpilibNewCommands-java", + "version": "wpilib" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "edu.wpi.first.wpilibNewCommands", + "artifactId": "wpilibNewCommands-cpp", + "version": "wpilib", + "libName": "wpilibNewCommands", + "headerClassifier": "headers", + "sourcesClassifier": "sources", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena", + "linuxraspbian", + "linuxaarch64bionic", + "windowsx86-64", + "windowsx86", + "linuxx86-64", + "osxx86-64" + ] + } + ] +}