diff --git a/software/archive/files/normal_mode.png b/software/archive/files/normal_mode.png deleted file mode 100644 index 0803c24..0000000 Binary files a/software/archive/files/normal_mode.png and /dev/null differ diff --git a/software/archive/files/setting_mode.png b/software/archive/files/setting_mode.png deleted file mode 100644 index 615d0b7..0000000 Binary files a/software/archive/files/setting_mode.png and /dev/null differ diff --git a/software/archive/hexapod7697/.gitignore b/software/archive/hexapod7697/.gitignore deleted file mode 100644 index dbe9c82..0000000 --- a/software/archive/hexapod7697/.gitignore +++ /dev/null @@ -1 +0,0 @@ -.vscode/ \ No newline at end of file diff --git a/software/archive/hexapod7697/hexapod7697.ino b/software/archive/hexapod7697/hexapod7697.ino deleted file mode 100644 index f1e46e0..0000000 --- a/software/archive/hexapod7697/hexapod7697.ino +++ /dev/null @@ -1,84 +0,0 @@ - -#include "src/setting_mode.h" -#include "src/normal_mode.h" - -#include "src/hexapod/debug.h" -#include "src/hexapod/hexapod.h" - -// -// mode -// 0: normal mode -// 1: setting mode (for servo calibration) -// -static int _mode = 0; - -static void log_output(const char* log) { - Serial.println(log); -} - -// -// wait for N secs, enter setting mode if pressed USR button -// -void boot_wait(int wait_for = 2000) { - digitalWrite(LED_BUILTIN, HIGH); - - pinMode(6, INPUT); - while (wait_for > 0) { - if (HIGH == digitalRead(6)) { - _mode = 1; - break; - } - delay(100); - wait_for -= 100; - } - - digitalWrite(LED_BUILTIN, LOW); -} - -// -// Do common setup and mode-specific setup -// -void setup() { - //Initialize serial and wait for port to open: - Serial.begin(115200); - Serial.println("Starting..."); - - // - // Common setup() - // - - // Initialize GPIO - pinMode(LED_BUILTIN, OUTPUT); - - // Workaround for beta PCB - pinMode(2, INPUT); - pinMode(3, INPUT); - - boot_wait(); - - hexapod::initLogOutput(log_output, millis); - hexapod::Hexapod.init(_mode == 1); - - // - // Mode-specific setup() - // - - if (_mode == 0) { - normal_setup(); - } - else if (_mode == 1) { - setting_setup(); - } - - Serial.print("Started, mode="); - Serial.println(_mode); -} - -void loop() { - if (_mode == 0) { - normal_loop(); - } - else if (_mode == 1) { - setting_loop(); - } -} diff --git a/software/archive/hexapod7697/src/hexapod/base.h b/software/archive/hexapod7697/src/hexapod/base.h deleted file mode 100644 index 9941e3b..0000000 --- a/software/archive/hexapod7697/src/hexapod/base.h +++ /dev/null @@ -1,71 +0,0 @@ -#pragma once - -#include - -namespace hexapod { - - class Point3D { - public: - Point3D() = default; - Point3D(float x, float y, float z): x_{x}, y_{y}, z_{z} { - } - - public: - float x_; - float y_; - float z_; - }; - - inline Point3D operator-(const Point3D &lhs, const Point3D &rhs) { - return Point3D(lhs.x_ - rhs.x_, lhs.y_ - rhs.y_, lhs.z_ - rhs.z_); - }; - - inline Point3D operator*(const Point3D &lhs, const float& b) { - return Point3D(lhs.x_ * b, lhs.y_ * b, lhs.z_ * b); - }; - - inline Point3D& operator +=(Point3D& a, const Point3D& b) { - a.x_ += b.x_; - a.y_ += b.y_; - a.z_ += b.z_; - return a; - } - - inline bool operator ==(const Point3D &a, const Point3D &b) { - return (a.x_ == b.x_) && (a.y_ == b.y_) && (a.z_ == b.z_); - } - - class Locations { - public: - Locations() = default; - Locations(const Point3D& foreRight, const Point3D& right, const Point3D& hindRight, const Point3D& hindLeft, const Point3D& left, const Point3D& foreLeft): - points_{foreRight, right, hindRight, hindLeft, left, foreLeft} { - } - - const Point3D& get(int index) const { - return points_[index]; - } - - Locations operator-(const Locations &b) const { - return Locations{ - points_[0] - b.points_[0], points_[1] - b.points_[1], points_[2] - b.points_[2], - points_[3] - b.points_[3], points_[4] - b.points_[4], points_[5] - b.points_[5], - }; - } - - Locations operator*(const float& b) const { - return Locations{ - points_[0] * b, points_[1] * b, points_[2] * b, - points_[3] * b, points_[4] * b, points_[5] * b, - }; - } - - Locations& operator +=(const Locations& b) { - for(auto i=0;i<6;i++) - points_[i] += b.points_[i]; - return *this; - } - private: - Point3D points_[6]; - }; -} diff --git a/software/archive/hexapod7697/src/hexapod/config.h b/software/archive/hexapod7697/src/hexapod/config.h deleted file mode 100644 index 620182f..0000000 --- a/software/archive/hexapod7697/src/hexapod/config.h +++ /dev/null @@ -1,22 +0,0 @@ -#pragma once - -namespace hexapod { - - namespace config { - // all below definition use unit: mm - const float kLegMountLeftRightX = 29.87; - const float kLegMountOtherX = 22.41; - const float kLegMountOtherY = 55.41; - - const float kLegRootToJoint1 = 20.75; - const float kLegJoint1ToJoint2 = 28.0; - const float kLegJoint2ToJoint3 = 42.6; - const float kLegJoint3ToTip = 89.07; - - - // timing setting. unit: ms - const int movementInterval = 5; - const int movementSwitchDuration = 150; - } - -} \ No newline at end of file diff --git a/software/archive/hexapod7697/src/hexapod/debug.cpp b/software/archive/hexapod7697/src/hexapod/debug.cpp deleted file mode 100644 index b936220..0000000 --- a/software/archive/hexapod7697/src/hexapod/debug.cpp +++ /dev/null @@ -1,36 +0,0 @@ -#include "debug.h" - -#include -#include // For va_start, etc. - -namespace { - std::function _writer = nullptr; - std::function _time_func = nullptr; -} - -void _my_log_impl(const char* format, ...) -{ - char buffer[256]; - int pos = 0; - - if(_time_func) { - pos = sprintf(buffer, "[%d]", _time_func()); - } - - if (_writer) { - va_list ap; - va_start(ap, format); - vsprintf(buffer+pos, format, ap); - va_end(ap); - _writer(buffer); - } -} - -namespace hexapod { - - void initLogOutput(std::function writer, std::function time_func) { - _writer = writer; - _time_func = time_func; - } - -} \ No newline at end of file diff --git a/software/archive/hexapod7697/src/hexapod/debug.h b/software/archive/hexapod7697/src/hexapod/debug.h deleted file mode 100644 index 517326c..0000000 --- a/software/archive/hexapod7697/src/hexapod/debug.h +++ /dev/null @@ -1,25 +0,0 @@ -#pragma once - -#include - -#undef LOG_DEBUG_ON -#define LOG_INFO_ON - - -#ifdef LOG_DEBUG_ON -void _my_log_impl(const char* format, ...); -#define LOG_DEBUG(format, ...) _my_log_impl(format, ##__VA_ARGS__) -#else -#define LOG_DEBUG(format, ...) -#endif - -#ifdef LOG_INFO_ON -void _my_log_impl(const char* format, ...); -#define LOG_INFO(format, ...) _my_log_impl(format, ##__VA_ARGS__) -#else -#define LOG_INFO(format, ...) -#endif - -namespace hexapod { - void initLogOutput(std::function writer, std::function time_func); -} diff --git a/software/archive/hexapod7697/src/hexapod/hal/pwm.cpp b/software/archive/hexapod7697/src/hexapod/hal/pwm.cpp deleted file mode 100644 index 215088b..0000000 --- a/software/archive/hexapod7697/src/hexapod/hal/pwm.cpp +++ /dev/null @@ -1,29 +0,0 @@ - -#include -#include - -#include "pwm.h" - -namespace hexapod { namespace hal { - - PCA9685::PCA9685(int i2cAddress) { - obj_ = (void*)new Adafruit_PWMServoDriver(i2cAddress); - } - - PCA9685::~PCA9685() { - delete ((Adafruit_PWMServoDriver*)obj_); - } - - void PCA9685::begin() { - ((Adafruit_PWMServoDriver*)obj_)->begin(); - } - - void PCA9685::setPWMFreq(int freq) { - ((Adafruit_PWMServoDriver*)obj_)->setPWMFreq(freq); - } - - void PCA9685::setPWM(int index, int on, int off) { - ((Adafruit_PWMServoDriver*)obj_)->setPWM(index, (uint16_t)on, (uint16_t)off); - } - -}} \ No newline at end of file diff --git a/software/archive/hexapod7697/src/hexapod/hal/pwm.h b/software/archive/hexapod7697/src/hexapod/hal/pwm.h deleted file mode 100644 index 8f8ade5..0000000 --- a/software/archive/hexapod7697/src/hexapod/hal/pwm.h +++ /dev/null @@ -1,18 +0,0 @@ -#pragma once - -namespace hexapod { namespace hal { - - class PCA9685 { - public: - PCA9685(int i2cAddress = 0x40); - ~PCA9685(); - - void begin(); - void setPWMFreq(int freq); - void setPWM(int index, int on, int off); - - private: - void* obj_; - }; - -}} \ No newline at end of file diff --git a/software/archive/hexapod7697/src/hexapod/hexapod.cpp b/software/archive/hexapod7697/src/hexapod/hexapod.cpp deleted file mode 100644 index 9b9ac5d..0000000 --- a/software/archive/hexapod7697/src/hexapod/hexapod.cpp +++ /dev/null @@ -1,99 +0,0 @@ - -#include "hexapod.h" -#include "servo.h" -#include "debug.h" - -// TBD: move to hal -#include - -namespace hexapod { - - HexapodClass Hexapod; - - HexapodClass::HexapodClass(): - legs_{{0}, {1}, {2}, {3}, {4}, {5}}, - movement_{MOVEMENT_STANDBY}, - mode_{MOVEMENT_STANDBY} - { - - } - - void HexapodClass::init(bool setting) { - Servo::init(); - - LFlash.begin(); - calibrationLoad(); - - // default to standby mode - if (!setting) - processMovement(MOVEMENT_STANDBY); - - LOG_INFO("Hexapod init done."); - } - - void HexapodClass::processMovement(MovementMode mode, int elapsed) { - if (mode_ != mode) { - mode_ = mode; - movement_.setMode(mode_); - } - - auto& location = movement_.next(elapsed); - for(int i=0;i<6;i++) { - legs_[i].moveTip(location.get(i)); - } - } - - void HexapodClass::calibrationSave() { - - short data[6*3*2]; - - for(int i=0;i<6;i++) { - for(int j=0;j<3;j++) { - int offset, scale; - legs_[i].get(j)->getParameter(offset, scale); - data[2*3*i + 2*j] = (short)offset; - data[2*3*i + 2*j + 1] = (short)scale; - } - } - - LFlash.write( - "HEXAPOD", - "CALI", - LFLASH_RAW_DATA, - (const uint8_t *)data, - sizeof(data) - ); - - } - - void HexapodClass::calibrationGet(int legIndex, int partIndex, int& offset, int& scale) { - legs_[legIndex].get(partIndex)->getParameter(offset, scale); - } - - void HexapodClass::calibrationSet(int legIndex, int partIndex, int offset, int scale) { - legs_[legIndex].get(partIndex)->setParameter(offset, scale); - } - - void HexapodClass::calibrationTest(int legIndex, int partIndex, float angle) { - legs_[legIndex].get(partIndex)->setAngle(angle); - } - - void HexapodClass::calibrationLoad() { - short data[6*3*2] = {0}; - uint32_t size = sizeof(data); - - LFlash.read( - "HEXAPOD", - "CALI", - (uint8_t *)data, - &size - ); - - for(int i=0;i<6;i++) { - for(int j=0;j<3;j++) { - legs_[i].get(j)->setParameter(data[2*3*i + 2*j], data[2*3*i + 2*j + 1], false); - } - } - } - -} \ No newline at end of file diff --git a/software/archive/hexapod7697/src/hexapod/hexapod.h b/software/archive/hexapod7697/src/hexapod/hexapod.h deleted file mode 100644 index 9cc4fb2..0000000 --- a/software/archive/hexapod7697/src/hexapod/hexapod.h +++ /dev/null @@ -1,37 +0,0 @@ -#pragma once - -#include "movement.h" -#include "leg.h" - -namespace hexapod { - - class HexapodClass { - public: - HexapodClass(); - - // init - - void init(bool setting = false); - - // Movement API - - void processMovement(MovementMode mode, int elapsed = 0); - - // Calibration API - - void calibrationSave(); // write to flash - void calibrationGet(int legIndex, int partIndex, int& offset, int& scale); // read servo setting - void calibrationSet(int legIndex, int partIndex, int offset, int scale); // update servo setting - void calibrationTest(int legIndex, int partIndex, float angle); // test servo setting - - private: - void calibrationLoad(); // read from flash - - private: - MovementMode mode_; - Movement movement_; - Leg legs_[6]; - }; - - extern HexapodClass Hexapod; -} \ No newline at end of file diff --git a/software/archive/hexapod7697/src/hexapod/leg.cpp b/software/archive/hexapod7697/src/hexapod/leg.cpp deleted file mode 100644 index 30deb61..0000000 --- a/software/archive/hexapod7697/src/hexapod/leg.cpp +++ /dev/null @@ -1,201 +0,0 @@ -#include - -#include "leg.h" -#include "config.h" -#include "debug.h" - -#include - -using namespace hexapod::config; - -// Angle (CCW) -// 0 : + X-axis -// 90 : + Y-axis -// 180 : - X-axis -// 270 : - Y-axis - -namespace hexapod { - - namespace { - - // rotate matrix: - // x' = x * cos - y * sin - // y' = x * sin + y * cos - - #define SIN45 0.7071 - #define COS45 0.7071 - - void rotate0(const Point3D& src, Point3D& dest) { - dest = src; - } - - void rotate45(const Point3D& src, Point3D& dest) { - dest.x_ = src.x_ * COS45 - src.y_ * SIN45; - dest.y_ = src.x_ * SIN45 + src.y_ * COS45; - dest.z_ = src.z_; - } - - void rotate135(const Point3D& src, Point3D& dest) { - dest.x_ = src.x_ * (-COS45) - src.y_ * SIN45; - dest.y_ = src.x_ * SIN45 + src.y_ * (-COS45); - dest.z_ = src.z_; - } - - void rotate180(const Point3D& src, Point3D& dest) { - dest.x_ = -src.x_; - dest.y_ = -src.y_; - dest.z_ = src.z_; - } - - void rotate225(const Point3D& src, Point3D& dest) { - dest.x_ = src.x_ * (-COS45) - src.y_ * (-SIN45); - dest.y_ = src.x_ * (-SIN45) + src.y_ * (-COS45); - dest.z_ = src.z_; - } - - void rotate315(const Point3D& src, Point3D& dest) { - dest.x_ = src.x_ * COS45 - src.y_ * (-SIN45); - dest.y_ = src.x_ * (-SIN45) + src.y_ * COS45; - dest.z_ = src.z_; - } - } - - // Public - - Leg::Leg(int legIndex): index_(legIndex) { - switch(legIndex) { - case 0: // 45 degree - mountPosition_ = Point3D(kLegMountOtherX, kLegMountOtherY, 0); - localConv_ = rotate315; - worldConv_ = rotate45; - break; - case 1: // 0 degree - mountPosition_ = Point3D(kLegMountLeftRightX, 0, 0); - localConv_ = rotate0; - worldConv_ = rotate0; - break; - case 2: // -45 or 315 degree - mountPosition_ = Point3D(kLegMountOtherX, -kLegMountOtherY, 0); - localConv_ = rotate45; - worldConv_ = rotate315; - break; - case 3: // -135 or 225 degree - mountPosition_ = Point3D(-kLegMountOtherX, -kLegMountOtherY, 0); - localConv_ = rotate135; - worldConv_ = rotate225; - break; - case 4: // 180 degree - mountPosition_ = Point3D(-kLegMountLeftRightX, 0, 0); - localConv_ = rotate180; - worldConv_ = rotate180; - break; - case 5: // 135 degree - mountPosition_ = Point3D(-kLegMountOtherX, kLegMountOtherY, 0); - localConv_ = rotate225; - worldConv_ = rotate135; - break; - } - - for(int i=0;i<3;i++) - servos_[i] = new hexapod::Servo(legIndex, i); - } - - Leg::~Leg() { - for(int i=0;i<3;i++) { - delete servos_[i]; - servos_[i] = nullptr; - } - } - - void Leg::translateToLocal(const Point3D& world, Point3D& local) { - localConv_(world - mountPosition_, local); - } - - void Leg::translateToWorld(const Point3D& local, Point3D& world) { - worldConv_(local, world); - world += mountPosition_; - } - - void Leg::setJointAngle(float angle[3]) { - Point3D to; - _forwardKinematics(angle, to); - moveTipLocal(to); - } - - void Leg::moveTip(const Point3D& to) { - if (to == tipPos_) - return; - - Point3D local; - translateToLocal(to, local); - LOG_DEBUG("leg(%d) moveTip(%f,%f,%f)(%f,%f,%f)", index_, to.x_, to.y_, to.z_, local.x_, local.y_, local.z_); - _move(local); - tipPos_ = to; - tipPosLocal_ = local; - } - - const Point3D& Leg::getTipPosition(void) { - return tipPos_; - } - - void Leg::moveTipLocal(const Point3D& to) { - if (to == tipPosLocal_) - return; - - Point3D world; - translateToWorld(to, world); - _move(to); - tipPos_ = world; - tipPosLocal_ = to; - } - - const Point3D& Leg::getTipPositionLocal(void) { - return tipPosLocal_; - } - - // - // Private - // - const float pi = std::acos(-1); - const float hpi = pi/2; - - void Leg::_forwardKinematics(float angle[3], Point3D& out) { - float radian[3]; - for(int i=0; i<3; i++) - radian[i] = pi * angle [i] / 180; - - float x = kLegJoint1ToJoint2 + std::cos(radian[1]) * kLegJoint2ToJoint3 + std::cos(radian[1] + radian[2] - hpi) * kLegJoint3ToTip; - - out.x_ = kLegRootToJoint1 + std::cos(radian[0]) * x; - out.y_ = std::sin(radian[0]) * x; - out.z_ = std::sin(radian[1]) * kLegJoint2ToJoint3 + std::sin(radian[1] + radian[2] - hpi) * kLegJoint3ToTip; - } - - void Leg::_inverseKinematics(const Point3D& to, float angles[3]) { - - float x = to.x_ - kLegRootToJoint1; - float y = to.y_; - - angles[0] = std::atan2(y, x) * 180 / pi; - - x = std::sqrt(x*x + y*y) - kLegJoint1ToJoint2; - y = to.z_; - float ar = std::atan2(y, x); - float lr2 = x*x + y*y; - float lr = std::sqrt(lr2); - float a1 = std::acos((lr2 + kLegJoint2ToJoint3*kLegJoint2ToJoint3 - kLegJoint3ToTip*kLegJoint3ToTip)/(2*kLegJoint2ToJoint3*lr)); - float a2 = std::acos((lr2 - kLegJoint2ToJoint3*kLegJoint2ToJoint3 + kLegJoint3ToTip*kLegJoint3ToTip)/(2*kLegJoint3ToTip*lr)); - angles[1] = (ar + a1) * 180 / pi; - angles[2] = 90 - ((a1 + a2) * 180 / pi); - } - - void Leg::_move(const Point3D& to) { - float angles[3]; - _inverseKinematics(to, angles); - LOG_DEBUG("leg(%d) move: (%f,%f,%f)", index_, angles[0], angles[1], angles[2]); - for(int i=0; i<3; i++) { - servos_[i]->setAngle(angles[i]); - } - } - -} \ No newline at end of file diff --git a/software/archive/hexapod7697/src/hexapod/leg.h b/software/archive/hexapod7697/src/hexapod/leg.h deleted file mode 100644 index 7dc2148..0000000 --- a/software/archive/hexapod7697/src/hexapod/leg.h +++ /dev/null @@ -1,52 +0,0 @@ -#pragma once - -#include "base.h" -#include "servo.h" - -#include - -namespace hexapod { - - class Leg { - public: - Leg(int legIndex); - virtual ~Leg(); - - // coordinate system translation - void translateToLocal(const Point3D& world, Point3D& local); - void translateToWorld(const Point3D& local, Point3D& world); - - void setJointAngle(float angle[3]); - - // world coordinate system (default) - void moveTip(const Point3D& to); - const Point3D& getTipPosition(void); - - // local coordinate system version - void moveTipLocal(const Point3D& to); - const Point3D& getTipPositionLocal(void); - - // - Servo* get(int partIndex) { - return servos_[partIndex]; - } - - private: - // Local coorinate system - static void _forwardKinematics(float angle[3], Point3D& out); - static void _inverseKinematics(const Point3D& to, float angles[3]); - void _move(const Point3D& to); - - private: - int index_; - Servo* servos_[3]; - Point3D mountPosition_; - std::function localConv_; - std::function worldConv_; - - Point3D tipPos_; - Point3D tipPosLocal_; - - }; - -} \ No newline at end of file diff --git a/software/archive/hexapod7697/src/hexapod/movement.cpp b/software/archive/hexapod7697/src/hexapod/movement.cpp deleted file mode 100644 index f291bd0..0000000 --- a/software/archive/hexapod7697/src/hexapod/movement.cpp +++ /dev/null @@ -1,79 +0,0 @@ -#include "movement.h" -#include "debug.h" -#include "config.h" - -#include - -namespace hexapod { - - extern const MovementTable& standbyTable(); - extern const MovementTable& forwardTable(); - extern const MovementTable& forwardfastTable(); - extern const MovementTable& backwardTable(); - extern const MovementTable& turnleftTable(); - extern const MovementTable& turnrightTable(); - extern const MovementTable& shiftleftTable(); - extern const MovementTable& shiftrightTable(); - extern const MovementTable& climbTable(); - extern const MovementTable& rotatexTable(); - extern const MovementTable& rotateyTable(); - extern const MovementTable& rotatezTable(); - extern const MovementTable& twistTable(); - - const MovementTable kTable[MOVEMENT_TOTAL] { - standbyTable(), - forwardTable(), - forwardfastTable(), - backwardTable(), - turnleftTable(), - turnrightTable(), - shiftleftTable(), - shiftrightTable(), - climbTable(), - rotatexTable(), - rotateyTable(), - rotatezTable(), - twistTable(), - }; - - Movement::Movement(MovementMode mode): - mode_{mode}, transiting_{false} - { - } - - void Movement::setMode(MovementMode newMode) { - - if (!kTable[newMode].entries) { - LOG_INFO("Error: null movement of mode(%d)!", newMode); - return; - } - - mode_ = newMode; - - const MovementTable& table = kTable[mode_]; - - index_ = table.entries[std::rand() % table.entriesCount]; - remainTime_ = config::movementSwitchDuration > table.stepDuration ? config::movementSwitchDuration : table.stepDuration; - } - - const Locations& Movement::next(int elapsed) { - - const MovementTable& table = kTable[mode_]; - - if (elapsed <= 0) - elapsed = table.stepDuration; - - if (remainTime_ <= 0) { - index_ = (index_ + 1)%table.length; - remainTime_ = table.stepDuration; - } - if (elapsed >= remainTime_) - elapsed = remainTime_; - - auto ratio = (float)elapsed / remainTime_; - position_ += (table.table[index_] - position_)*ratio; - remainTime_ -= elapsed; - - return position_; - } -} \ No newline at end of file diff --git a/software/archive/hexapod7697/src/hexapod/movement.h b/software/archive/hexapod7697/src/hexapod/movement.h deleted file mode 100644 index 394d395..0000000 --- a/software/archive/hexapod7697/src/hexapod/movement.h +++ /dev/null @@ -1,56 +0,0 @@ -#pragma once - -#include "base.h" - -namespace hexapod { - - enum MovementMode { - MOVEMENT_STANDBY = 0, - - MOVEMENT_FORWARD, - MOVEMENT_FORWARDFAST, - MOVEMENT_BACKWARD, - MOVEMENT_TURNLEFT, - MOVEMENT_TURNRIGHT, - MOVEMENT_SHIFTLEFT, - MOVEMENT_SHIFTRIGHT, - MOVEMENT_CLIMB, - MOVEMENT_ROTATEX, - MOVEMENT_ROTATEY, - MOVEMENT_ROTATEZ, - MOVEMENT_TWIST, - - MOVEMENT_TOTAL, - }; - - inline MovementMode operator++ (MovementMode& m, int) { - if (m < MOVEMENT_TOTAL) - m = static_cast(static_cast(m) + 1); - return m; - } - - struct MovementTable { - const Locations* table; - int length; - int stepDuration; - const int* entries; - int entriesCount; - }; - - class Movement { - public: - Movement(MovementMode mode); - - void setMode(MovementMode newMode); - - const Locations& next(int elapsed); - - private: - MovementMode mode_; - Locations position_; - int index_; // index in mode position table - bool transiting_; // if still in transiting to new mode - int remainTime_; - }; - -} \ No newline at end of file diff --git a/software/archive/hexapod7697/src/hexapod/movement_table.h b/software/archive/hexapod7697/src/hexapod/movement_table.h deleted file mode 100644 index bc31056..0000000 --- a/software/archive/hexapod7697/src/hexapod/movement_table.h +++ /dev/null @@ -1,742 +0,0 @@ -// -// This file is generated, dont directly modify content... -// -namespace { - -const Locations backward_paths[] { - {{P1X+(0.00), P1Y+(0.00), P1Z+(25.00)}, {P2X+(0.00), P2Y+(0.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(0.00), P3Z+(25.00)}, {P4X+(0.00), P4Y+(0.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(0.00), P5Z+(25.00)}, {P6X+(0.00), P6Y+(0.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(-7.73), P1Z+(23.78)}, {P2X+(0.00), P2Y+(5.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(-7.73), P3Z+(23.78)}, {P4X+(0.00), P4Y+(5.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(-7.73), P5Z+(23.78)}, {P6X+(0.00), P6Y+(5.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(-14.69), P1Z+(20.23)}, {P2X+(0.00), P2Y+(10.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(-14.69), P3Z+(20.23)}, {P4X+(0.00), P4Y+(10.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(-14.69), P5Z+(20.23)}, {P6X+(0.00), P6Y+(10.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(-20.23), P1Z+(14.69)}, {P2X+(0.00), P2Y+(15.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(-20.23), P3Z+(14.69)}, {P4X+(0.00), P4Y+(15.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(-20.23), P5Z+(14.69)}, {P6X+(0.00), P6Y+(15.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(-23.78), P1Z+(7.73)}, {P2X+(0.00), P2Y+(20.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(-23.78), P3Z+(7.73)}, {P4X+(0.00), P4Y+(20.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(-23.78), P5Z+(7.73)}, {P6X+(0.00), P6Y+(20.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(-25.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(25.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(-25.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(25.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(-25.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(25.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(-20.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(23.78), P2Z+(7.73)}, {P3X+(0.00), P3Y+(-20.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(23.78), P4Z+(7.73)}, {P5X+(0.00), P5Y+(-20.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(23.78), P6Z+(7.73)}}, - {{P1X+(0.00), P1Y+(-15.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(20.23), P2Z+(14.69)}, {P3X+(0.00), P3Y+(-15.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(20.23), P4Z+(14.69)}, {P5X+(0.00), P5Y+(-15.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(20.23), P6Z+(14.69)}}, - {{P1X+(0.00), P1Y+(-10.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(14.69), P2Z+(20.23)}, {P3X+(0.00), P3Y+(-10.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(14.69), P4Z+(20.23)}, {P5X+(0.00), P5Y+(-10.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(14.69), P6Z+(20.23)}}, - {{P1X+(0.00), P1Y+(-5.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(7.73), P2Z+(23.78)}, {P3X+(0.00), P3Y+(-5.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(7.73), P4Z+(23.78)}, {P5X+(0.00), P5Y+(-5.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(7.73), P6Z+(23.78)}}, - {{P1X+(0.00), P1Y+(0.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(0.00), P2Z+(25.00)}, {P3X+(0.00), P3Y+(0.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(0.00), P4Z+(25.00)}, {P5X+(0.00), P5Y+(0.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(0.00), P6Z+(25.00)}}, - {{P1X+(0.00), P1Y+(5.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(-7.73), P2Z+(23.78)}, {P3X+(0.00), P3Y+(5.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(-7.73), P4Z+(23.78)}, {P5X+(0.00), P5Y+(5.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(-7.73), P6Z+(23.78)}}, - {{P1X+(0.00), P1Y+(10.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(-14.69), P2Z+(20.23)}, {P3X+(0.00), P3Y+(10.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(-14.69), P4Z+(20.23)}, {P5X+(0.00), P5Y+(10.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(-14.69), P6Z+(20.23)}}, - {{P1X+(0.00), P1Y+(15.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(-20.23), P2Z+(14.69)}, {P3X+(0.00), P3Y+(15.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(-20.23), P4Z+(14.69)}, {P5X+(0.00), P5Y+(15.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(-20.23), P6Z+(14.69)}}, - {{P1X+(0.00), P1Y+(20.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(-23.78), P2Z+(7.73)}, {P3X+(0.00), P3Y+(20.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(-23.78), P4Z+(7.73)}, {P5X+(0.00), P5Y+(20.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(-23.78), P6Z+(7.73)}}, - {{P1X+(0.00), P1Y+(25.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(-25.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(25.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(-25.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(25.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(-25.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(23.78), P1Z+(7.73)}, {P2X+(0.00), P2Y+(-20.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(23.78), P3Z+(7.73)}, {P4X+(0.00), P4Y+(-20.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(23.78), P5Z+(7.73)}, {P6X+(0.00), P6Y+(-20.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(20.23), P1Z+(14.69)}, {P2X+(0.00), P2Y+(-15.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(20.23), P3Z+(14.69)}, {P4X+(0.00), P4Y+(-15.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(20.23), P5Z+(14.69)}, {P6X+(0.00), P6Y+(-15.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(14.69), P1Z+(20.23)}, {P2X+(0.00), P2Y+(-10.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(14.69), P3Z+(20.23)}, {P4X+(0.00), P4Y+(-10.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(14.69), P5Z+(20.23)}, {P6X+(0.00), P6Y+(-10.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(7.73), P1Z+(23.78)}, {P2X+(0.00), P2Y+(-5.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(7.73), P3Z+(23.78)}, {P4X+(0.00), P4Y+(-5.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(7.73), P5Z+(23.78)}, {P6X+(0.00), P6Y+(-5.00), P6Z+(0.00)}}, -}; -const int backward_entries[] { 0,10 }; -const MovementTable backward_table {backward_paths, 20, 20, backward_entries, 2 }; - -const Locations climb_paths[] { - {{P1X+(30.00), P1Y+(0.00), P1Z+(50.00)}, {P2X+(0.00), P2Y+(0.00), P2Z+(-30.00)}, {P3X+(30.00), P3Y+(0.00), P3Z+(50.00)}, {P4X+(0.00), P4Y+(0.00), P4Z+(-30.00)}, {P5X+(-30.00), P5Y+(0.00), P5Z+(50.00)}, {P6X+(0.00), P6Y+(0.00), P6Z+(-30.00)}}, - {{P1X+(28.53), P1Y+(6.18), P1Z+(46.08)}, {P2X+(0.00), P2Y+(-4.00), P2Z+(-30.00)}, {P3X+(28.53), P3Y+(6.18), P3Z+(46.08)}, {P4X+(0.00), P4Y+(-4.00), P4Z+(-30.00)}, {P5X+(-28.53), P5Y+(6.18), P5Z+(46.08)}, {P6X+(0.00), P6Y+(-4.00), P6Z+(-30.00)}}, - {{P1X+(24.27), P1Y+(11.76), P1Z+(34.72)}, {P2X+(0.00), P2Y+(-8.00), P2Z+(-30.00)}, {P3X+(24.27), P3Y+(11.76), P3Z+(34.72)}, {P4X+(0.00), P4Y+(-8.00), P4Z+(-30.00)}, {P5X+(-24.27), P5Y+(11.76), P5Z+(34.72)}, {P6X+(0.00), P6Y+(-8.00), P6Z+(-30.00)}}, - {{P1X+(17.63), P1Y+(16.18), P1Z+(17.02)}, {P2X+(0.00), P2Y+(-12.00), P2Z+(-30.00)}, {P3X+(17.63), P3Y+(16.18), P3Z+(17.02)}, {P4X+(0.00), P4Y+(-12.00), P4Z+(-30.00)}, {P5X+(-17.63), P5Y+(16.18), P5Z+(17.02)}, {P6X+(0.00), P6Y+(-12.00), P6Z+(-30.00)}}, - {{P1X+(9.27), P1Y+(19.02), P1Z+(-5.28)}, {P2X+(0.00), P2Y+(-16.00), P2Z+(-30.00)}, {P3X+(9.27), P3Y+(19.02), P3Z+(-5.28)}, {P4X+(0.00), P4Y+(-16.00), P4Z+(-30.00)}, {P5X+(-9.27), P5Y+(19.02), P5Z+(-5.28)}, {P6X+(0.00), P6Y+(-16.00), P6Z+(-30.00)}}, - {{P1X+(0.00), P1Y+(20.00), P1Z+(-30.00)}, {P2X+(0.00), P2Y+(-20.00), P2Z+(-30.00)}, {P3X+(0.00), P3Y+(20.00), P3Z+(-30.00)}, {P4X+(-0.00), P4Y+(-20.00), P4Z+(-30.00)}, {P5X+(0.00), P5Y+(20.00), P5Z+(-30.00)}, {P6X+(-0.00), P6Y+(-20.00), P6Z+(-30.00)}}, - {{P1X+(0.00), P1Y+(16.00), P1Z+(-30.00)}, {P2X+(9.27), P2Y+(-19.02), P2Z+(-5.28)}, {P3X+(0.00), P3Y+(16.00), P3Z+(-30.00)}, {P4X+(-9.27), P4Y+(-19.02), P4Z+(-5.28)}, {P5X+(0.00), P5Y+(16.00), P5Z+(-30.00)}, {P6X+(-9.27), P6Y+(-19.02), P6Z+(-5.28)}}, - {{P1X+(0.00), P1Y+(12.00), P1Z+(-30.00)}, {P2X+(17.63), P2Y+(-16.18), P2Z+(17.02)}, {P3X+(0.00), P3Y+(12.00), P3Z+(-30.00)}, {P4X+(-17.63), P4Y+(-16.18), P4Z+(17.02)}, {P5X+(0.00), P5Y+(12.00), P5Z+(-30.00)}, {P6X+(-17.63), P6Y+(-16.18), P6Z+(17.02)}}, - {{P1X+(0.00), P1Y+(8.00), P1Z+(-30.00)}, {P2X+(24.27), P2Y+(-11.76), P2Z+(34.72)}, {P3X+(0.00), P3Y+(8.00), P3Z+(-30.00)}, {P4X+(-24.27), P4Y+(-11.76), P4Z+(34.72)}, {P5X+(0.00), P5Y+(8.00), P5Z+(-30.00)}, {P6X+(-24.27), P6Y+(-11.76), P6Z+(34.72)}}, - {{P1X+(0.00), P1Y+(4.00), P1Z+(-30.00)}, {P2X+(28.53), P2Y+(-6.18), P2Z+(46.08)}, {P3X+(0.00), P3Y+(4.00), P3Z+(-30.00)}, {P4X+(-28.53), P4Y+(-6.18), P4Z+(46.08)}, {P5X+(0.00), P5Y+(4.00), P5Z+(-30.00)}, {P6X+(-28.53), P6Y+(-6.18), P6Z+(46.08)}}, - {{P1X+(0.00), P1Y+(0.00), P1Z+(-30.00)}, {P2X+(30.00), P2Y+(0.00), P2Z+(50.00)}, {P3X+(0.00), P3Y+(0.00), P3Z+(-30.00)}, {P4X+(-30.00), P4Y+(0.00), P4Z+(50.00)}, {P5X+(0.00), P5Y+(0.00), P5Z+(-30.00)}, {P6X+(-30.00), P6Y+(0.00), P6Z+(50.00)}}, - {{P1X+(0.00), P1Y+(-4.00), P1Z+(-30.00)}, {P2X+(28.53), P2Y+(6.18), P2Z+(46.08)}, {P3X+(0.00), P3Y+(-4.00), P3Z+(-30.00)}, {P4X+(-28.53), P4Y+(6.18), P4Z+(46.08)}, {P5X+(0.00), P5Y+(-4.00), P5Z+(-30.00)}, {P6X+(-28.53), P6Y+(6.18), P6Z+(46.08)}}, - {{P1X+(0.00), P1Y+(-8.00), P1Z+(-30.00)}, {P2X+(24.27), P2Y+(11.76), P2Z+(34.72)}, {P3X+(0.00), P3Y+(-8.00), P3Z+(-30.00)}, {P4X+(-24.27), P4Y+(11.76), P4Z+(34.72)}, {P5X+(0.00), P5Y+(-8.00), P5Z+(-30.00)}, {P6X+(-24.27), P6Y+(11.76), P6Z+(34.72)}}, - {{P1X+(0.00), P1Y+(-12.00), P1Z+(-30.00)}, {P2X+(17.63), P2Y+(16.18), P2Z+(17.02)}, {P3X+(0.00), P3Y+(-12.00), P3Z+(-30.00)}, {P4X+(-17.63), P4Y+(16.18), P4Z+(17.02)}, {P5X+(0.00), P5Y+(-12.00), P5Z+(-30.00)}, {P6X+(-17.63), P6Y+(16.18), P6Z+(17.02)}}, - {{P1X+(0.00), P1Y+(-16.00), P1Z+(-30.00)}, {P2X+(9.27), P2Y+(19.02), P2Z+(-5.28)}, {P3X+(0.00), P3Y+(-16.00), P3Z+(-30.00)}, {P4X+(-9.27), P4Y+(19.02), P4Z+(-5.28)}, {P5X+(0.00), P5Y+(-16.00), P5Z+(-30.00)}, {P6X+(-9.27), P6Y+(19.02), P6Z+(-5.28)}}, - {{P1X+(0.00), P1Y+(-20.00), P1Z+(-30.00)}, {P2X+(0.00), P2Y+(20.00), P2Z+(-30.00)}, {P3X+(0.00), P3Y+(-20.00), P3Z+(-30.00)}, {P4X+(0.00), P4Y+(20.00), P4Z+(-30.00)}, {P5X+(-0.00), P5Y+(-20.00), P5Z+(-30.00)}, {P6X+(0.00), P6Y+(20.00), P6Z+(-30.00)}}, - {{P1X+(9.27), P1Y+(-19.02), P1Z+(-5.28)}, {P2X+(0.00), P2Y+(16.00), P2Z+(-30.00)}, {P3X+(9.27), P3Y+(-19.02), P3Z+(-5.28)}, {P4X+(0.00), P4Y+(16.00), P4Z+(-30.00)}, {P5X+(-9.27), P5Y+(-19.02), P5Z+(-5.28)}, {P6X+(0.00), P6Y+(16.00), P6Z+(-30.00)}}, - {{P1X+(17.63), P1Y+(-16.18), P1Z+(17.02)}, {P2X+(0.00), P2Y+(12.00), P2Z+(-30.00)}, {P3X+(17.63), P3Y+(-16.18), P3Z+(17.02)}, {P4X+(0.00), P4Y+(12.00), P4Z+(-30.00)}, {P5X+(-17.63), P5Y+(-16.18), P5Z+(17.02)}, {P6X+(0.00), P6Y+(12.00), P6Z+(-30.00)}}, - {{P1X+(24.27), P1Y+(-11.76), P1Z+(34.72)}, {P2X+(0.00), P2Y+(8.00), P2Z+(-30.00)}, {P3X+(24.27), P3Y+(-11.76), P3Z+(34.72)}, {P4X+(0.00), P4Y+(8.00), P4Z+(-30.00)}, {P5X+(-24.27), P5Y+(-11.76), P5Z+(34.72)}, {P6X+(0.00), P6Y+(8.00), P6Z+(-30.00)}}, - {{P1X+(28.53), P1Y+(-6.18), P1Z+(46.08)}, {P2X+(0.00), P2Y+(4.00), P2Z+(-30.00)}, {P3X+(28.53), P3Y+(-6.18), P3Z+(46.08)}, {P4X+(0.00), P4Y+(4.00), P4Z+(-30.00)}, {P5X+(-28.53), P5Y+(-6.18), P5Z+(46.08)}, {P6X+(0.00), P6Y+(4.00), P6Z+(-30.00)}}, -}; -const int climb_entries[] { 0,10 }; -const MovementTable climb_table {climb_paths, 20, 30, climb_entries, 2 }; - -const Locations forward_paths[] { - {{P1X+(0.00), P1Y+(0.00), P1Z+(25.00)}, {P2X+(0.00), P2Y+(0.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(0.00), P3Z+(25.00)}, {P4X+(0.00), P4Y+(0.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(0.00), P5Z+(25.00)}, {P6X+(0.00), P6Y+(0.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(7.73), P1Z+(23.78)}, {P2X+(0.00), P2Y+(-5.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(7.73), P3Z+(23.78)}, {P4X+(0.00), P4Y+(-5.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(7.73), P5Z+(23.78)}, {P6X+(0.00), P6Y+(-5.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(14.69), P1Z+(20.23)}, {P2X+(0.00), P2Y+(-10.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(14.69), P3Z+(20.23)}, {P4X+(0.00), P4Y+(-10.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(14.69), P5Z+(20.23)}, {P6X+(0.00), P6Y+(-10.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(20.23), P1Z+(14.69)}, {P2X+(0.00), P2Y+(-15.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(20.23), P3Z+(14.69)}, {P4X+(0.00), P4Y+(-15.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(20.23), P5Z+(14.69)}, {P6X+(0.00), P6Y+(-15.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(23.78), P1Z+(7.73)}, {P2X+(0.00), P2Y+(-20.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(23.78), P3Z+(7.73)}, {P4X+(0.00), P4Y+(-20.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(23.78), P5Z+(7.73)}, {P6X+(0.00), P6Y+(-20.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(25.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(-25.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(25.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(-25.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(25.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(-25.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(20.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(-23.78), P2Z+(7.73)}, {P3X+(0.00), P3Y+(20.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(-23.78), P4Z+(7.73)}, {P5X+(0.00), P5Y+(20.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(-23.78), P6Z+(7.73)}}, - {{P1X+(0.00), P1Y+(15.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(-20.23), P2Z+(14.69)}, {P3X+(0.00), P3Y+(15.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(-20.23), P4Z+(14.69)}, {P5X+(0.00), P5Y+(15.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(-20.23), P6Z+(14.69)}}, - {{P1X+(0.00), P1Y+(10.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(-14.69), P2Z+(20.23)}, {P3X+(0.00), P3Y+(10.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(-14.69), P4Z+(20.23)}, {P5X+(0.00), P5Y+(10.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(-14.69), P6Z+(20.23)}}, - {{P1X+(0.00), P1Y+(5.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(-7.73), P2Z+(23.78)}, {P3X+(0.00), P3Y+(5.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(-7.73), P4Z+(23.78)}, {P5X+(0.00), P5Y+(5.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(-7.73), P6Z+(23.78)}}, - {{P1X+(0.00), P1Y+(0.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(0.00), P2Z+(25.00)}, {P3X+(0.00), P3Y+(0.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(0.00), P4Z+(25.00)}, {P5X+(0.00), P5Y+(0.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(0.00), P6Z+(25.00)}}, - {{P1X+(0.00), P1Y+(-5.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(7.73), P2Z+(23.78)}, {P3X+(0.00), P3Y+(-5.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(7.73), P4Z+(23.78)}, {P5X+(0.00), P5Y+(-5.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(7.73), P6Z+(23.78)}}, - {{P1X+(0.00), P1Y+(-10.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(14.69), P2Z+(20.23)}, {P3X+(0.00), P3Y+(-10.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(14.69), P4Z+(20.23)}, {P5X+(0.00), P5Y+(-10.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(14.69), P6Z+(20.23)}}, - {{P1X+(0.00), P1Y+(-15.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(20.23), P2Z+(14.69)}, {P3X+(0.00), P3Y+(-15.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(20.23), P4Z+(14.69)}, {P5X+(0.00), P5Y+(-15.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(20.23), P6Z+(14.69)}}, - {{P1X+(0.00), P1Y+(-20.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(23.78), P2Z+(7.73)}, {P3X+(0.00), P3Y+(-20.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(23.78), P4Z+(7.73)}, {P5X+(0.00), P5Y+(-20.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(23.78), P6Z+(7.73)}}, - {{P1X+(0.00), P1Y+(-25.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(25.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(-25.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(25.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(-25.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(25.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(-23.78), P1Z+(7.73)}, {P2X+(0.00), P2Y+(20.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(-23.78), P3Z+(7.73)}, {P4X+(0.00), P4Y+(20.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(-23.78), P5Z+(7.73)}, {P6X+(0.00), P6Y+(20.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(-20.23), P1Z+(14.69)}, {P2X+(0.00), P2Y+(15.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(-20.23), P3Z+(14.69)}, {P4X+(0.00), P4Y+(15.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(-20.23), P5Z+(14.69)}, {P6X+(0.00), P6Y+(15.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(-14.69), P1Z+(20.23)}, {P2X+(0.00), P2Y+(10.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(-14.69), P3Z+(20.23)}, {P4X+(0.00), P4Y+(10.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(-14.69), P5Z+(20.23)}, {P6X+(0.00), P6Y+(10.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(-7.73), P1Z+(23.78)}, {P2X+(0.00), P2Y+(5.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(-7.73), P3Z+(23.78)}, {P4X+(0.00), P4Y+(5.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(-7.73), P5Z+(23.78)}, {P6X+(0.00), P6Y+(5.00), P6Z+(0.00)}}, -}; -const int forward_entries[] { 0,10 }; -const MovementTable forward_table {forward_paths, 20, 20, forward_entries, 2 }; - -const Locations forwardfast_paths[] { - {{P1X+(10.00), P1Y+(0.00), P1Z+(30.00)}, {P2X+(0.00), P2Y+(0.00), P2Z+(0.00)}, {P3X+(10.00), P3Y+(0.00), P3Z+(30.00)}, {P4X+(0.00), P4Y+(0.00), P4Z+(0.00)}, {P5X+(-10.00), P5Y+(0.00), P5Z+(30.00)}, {P6X+(0.00), P6Y+(0.00), P6Z+(0.00)}}, - {{P1X+(9.51), P1Y+(15.45), P1Z+(28.53)}, {P2X+(0.00), P2Y+(-10.00), P2Z+(0.00)}, {P3X+(9.51), P3Y+(15.45), P3Z+(28.53)}, {P4X+(0.00), P4Y+(-10.00), P4Z+(0.00)}, {P5X+(-9.51), P5Y+(15.45), P5Z+(28.53)}, {P6X+(0.00), P6Y+(-10.00), P6Z+(0.00)}}, - {{P1X+(8.09), P1Y+(29.39), P1Z+(24.27)}, {P2X+(0.00), P2Y+(-20.00), P2Z+(0.00)}, {P3X+(8.09), P3Y+(29.39), P3Z+(24.27)}, {P4X+(0.00), P4Y+(-20.00), P4Z+(0.00)}, {P5X+(-8.09), P5Y+(29.39), P5Z+(24.27)}, {P6X+(0.00), P6Y+(-20.00), P6Z+(0.00)}}, - {{P1X+(5.88), P1Y+(40.45), P1Z+(17.63)}, {P2X+(0.00), P2Y+(-30.00), P2Z+(0.00)}, {P3X+(5.88), P3Y+(40.45), P3Z+(17.63)}, {P4X+(0.00), P4Y+(-30.00), P4Z+(0.00)}, {P5X+(-5.88), P5Y+(40.45), P5Z+(17.63)}, {P6X+(0.00), P6Y+(-30.00), P6Z+(0.00)}}, - {{P1X+(3.09), P1Y+(47.55), P1Z+(9.27)}, {P2X+(0.00), P2Y+(-40.00), P2Z+(0.00)}, {P3X+(3.09), P3Y+(47.55), P3Z+(9.27)}, {P4X+(0.00), P4Y+(-40.00), P4Z+(0.00)}, {P5X+(-3.09), P5Y+(47.55), P5Z+(9.27)}, {P6X+(0.00), P6Y+(-40.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(50.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(-50.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(50.00), P3Z+(0.00)}, {P4X+(-0.00), P4Y+(-50.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(50.00), P5Z+(0.00)}, {P6X+(-0.00), P6Y+(-50.00), P6Z+(0.00)}}, - {{P1X+(0.00), P1Y+(40.00), P1Z+(0.00)}, {P2X+(3.09), P2Y+(-47.55), P2Z+(9.27)}, {P3X+(0.00), P3Y+(40.00), P3Z+(0.00)}, {P4X+(-3.09), P4Y+(-47.55), P4Z+(9.27)}, {P5X+(0.00), P5Y+(40.00), P5Z+(0.00)}, {P6X+(-3.09), P6Y+(-47.55), P6Z+(9.27)}}, - {{P1X+(0.00), P1Y+(30.00), P1Z+(0.00)}, {P2X+(5.88), P2Y+(-40.45), P2Z+(17.63)}, {P3X+(0.00), P3Y+(30.00), P3Z+(0.00)}, {P4X+(-5.88), P4Y+(-40.45), P4Z+(17.63)}, {P5X+(0.00), P5Y+(30.00), P5Z+(0.00)}, {P6X+(-5.88), P6Y+(-40.45), P6Z+(17.63)}}, - {{P1X+(0.00), P1Y+(20.00), P1Z+(0.00)}, {P2X+(8.09), P2Y+(-29.39), P2Z+(24.27)}, {P3X+(0.00), P3Y+(20.00), P3Z+(0.00)}, {P4X+(-8.09), P4Y+(-29.39), P4Z+(24.27)}, {P5X+(0.00), P5Y+(20.00), P5Z+(0.00)}, {P6X+(-8.09), P6Y+(-29.39), P6Z+(24.27)}}, - {{P1X+(0.00), P1Y+(10.00), P1Z+(0.00)}, {P2X+(9.51), P2Y+(-15.45), P2Z+(28.53)}, {P3X+(0.00), P3Y+(10.00), P3Z+(0.00)}, {P4X+(-9.51), P4Y+(-15.45), P4Z+(28.53)}, {P5X+(0.00), P5Y+(10.00), P5Z+(0.00)}, {P6X+(-9.51), P6Y+(-15.45), P6Z+(28.53)}}, - {{P1X+(0.00), P1Y+(0.00), P1Z+(0.00)}, {P2X+(10.00), P2Y+(0.00), P2Z+(30.00)}, {P3X+(0.00), P3Y+(0.00), P3Z+(0.00)}, {P4X+(-10.00), P4Y+(0.00), P4Z+(30.00)}, {P5X+(0.00), P5Y+(0.00), P5Z+(0.00)}, {P6X+(-10.00), P6Y+(0.00), P6Z+(30.00)}}, - {{P1X+(0.00), P1Y+(-10.00), P1Z+(0.00)}, {P2X+(9.51), P2Y+(15.45), P2Z+(28.53)}, {P3X+(0.00), P3Y+(-10.00), P3Z+(0.00)}, {P4X+(-9.51), P4Y+(15.45), P4Z+(28.53)}, {P5X+(0.00), P5Y+(-10.00), P5Z+(0.00)}, {P6X+(-9.51), P6Y+(15.45), P6Z+(28.53)}}, - {{P1X+(0.00), P1Y+(-20.00), P1Z+(0.00)}, {P2X+(8.09), P2Y+(29.39), P2Z+(24.27)}, {P3X+(0.00), P3Y+(-20.00), P3Z+(0.00)}, {P4X+(-8.09), P4Y+(29.39), P4Z+(24.27)}, {P5X+(0.00), P5Y+(-20.00), P5Z+(0.00)}, {P6X+(-8.09), P6Y+(29.39), P6Z+(24.27)}}, - {{P1X+(0.00), P1Y+(-30.00), P1Z+(0.00)}, {P2X+(5.88), P2Y+(40.45), P2Z+(17.63)}, {P3X+(0.00), P3Y+(-30.00), P3Z+(0.00)}, {P4X+(-5.88), P4Y+(40.45), P4Z+(17.63)}, {P5X+(0.00), P5Y+(-30.00), P5Z+(0.00)}, {P6X+(-5.88), P6Y+(40.45), P6Z+(17.63)}}, - {{P1X+(0.00), P1Y+(-40.00), P1Z+(0.00)}, {P2X+(3.09), P2Y+(47.55), P2Z+(9.27)}, {P3X+(0.00), P3Y+(-40.00), P3Z+(0.00)}, {P4X+(-3.09), P4Y+(47.55), P4Z+(9.27)}, {P5X+(0.00), P5Y+(-40.00), P5Z+(0.00)}, {P6X+(-3.09), P6Y+(47.55), P6Z+(9.27)}}, - {{P1X+(0.00), P1Y+(-50.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(50.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(-50.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(50.00), P4Z+(0.00)}, {P5X+(-0.00), P5Y+(-50.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(50.00), P6Z+(0.00)}}, - {{P1X+(3.09), P1Y+(-47.55), P1Z+(9.27)}, {P2X+(0.00), P2Y+(40.00), P2Z+(0.00)}, {P3X+(3.09), P3Y+(-47.55), P3Z+(9.27)}, {P4X+(0.00), P4Y+(40.00), P4Z+(0.00)}, {P5X+(-3.09), P5Y+(-47.55), P5Z+(9.27)}, {P6X+(0.00), P6Y+(40.00), P6Z+(0.00)}}, - {{P1X+(5.88), P1Y+(-40.45), P1Z+(17.63)}, {P2X+(0.00), P2Y+(30.00), P2Z+(0.00)}, {P3X+(5.88), P3Y+(-40.45), P3Z+(17.63)}, {P4X+(0.00), P4Y+(30.00), P4Z+(0.00)}, {P5X+(-5.88), P5Y+(-40.45), P5Z+(17.63)}, {P6X+(0.00), P6Y+(30.00), P6Z+(0.00)}}, - {{P1X+(8.09), P1Y+(-29.39), P1Z+(24.27)}, {P2X+(0.00), P2Y+(20.00), P2Z+(0.00)}, {P3X+(8.09), P3Y+(-29.39), P3Z+(24.27)}, {P4X+(0.00), P4Y+(20.00), P4Z+(0.00)}, {P5X+(-8.09), P5Y+(-29.39), P5Z+(24.27)}, {P6X+(0.00), P6Y+(20.00), P6Z+(0.00)}}, - {{P1X+(9.51), P1Y+(-15.45), P1Z+(28.53)}, {P2X+(0.00), P2Y+(10.00), P2Z+(0.00)}, {P3X+(9.51), P3Y+(-15.45), P3Z+(28.53)}, {P4X+(0.00), P4Y+(10.00), P4Z+(0.00)}, {P5X+(-9.51), P5Y+(-15.45), P5Z+(28.53)}, {P6X+(0.00), P6Y+(10.00), P6Z+(0.00)}}, -}; -const int forwardfast_entries[] { 0,10 }; -const MovementTable forwardfast_table {forwardfast_paths, 20, 20, forwardfast_entries, 2 }; - -const Locations rotatex_paths[] { - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*0.97 + P1Z*-0.26 + 0.00, P1X*0.00 + P1Y*0.26 + P1Z*0.97 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*0.97 + P2Z*-0.26 + 0.00, P2X*0.00 + P2Y*0.26 + P2Z*0.97 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*0.97 + P3Z*-0.26 + 0.00, P3X*0.00 + P3Y*0.26 + P3Z*0.97 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*0.97 + P4Z*-0.26 + 0.00, P4X*0.00 + P4Y*0.26 + P4Z*0.97 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*0.97 + P5Z*-0.26 + 0.00, P5X*0.00 + P5Y*0.26 + P5Z*0.97 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*0.97 + P6Z*-0.26 + 0.00, P6X*0.00 + P6Y*0.26 + P6Z*0.97 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*0.98 + P1Z*-0.21 + -3.00, P1X*0.00 + P1Y*0.21 + P1Z*0.98 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*0.98 + P2Z*-0.21 + -3.00, P2X*0.00 + P2Y*0.21 + P2Z*0.98 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*0.98 + P3Z*-0.21 + -3.00, P3X*0.00 + P3Y*0.21 + P3Z*0.98 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*0.98 + P4Z*-0.21 + -3.00, P4X*0.00 + P4Y*0.21 + P4Z*0.98 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*0.98 + P5Z*-0.21 + -3.00, P5X*0.00 + P5Y*0.21 + P5Z*0.98 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*0.98 + P6Z*-0.21 + -3.00, P6X*0.00 + P6Y*0.21 + P6Z*0.98 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*0.99 + P1Z*-0.16 + -6.00, P1X*0.00 + P1Y*0.16 + P1Z*0.99 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*0.99 + P2Z*-0.16 + -6.00, P2X*0.00 + P2Y*0.16 + P2Z*0.99 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*0.99 + P3Z*-0.16 + -6.00, P3X*0.00 + P3Y*0.16 + P3Z*0.99 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*0.99 + P4Z*-0.16 + -6.00, P4X*0.00 + P4Y*0.16 + P4Z*0.99 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*0.99 + P5Z*-0.16 + -6.00, P5X*0.00 + P5Y*0.16 + P5Z*0.99 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*0.99 + P6Z*-0.16 + -6.00, P6X*0.00 + P6Y*0.16 + P6Z*0.99 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*0.99 + P1Z*-0.10 + -9.00, P1X*0.00 + P1Y*0.10 + P1Z*0.99 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*0.99 + P2Z*-0.10 + -9.00, P2X*0.00 + P2Y*0.10 + P2Z*0.99 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*0.99 + P3Z*-0.10 + -9.00, P3X*0.00 + P3Y*0.10 + P3Z*0.99 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*0.99 + P4Z*-0.10 + -9.00, P4X*0.00 + P4Y*0.10 + P4Z*0.99 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*0.99 + P5Z*-0.10 + -9.00, P5X*0.00 + P5Y*0.10 + P5Z*0.99 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*0.99 + P6Z*-0.10 + -9.00, P6X*0.00 + P6Y*0.10 + P6Z*0.99 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*1.00 + P1Z*-0.05 + -12.00, P1X*0.00 + P1Y*0.05 + P1Z*1.00 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*1.00 + P2Z*-0.05 + -12.00, P2X*0.00 + P2Y*0.05 + P2Z*1.00 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*1.00 + P3Z*-0.05 + -12.00, P3X*0.00 + P3Y*0.05 + P3Z*1.00 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*1.00 + P4Z*-0.05 + -12.00, P4X*0.00 + P4Y*0.05 + P4Z*1.00 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*1.00 + P5Z*-0.05 + -12.00, P5X*0.00 + P5Y*0.05 + P5Z*1.00 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*1.00 + P6Z*-0.05 + -12.00, P6X*0.00 + P6Y*0.05 + P6Z*1.00 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*1.00 + P1Z*-0.00 + -15.00, P1X*0.00 + P1Y*0.00 + P1Z*1.00 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*1.00 + P2Z*-0.00 + -15.00, P2X*0.00 + P2Y*0.00 + P2Z*1.00 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*1.00 + P3Z*-0.00 + -15.00, P3X*0.00 + P3Y*0.00 + P3Z*1.00 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*1.00 + P4Z*-0.00 + -15.00, P4X*0.00 + P4Y*0.00 + P4Z*1.00 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*1.00 + P5Z*-0.00 + -15.00, P5X*0.00 + P5Y*0.00 + P5Z*1.00 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*1.00 + P6Z*-0.00 + -15.00, P6X*0.00 + P6Y*0.00 + P6Z*1.00 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*1.00 + P1Z*0.05 + -12.00, P1X*0.00 + P1Y*-0.05 + P1Z*1.00 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*1.00 + P2Z*0.05 + -12.00, P2X*0.00 + P2Y*-0.05 + P2Z*1.00 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*1.00 + P3Z*0.05 + -12.00, P3X*0.00 + P3Y*-0.05 + P3Z*1.00 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*1.00 + P4Z*0.05 + -12.00, P4X*0.00 + P4Y*-0.05 + P4Z*1.00 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*1.00 + P5Z*0.05 + -12.00, P5X*0.00 + P5Y*-0.05 + P5Z*1.00 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*1.00 + P6Z*0.05 + -12.00, P6X*0.00 + P6Y*-0.05 + P6Z*1.00 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*0.99 + P1Z*0.10 + -9.00, P1X*0.00 + P1Y*-0.10 + P1Z*0.99 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*0.99 + P2Z*0.10 + -9.00, P2X*0.00 + P2Y*-0.10 + P2Z*0.99 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*0.99 + P3Z*0.10 + -9.00, P3X*0.00 + P3Y*-0.10 + P3Z*0.99 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*0.99 + P4Z*0.10 + -9.00, P4X*0.00 + P4Y*-0.10 + P4Z*0.99 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*0.99 + P5Z*0.10 + -9.00, P5X*0.00 + P5Y*-0.10 + P5Z*0.99 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*0.99 + P6Z*0.10 + -9.00, P6X*0.00 + P6Y*-0.10 + P6Z*0.99 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*0.99 + P1Z*0.16 + -6.00, P1X*0.00 + P1Y*-0.16 + P1Z*0.99 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*0.99 + P2Z*0.16 + -6.00, P2X*0.00 + P2Y*-0.16 + P2Z*0.99 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*0.99 + P3Z*0.16 + -6.00, P3X*0.00 + P3Y*-0.16 + P3Z*0.99 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*0.99 + P4Z*0.16 + -6.00, P4X*0.00 + P4Y*-0.16 + P4Z*0.99 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*0.99 + P5Z*0.16 + -6.00, P5X*0.00 + P5Y*-0.16 + P5Z*0.99 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*0.99 + P6Z*0.16 + -6.00, P6X*0.00 + P6Y*-0.16 + P6Z*0.99 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*0.98 + P1Z*0.21 + -3.00, P1X*0.00 + P1Y*-0.21 + P1Z*0.98 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*0.98 + P2Z*0.21 + -3.00, P2X*0.00 + P2Y*-0.21 + P2Z*0.98 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*0.98 + P3Z*0.21 + -3.00, P3X*0.00 + P3Y*-0.21 + P3Z*0.98 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*0.98 + P4Z*0.21 + -3.00, P4X*0.00 + P4Y*-0.21 + P4Z*0.98 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*0.98 + P5Z*0.21 + -3.00, P5X*0.00 + P5Y*-0.21 + P5Z*0.98 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*0.98 + P6Z*0.21 + -3.00, P6X*0.00 + P6Y*-0.21 + P6Z*0.98 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*0.97 + P1Z*0.26 + 0.00, P1X*0.00 + P1Y*-0.26 + P1Z*0.97 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*0.97 + P2Z*0.26 + 0.00, P2X*0.00 + P2Y*-0.26 + P2Z*0.97 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*0.97 + P3Z*0.26 + 0.00, P3X*0.00 + P3Y*-0.26 + P3Z*0.97 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*0.97 + P4Z*0.26 + 0.00, P4X*0.00 + P4Y*-0.26 + P4Z*0.97 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*0.97 + P5Z*0.26 + 0.00, P5X*0.00 + P5Y*-0.26 + P5Z*0.97 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*0.97 + P6Z*0.26 + 0.00, P6X*0.00 + P6Y*-0.26 + P6Z*0.97 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*0.98 + P1Z*0.21 + 3.00, P1X*0.00 + P1Y*-0.21 + P1Z*0.98 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*0.98 + P2Z*0.21 + 3.00, P2X*0.00 + P2Y*-0.21 + P2Z*0.98 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*0.98 + P3Z*0.21 + 3.00, P3X*0.00 + P3Y*-0.21 + P3Z*0.98 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*0.98 + P4Z*0.21 + 3.00, P4X*0.00 + P4Y*-0.21 + P4Z*0.98 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*0.98 + P5Z*0.21 + 3.00, P5X*0.00 + P5Y*-0.21 + P5Z*0.98 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*0.98 + P6Z*0.21 + 3.00, P6X*0.00 + P6Y*-0.21 + P6Z*0.98 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*0.99 + P1Z*0.16 + 6.00, P1X*0.00 + P1Y*-0.16 + P1Z*0.99 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*0.99 + P2Z*0.16 + 6.00, P2X*0.00 + P2Y*-0.16 + P2Z*0.99 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*0.99 + P3Z*0.16 + 6.00, P3X*0.00 + P3Y*-0.16 + P3Z*0.99 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*0.99 + P4Z*0.16 + 6.00, P4X*0.00 + P4Y*-0.16 + P4Z*0.99 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*0.99 + P5Z*0.16 + 6.00, P5X*0.00 + P5Y*-0.16 + P5Z*0.99 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*0.99 + P6Z*0.16 + 6.00, P6X*0.00 + P6Y*-0.16 + P6Z*0.99 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*0.99 + P1Z*0.10 + 9.00, P1X*0.00 + P1Y*-0.10 + P1Z*0.99 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*0.99 + P2Z*0.10 + 9.00, P2X*0.00 + P2Y*-0.10 + P2Z*0.99 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*0.99 + P3Z*0.10 + 9.00, P3X*0.00 + P3Y*-0.10 + P3Z*0.99 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*0.99 + P4Z*0.10 + 9.00, P4X*0.00 + P4Y*-0.10 + P4Z*0.99 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*0.99 + P5Z*0.10 + 9.00, P5X*0.00 + P5Y*-0.10 + P5Z*0.99 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*0.99 + P6Z*0.10 + 9.00, P6X*0.00 + P6Y*-0.10 + P6Z*0.99 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*1.00 + P1Z*0.05 + 12.00, P1X*0.00 + P1Y*-0.05 + P1Z*1.00 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*1.00 + P2Z*0.05 + 12.00, P2X*0.00 + P2Y*-0.05 + P2Z*1.00 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*1.00 + P3Z*0.05 + 12.00, P3X*0.00 + P3Y*-0.05 + P3Z*1.00 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*1.00 + P4Z*0.05 + 12.00, P4X*0.00 + P4Y*-0.05 + P4Z*1.00 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*1.00 + P5Z*0.05 + 12.00, P5X*0.00 + P5Y*-0.05 + P5Z*1.00 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*1.00 + P6Z*0.05 + 12.00, P6X*0.00 + P6Y*-0.05 + P6Z*1.00 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*1.00 + P1Z*-0.00 + 15.00, P1X*0.00 + P1Y*0.00 + P1Z*1.00 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*1.00 + P2Z*-0.00 + 15.00, P2X*0.00 + P2Y*0.00 + P2Z*1.00 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*1.00 + P3Z*-0.00 + 15.00, P3X*0.00 + P3Y*0.00 + P3Z*1.00 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*1.00 + P4Z*-0.00 + 15.00, P4X*0.00 + P4Y*0.00 + P4Z*1.00 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*1.00 + P5Z*-0.00 + 15.00, P5X*0.00 + P5Y*0.00 + P5Z*1.00 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*1.00 + P6Z*-0.00 + 15.00, P6X*0.00 + P6Y*0.00 + P6Z*1.00 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*1.00 + P1Z*-0.05 + 12.00, P1X*0.00 + P1Y*0.05 + P1Z*1.00 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*1.00 + P2Z*-0.05 + 12.00, P2X*0.00 + P2Y*0.05 + P2Z*1.00 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*1.00 + P3Z*-0.05 + 12.00, P3X*0.00 + P3Y*0.05 + P3Z*1.00 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*1.00 + P4Z*-0.05 + 12.00, P4X*0.00 + P4Y*0.05 + P4Z*1.00 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*1.00 + P5Z*-0.05 + 12.00, P5X*0.00 + P5Y*0.05 + P5Z*1.00 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*1.00 + P6Z*-0.05 + 12.00, P6X*0.00 + P6Y*0.05 + P6Z*1.00 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*0.99 + P1Z*-0.10 + 9.00, P1X*0.00 + P1Y*0.10 + P1Z*0.99 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*0.99 + P2Z*-0.10 + 9.00, P2X*0.00 + P2Y*0.10 + P2Z*0.99 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*0.99 + P3Z*-0.10 + 9.00, P3X*0.00 + P3Y*0.10 + P3Z*0.99 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*0.99 + P4Z*-0.10 + 9.00, P4X*0.00 + P4Y*0.10 + P4Z*0.99 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*0.99 + P5Z*-0.10 + 9.00, P5X*0.00 + P5Y*0.10 + P5Z*0.99 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*0.99 + P6Z*-0.10 + 9.00, P6X*0.00 + P6Y*0.10 + P6Z*0.99 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*0.99 + P1Z*-0.16 + 6.00, P1X*0.00 + P1Y*0.16 + P1Z*0.99 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*0.99 + P2Z*-0.16 + 6.00, P2X*0.00 + P2Y*0.16 + P2Z*0.99 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*0.99 + P3Z*-0.16 + 6.00, P3X*0.00 + P3Y*0.16 + P3Z*0.99 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*0.99 + P4Z*-0.16 + 6.00, P4X*0.00 + P4Y*0.16 + P4Z*0.99 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*0.99 + P5Z*-0.16 + 6.00, P5X*0.00 + P5Y*0.16 + P5Z*0.99 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*0.99 + P6Z*-0.16 + 6.00, P6X*0.00 + P6Y*0.16 + P6Z*0.99 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*0.98 + P1Z*-0.21 + 3.00, P1X*0.00 + P1Y*0.21 + P1Z*0.98 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*0.98 + P2Z*-0.21 + 3.00, P2X*0.00 + P2Y*0.21 + P2Z*0.98 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*0.98 + P3Z*-0.21 + 3.00, P3X*0.00 + P3Y*0.21 + P3Z*0.98 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*0.98 + P4Z*-0.21 + 3.00, P4X*0.00 + P4Y*0.21 + P4Z*0.98 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*0.98 + P5Z*-0.21 + 3.00, P5X*0.00 + P5Y*0.21 + P5Z*0.98 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*0.98 + P6Z*-0.21 + 3.00, P6X*0.00 + P6Y*0.21 + P6Z*0.98 + 0.00}}, -}; -const int rotatex_entries[] { 0,10 }; -const MovementTable rotatex_table {rotatex_paths, 20, 50, rotatex_entries, 2 }; - -const Locations rotatey_paths[] { - {{P1X*0.97 + P1Y*0.00 + P1Z*0.26 + 0.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*-0.26 + P1Y*0.00 + P1Z*0.97 + 0.00}, - {P2X*0.97 + P2Y*0.00 + P2Z*0.26 + 0.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*-0.26 + P2Y*0.00 + P2Z*0.97 + 0.00}, - {P3X*0.97 + P3Y*0.00 + P3Z*0.26 + 0.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*-0.26 + P3Y*0.00 + P3Z*0.97 + 0.00}, - {P4X*0.97 + P4Y*0.00 + P4Z*0.26 + 0.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*-0.26 + P4Y*0.00 + P4Z*0.97 + 0.00}, - {P5X*0.97 + P5Y*0.00 + P5Z*0.26 + 0.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*-0.26 + P5Y*0.00 + P5Z*0.97 + 0.00}, - {P6X*0.97 + P6Y*0.00 + P6Z*0.26 + 0.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*-0.26 + P6Y*0.00 + P6Z*0.97 + 0.00}}, - {{P1X*0.98 + P1Y*0.00 + P1Z*0.21 + -3.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*-0.21 + P1Y*0.00 + P1Z*0.98 + 0.00}, - {P2X*0.98 + P2Y*0.00 + P2Z*0.21 + -3.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*-0.21 + P2Y*0.00 + P2Z*0.98 + 0.00}, - {P3X*0.98 + P3Y*0.00 + P3Z*0.21 + -3.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*-0.21 + P3Y*0.00 + P3Z*0.98 + 0.00}, - {P4X*0.98 + P4Y*0.00 + P4Z*0.21 + -3.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*-0.21 + P4Y*0.00 + P4Z*0.98 + 0.00}, - {P5X*0.98 + P5Y*0.00 + P5Z*0.21 + -3.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*-0.21 + P5Y*0.00 + P5Z*0.98 + 0.00}, - {P6X*0.98 + P6Y*0.00 + P6Z*0.21 + -3.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*-0.21 + P6Y*0.00 + P6Z*0.98 + 0.00}}, - {{P1X*0.99 + P1Y*0.00 + P1Z*0.16 + -6.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*-0.16 + P1Y*0.00 + P1Z*0.99 + 0.00}, - {P2X*0.99 + P2Y*0.00 + P2Z*0.16 + -6.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*-0.16 + P2Y*0.00 + P2Z*0.99 + 0.00}, - {P3X*0.99 + P3Y*0.00 + P3Z*0.16 + -6.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*-0.16 + P3Y*0.00 + P3Z*0.99 + 0.00}, - {P4X*0.99 + P4Y*0.00 + P4Z*0.16 + -6.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*-0.16 + P4Y*0.00 + P4Z*0.99 + 0.00}, - {P5X*0.99 + P5Y*0.00 + P5Z*0.16 + -6.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*-0.16 + P5Y*0.00 + P5Z*0.99 + 0.00}, - {P6X*0.99 + P6Y*0.00 + P6Z*0.16 + -6.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*-0.16 + P6Y*0.00 + P6Z*0.99 + 0.00}}, - {{P1X*0.99 + P1Y*0.00 + P1Z*0.10 + -9.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*-0.10 + P1Y*0.00 + P1Z*0.99 + 0.00}, - {P2X*0.99 + P2Y*0.00 + P2Z*0.10 + -9.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*-0.10 + P2Y*0.00 + P2Z*0.99 + 0.00}, - {P3X*0.99 + P3Y*0.00 + P3Z*0.10 + -9.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*-0.10 + P3Y*0.00 + P3Z*0.99 + 0.00}, - {P4X*0.99 + P4Y*0.00 + P4Z*0.10 + -9.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*-0.10 + P4Y*0.00 + P4Z*0.99 + 0.00}, - {P5X*0.99 + P5Y*0.00 + P5Z*0.10 + -9.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*-0.10 + P5Y*0.00 + P5Z*0.99 + 0.00}, - {P6X*0.99 + P6Y*0.00 + P6Z*0.10 + -9.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*-0.10 + P6Y*0.00 + P6Z*0.99 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.05 + -12.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*-0.05 + P1Y*0.00 + P1Z*1.00 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.05 + -12.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*-0.05 + P2Y*0.00 + P2Z*1.00 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.05 + -12.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*-0.05 + P3Y*0.00 + P3Z*1.00 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.05 + -12.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*-0.05 + P4Y*0.00 + P4Z*1.00 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.05 + -12.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*-0.05 + P5Y*0.00 + P5Z*1.00 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.05 + -12.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*-0.05 + P6Y*0.00 + P6Z*1.00 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + -15.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*-0.00 + P1Y*0.00 + P1Z*1.00 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + -15.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*-0.00 + P2Y*0.00 + P2Z*1.00 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + -15.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*-0.00 + P3Y*0.00 + P3Z*1.00 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + -15.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*-0.00 + P4Y*0.00 + P4Z*1.00 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + -15.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*-0.00 + P5Y*0.00 + P5Z*1.00 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + -15.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*-0.00 + P6Y*0.00 + P6Z*1.00 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*-0.05 + -12.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*0.05 + P1Y*0.00 + P1Z*1.00 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*-0.05 + -12.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*0.05 + P2Y*0.00 + P2Z*1.00 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*-0.05 + -12.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*0.05 + P3Y*0.00 + P3Z*1.00 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*-0.05 + -12.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*0.05 + P4Y*0.00 + P4Z*1.00 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*-0.05 + -12.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*0.05 + P5Y*0.00 + P5Z*1.00 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*-0.05 + -12.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*0.05 + P6Y*0.00 + P6Z*1.00 + 0.00}}, - {{P1X*0.99 + P1Y*0.00 + P1Z*-0.10 + -9.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*0.10 + P1Y*0.00 + P1Z*0.99 + 0.00}, - {P2X*0.99 + P2Y*0.00 + P2Z*-0.10 + -9.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*0.10 + P2Y*0.00 + P2Z*0.99 + 0.00}, - {P3X*0.99 + P3Y*0.00 + P3Z*-0.10 + -9.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*0.10 + P3Y*0.00 + P3Z*0.99 + 0.00}, - {P4X*0.99 + P4Y*0.00 + P4Z*-0.10 + -9.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*0.10 + P4Y*0.00 + P4Z*0.99 + 0.00}, - {P5X*0.99 + P5Y*0.00 + P5Z*-0.10 + -9.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*0.10 + P5Y*0.00 + P5Z*0.99 + 0.00}, - {P6X*0.99 + P6Y*0.00 + P6Z*-0.10 + -9.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*0.10 + P6Y*0.00 + P6Z*0.99 + 0.00}}, - {{P1X*0.99 + P1Y*0.00 + P1Z*-0.16 + -6.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*0.16 + P1Y*0.00 + P1Z*0.99 + 0.00}, - {P2X*0.99 + P2Y*0.00 + P2Z*-0.16 + -6.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*0.16 + P2Y*0.00 + P2Z*0.99 + 0.00}, - {P3X*0.99 + P3Y*0.00 + P3Z*-0.16 + -6.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*0.16 + P3Y*0.00 + P3Z*0.99 + 0.00}, - {P4X*0.99 + P4Y*0.00 + P4Z*-0.16 + -6.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*0.16 + P4Y*0.00 + P4Z*0.99 + 0.00}, - {P5X*0.99 + P5Y*0.00 + P5Z*-0.16 + -6.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*0.16 + P5Y*0.00 + P5Z*0.99 + 0.00}, - {P6X*0.99 + P6Y*0.00 + P6Z*-0.16 + -6.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*0.16 + P6Y*0.00 + P6Z*0.99 + 0.00}}, - {{P1X*0.98 + P1Y*0.00 + P1Z*-0.21 + -3.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*0.21 + P1Y*0.00 + P1Z*0.98 + 0.00}, - {P2X*0.98 + P2Y*0.00 + P2Z*-0.21 + -3.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*0.21 + P2Y*0.00 + P2Z*0.98 + 0.00}, - {P3X*0.98 + P3Y*0.00 + P3Z*-0.21 + -3.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*0.21 + P3Y*0.00 + P3Z*0.98 + 0.00}, - {P4X*0.98 + P4Y*0.00 + P4Z*-0.21 + -3.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*0.21 + P4Y*0.00 + P4Z*0.98 + 0.00}, - {P5X*0.98 + P5Y*0.00 + P5Z*-0.21 + -3.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*0.21 + P5Y*0.00 + P5Z*0.98 + 0.00}, - {P6X*0.98 + P6Y*0.00 + P6Z*-0.21 + -3.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*0.21 + P6Y*0.00 + P6Z*0.98 + 0.00}}, - {{P1X*0.97 + P1Y*0.00 + P1Z*-0.26 + 0.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*0.26 + P1Y*0.00 + P1Z*0.97 + 0.00}, - {P2X*0.97 + P2Y*0.00 + P2Z*-0.26 + 0.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*0.26 + P2Y*0.00 + P2Z*0.97 + 0.00}, - {P3X*0.97 + P3Y*0.00 + P3Z*-0.26 + 0.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*0.26 + P3Y*0.00 + P3Z*0.97 + 0.00}, - {P4X*0.97 + P4Y*0.00 + P4Z*-0.26 + 0.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*0.26 + P4Y*0.00 + P4Z*0.97 + 0.00}, - {P5X*0.97 + P5Y*0.00 + P5Z*-0.26 + 0.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*0.26 + P5Y*0.00 + P5Z*0.97 + 0.00}, - {P6X*0.97 + P6Y*0.00 + P6Z*-0.26 + 0.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*0.26 + P6Y*0.00 + P6Z*0.97 + 0.00}}, - {{P1X*0.98 + P1Y*0.00 + P1Z*-0.21 + 3.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*0.21 + P1Y*0.00 + P1Z*0.98 + 0.00}, - {P2X*0.98 + P2Y*0.00 + P2Z*-0.21 + 3.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*0.21 + P2Y*0.00 + P2Z*0.98 + 0.00}, - {P3X*0.98 + P3Y*0.00 + P3Z*-0.21 + 3.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*0.21 + P3Y*0.00 + P3Z*0.98 + 0.00}, - {P4X*0.98 + P4Y*0.00 + P4Z*-0.21 + 3.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*0.21 + P4Y*0.00 + P4Z*0.98 + 0.00}, - {P5X*0.98 + P5Y*0.00 + P5Z*-0.21 + 3.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*0.21 + P5Y*0.00 + P5Z*0.98 + 0.00}, - {P6X*0.98 + P6Y*0.00 + P6Z*-0.21 + 3.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*0.21 + P6Y*0.00 + P6Z*0.98 + 0.00}}, - {{P1X*0.99 + P1Y*0.00 + P1Z*-0.16 + 6.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*0.16 + P1Y*0.00 + P1Z*0.99 + 0.00}, - {P2X*0.99 + P2Y*0.00 + P2Z*-0.16 + 6.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*0.16 + P2Y*0.00 + P2Z*0.99 + 0.00}, - {P3X*0.99 + P3Y*0.00 + P3Z*-0.16 + 6.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*0.16 + P3Y*0.00 + P3Z*0.99 + 0.00}, - {P4X*0.99 + P4Y*0.00 + P4Z*-0.16 + 6.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*0.16 + P4Y*0.00 + P4Z*0.99 + 0.00}, - {P5X*0.99 + P5Y*0.00 + P5Z*-0.16 + 6.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*0.16 + P5Y*0.00 + P5Z*0.99 + 0.00}, - {P6X*0.99 + P6Y*0.00 + P6Z*-0.16 + 6.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*0.16 + P6Y*0.00 + P6Z*0.99 + 0.00}}, - {{P1X*0.99 + P1Y*0.00 + P1Z*-0.10 + 9.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*0.10 + P1Y*0.00 + P1Z*0.99 + 0.00}, - {P2X*0.99 + P2Y*0.00 + P2Z*-0.10 + 9.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*0.10 + P2Y*0.00 + P2Z*0.99 + 0.00}, - {P3X*0.99 + P3Y*0.00 + P3Z*-0.10 + 9.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*0.10 + P3Y*0.00 + P3Z*0.99 + 0.00}, - {P4X*0.99 + P4Y*0.00 + P4Z*-0.10 + 9.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*0.10 + P4Y*0.00 + P4Z*0.99 + 0.00}, - {P5X*0.99 + P5Y*0.00 + P5Z*-0.10 + 9.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*0.10 + P5Y*0.00 + P5Z*0.99 + 0.00}, - {P6X*0.99 + P6Y*0.00 + P6Z*-0.10 + 9.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*0.10 + P6Y*0.00 + P6Z*0.99 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*-0.05 + 12.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*0.05 + P1Y*0.00 + P1Z*1.00 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*-0.05 + 12.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*0.05 + P2Y*0.00 + P2Z*1.00 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*-0.05 + 12.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*0.05 + P3Y*0.00 + P3Z*1.00 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*-0.05 + 12.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*0.05 + P4Y*0.00 + P4Z*1.00 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*-0.05 + 12.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*0.05 + P5Y*0.00 + P5Z*1.00 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*-0.05 + 12.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*0.05 + P6Y*0.00 + P6Z*1.00 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 15.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*-0.00 + P1Y*0.00 + P1Z*1.00 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 15.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*-0.00 + P2Y*0.00 + P2Z*1.00 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 15.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*-0.00 + P3Y*0.00 + P3Z*1.00 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 15.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*-0.00 + P4Y*0.00 + P4Z*1.00 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 15.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*-0.00 + P5Y*0.00 + P5Z*1.00 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 15.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*-0.00 + P6Y*0.00 + P6Z*1.00 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.05 + 12.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*-0.05 + P1Y*0.00 + P1Z*1.00 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.05 + 12.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*-0.05 + P2Y*0.00 + P2Z*1.00 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.05 + 12.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*-0.05 + P3Y*0.00 + P3Z*1.00 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.05 + 12.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*-0.05 + P4Y*0.00 + P4Z*1.00 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.05 + 12.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*-0.05 + P5Y*0.00 + P5Z*1.00 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.05 + 12.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*-0.05 + P6Y*0.00 + P6Z*1.00 + 0.00}}, - {{P1X*0.99 + P1Y*0.00 + P1Z*0.10 + 9.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*-0.10 + P1Y*0.00 + P1Z*0.99 + 0.00}, - {P2X*0.99 + P2Y*0.00 + P2Z*0.10 + 9.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*-0.10 + P2Y*0.00 + P2Z*0.99 + 0.00}, - {P3X*0.99 + P3Y*0.00 + P3Z*0.10 + 9.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*-0.10 + P3Y*0.00 + P3Z*0.99 + 0.00}, - {P4X*0.99 + P4Y*0.00 + P4Z*0.10 + 9.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*-0.10 + P4Y*0.00 + P4Z*0.99 + 0.00}, - {P5X*0.99 + P5Y*0.00 + P5Z*0.10 + 9.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*-0.10 + P5Y*0.00 + P5Z*0.99 + 0.00}, - {P6X*0.99 + P6Y*0.00 + P6Z*0.10 + 9.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*-0.10 + P6Y*0.00 + P6Z*0.99 + 0.00}}, - {{P1X*0.99 + P1Y*0.00 + P1Z*0.16 + 6.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*-0.16 + P1Y*0.00 + P1Z*0.99 + 0.00}, - {P2X*0.99 + P2Y*0.00 + P2Z*0.16 + 6.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*-0.16 + P2Y*0.00 + P2Z*0.99 + 0.00}, - {P3X*0.99 + P3Y*0.00 + P3Z*0.16 + 6.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*-0.16 + P3Y*0.00 + P3Z*0.99 + 0.00}, - {P4X*0.99 + P4Y*0.00 + P4Z*0.16 + 6.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*-0.16 + P4Y*0.00 + P4Z*0.99 + 0.00}, - {P5X*0.99 + P5Y*0.00 + P5Z*0.16 + 6.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*-0.16 + P5Y*0.00 + P5Z*0.99 + 0.00}, - {P6X*0.99 + P6Y*0.00 + P6Z*0.16 + 6.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*-0.16 + P6Y*0.00 + P6Z*0.99 + 0.00}}, - {{P1X*0.98 + P1Y*0.00 + P1Z*0.21 + 3.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*-0.21 + P1Y*0.00 + P1Z*0.98 + 0.00}, - {P2X*0.98 + P2Y*0.00 + P2Z*0.21 + 3.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*-0.21 + P2Y*0.00 + P2Z*0.98 + 0.00}, - {P3X*0.98 + P3Y*0.00 + P3Z*0.21 + 3.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*-0.21 + P3Y*0.00 + P3Z*0.98 + 0.00}, - {P4X*0.98 + P4Y*0.00 + P4Z*0.21 + 3.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*-0.21 + P4Y*0.00 + P4Z*0.98 + 0.00}, - {P5X*0.98 + P5Y*0.00 + P5Z*0.21 + 3.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*-0.21 + P5Y*0.00 + P5Z*0.98 + 0.00}, - {P6X*0.98 + P6Y*0.00 + P6Z*0.21 + 3.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*-0.21 + P6Y*0.00 + P6Z*0.98 + 0.00}}, -}; -const int rotatey_entries[] { 0,10 }; -const MovementTable rotatey_table {rotatey_paths, 20, 50, rotatey_entries, 2 }; - -const Locations rotatez_paths[] { - {{P1X*0.98 + P1Y*0.00 + P1Z*0.22 + 0.00, P1X*0.00 + P1Y*1.00 + P1Z*0.00 + 0.00, P1X*-0.22 + P1Y*0.00 + P1Z*0.98 + 0.00}, - {P2X*0.98 + P2Y*0.00 + P2Z*0.22 + 0.00, P2X*0.00 + P2Y*1.00 + P2Z*0.00 + 0.00, P2X*-0.22 + P2Y*0.00 + P2Z*0.98 + 0.00}, - {P3X*0.98 + P3Y*0.00 + P3Z*0.22 + 0.00, P3X*0.00 + P3Y*1.00 + P3Z*0.00 + 0.00, P3X*-0.22 + P3Y*0.00 + P3Z*0.98 + 0.00}, - {P4X*0.98 + P4Y*0.00 + P4Z*0.22 + 0.00, P4X*0.00 + P4Y*1.00 + P4Z*0.00 + 0.00, P4X*-0.22 + P4Y*0.00 + P4Z*0.98 + 0.00}, - {P5X*0.98 + P5Y*0.00 + P5Z*0.22 + 0.00, P5X*0.00 + P5Y*1.00 + P5Z*0.00 + 0.00, P5X*-0.22 + P5Y*0.00 + P5Z*0.98 + 0.00}, - {P6X*0.98 + P6Y*0.00 + P6Z*0.22 + 0.00, P6X*0.00 + P6Y*1.00 + P6Z*0.00 + 0.00, P6X*-0.22 + P6Y*0.00 + P6Z*0.98 + 0.00}}, - {{P1X*0.98 + P1Y*0.01 + P1Z*0.21 + 0.00, P1X*0.00 + P1Y*1.00 + P1Z*-0.07 + 0.00, P1X*-0.21 + P1Y*0.07 + P1Z*0.98 + 0.00}, - {P2X*0.98 + P2Y*0.01 + P2Z*0.21 + 0.00, P2X*0.00 + P2Y*1.00 + P2Z*-0.07 + 0.00, P2X*-0.21 + P2Y*0.07 + P2Z*0.98 + 0.00}, - {P3X*0.98 + P3Y*0.01 + P3Z*0.21 + 0.00, P3X*0.00 + P3Y*1.00 + P3Z*-0.07 + 0.00, P3X*-0.21 + P3Y*0.07 + P3Z*0.98 + 0.00}, - {P4X*0.98 + P4Y*0.01 + P4Z*0.21 + 0.00, P4X*0.00 + P4Y*1.00 + P4Z*-0.07 + 0.00, P4X*-0.21 + P4Y*0.07 + P4Z*0.98 + 0.00}, - {P5X*0.98 + P5Y*0.01 + P5Z*0.21 + 0.00, P5X*0.00 + P5Y*1.00 + P5Z*-0.07 + 0.00, P5X*-0.21 + P5Y*0.07 + P5Z*0.98 + 0.00}, - {P6X*0.98 + P6Y*0.01 + P6Z*0.21 + 0.00, P6X*0.00 + P6Y*1.00 + P6Z*-0.07 + 0.00, P6X*-0.21 + P6Y*0.07 + P6Z*0.98 + 0.00}}, - {{P1X*0.98 + P1Y*0.02 + P1Z*0.18 + 0.00, P1X*0.00 + P1Y*0.99 + P1Z*-0.13 + 0.00, P1X*-0.18 + P1Y*0.13 + P1Z*0.98 + 0.00}, - {P2X*0.98 + P2Y*0.02 + P2Z*0.18 + 0.00, P2X*0.00 + P2Y*0.99 + P2Z*-0.13 + 0.00, P2X*-0.18 + P2Y*0.13 + P2Z*0.98 + 0.00}, - {P3X*0.98 + P3Y*0.02 + P3Z*0.18 + 0.00, P3X*0.00 + P3Y*0.99 + P3Z*-0.13 + 0.00, P3X*-0.18 + P3Y*0.13 + P3Z*0.98 + 0.00}, - {P4X*0.98 + P4Y*0.02 + P4Z*0.18 + 0.00, P4X*0.00 + P4Y*0.99 + P4Z*-0.13 + 0.00, P4X*-0.18 + P4Y*0.13 + P4Z*0.98 + 0.00}, - {P5X*0.98 + P5Y*0.02 + P5Z*0.18 + 0.00, P5X*0.00 + P5Y*0.99 + P5Z*-0.13 + 0.00, P5X*-0.18 + P5Y*0.13 + P5Z*0.98 + 0.00}, - {P6X*0.98 + P6Y*0.02 + P6Z*0.18 + 0.00, P6X*0.00 + P6Y*0.99 + P6Z*-0.13 + 0.00, P6X*-0.18 + P6Y*0.13 + P6Z*0.98 + 0.00}}, - {{P1X*0.99 + P1Y*0.02 + P1Z*0.13 + 0.00, P1X*0.00 + P1Y*0.98 + P1Z*-0.18 + 0.00, P1X*-0.13 + P1Y*0.18 + P1Z*0.98 + 0.00}, - {P2X*0.99 + P2Y*0.02 + P2Z*0.13 + 0.00, P2X*0.00 + P2Y*0.98 + P2Z*-0.18 + 0.00, P2X*-0.13 + P2Y*0.18 + P2Z*0.98 + 0.00}, - {P3X*0.99 + P3Y*0.02 + P3Z*0.13 + 0.00, P3X*0.00 + P3Y*0.98 + P3Z*-0.18 + 0.00, P3X*-0.13 + P3Y*0.18 + P3Z*0.98 + 0.00}, - {P4X*0.99 + P4Y*0.02 + P4Z*0.13 + 0.00, P4X*0.00 + P4Y*0.98 + P4Z*-0.18 + 0.00, P4X*-0.13 + P4Y*0.18 + P4Z*0.98 + 0.00}, - {P5X*0.99 + P5Y*0.02 + P5Z*0.13 + 0.00, P5X*0.00 + P5Y*0.98 + P5Z*-0.18 + 0.00, P5X*-0.13 + P5Y*0.18 + P5Z*0.98 + 0.00}, - {P6X*0.99 + P6Y*0.02 + P6Z*0.13 + 0.00, P6X*0.00 + P6Y*0.98 + P6Z*-0.18 + 0.00, P6X*-0.13 + P6Y*0.18 + P6Z*0.98 + 0.00}}, - {{P1X*1.00 + P1Y*0.01 + P1Z*0.07 + 0.00, P1X*0.00 + P1Y*0.98 + P1Z*-0.21 + 0.00, P1X*-0.07 + P1Y*0.21 + P1Z*0.98 + 0.00}, - {P2X*1.00 + P2Y*0.01 + P2Z*0.07 + 0.00, P2X*0.00 + P2Y*0.98 + P2Z*-0.21 + 0.00, P2X*-0.07 + P2Y*0.21 + P2Z*0.98 + 0.00}, - {P3X*1.00 + P3Y*0.01 + P3Z*0.07 + 0.00, P3X*0.00 + P3Y*0.98 + P3Z*-0.21 + 0.00, P3X*-0.07 + P3Y*0.21 + P3Z*0.98 + 0.00}, - {P4X*1.00 + P4Y*0.01 + P4Z*0.07 + 0.00, P4X*0.00 + P4Y*0.98 + P4Z*-0.21 + 0.00, P4X*-0.07 + P4Y*0.21 + P4Z*0.98 + 0.00}, - {P5X*1.00 + P5Y*0.01 + P5Z*0.07 + 0.00, P5X*0.00 + P5Y*0.98 + P5Z*-0.21 + 0.00, P5X*-0.07 + P5Y*0.21 + P5Z*0.98 + 0.00}, - {P6X*1.00 + P6Y*0.01 + P6Z*0.07 + 0.00, P6X*0.00 + P6Y*0.98 + P6Z*-0.21 + 0.00, P6X*-0.07 + P6Y*0.21 + P6Z*0.98 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*0.98 + P1Z*-0.22 + 0.00, P1X*-0.00 + P1Y*0.22 + P1Z*0.98 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*0.98 + P2Z*-0.22 + 0.00, P2X*-0.00 + P2Y*0.22 + P2Z*0.98 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*0.98 + P3Z*-0.22 + 0.00, P3X*-0.00 + P3Y*0.22 + P3Z*0.98 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*0.98 + P4Z*-0.22 + 0.00, P4X*-0.00 + P4Y*0.22 + P4Z*0.98 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*0.98 + P5Z*-0.22 + 0.00, P5X*-0.00 + P5Y*0.22 + P5Z*0.98 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*0.98 + P6Z*-0.22 + 0.00, P6X*-0.00 + P6Y*0.22 + P6Z*0.98 + 0.00}}, - {{P1X*1.00 + P1Y*-0.01 + P1Z*-0.07 + 0.00, P1X*0.00 + P1Y*0.98 + P1Z*-0.21 + 0.00, P1X*0.07 + P1Y*0.21 + P1Z*0.98 + 0.00}, - {P2X*1.00 + P2Y*-0.01 + P2Z*-0.07 + 0.00, P2X*0.00 + P2Y*0.98 + P2Z*-0.21 + 0.00, P2X*0.07 + P2Y*0.21 + P2Z*0.98 + 0.00}, - {P3X*1.00 + P3Y*-0.01 + P3Z*-0.07 + 0.00, P3X*0.00 + P3Y*0.98 + P3Z*-0.21 + 0.00, P3X*0.07 + P3Y*0.21 + P3Z*0.98 + 0.00}, - {P4X*1.00 + P4Y*-0.01 + P4Z*-0.07 + 0.00, P4X*0.00 + P4Y*0.98 + P4Z*-0.21 + 0.00, P4X*0.07 + P4Y*0.21 + P4Z*0.98 + 0.00}, - {P5X*1.00 + P5Y*-0.01 + P5Z*-0.07 + 0.00, P5X*0.00 + P5Y*0.98 + P5Z*-0.21 + 0.00, P5X*0.07 + P5Y*0.21 + P5Z*0.98 + 0.00}, - {P6X*1.00 + P6Y*-0.01 + P6Z*-0.07 + 0.00, P6X*0.00 + P6Y*0.98 + P6Z*-0.21 + 0.00, P6X*0.07 + P6Y*0.21 + P6Z*0.98 + 0.00}}, - {{P1X*0.99 + P1Y*-0.02 + P1Z*-0.13 + 0.00, P1X*0.00 + P1Y*0.98 + P1Z*-0.18 + 0.00, P1X*0.13 + P1Y*0.18 + P1Z*0.98 + 0.00}, - {P2X*0.99 + P2Y*-0.02 + P2Z*-0.13 + 0.00, P2X*0.00 + P2Y*0.98 + P2Z*-0.18 + 0.00, P2X*0.13 + P2Y*0.18 + P2Z*0.98 + 0.00}, - {P3X*0.99 + P3Y*-0.02 + P3Z*-0.13 + 0.00, P3X*0.00 + P3Y*0.98 + P3Z*-0.18 + 0.00, P3X*0.13 + P3Y*0.18 + P3Z*0.98 + 0.00}, - {P4X*0.99 + P4Y*-0.02 + P4Z*-0.13 + 0.00, P4X*0.00 + P4Y*0.98 + P4Z*-0.18 + 0.00, P4X*0.13 + P4Y*0.18 + P4Z*0.98 + 0.00}, - {P5X*0.99 + P5Y*-0.02 + P5Z*-0.13 + 0.00, P5X*0.00 + P5Y*0.98 + P5Z*-0.18 + 0.00, P5X*0.13 + P5Y*0.18 + P5Z*0.98 + 0.00}, - {P6X*0.99 + P6Y*-0.02 + P6Z*-0.13 + 0.00, P6X*0.00 + P6Y*0.98 + P6Z*-0.18 + 0.00, P6X*0.13 + P6Y*0.18 + P6Z*0.98 + 0.00}}, - {{P1X*0.98 + P1Y*-0.02 + P1Z*-0.18 + 0.00, P1X*0.00 + P1Y*0.99 + P1Z*-0.13 + 0.00, P1X*0.18 + P1Y*0.13 + P1Z*0.98 + 0.00}, - {P2X*0.98 + P2Y*-0.02 + P2Z*-0.18 + 0.00, P2X*0.00 + P2Y*0.99 + P2Z*-0.13 + 0.00, P2X*0.18 + P2Y*0.13 + P2Z*0.98 + 0.00}, - {P3X*0.98 + P3Y*-0.02 + P3Z*-0.18 + 0.00, P3X*0.00 + P3Y*0.99 + P3Z*-0.13 + 0.00, P3X*0.18 + P3Y*0.13 + P3Z*0.98 + 0.00}, - {P4X*0.98 + P4Y*-0.02 + P4Z*-0.18 + 0.00, P4X*0.00 + P4Y*0.99 + P4Z*-0.13 + 0.00, P4X*0.18 + P4Y*0.13 + P4Z*0.98 + 0.00}, - {P5X*0.98 + P5Y*-0.02 + P5Z*-0.18 + 0.00, P5X*0.00 + P5Y*0.99 + P5Z*-0.13 + 0.00, P5X*0.18 + P5Y*0.13 + P5Z*0.98 + 0.00}, - {P6X*0.98 + P6Y*-0.02 + P6Z*-0.18 + 0.00, P6X*0.00 + P6Y*0.99 + P6Z*-0.13 + 0.00, P6X*0.18 + P6Y*0.13 + P6Z*0.98 + 0.00}}, - {{P1X*0.98 + P1Y*-0.01 + P1Z*-0.21 + 0.00, P1X*0.00 + P1Y*1.00 + P1Z*-0.07 + 0.00, P1X*0.21 + P1Y*0.07 + P1Z*0.98 + 0.00}, - {P2X*0.98 + P2Y*-0.01 + P2Z*-0.21 + 0.00, P2X*0.00 + P2Y*1.00 + P2Z*-0.07 + 0.00, P2X*0.21 + P2Y*0.07 + P2Z*0.98 + 0.00}, - {P3X*0.98 + P3Y*-0.01 + P3Z*-0.21 + 0.00, P3X*0.00 + P3Y*1.00 + P3Z*-0.07 + 0.00, P3X*0.21 + P3Y*0.07 + P3Z*0.98 + 0.00}, - {P4X*0.98 + P4Y*-0.01 + P4Z*-0.21 + 0.00, P4X*0.00 + P4Y*1.00 + P4Z*-0.07 + 0.00, P4X*0.21 + P4Y*0.07 + P4Z*0.98 + 0.00}, - {P5X*0.98 + P5Y*-0.01 + P5Z*-0.21 + 0.00, P5X*0.00 + P5Y*1.00 + P5Z*-0.07 + 0.00, P5X*0.21 + P5Y*0.07 + P5Z*0.98 + 0.00}, - {P6X*0.98 + P6Y*-0.01 + P6Z*-0.21 + 0.00, P6X*0.00 + P6Y*1.00 + P6Z*-0.07 + 0.00, P6X*0.21 + P6Y*0.07 + P6Z*0.98 + 0.00}}, - {{P1X*0.98 + P1Y*-0.00 + P1Z*-0.22 + 0.00, P1X*0.00 + P1Y*1.00 + P1Z*-0.00 + 0.00, P1X*0.22 + P1Y*0.00 + P1Z*0.98 + 0.00}, - {P2X*0.98 + P2Y*-0.00 + P2Z*-0.22 + 0.00, P2X*0.00 + P2Y*1.00 + P2Z*-0.00 + 0.00, P2X*0.22 + P2Y*0.00 + P2Z*0.98 + 0.00}, - {P3X*0.98 + P3Y*-0.00 + P3Z*-0.22 + 0.00, P3X*0.00 + P3Y*1.00 + P3Z*-0.00 + 0.00, P3X*0.22 + P3Y*0.00 + P3Z*0.98 + 0.00}, - {P4X*0.98 + P4Y*-0.00 + P4Z*-0.22 + 0.00, P4X*0.00 + P4Y*1.00 + P4Z*-0.00 + 0.00, P4X*0.22 + P4Y*0.00 + P4Z*0.98 + 0.00}, - {P5X*0.98 + P5Y*-0.00 + P5Z*-0.22 + 0.00, P5X*0.00 + P5Y*1.00 + P5Z*-0.00 + 0.00, P5X*0.22 + P5Y*0.00 + P5Z*0.98 + 0.00}, - {P6X*0.98 + P6Y*-0.00 + P6Z*-0.22 + 0.00, P6X*0.00 + P6Y*1.00 + P6Z*-0.00 + 0.00, P6X*0.22 + P6Y*0.00 + P6Z*0.98 + 0.00}}, - {{P1X*0.98 + P1Y*0.01 + P1Z*-0.21 + 0.00, P1X*0.00 + P1Y*1.00 + P1Z*0.07 + 0.00, P1X*0.21 + P1Y*-0.07 + P1Z*0.98 + 0.00}, - {P2X*0.98 + P2Y*0.01 + P2Z*-0.21 + 0.00, P2X*0.00 + P2Y*1.00 + P2Z*0.07 + 0.00, P2X*0.21 + P2Y*-0.07 + P2Z*0.98 + 0.00}, - {P3X*0.98 + P3Y*0.01 + P3Z*-0.21 + 0.00, P3X*0.00 + P3Y*1.00 + P3Z*0.07 + 0.00, P3X*0.21 + P3Y*-0.07 + P3Z*0.98 + 0.00}, - {P4X*0.98 + P4Y*0.01 + P4Z*-0.21 + 0.00, P4X*0.00 + P4Y*1.00 + P4Z*0.07 + 0.00, P4X*0.21 + P4Y*-0.07 + P4Z*0.98 + 0.00}, - {P5X*0.98 + P5Y*0.01 + P5Z*-0.21 + 0.00, P5X*0.00 + P5Y*1.00 + P5Z*0.07 + 0.00, P5X*0.21 + P5Y*-0.07 + P5Z*0.98 + 0.00}, - {P6X*0.98 + P6Y*0.01 + P6Z*-0.21 + 0.00, P6X*0.00 + P6Y*1.00 + P6Z*0.07 + 0.00, P6X*0.21 + P6Y*-0.07 + P6Z*0.98 + 0.00}}, - {{P1X*0.98 + P1Y*0.02 + P1Z*-0.18 + 0.00, P1X*0.00 + P1Y*0.99 + P1Z*0.13 + 0.00, P1X*0.18 + P1Y*-0.13 + P1Z*0.98 + 0.00}, - {P2X*0.98 + P2Y*0.02 + P2Z*-0.18 + 0.00, P2X*0.00 + P2Y*0.99 + P2Z*0.13 + 0.00, P2X*0.18 + P2Y*-0.13 + P2Z*0.98 + 0.00}, - {P3X*0.98 + P3Y*0.02 + P3Z*-0.18 + 0.00, P3X*0.00 + P3Y*0.99 + P3Z*0.13 + 0.00, P3X*0.18 + P3Y*-0.13 + P3Z*0.98 + 0.00}, - {P4X*0.98 + P4Y*0.02 + P4Z*-0.18 + 0.00, P4X*0.00 + P4Y*0.99 + P4Z*0.13 + 0.00, P4X*0.18 + P4Y*-0.13 + P4Z*0.98 + 0.00}, - {P5X*0.98 + P5Y*0.02 + P5Z*-0.18 + 0.00, P5X*0.00 + P5Y*0.99 + P5Z*0.13 + 0.00, P5X*0.18 + P5Y*-0.13 + P5Z*0.98 + 0.00}, - {P6X*0.98 + P6Y*0.02 + P6Z*-0.18 + 0.00, P6X*0.00 + P6Y*0.99 + P6Z*0.13 + 0.00, P6X*0.18 + P6Y*-0.13 + P6Z*0.98 + 0.00}}, - {{P1X*0.99 + P1Y*0.02 + P1Z*-0.13 + 0.00, P1X*0.00 + P1Y*0.98 + P1Z*0.18 + 0.00, P1X*0.13 + P1Y*-0.18 + P1Z*0.98 + 0.00}, - {P2X*0.99 + P2Y*0.02 + P2Z*-0.13 + 0.00, P2X*0.00 + P2Y*0.98 + P2Z*0.18 + 0.00, P2X*0.13 + P2Y*-0.18 + P2Z*0.98 + 0.00}, - {P3X*0.99 + P3Y*0.02 + P3Z*-0.13 + 0.00, P3X*0.00 + P3Y*0.98 + P3Z*0.18 + 0.00, P3X*0.13 + P3Y*-0.18 + P3Z*0.98 + 0.00}, - {P4X*0.99 + P4Y*0.02 + P4Z*-0.13 + 0.00, P4X*0.00 + P4Y*0.98 + P4Z*0.18 + 0.00, P4X*0.13 + P4Y*-0.18 + P4Z*0.98 + 0.00}, - {P5X*0.99 + P5Y*0.02 + P5Z*-0.13 + 0.00, P5X*0.00 + P5Y*0.98 + P5Z*0.18 + 0.00, P5X*0.13 + P5Y*-0.18 + P5Z*0.98 + 0.00}, - {P6X*0.99 + P6Y*0.02 + P6Z*-0.13 + 0.00, P6X*0.00 + P6Y*0.98 + P6Z*0.18 + 0.00, P6X*0.13 + P6Y*-0.18 + P6Z*0.98 + 0.00}}, - {{P1X*1.00 + P1Y*0.01 + P1Z*-0.07 + 0.00, P1X*0.00 + P1Y*0.98 + P1Z*0.21 + 0.00, P1X*0.07 + P1Y*-0.21 + P1Z*0.98 + 0.00}, - {P2X*1.00 + P2Y*0.01 + P2Z*-0.07 + 0.00, P2X*0.00 + P2Y*0.98 + P2Z*0.21 + 0.00, P2X*0.07 + P2Y*-0.21 + P2Z*0.98 + 0.00}, - {P3X*1.00 + P3Y*0.01 + P3Z*-0.07 + 0.00, P3X*0.00 + P3Y*0.98 + P3Z*0.21 + 0.00, P3X*0.07 + P3Y*-0.21 + P3Z*0.98 + 0.00}, - {P4X*1.00 + P4Y*0.01 + P4Z*-0.07 + 0.00, P4X*0.00 + P4Y*0.98 + P4Z*0.21 + 0.00, P4X*0.07 + P4Y*-0.21 + P4Z*0.98 + 0.00}, - {P5X*1.00 + P5Y*0.01 + P5Z*-0.07 + 0.00, P5X*0.00 + P5Y*0.98 + P5Z*0.21 + 0.00, P5X*0.07 + P5Y*-0.21 + P5Z*0.98 + 0.00}, - {P6X*1.00 + P6Y*0.01 + P6Z*-0.07 + 0.00, P6X*0.00 + P6Y*0.98 + P6Z*0.21 + 0.00, P6X*0.07 + P6Y*-0.21 + P6Z*0.98 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*-0.00 + 0.00, P1X*0.00 + P1Y*0.98 + P1Z*0.22 + 0.00, P1X*0.00 + P1Y*-0.22 + P1Z*0.98 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*-0.00 + 0.00, P2X*0.00 + P2Y*0.98 + P2Z*0.22 + 0.00, P2X*0.00 + P2Y*-0.22 + P2Z*0.98 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*-0.00 + 0.00, P3X*0.00 + P3Y*0.98 + P3Z*0.22 + 0.00, P3X*0.00 + P3Y*-0.22 + P3Z*0.98 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*-0.00 + 0.00, P4X*0.00 + P4Y*0.98 + P4Z*0.22 + 0.00, P4X*0.00 + P4Y*-0.22 + P4Z*0.98 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*-0.00 + 0.00, P5X*0.00 + P5Y*0.98 + P5Z*0.22 + 0.00, P5X*0.00 + P5Y*-0.22 + P5Z*0.98 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*-0.00 + 0.00, P6X*0.00 + P6Y*0.98 + P6Z*0.22 + 0.00, P6X*0.00 + P6Y*-0.22 + P6Z*0.98 + 0.00}}, - {{P1X*1.00 + P1Y*-0.01 + P1Z*0.07 + 0.00, P1X*0.00 + P1Y*0.98 + P1Z*0.21 + 0.00, P1X*-0.07 + P1Y*-0.21 + P1Z*0.98 + 0.00}, - {P2X*1.00 + P2Y*-0.01 + P2Z*0.07 + 0.00, P2X*0.00 + P2Y*0.98 + P2Z*0.21 + 0.00, P2X*-0.07 + P2Y*-0.21 + P2Z*0.98 + 0.00}, - {P3X*1.00 + P3Y*-0.01 + P3Z*0.07 + 0.00, P3X*0.00 + P3Y*0.98 + P3Z*0.21 + 0.00, P3X*-0.07 + P3Y*-0.21 + P3Z*0.98 + 0.00}, - {P4X*1.00 + P4Y*-0.01 + P4Z*0.07 + 0.00, P4X*0.00 + P4Y*0.98 + P4Z*0.21 + 0.00, P4X*-0.07 + P4Y*-0.21 + P4Z*0.98 + 0.00}, - {P5X*1.00 + P5Y*-0.01 + P5Z*0.07 + 0.00, P5X*0.00 + P5Y*0.98 + P5Z*0.21 + 0.00, P5X*-0.07 + P5Y*-0.21 + P5Z*0.98 + 0.00}, - {P6X*1.00 + P6Y*-0.01 + P6Z*0.07 + 0.00, P6X*0.00 + P6Y*0.98 + P6Z*0.21 + 0.00, P6X*-0.07 + P6Y*-0.21 + P6Z*0.98 + 0.00}}, - {{P1X*0.99 + P1Y*-0.02 + P1Z*0.13 + 0.00, P1X*0.00 + P1Y*0.98 + P1Z*0.18 + 0.00, P1X*-0.13 + P1Y*-0.18 + P1Z*0.98 + 0.00}, - {P2X*0.99 + P2Y*-0.02 + P2Z*0.13 + 0.00, P2X*0.00 + P2Y*0.98 + P2Z*0.18 + 0.00, P2X*-0.13 + P2Y*-0.18 + P2Z*0.98 + 0.00}, - {P3X*0.99 + P3Y*-0.02 + P3Z*0.13 + 0.00, P3X*0.00 + P3Y*0.98 + P3Z*0.18 + 0.00, P3X*-0.13 + P3Y*-0.18 + P3Z*0.98 + 0.00}, - {P4X*0.99 + P4Y*-0.02 + P4Z*0.13 + 0.00, P4X*0.00 + P4Y*0.98 + P4Z*0.18 + 0.00, P4X*-0.13 + P4Y*-0.18 + P4Z*0.98 + 0.00}, - {P5X*0.99 + P5Y*-0.02 + P5Z*0.13 + 0.00, P5X*0.00 + P5Y*0.98 + P5Z*0.18 + 0.00, P5X*-0.13 + P5Y*-0.18 + P5Z*0.98 + 0.00}, - {P6X*0.99 + P6Y*-0.02 + P6Z*0.13 + 0.00, P6X*0.00 + P6Y*0.98 + P6Z*0.18 + 0.00, P6X*-0.13 + P6Y*-0.18 + P6Z*0.98 + 0.00}}, - {{P1X*0.98 + P1Y*-0.02 + P1Z*0.18 + 0.00, P1X*0.00 + P1Y*0.99 + P1Z*0.13 + 0.00, P1X*-0.18 + P1Y*-0.13 + P1Z*0.98 + 0.00}, - {P2X*0.98 + P2Y*-0.02 + P2Z*0.18 + 0.00, P2X*0.00 + P2Y*0.99 + P2Z*0.13 + 0.00, P2X*-0.18 + P2Y*-0.13 + P2Z*0.98 + 0.00}, - {P3X*0.98 + P3Y*-0.02 + P3Z*0.18 + 0.00, P3X*0.00 + P3Y*0.99 + P3Z*0.13 + 0.00, P3X*-0.18 + P3Y*-0.13 + P3Z*0.98 + 0.00}, - {P4X*0.98 + P4Y*-0.02 + P4Z*0.18 + 0.00, P4X*0.00 + P4Y*0.99 + P4Z*0.13 + 0.00, P4X*-0.18 + P4Y*-0.13 + P4Z*0.98 + 0.00}, - {P5X*0.98 + P5Y*-0.02 + P5Z*0.18 + 0.00, P5X*0.00 + P5Y*0.99 + P5Z*0.13 + 0.00, P5X*-0.18 + P5Y*-0.13 + P5Z*0.98 + 0.00}, - {P6X*0.98 + P6Y*-0.02 + P6Z*0.18 + 0.00, P6X*0.00 + P6Y*0.99 + P6Z*0.13 + 0.00, P6X*-0.18 + P6Y*-0.13 + P6Z*0.98 + 0.00}}, - {{P1X*0.98 + P1Y*-0.01 + P1Z*0.21 + 0.00, P1X*0.00 + P1Y*1.00 + P1Z*0.07 + 0.00, P1X*-0.21 + P1Y*-0.07 + P1Z*0.98 + 0.00}, - {P2X*0.98 + P2Y*-0.01 + P2Z*0.21 + 0.00, P2X*0.00 + P2Y*1.00 + P2Z*0.07 + 0.00, P2X*-0.21 + P2Y*-0.07 + P2Z*0.98 + 0.00}, - {P3X*0.98 + P3Y*-0.01 + P3Z*0.21 + 0.00, P3X*0.00 + P3Y*1.00 + P3Z*0.07 + 0.00, P3X*-0.21 + P3Y*-0.07 + P3Z*0.98 + 0.00}, - {P4X*0.98 + P4Y*-0.01 + P4Z*0.21 + 0.00, P4X*0.00 + P4Y*1.00 + P4Z*0.07 + 0.00, P4X*-0.21 + P4Y*-0.07 + P4Z*0.98 + 0.00}, - {P5X*0.98 + P5Y*-0.01 + P5Z*0.21 + 0.00, P5X*0.00 + P5Y*1.00 + P5Z*0.07 + 0.00, P5X*-0.21 + P5Y*-0.07 + P5Z*0.98 + 0.00}, - {P6X*0.98 + P6Y*-0.01 + P6Z*0.21 + 0.00, P6X*0.00 + P6Y*1.00 + P6Z*0.07 + 0.00, P6X*-0.21 + P6Y*-0.07 + P6Z*0.98 + 0.00}}, -}; -const int rotatez_entries[] { 0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19 }; -const MovementTable rotatez_table {rotatez_paths, 20, 50, rotatez_entries, 20 }; - -const Locations shiftleft_paths[] { - {{P1X+(-0.00), P1Y+(0.00), P1Z+(25.00)}, {P2X+(0.00), P2Y+(0.00), P2Z+(0.00)}, {P3X+(-0.00), P3Y+(0.00), P3Z+(25.00)}, {P4X+(0.00), P4Y+(0.00), P4Z+(0.00)}, {P5X+(-0.00), P5Y+(0.00), P5Z+(25.00)}, {P6X+(0.00), P6Y+(0.00), P6Z+(0.00)}}, - {{P1X+(-7.73), P1Y+(0.00), P1Z+(23.78)}, {P2X+(5.00), P2Y+(-0.00), P2Z+(0.00)}, {P3X+(-7.73), P3Y+(0.00), P3Z+(23.78)}, {P4X+(5.00), P4Y+(-0.00), P4Z+(0.00)}, {P5X+(-7.73), P5Y+(0.00), P5Z+(23.78)}, {P6X+(5.00), P6Y+(-0.00), P6Z+(0.00)}}, - {{P1X+(-14.69), P1Y+(0.00), P1Z+(20.23)}, {P2X+(10.00), P2Y+(-0.00), P2Z+(0.00)}, {P3X+(-14.69), P3Y+(0.00), P3Z+(20.23)}, {P4X+(10.00), P4Y+(-0.00), P4Z+(0.00)}, {P5X+(-14.69), P5Y+(0.00), P5Z+(20.23)}, {P6X+(10.00), P6Y+(-0.00), P6Z+(0.00)}}, - {{P1X+(-20.23), P1Y+(0.00), P1Z+(14.69)}, {P2X+(15.00), P2Y+(-0.00), P2Z+(0.00)}, {P3X+(-20.23), P3Y+(0.00), P3Z+(14.69)}, {P4X+(15.00), P4Y+(-0.00), P4Z+(0.00)}, {P5X+(-20.23), P5Y+(0.00), P5Z+(14.69)}, {P6X+(15.00), P6Y+(-0.00), P6Z+(0.00)}}, - {{P1X+(-23.78), P1Y+(0.00), P1Z+(7.73)}, {P2X+(20.00), P2Y+(-0.00), P2Z+(0.00)}, {P3X+(-23.78), P3Y+(0.00), P3Z+(7.73)}, {P4X+(20.00), P4Y+(-0.00), P4Z+(0.00)}, {P5X+(-23.78), P5Y+(0.00), P5Z+(7.73)}, {P6X+(20.00), P6Y+(-0.00), P6Z+(0.00)}}, - {{P1X+(-25.00), P1Y+(0.00), P1Z+(0.00)}, {P2X+(25.00), P2Y+(-0.00), P2Z+(0.00)}, {P3X+(-25.00), P3Y+(0.00), P3Z+(0.00)}, {P4X+(25.00), P4Y+(-0.00), P4Z+(0.00)}, {P5X+(-25.00), P5Y+(0.00), P5Z+(0.00)}, {P6X+(25.00), P6Y+(-0.00), P6Z+(0.00)}}, - {{P1X+(-20.00), P1Y+(0.00), P1Z+(0.00)}, {P2X+(23.78), P2Y+(-0.00), P2Z+(7.73)}, {P3X+(-20.00), P3Y+(0.00), P3Z+(0.00)}, {P4X+(23.78), P4Y+(-0.00), P4Z+(7.73)}, {P5X+(-20.00), P5Y+(0.00), P5Z+(0.00)}, {P6X+(23.78), P6Y+(-0.00), P6Z+(7.73)}}, - {{P1X+(-15.00), P1Y+(0.00), P1Z+(0.00)}, {P2X+(20.23), P2Y+(-0.00), P2Z+(14.69)}, {P3X+(-15.00), P3Y+(0.00), P3Z+(0.00)}, {P4X+(20.23), P4Y+(-0.00), P4Z+(14.69)}, {P5X+(-15.00), P5Y+(0.00), P5Z+(0.00)}, {P6X+(20.23), P6Y+(-0.00), P6Z+(14.69)}}, - {{P1X+(-10.00), P1Y+(0.00), P1Z+(0.00)}, {P2X+(14.69), P2Y+(-0.00), P2Z+(20.23)}, {P3X+(-10.00), P3Y+(0.00), P3Z+(0.00)}, {P4X+(14.69), P4Y+(-0.00), P4Z+(20.23)}, {P5X+(-10.00), P5Y+(0.00), P5Z+(0.00)}, {P6X+(14.69), P6Y+(-0.00), P6Z+(20.23)}}, - {{P1X+(-5.00), P1Y+(0.00), P1Z+(0.00)}, {P2X+(7.73), P2Y+(-0.00), P2Z+(23.78)}, {P3X+(-5.00), P3Y+(0.00), P3Z+(0.00)}, {P4X+(7.73), P4Y+(-0.00), P4Z+(23.78)}, {P5X+(-5.00), P5Y+(0.00), P5Z+(0.00)}, {P6X+(7.73), P6Y+(-0.00), P6Z+(23.78)}}, - {{P1X+(0.00), P1Y+(0.00), P1Z+(0.00)}, {P2X+(-0.00), P2Y+(0.00), P2Z+(25.00)}, {P3X+(0.00), P3Y+(0.00), P3Z+(0.00)}, {P4X+(-0.00), P4Y+(0.00), P4Z+(25.00)}, {P5X+(0.00), P5Y+(0.00), P5Z+(0.00)}, {P6X+(-0.00), P6Y+(0.00), P6Z+(25.00)}}, - {{P1X+(5.00), P1Y+(-0.00), P1Z+(0.00)}, {P2X+(-7.73), P2Y+(0.00), P2Z+(23.78)}, {P3X+(5.00), P3Y+(-0.00), P3Z+(0.00)}, {P4X+(-7.73), P4Y+(0.00), P4Z+(23.78)}, {P5X+(5.00), P5Y+(-0.00), P5Z+(0.00)}, {P6X+(-7.73), P6Y+(0.00), P6Z+(23.78)}}, - {{P1X+(10.00), P1Y+(-0.00), P1Z+(0.00)}, {P2X+(-14.69), P2Y+(0.00), P2Z+(20.23)}, {P3X+(10.00), P3Y+(-0.00), P3Z+(0.00)}, {P4X+(-14.69), P4Y+(0.00), P4Z+(20.23)}, {P5X+(10.00), P5Y+(-0.00), P5Z+(0.00)}, {P6X+(-14.69), P6Y+(0.00), P6Z+(20.23)}}, - {{P1X+(15.00), P1Y+(-0.00), P1Z+(0.00)}, {P2X+(-20.23), P2Y+(0.00), P2Z+(14.69)}, {P3X+(15.00), P3Y+(-0.00), P3Z+(0.00)}, {P4X+(-20.23), P4Y+(0.00), P4Z+(14.69)}, {P5X+(15.00), P5Y+(-0.00), P5Z+(0.00)}, {P6X+(-20.23), P6Y+(0.00), P6Z+(14.69)}}, - {{P1X+(20.00), P1Y+(-0.00), P1Z+(0.00)}, {P2X+(-23.78), P2Y+(0.00), P2Z+(7.73)}, {P3X+(20.00), P3Y+(-0.00), P3Z+(0.00)}, {P4X+(-23.78), P4Y+(0.00), P4Z+(7.73)}, {P5X+(20.00), P5Y+(-0.00), P5Z+(0.00)}, {P6X+(-23.78), P6Y+(0.00), P6Z+(7.73)}}, - {{P1X+(25.00), P1Y+(-0.00), P1Z+(0.00)}, {P2X+(-25.00), P2Y+(0.00), P2Z+(0.00)}, {P3X+(25.00), P3Y+(-0.00), P3Z+(0.00)}, {P4X+(-25.00), P4Y+(0.00), P4Z+(0.00)}, {P5X+(25.00), P5Y+(-0.00), P5Z+(0.00)}, {P6X+(-25.00), P6Y+(0.00), P6Z+(0.00)}}, - {{P1X+(23.78), P1Y+(-0.00), P1Z+(7.73)}, {P2X+(-20.00), P2Y+(0.00), P2Z+(0.00)}, {P3X+(23.78), P3Y+(-0.00), P3Z+(7.73)}, {P4X+(-20.00), P4Y+(0.00), P4Z+(0.00)}, {P5X+(23.78), P5Y+(-0.00), P5Z+(7.73)}, {P6X+(-20.00), P6Y+(0.00), P6Z+(0.00)}}, - {{P1X+(20.23), P1Y+(-0.00), P1Z+(14.69)}, {P2X+(-15.00), P2Y+(0.00), P2Z+(0.00)}, {P3X+(20.23), P3Y+(-0.00), P3Z+(14.69)}, {P4X+(-15.00), P4Y+(0.00), P4Z+(0.00)}, {P5X+(20.23), P5Y+(-0.00), P5Z+(14.69)}, {P6X+(-15.00), P6Y+(0.00), P6Z+(0.00)}}, - {{P1X+(14.69), P1Y+(-0.00), P1Z+(20.23)}, {P2X+(-10.00), P2Y+(0.00), P2Z+(0.00)}, {P3X+(14.69), P3Y+(-0.00), P3Z+(20.23)}, {P4X+(-10.00), P4Y+(0.00), P4Z+(0.00)}, {P5X+(14.69), P5Y+(-0.00), P5Z+(20.23)}, {P6X+(-10.00), P6Y+(0.00), P6Z+(0.00)}}, - {{P1X+(7.73), P1Y+(-0.00), P1Z+(23.78)}, {P2X+(-5.00), P2Y+(0.00), P2Z+(0.00)}, {P3X+(7.73), P3Y+(-0.00), P3Z+(23.78)}, {P4X+(-5.00), P4Y+(0.00), P4Z+(0.00)}, {P5X+(7.73), P5Y+(-0.00), P5Z+(23.78)}, {P6X+(-5.00), P6Y+(0.00), P6Z+(0.00)}}, -}; -const int shiftleft_entries[] { 0,10 }; -const MovementTable shiftleft_table {shiftleft_paths, 20, 20, shiftleft_entries, 2 }; - -const Locations shiftright_paths[] { - {{P1X+(0.00), P1Y+(-0.00), P1Z+(25.00)}, {P2X+(0.00), P2Y+(0.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(-0.00), P3Z+(25.00)}, {P4X+(0.00), P4Y+(0.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(-0.00), P5Z+(25.00)}, {P6X+(0.00), P6Y+(0.00), P6Z+(0.00)}}, - {{P1X+(7.73), P1Y+(-0.00), P1Z+(23.78)}, {P2X+(-5.00), P2Y+(0.00), P2Z+(0.00)}, {P3X+(7.73), P3Y+(-0.00), P3Z+(23.78)}, {P4X+(-5.00), P4Y+(0.00), P4Z+(0.00)}, {P5X+(7.73), P5Y+(-0.00), P5Z+(23.78)}, {P6X+(-5.00), P6Y+(0.00), P6Z+(0.00)}}, - {{P1X+(14.69), P1Y+(-0.00), P1Z+(20.23)}, {P2X+(-10.00), P2Y+(0.00), P2Z+(0.00)}, {P3X+(14.69), P3Y+(-0.00), P3Z+(20.23)}, {P4X+(-10.00), P4Y+(0.00), P4Z+(0.00)}, {P5X+(14.69), P5Y+(-0.00), P5Z+(20.23)}, {P6X+(-10.00), P6Y+(0.00), P6Z+(0.00)}}, - {{P1X+(20.23), P1Y+(-0.00), P1Z+(14.69)}, {P2X+(-15.00), P2Y+(0.00), P2Z+(0.00)}, {P3X+(20.23), P3Y+(-0.00), P3Z+(14.69)}, {P4X+(-15.00), P4Y+(0.00), P4Z+(0.00)}, {P5X+(20.23), P5Y+(-0.00), P5Z+(14.69)}, {P6X+(-15.00), P6Y+(0.00), P6Z+(0.00)}}, - {{P1X+(23.78), P1Y+(-0.00), P1Z+(7.73)}, {P2X+(-20.00), P2Y+(0.00), P2Z+(0.00)}, {P3X+(23.78), P3Y+(-0.00), P3Z+(7.73)}, {P4X+(-20.00), P4Y+(0.00), P4Z+(0.00)}, {P5X+(23.78), P5Y+(-0.00), P5Z+(7.73)}, {P6X+(-20.00), P6Y+(0.00), P6Z+(0.00)}}, - {{P1X+(25.00), P1Y+(-0.00), P1Z+(0.00)}, {P2X+(-25.00), P2Y+(0.00), P2Z+(0.00)}, {P3X+(25.00), P3Y+(-0.00), P3Z+(0.00)}, {P4X+(-25.00), P4Y+(0.00), P4Z+(0.00)}, {P5X+(25.00), P5Y+(-0.00), P5Z+(0.00)}, {P6X+(-25.00), P6Y+(0.00), P6Z+(0.00)}}, - {{P1X+(20.00), P1Y+(-0.00), P1Z+(0.00)}, {P2X+(-23.78), P2Y+(0.00), P2Z+(7.73)}, {P3X+(20.00), P3Y+(-0.00), P3Z+(0.00)}, {P4X+(-23.78), P4Y+(0.00), P4Z+(7.73)}, {P5X+(20.00), P5Y+(-0.00), P5Z+(0.00)}, {P6X+(-23.78), P6Y+(0.00), P6Z+(7.73)}}, - {{P1X+(15.00), P1Y+(-0.00), P1Z+(0.00)}, {P2X+(-20.23), P2Y+(0.00), P2Z+(14.69)}, {P3X+(15.00), P3Y+(-0.00), P3Z+(0.00)}, {P4X+(-20.23), P4Y+(0.00), P4Z+(14.69)}, {P5X+(15.00), P5Y+(-0.00), P5Z+(0.00)}, {P6X+(-20.23), P6Y+(0.00), P6Z+(14.69)}}, - {{P1X+(10.00), P1Y+(-0.00), P1Z+(0.00)}, {P2X+(-14.69), P2Y+(0.00), P2Z+(20.23)}, {P3X+(10.00), P3Y+(-0.00), P3Z+(0.00)}, {P4X+(-14.69), P4Y+(0.00), P4Z+(20.23)}, {P5X+(10.00), P5Y+(-0.00), P5Z+(0.00)}, {P6X+(-14.69), P6Y+(0.00), P6Z+(20.23)}}, - {{P1X+(5.00), P1Y+(-0.00), P1Z+(0.00)}, {P2X+(-7.73), P2Y+(0.00), P2Z+(23.78)}, {P3X+(5.00), P3Y+(-0.00), P3Z+(0.00)}, {P4X+(-7.73), P4Y+(0.00), P4Z+(23.78)}, {P5X+(5.00), P5Y+(-0.00), P5Z+(0.00)}, {P6X+(-7.73), P6Y+(0.00), P6Z+(23.78)}}, - {{P1X+(0.00), P1Y+(0.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(-0.00), P2Z+(25.00)}, {P3X+(0.00), P3Y+(0.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(-0.00), P4Z+(25.00)}, {P5X+(0.00), P5Y+(0.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(-0.00), P6Z+(25.00)}}, - {{P1X+(-5.00), P1Y+(0.00), P1Z+(0.00)}, {P2X+(7.73), P2Y+(-0.00), P2Z+(23.78)}, {P3X+(-5.00), P3Y+(0.00), P3Z+(0.00)}, {P4X+(7.73), P4Y+(-0.00), P4Z+(23.78)}, {P5X+(-5.00), P5Y+(0.00), P5Z+(0.00)}, {P6X+(7.73), P6Y+(-0.00), P6Z+(23.78)}}, - {{P1X+(-10.00), P1Y+(0.00), P1Z+(0.00)}, {P2X+(14.69), P2Y+(-0.00), P2Z+(20.23)}, {P3X+(-10.00), P3Y+(0.00), P3Z+(0.00)}, {P4X+(14.69), P4Y+(-0.00), P4Z+(20.23)}, {P5X+(-10.00), P5Y+(0.00), P5Z+(0.00)}, {P6X+(14.69), P6Y+(-0.00), P6Z+(20.23)}}, - {{P1X+(-15.00), P1Y+(0.00), P1Z+(0.00)}, {P2X+(20.23), P2Y+(-0.00), P2Z+(14.69)}, {P3X+(-15.00), P3Y+(0.00), P3Z+(0.00)}, {P4X+(20.23), P4Y+(-0.00), P4Z+(14.69)}, {P5X+(-15.00), P5Y+(0.00), P5Z+(0.00)}, {P6X+(20.23), P6Y+(-0.00), P6Z+(14.69)}}, - {{P1X+(-20.00), P1Y+(0.00), P1Z+(0.00)}, {P2X+(23.78), P2Y+(-0.00), P2Z+(7.73)}, {P3X+(-20.00), P3Y+(0.00), P3Z+(0.00)}, {P4X+(23.78), P4Y+(-0.00), P4Z+(7.73)}, {P5X+(-20.00), P5Y+(0.00), P5Z+(0.00)}, {P6X+(23.78), P6Y+(-0.00), P6Z+(7.73)}}, - {{P1X+(-25.00), P1Y+(0.00), P1Z+(0.00)}, {P2X+(25.00), P2Y+(-0.00), P2Z+(0.00)}, {P3X+(-25.00), P3Y+(0.00), P3Z+(0.00)}, {P4X+(25.00), P4Y+(-0.00), P4Z+(0.00)}, {P5X+(-25.00), P5Y+(0.00), P5Z+(0.00)}, {P6X+(25.00), P6Y+(-0.00), P6Z+(0.00)}}, - {{P1X+(-23.78), P1Y+(0.00), P1Z+(7.73)}, {P2X+(20.00), P2Y+(-0.00), P2Z+(0.00)}, {P3X+(-23.78), P3Y+(0.00), P3Z+(7.73)}, {P4X+(20.00), P4Y+(-0.00), P4Z+(0.00)}, {P5X+(-23.78), P5Y+(0.00), P5Z+(7.73)}, {P6X+(20.00), P6Y+(-0.00), P6Z+(0.00)}}, - {{P1X+(-20.23), P1Y+(0.00), P1Z+(14.69)}, {P2X+(15.00), P2Y+(-0.00), P2Z+(0.00)}, {P3X+(-20.23), P3Y+(0.00), P3Z+(14.69)}, {P4X+(15.00), P4Y+(-0.00), P4Z+(0.00)}, {P5X+(-20.23), P5Y+(0.00), P5Z+(14.69)}, {P6X+(15.00), P6Y+(-0.00), P6Z+(0.00)}}, - {{P1X+(-14.69), P1Y+(0.00), P1Z+(20.23)}, {P2X+(10.00), P2Y+(-0.00), P2Z+(0.00)}, {P3X+(-14.69), P3Y+(0.00), P3Z+(20.23)}, {P4X+(10.00), P4Y+(-0.00), P4Z+(0.00)}, {P5X+(-14.69), P5Y+(0.00), P5Z+(20.23)}, {P6X+(10.00), P6Y+(-0.00), P6Z+(0.00)}}, - {{P1X+(-7.73), P1Y+(0.00), P1Z+(23.78)}, {P2X+(5.00), P2Y+(-0.00), P2Z+(0.00)}, {P3X+(-7.73), P3Y+(0.00), P3Z+(23.78)}, {P4X+(5.00), P4Y+(-0.00), P4Z+(0.00)}, {P5X+(-7.73), P5Y+(0.00), P5Z+(23.78)}, {P6X+(5.00), P6Y+(-0.00), P6Z+(0.00)}}, -}; -const int shiftright_entries[] { 0,10 }; -const MovementTable shiftright_table {shiftright_paths, 20, 20, shiftright_entries, 2 }; - -const Locations turnleft_paths[] { - {{P1X+(-0.00), P1Y+(0.00), P1Z+(25.00)}, {P2X+(0.00), P2Y+(0.00), P2Z+(0.00)}, {P3X+(0.00), P3Y+(0.00), P3Z+(25.00)}, {P4X+(0.00), P4Y+(0.00), P4Z+(0.00)}, {P5X+(-0.00), P5Y+(-0.00), P5Z+(25.00)}, {P6X+(0.00), P6Y+(0.00), P6Z+(0.00)}}, - {{P1X+(-5.46), P1Y+(5.46), P1Z+(23.78)}, {P2X+(0.00), P2Y+(-5.00), P2Z+(0.00)}, {P3X+(5.46), P3Y+(5.46), P3Z+(23.78)}, {P4X+(-3.54), P4Y+(3.54), P4Z+(0.00)}, {P5X+(-0.00), P5Y+(-7.73), P5Z+(23.78)}, {P6X+(3.54), P6Y+(3.54), P6Z+(0.00)}}, - {{P1X+(-10.39), P1Y+(10.39), P1Z+(20.23)}, {P2X+(0.00), P2Y+(-10.00), P2Z+(0.00)}, {P3X+(10.39), P3Y+(10.39), P3Z+(20.23)}, {P4X+(-7.07), P4Y+(7.07), P4Z+(0.00)}, {P5X+(-0.00), P5Y+(-14.69), P5Z+(20.23)}, {P6X+(7.07), P6Y+(7.07), P6Z+(0.00)}}, - {{P1X+(-14.30), P1Y+(14.30), P1Z+(14.69)}, {P2X+(0.00), P2Y+(-15.00), P2Z+(0.00)}, {P3X+(14.30), P3Y+(14.30), P3Z+(14.69)}, {P4X+(-10.61), P4Y+(10.61), P4Z+(0.00)}, {P5X+(-0.00), P5Y+(-20.23), P5Z+(14.69)}, {P6X+(10.61), P6Y+(10.61), P6Z+(0.00)}}, - {{P1X+(-16.81), P1Y+(16.81), P1Z+(7.73)}, {P2X+(0.00), P2Y+(-20.00), P2Z+(0.00)}, {P3X+(16.81), P3Y+(16.81), P3Z+(7.73)}, {P4X+(-14.14), P4Y+(14.14), P4Z+(0.00)}, {P5X+(-0.00), P5Y+(-23.78), P5Z+(7.73)}, {P6X+(14.14), P6Y+(14.14), P6Z+(0.00)}}, - {{P1X+(-17.68), P1Y+(17.68), P1Z+(0.00)}, {P2X+(0.00), P2Y+(-25.00), P2Z+(0.00)}, {P3X+(17.68), P3Y+(17.68), P3Z+(0.00)}, {P4X+(-17.68), P4Y+(17.68), P4Z+(0.00)}, {P5X+(-0.00), P5Y+(-25.00), P5Z+(0.00)}, {P6X+(17.68), P6Y+(17.68), P6Z+(0.00)}}, - {{P1X+(-14.14), P1Y+(14.14), P1Z+(0.00)}, {P2X+(0.00), P2Y+(-23.78), P2Z+(7.73)}, {P3X+(14.14), P3Y+(14.14), P3Z+(0.00)}, {P4X+(-16.81), P4Y+(16.81), P4Z+(7.73)}, {P5X+(-0.00), P5Y+(-20.00), P5Z+(0.00)}, {P6X+(16.81), P6Y+(16.81), P6Z+(7.73)}}, - {{P1X+(-10.61), P1Y+(10.61), P1Z+(0.00)}, {P2X+(0.00), P2Y+(-20.23), P2Z+(14.69)}, {P3X+(10.61), P3Y+(10.61), P3Z+(0.00)}, {P4X+(-14.30), P4Y+(14.30), P4Z+(14.69)}, {P5X+(-0.00), P5Y+(-15.00), P5Z+(0.00)}, {P6X+(14.30), P6Y+(14.30), P6Z+(14.69)}}, - {{P1X+(-7.07), P1Y+(7.07), P1Z+(0.00)}, {P2X+(0.00), P2Y+(-14.69), P2Z+(20.23)}, {P3X+(7.07), P3Y+(7.07), P3Z+(0.00)}, {P4X+(-10.39), P4Y+(10.39), P4Z+(20.23)}, {P5X+(-0.00), P5Y+(-10.00), P5Z+(0.00)}, {P6X+(10.39), P6Y+(10.39), P6Z+(20.23)}}, - {{P1X+(-3.54), P1Y+(3.54), P1Z+(0.00)}, {P2X+(0.00), P2Y+(-7.73), P2Z+(23.78)}, {P3X+(3.54), P3Y+(3.54), P3Z+(0.00)}, {P4X+(-5.46), P4Y+(5.46), P4Z+(23.78)}, {P5X+(-0.00), P5Y+(-5.00), P5Z+(0.00)}, {P6X+(5.46), P6Y+(5.46), P6Z+(23.78)}}, - {{P1X+(0.00), P1Y+(0.00), P1Z+(0.00)}, {P2X+(0.00), P2Y+(0.00), P2Z+(25.00)}, {P3X+(0.00), P3Y+(0.00), P3Z+(0.00)}, {P4X+(0.00), P4Y+(-0.00), P4Z+(25.00)}, {P5X+(0.00), P5Y+(0.00), P5Z+(0.00)}, {P6X+(-0.00), P6Y+(-0.00), P6Z+(25.00)}}, - {{P1X+(3.54), P1Y+(-3.54), P1Z+(0.00)}, {P2X+(0.00), P2Y+(7.73), P2Z+(23.78)}, {P3X+(-3.54), P3Y+(-3.54), P3Z+(0.00)}, {P4X+(5.46), P4Y+(-5.46), P4Z+(23.78)}, {P5X+(0.00), P5Y+(5.00), P5Z+(0.00)}, {P6X+(-5.46), P6Y+(-5.46), P6Z+(23.78)}}, - {{P1X+(7.07), P1Y+(-7.07), P1Z+(0.00)}, {P2X+(0.00), P2Y+(14.69), P2Z+(20.23)}, {P3X+(-7.07), P3Y+(-7.07), P3Z+(0.00)}, {P4X+(10.39), P4Y+(-10.39), P4Z+(20.23)}, {P5X+(0.00), P5Y+(10.00), P5Z+(0.00)}, {P6X+(-10.39), P6Y+(-10.39), P6Z+(20.23)}}, - {{P1X+(10.61), P1Y+(-10.61), P1Z+(0.00)}, {P2X+(0.00), P2Y+(20.23), P2Z+(14.69)}, {P3X+(-10.61), P3Y+(-10.61), P3Z+(0.00)}, {P4X+(14.30), P4Y+(-14.30), P4Z+(14.69)}, {P5X+(0.00), P5Y+(15.00), P5Z+(0.00)}, {P6X+(-14.30), P6Y+(-14.30), P6Z+(14.69)}}, - {{P1X+(14.14), P1Y+(-14.14), P1Z+(0.00)}, {P2X+(0.00), P2Y+(23.78), P2Z+(7.73)}, {P3X+(-14.14), P3Y+(-14.14), P3Z+(0.00)}, {P4X+(16.81), P4Y+(-16.81), P4Z+(7.73)}, {P5X+(0.00), P5Y+(20.00), P5Z+(0.00)}, {P6X+(-16.81), P6Y+(-16.81), P6Z+(7.73)}}, - {{P1X+(17.68), P1Y+(-17.68), P1Z+(0.00)}, {P2X+(0.00), P2Y+(25.00), P2Z+(0.00)}, {P3X+(-17.68), P3Y+(-17.68), P3Z+(0.00)}, {P4X+(17.68), P4Y+(-17.68), P4Z+(0.00)}, {P5X+(0.00), P5Y+(25.00), P5Z+(0.00)}, {P6X+(-17.68), P6Y+(-17.68), P6Z+(0.00)}}, - {{P1X+(16.81), P1Y+(-16.81), P1Z+(7.73)}, {P2X+(0.00), P2Y+(20.00), P2Z+(0.00)}, {P3X+(-16.81), P3Y+(-16.81), P3Z+(7.73)}, {P4X+(14.14), P4Y+(-14.14), P4Z+(0.00)}, {P5X+(0.00), P5Y+(23.78), P5Z+(7.73)}, {P6X+(-14.14), P6Y+(-14.14), P6Z+(0.00)}}, - {{P1X+(14.30), P1Y+(-14.30), P1Z+(14.69)}, {P2X+(0.00), P2Y+(15.00), P2Z+(0.00)}, {P3X+(-14.30), P3Y+(-14.30), P3Z+(14.69)}, {P4X+(10.61), P4Y+(-10.61), P4Z+(0.00)}, {P5X+(0.00), P5Y+(20.23), P5Z+(14.69)}, {P6X+(-10.61), P6Y+(-10.61), P6Z+(0.00)}}, - {{P1X+(10.39), P1Y+(-10.39), P1Z+(20.23)}, {P2X+(0.00), P2Y+(10.00), P2Z+(0.00)}, {P3X+(-10.39), P3Y+(-10.39), P3Z+(20.23)}, {P4X+(7.07), P4Y+(-7.07), P4Z+(0.00)}, {P5X+(0.00), P5Y+(14.69), P5Z+(20.23)}, {P6X+(-7.07), P6Y+(-7.07), P6Z+(0.00)}}, - {{P1X+(5.46), P1Y+(-5.46), P1Z+(23.78)}, {P2X+(0.00), P2Y+(5.00), P2Z+(0.00)}, {P3X+(-5.46), P3Y+(-5.46), P3Z+(23.78)}, {P4X+(3.54), P4Y+(-3.54), P4Z+(0.00)}, {P5X+(0.00), P5Y+(7.73), P5Z+(23.78)}, {P6X+(-3.54), P6Y+(-3.54), P6Z+(0.00)}}, -}; -const int turnleft_entries[] { 0,10 }; -const MovementTable turnleft_table {turnleft_paths, 20, 20, turnleft_entries, 2 }; - -const Locations turnright_paths[] { - {{P1X+(0.00), P1Y+(-0.00), P1Z+(25.00)}, {P2X+(0.00), P2Y+(0.00), P2Z+(0.00)}, {P3X+(-0.00), P3Y+(-0.00), P3Z+(25.00)}, {P4X+(0.00), P4Y+(0.00), P4Z+(0.00)}, {P5X+(0.00), P5Y+(0.00), P5Z+(25.00)}, {P6X+(0.00), P6Y+(0.00), P6Z+(0.00)}}, - {{P1X+(5.46), P1Y+(-5.46), P1Z+(23.78)}, {P2X+(0.00), P2Y+(5.00), P2Z+(0.00)}, {P3X+(-5.46), P3Y+(-5.46), P3Z+(23.78)}, {P4X+(3.54), P4Y+(-3.54), P4Z+(0.00)}, {P5X+(0.00), P5Y+(7.73), P5Z+(23.78)}, {P6X+(-3.54), P6Y+(-3.54), P6Z+(0.00)}}, - {{P1X+(10.39), P1Y+(-10.39), P1Z+(20.23)}, {P2X+(0.00), P2Y+(10.00), P2Z+(0.00)}, {P3X+(-10.39), P3Y+(-10.39), P3Z+(20.23)}, {P4X+(7.07), P4Y+(-7.07), P4Z+(0.00)}, {P5X+(0.00), P5Y+(14.69), P5Z+(20.23)}, {P6X+(-7.07), P6Y+(-7.07), P6Z+(0.00)}}, - {{P1X+(14.30), P1Y+(-14.30), P1Z+(14.69)}, {P2X+(0.00), P2Y+(15.00), P2Z+(0.00)}, {P3X+(-14.30), P3Y+(-14.30), P3Z+(14.69)}, {P4X+(10.61), P4Y+(-10.61), P4Z+(0.00)}, {P5X+(0.00), P5Y+(20.23), P5Z+(14.69)}, {P6X+(-10.61), P6Y+(-10.61), P6Z+(0.00)}}, - {{P1X+(16.81), P1Y+(-16.81), P1Z+(7.73)}, {P2X+(0.00), P2Y+(20.00), P2Z+(0.00)}, {P3X+(-16.81), P3Y+(-16.81), P3Z+(7.73)}, {P4X+(14.14), P4Y+(-14.14), P4Z+(0.00)}, {P5X+(0.00), P5Y+(23.78), P5Z+(7.73)}, {P6X+(-14.14), P6Y+(-14.14), P6Z+(0.00)}}, - {{P1X+(17.68), P1Y+(-17.68), P1Z+(0.00)}, {P2X+(0.00), P2Y+(25.00), P2Z+(0.00)}, {P3X+(-17.68), P3Y+(-17.68), P3Z+(0.00)}, {P4X+(17.68), P4Y+(-17.68), P4Z+(0.00)}, {P5X+(0.00), P5Y+(25.00), P5Z+(0.00)}, {P6X+(-17.68), P6Y+(-17.68), P6Z+(0.00)}}, - {{P1X+(14.14), P1Y+(-14.14), P1Z+(0.00)}, {P2X+(0.00), P2Y+(23.78), P2Z+(7.73)}, {P3X+(-14.14), P3Y+(-14.14), P3Z+(0.00)}, {P4X+(16.81), P4Y+(-16.81), P4Z+(7.73)}, {P5X+(0.00), P5Y+(20.00), P5Z+(0.00)}, {P6X+(-16.81), P6Y+(-16.81), P6Z+(7.73)}}, - {{P1X+(10.61), P1Y+(-10.61), P1Z+(0.00)}, {P2X+(0.00), P2Y+(20.23), P2Z+(14.69)}, {P3X+(-10.61), P3Y+(-10.61), P3Z+(0.00)}, {P4X+(14.30), P4Y+(-14.30), P4Z+(14.69)}, {P5X+(0.00), P5Y+(15.00), P5Z+(0.00)}, {P6X+(-14.30), P6Y+(-14.30), P6Z+(14.69)}}, - {{P1X+(7.07), P1Y+(-7.07), P1Z+(0.00)}, {P2X+(0.00), P2Y+(14.69), P2Z+(20.23)}, {P3X+(-7.07), P3Y+(-7.07), P3Z+(0.00)}, {P4X+(10.39), P4Y+(-10.39), P4Z+(20.23)}, {P5X+(0.00), P5Y+(10.00), P5Z+(0.00)}, {P6X+(-10.39), P6Y+(-10.39), P6Z+(20.23)}}, - {{P1X+(3.54), P1Y+(-3.54), P1Z+(0.00)}, {P2X+(0.00), P2Y+(7.73), P2Z+(23.78)}, {P3X+(-3.54), P3Y+(-3.54), P3Z+(0.00)}, {P4X+(5.46), P4Y+(-5.46), P4Z+(23.78)}, {P5X+(0.00), P5Y+(5.00), P5Z+(0.00)}, {P6X+(-5.46), P6Y+(-5.46), P6Z+(23.78)}}, - {{P1X+(0.00), P1Y+(0.00), P1Z+(0.00)}, {P2X+(-0.00), P2Y+(-0.00), P2Z+(25.00)}, {P3X+(0.00), P3Y+(0.00), P3Z+(0.00)}, {P4X+(-0.00), P4Y+(0.00), P4Z+(25.00)}, {P5X+(0.00), P5Y+(0.00), P5Z+(0.00)}, {P6X+(0.00), P6Y+(0.00), P6Z+(25.00)}}, - {{P1X+(-3.54), P1Y+(3.54), P1Z+(0.00)}, {P2X+(-0.00), P2Y+(-7.73), P2Z+(23.78)}, {P3X+(3.54), P3Y+(3.54), P3Z+(0.00)}, {P4X+(-5.46), P4Y+(5.46), P4Z+(23.78)}, {P5X+(-0.00), P5Y+(-5.00), P5Z+(0.00)}, {P6X+(5.46), P6Y+(5.46), P6Z+(23.78)}}, - {{P1X+(-7.07), P1Y+(7.07), P1Z+(0.00)}, {P2X+(-0.00), P2Y+(-14.69), P2Z+(20.23)}, {P3X+(7.07), P3Y+(7.07), P3Z+(0.00)}, {P4X+(-10.39), P4Y+(10.39), P4Z+(20.23)}, {P5X+(-0.00), P5Y+(-10.00), P5Z+(0.00)}, {P6X+(10.39), P6Y+(10.39), P6Z+(20.23)}}, - {{P1X+(-10.61), P1Y+(10.61), P1Z+(0.00)}, {P2X+(-0.00), P2Y+(-20.23), P2Z+(14.69)}, {P3X+(10.61), P3Y+(10.61), P3Z+(0.00)}, {P4X+(-14.30), P4Y+(14.30), P4Z+(14.69)}, {P5X+(-0.00), P5Y+(-15.00), P5Z+(0.00)}, {P6X+(14.30), P6Y+(14.30), P6Z+(14.69)}}, - {{P1X+(-14.14), P1Y+(14.14), P1Z+(0.00)}, {P2X+(-0.00), P2Y+(-23.78), P2Z+(7.73)}, {P3X+(14.14), P3Y+(14.14), P3Z+(0.00)}, {P4X+(-16.81), P4Y+(16.81), P4Z+(7.73)}, {P5X+(-0.00), P5Y+(-20.00), P5Z+(0.00)}, {P6X+(16.81), P6Y+(16.81), P6Z+(7.73)}}, - {{P1X+(-17.68), P1Y+(17.68), P1Z+(0.00)}, {P2X+(-0.00), P2Y+(-25.00), P2Z+(0.00)}, {P3X+(17.68), P3Y+(17.68), P3Z+(0.00)}, {P4X+(-17.68), P4Y+(17.68), P4Z+(0.00)}, {P5X+(-0.00), P5Y+(-25.00), P5Z+(0.00)}, {P6X+(17.68), P6Y+(17.68), P6Z+(0.00)}}, - {{P1X+(-16.81), P1Y+(16.81), P1Z+(7.73)}, {P2X+(-0.00), P2Y+(-20.00), P2Z+(0.00)}, {P3X+(16.81), P3Y+(16.81), P3Z+(7.73)}, {P4X+(-14.14), P4Y+(14.14), P4Z+(0.00)}, {P5X+(-0.00), P5Y+(-23.78), P5Z+(7.73)}, {P6X+(14.14), P6Y+(14.14), P6Z+(0.00)}}, - {{P1X+(-14.30), P1Y+(14.30), P1Z+(14.69)}, {P2X+(-0.00), P2Y+(-15.00), P2Z+(0.00)}, {P3X+(14.30), P3Y+(14.30), P3Z+(14.69)}, {P4X+(-10.61), P4Y+(10.61), P4Z+(0.00)}, {P5X+(-0.00), P5Y+(-20.23), P5Z+(14.69)}, {P6X+(10.61), P6Y+(10.61), P6Z+(0.00)}}, - {{P1X+(-10.39), P1Y+(10.39), P1Z+(20.23)}, {P2X+(-0.00), P2Y+(-10.00), P2Z+(0.00)}, {P3X+(10.39), P3Y+(10.39), P3Z+(20.23)}, {P4X+(-7.07), P4Y+(7.07), P4Z+(0.00)}, {P5X+(-0.00), P5Y+(-14.69), P5Z+(20.23)}, {P6X+(7.07), P6Y+(7.07), P6Z+(0.00)}}, - {{P1X+(-5.46), P1Y+(5.46), P1Z+(23.78)}, {P2X+(-0.00), P2Y+(-5.00), P2Z+(0.00)}, {P3X+(5.46), P3Y+(5.46), P3Z+(23.78)}, {P4X+(-3.54), P4Y+(3.54), P4Z+(0.00)}, {P5X+(-0.00), P5Y+(-7.73), P5Z+(23.78)}, {P6X+(3.54), P6Y+(3.54), P6Z+(0.00)}}, -}; -const int turnright_entries[] { 0,10 }; -const MovementTable turnright_table {turnright_paths, 20, 20, turnright_entries, 2 }; - -const Locations twist_paths[] { - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*1.00 + P1Z*-0.05 + 0.00, P1X*0.00 + P1Y*0.05 + P1Z*1.00 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*1.00 + P2Z*-0.05 + 0.00, P2X*0.00 + P2Y*0.05 + P2Z*1.00 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*1.00 + P3Z*-0.05 + 0.00, P3X*0.00 + P3Y*0.05 + P3Z*1.00 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*1.00 + P4Z*-0.05 + 0.00, P4X*0.00 + P4Y*0.05 + P4Z*1.00 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*1.00 + P5Z*-0.05 + 0.00, P5X*0.00 + P5Y*0.05 + P5Z*1.00 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*1.00 + P6Z*-0.05 + 0.00, P6X*0.00 + P6Y*0.05 + P6Z*1.00 + 0.00}}, - {{P1X*1.00 + P1Y*-0.07 + P1Z*0.00 + 0.00, P1X*0.07 + P1Y*0.99 + P1Z*-0.09 + 0.00, P1X*0.00 + P1Y*0.09 + P1Z*1.00 + 0.00}, - {P2X*1.00 + P2Y*-0.07 + P2Z*0.00 + 0.00, P2X*0.07 + P2Y*0.99 + P2Z*-0.09 + 0.00, P2X*0.00 + P2Y*0.09 + P2Z*1.00 + 0.00}, - {P3X*1.00 + P3Y*-0.07 + P3Z*0.00 + 0.00, P3X*0.07 + P3Y*0.99 + P3Z*-0.09 + 0.00, P3X*0.00 + P3Y*0.09 + P3Z*1.00 + 0.00}, - {P4X*1.00 + P4Y*-0.07 + P4Z*0.00 + 0.00, P4X*0.07 + P4Y*0.99 + P4Z*-0.09 + 0.00, P4X*0.00 + P4Y*0.09 + P4Z*1.00 + 0.00}, - {P5X*1.00 + P5Y*-0.07 + P5Z*0.00 + 0.00, P5X*0.07 + P5Y*0.99 + P5Z*-0.09 + 0.00, P5X*0.00 + P5Y*0.09 + P5Z*1.00 + 0.00}, - {P6X*1.00 + P6Y*-0.07 + P6Z*0.00 + 0.00, P6X*0.07 + P6Y*0.99 + P6Z*-0.09 + 0.00, P6X*0.00 + P6Y*0.09 + P6Z*1.00 + 0.00}}, - {{P1X*0.99 + P1Y*-0.14 + P1Z*0.01 + 0.00, P1X*0.14 + P1Y*0.98 + P1Z*-0.13 + 0.00, P1X*0.01 + P1Y*0.14 + P1Z*0.99 + 0.00}, - {P2X*0.99 + P2Y*-0.14 + P2Z*0.01 + 0.00, P2X*0.14 + P2Y*0.98 + P2Z*-0.13 + 0.00, P2X*0.01 + P2Y*0.14 + P2Z*0.99 + 0.00}, - {P3X*0.99 + P3Y*-0.14 + P3Z*0.01 + 0.00, P3X*0.14 + P3Y*0.98 + P3Z*-0.13 + 0.00, P3X*0.01 + P3Y*0.14 + P3Z*0.99 + 0.00}, - {P4X*0.99 + P4Y*-0.14 + P4Z*0.01 + 0.00, P4X*0.14 + P4Y*0.98 + P4Z*-0.13 + 0.00, P4X*0.01 + P4Y*0.14 + P4Z*0.99 + 0.00}, - {P5X*0.99 + P5Y*-0.14 + P5Z*0.01 + 0.00, P5X*0.14 + P5Y*0.98 + P5Z*-0.13 + 0.00, P5X*0.01 + P5Y*0.14 + P5Z*0.99 + 0.00}, - {P6X*0.99 + P6Y*-0.14 + P6Z*0.01 + 0.00, P6X*0.14 + P6Y*0.98 + P6Z*-0.13 + 0.00, P6X*0.01 + P6Y*0.14 + P6Z*0.99 + 0.00}}, - {{P1X*0.98 + P1Y*-0.21 + P1Z*0.03 + 0.00, P1X*0.21 + P1Y*0.96 + P1Z*-0.17 + 0.00, P1X*0.01 + P1Y*0.18 + P1Z*0.98 + 0.00}, - {P2X*0.98 + P2Y*-0.21 + P2Z*0.03 + 0.00, P2X*0.21 + P2Y*0.96 + P2Z*-0.17 + 0.00, P2X*0.01 + P2Y*0.18 + P2Z*0.98 + 0.00}, - {P3X*0.98 + P3Y*-0.21 + P3Z*0.03 + 0.00, P3X*0.21 + P3Y*0.96 + P3Z*-0.17 + 0.00, P3X*0.01 + P3Y*0.18 + P3Z*0.98 + 0.00}, - {P4X*0.98 + P4Y*-0.21 + P4Z*0.03 + 0.00, P4X*0.21 + P4Y*0.96 + P4Z*-0.17 + 0.00, P4X*0.01 + P4Y*0.18 + P4Z*0.98 + 0.00}, - {P5X*0.98 + P5Y*-0.21 + P5Z*0.03 + 0.00, P5X*0.21 + P5Y*0.96 + P5Z*-0.17 + 0.00, P5X*0.01 + P5Y*0.18 + P5Z*0.98 + 0.00}, - {P6X*0.98 + P6Y*-0.21 + P6Z*0.03 + 0.00, P6X*0.21 + P6Y*0.96 + P6Z*-0.17 + 0.00, P6X*0.01 + P6Y*0.18 + P6Z*0.98 + 0.00}}, - {{P1X*0.96 + P1Y*-0.27 + P1Z*0.05 + 0.00, P1X*0.28 + P1Y*0.94 + P1Z*-0.21 + 0.00, P1X*0.01 + P1Y*0.22 + P1Z*0.98 + 0.00}, - {P2X*0.96 + P2Y*-0.27 + P2Z*0.05 + 0.00, P2X*0.28 + P2Y*0.94 + P2Z*-0.21 + 0.00, P2X*0.01 + P2Y*0.22 + P2Z*0.98 + 0.00}, - {P3X*0.96 + P3Y*-0.27 + P3Z*0.05 + 0.00, P3X*0.28 + P3Y*0.94 + P3Z*-0.21 + 0.00, P3X*0.01 + P3Y*0.22 + P3Z*0.98 + 0.00}, - {P4X*0.96 + P4Y*-0.27 + P4Z*0.05 + 0.00, P4X*0.28 + P4Y*0.94 + P4Z*-0.21 + 0.00, P4X*0.01 + P4Y*0.22 + P4Z*0.98 + 0.00}, - {P5X*0.96 + P5Y*-0.27 + P5Z*0.05 + 0.00, P5X*0.28 + P5Y*0.94 + P5Z*-0.21 + 0.00, P5X*0.01 + P5Y*0.22 + P5Z*0.98 + 0.00}, - {P6X*0.96 + P6Y*-0.27 + P6Z*0.05 + 0.00, P6X*0.28 + P6Y*0.94 + P6Z*-0.21 + 0.00, P6X*0.01 + P6Y*0.22 + P6Z*0.98 + 0.00}}, - {{P1X*0.94 + P1Y*-0.33 + P1Z*0.07 + 0.00, P1X*0.34 + P1Y*0.91 + P1Z*-0.25 + 0.00, P1X*0.02 + P1Y*0.26 + P1Z*0.97 + 0.00}, - {P2X*0.94 + P2Y*-0.33 + P2Z*0.07 + 0.00, P2X*0.34 + P2Y*0.91 + P2Z*-0.25 + 0.00, P2X*0.02 + P2Y*0.26 + P2Z*0.97 + 0.00}, - {P3X*0.94 + P3Y*-0.33 + P3Z*0.07 + 0.00, P3X*0.34 + P3Y*0.91 + P3Z*-0.25 + 0.00, P3X*0.02 + P3Y*0.26 + P3Z*0.97 + 0.00}, - {P4X*0.94 + P4Y*-0.33 + P4Z*0.07 + 0.00, P4X*0.34 + P4Y*0.91 + P4Z*-0.25 + 0.00, P4X*0.02 + P4Y*0.26 + P4Z*0.97 + 0.00}, - {P5X*0.94 + P5Y*-0.33 + P5Z*0.07 + 0.00, P5X*0.34 + P5Y*0.91 + P5Z*-0.25 + 0.00, P5X*0.02 + P5Y*0.26 + P5Z*0.97 + 0.00}, - {P6X*0.94 + P6Y*-0.33 + P6Z*0.07 + 0.00, P6X*0.34 + P6Y*0.91 + P6Z*-0.25 + 0.00, P6X*0.02 + P6Y*0.26 + P6Z*0.97 + 0.00}}, - {{P1X*0.96 + P1Y*-0.27 + P1Z*0.05 + 0.00, P1X*0.28 + P1Y*0.94 + P1Z*-0.21 + 0.00, P1X*0.01 + P1Y*0.22 + P1Z*0.98 + 0.00}, - {P2X*0.96 + P2Y*-0.27 + P2Z*0.05 + 0.00, P2X*0.28 + P2Y*0.94 + P2Z*-0.21 + 0.00, P2X*0.01 + P2Y*0.22 + P2Z*0.98 + 0.00}, - {P3X*0.96 + P3Y*-0.27 + P3Z*0.05 + 0.00, P3X*0.28 + P3Y*0.94 + P3Z*-0.21 + 0.00, P3X*0.01 + P3Y*0.22 + P3Z*0.98 + 0.00}, - {P4X*0.96 + P4Y*-0.27 + P4Z*0.05 + 0.00, P4X*0.28 + P4Y*0.94 + P4Z*-0.21 + 0.00, P4X*0.01 + P4Y*0.22 + P4Z*0.98 + 0.00}, - {P5X*0.96 + P5Y*-0.27 + P5Z*0.05 + 0.00, P5X*0.28 + P5Y*0.94 + P5Z*-0.21 + 0.00, P5X*0.01 + P5Y*0.22 + P5Z*0.98 + 0.00}, - {P6X*0.96 + P6Y*-0.27 + P6Z*0.05 + 0.00, P6X*0.28 + P6Y*0.94 + P6Z*-0.21 + 0.00, P6X*0.01 + P6Y*0.22 + P6Z*0.98 + 0.00}}, - {{P1X*0.98 + P1Y*-0.21 + P1Z*0.03 + 0.00, P1X*0.21 + P1Y*0.96 + P1Z*-0.17 + 0.00, P1X*0.01 + P1Y*0.18 + P1Z*0.98 + 0.00}, - {P2X*0.98 + P2Y*-0.21 + P2Z*0.03 + 0.00, P2X*0.21 + P2Y*0.96 + P2Z*-0.17 + 0.00, P2X*0.01 + P2Y*0.18 + P2Z*0.98 + 0.00}, - {P3X*0.98 + P3Y*-0.21 + P3Z*0.03 + 0.00, P3X*0.21 + P3Y*0.96 + P3Z*-0.17 + 0.00, P3X*0.01 + P3Y*0.18 + P3Z*0.98 + 0.00}, - {P4X*0.98 + P4Y*-0.21 + P4Z*0.03 + 0.00, P4X*0.21 + P4Y*0.96 + P4Z*-0.17 + 0.00, P4X*0.01 + P4Y*0.18 + P4Z*0.98 + 0.00}, - {P5X*0.98 + P5Y*-0.21 + P5Z*0.03 + 0.00, P5X*0.21 + P5Y*0.96 + P5Z*-0.17 + 0.00, P5X*0.01 + P5Y*0.18 + P5Z*0.98 + 0.00}, - {P6X*0.98 + P6Y*-0.21 + P6Z*0.03 + 0.00, P6X*0.21 + P6Y*0.96 + P6Z*-0.17 + 0.00, P6X*0.01 + P6Y*0.18 + P6Z*0.98 + 0.00}}, - {{P1X*0.99 + P1Y*-0.14 + P1Z*0.01 + 0.00, P1X*0.14 + P1Y*0.98 + P1Z*-0.13 + 0.00, P1X*0.01 + P1Y*0.14 + P1Z*0.99 + 0.00}, - {P2X*0.99 + P2Y*-0.14 + P2Z*0.01 + 0.00, P2X*0.14 + P2Y*0.98 + P2Z*-0.13 + 0.00, P2X*0.01 + P2Y*0.14 + P2Z*0.99 + 0.00}, - {P3X*0.99 + P3Y*-0.14 + P3Z*0.01 + 0.00, P3X*0.14 + P3Y*0.98 + P3Z*-0.13 + 0.00, P3X*0.01 + P3Y*0.14 + P3Z*0.99 + 0.00}, - {P4X*0.99 + P4Y*-0.14 + P4Z*0.01 + 0.00, P4X*0.14 + P4Y*0.98 + P4Z*-0.13 + 0.00, P4X*0.01 + P4Y*0.14 + P4Z*0.99 + 0.00}, - {P5X*0.99 + P5Y*-0.14 + P5Z*0.01 + 0.00, P5X*0.14 + P5Y*0.98 + P5Z*-0.13 + 0.00, P5X*0.01 + P5Y*0.14 + P5Z*0.99 + 0.00}, - {P6X*0.99 + P6Y*-0.14 + P6Z*0.01 + 0.00, P6X*0.14 + P6Y*0.98 + P6Z*-0.13 + 0.00, P6X*0.01 + P6Y*0.14 + P6Z*0.99 + 0.00}}, - {{P1X*1.00 + P1Y*-0.07 + P1Z*0.00 + 0.00, P1X*0.07 + P1Y*0.99 + P1Z*-0.09 + 0.00, P1X*0.00 + P1Y*0.09 + P1Z*1.00 + 0.00}, - {P2X*1.00 + P2Y*-0.07 + P2Z*0.00 + 0.00, P2X*0.07 + P2Y*0.99 + P2Z*-0.09 + 0.00, P2X*0.00 + P2Y*0.09 + P2Z*1.00 + 0.00}, - {P3X*1.00 + P3Y*-0.07 + P3Z*0.00 + 0.00, P3X*0.07 + P3Y*0.99 + P3Z*-0.09 + 0.00, P3X*0.00 + P3Y*0.09 + P3Z*1.00 + 0.00}, - {P4X*1.00 + P4Y*-0.07 + P4Z*0.00 + 0.00, P4X*0.07 + P4Y*0.99 + P4Z*-0.09 + 0.00, P4X*0.00 + P4Y*0.09 + P4Z*1.00 + 0.00}, - {P5X*1.00 + P5Y*-0.07 + P5Z*0.00 + 0.00, P5X*0.07 + P5Y*0.99 + P5Z*-0.09 + 0.00, P5X*0.00 + P5Y*0.09 + P5Z*1.00 + 0.00}, - {P6X*1.00 + P6Y*-0.07 + P6Z*0.00 + 0.00, P6X*0.07 + P6Y*0.99 + P6Z*-0.09 + 0.00, P6X*0.00 + P6Y*0.09 + P6Z*1.00 + 0.00}}, - {{P1X*1.00 + P1Y*0.00 + P1Z*0.00 + 0.00, P1X*0.00 + P1Y*1.00 + P1Z*-0.05 + 0.00, P1X*0.00 + P1Y*0.05 + P1Z*1.00 + 0.00}, - {P2X*1.00 + P2Y*0.00 + P2Z*0.00 + 0.00, P2X*0.00 + P2Y*1.00 + P2Z*-0.05 + 0.00, P2X*0.00 + P2Y*0.05 + P2Z*1.00 + 0.00}, - {P3X*1.00 + P3Y*0.00 + P3Z*0.00 + 0.00, P3X*0.00 + P3Y*1.00 + P3Z*-0.05 + 0.00, P3X*0.00 + P3Y*0.05 + P3Z*1.00 + 0.00}, - {P4X*1.00 + P4Y*0.00 + P4Z*0.00 + 0.00, P4X*0.00 + P4Y*1.00 + P4Z*-0.05 + 0.00, P4X*0.00 + P4Y*0.05 + P4Z*1.00 + 0.00}, - {P5X*1.00 + P5Y*0.00 + P5Z*0.00 + 0.00, P5X*0.00 + P5Y*1.00 + P5Z*-0.05 + 0.00, P5X*0.00 + P5Y*0.05 + P5Z*1.00 + 0.00}, - {P6X*1.00 + P6Y*0.00 + P6Z*0.00 + 0.00, P6X*0.00 + P6Y*1.00 + P6Z*-0.05 + 0.00, P6X*0.00 + P6Y*0.05 + P6Z*1.00 + 0.00}}, - {{P1X*1.00 + P1Y*0.07 + P1Z*-0.00 + 0.00, P1X*-0.07 + P1Y*0.99 + P1Z*-0.09 + 0.00, P1X*-0.00 + P1Y*0.09 + P1Z*1.00 + 0.00}, - {P2X*1.00 + P2Y*0.07 + P2Z*-0.00 + 0.00, P2X*-0.07 + P2Y*0.99 + P2Z*-0.09 + 0.00, P2X*-0.00 + P2Y*0.09 + P2Z*1.00 + 0.00}, - {P3X*1.00 + P3Y*0.07 + P3Z*-0.00 + 0.00, P3X*-0.07 + P3Y*0.99 + P3Z*-0.09 + 0.00, P3X*-0.00 + P3Y*0.09 + P3Z*1.00 + 0.00}, - {P4X*1.00 + P4Y*0.07 + P4Z*-0.00 + 0.00, P4X*-0.07 + P4Y*0.99 + P4Z*-0.09 + 0.00, P4X*-0.00 + P4Y*0.09 + P4Z*1.00 + 0.00}, - {P5X*1.00 + P5Y*0.07 + P5Z*-0.00 + 0.00, P5X*-0.07 + P5Y*0.99 + P5Z*-0.09 + 0.00, P5X*-0.00 + P5Y*0.09 + P5Z*1.00 + 0.00}, - {P6X*1.00 + P6Y*0.07 + P6Z*-0.00 + 0.00, P6X*-0.07 + P6Y*0.99 + P6Z*-0.09 + 0.00, P6X*-0.00 + P6Y*0.09 + P6Z*1.00 + 0.00}}, - {{P1X*0.99 + P1Y*0.14 + P1Z*-0.01 + 0.00, P1X*-0.14 + P1Y*0.98 + P1Z*-0.13 + 0.00, P1X*-0.01 + P1Y*0.14 + P1Z*0.99 + 0.00}, - {P2X*0.99 + P2Y*0.14 + P2Z*-0.01 + 0.00, P2X*-0.14 + P2Y*0.98 + P2Z*-0.13 + 0.00, P2X*-0.01 + P2Y*0.14 + P2Z*0.99 + 0.00}, - {P3X*0.99 + P3Y*0.14 + P3Z*-0.01 + 0.00, P3X*-0.14 + P3Y*0.98 + P3Z*-0.13 + 0.00, P3X*-0.01 + P3Y*0.14 + P3Z*0.99 + 0.00}, - {P4X*0.99 + P4Y*0.14 + P4Z*-0.01 + 0.00, P4X*-0.14 + P4Y*0.98 + P4Z*-0.13 + 0.00, P4X*-0.01 + P4Y*0.14 + P4Z*0.99 + 0.00}, - {P5X*0.99 + P5Y*0.14 + P5Z*-0.01 + 0.00, P5X*-0.14 + P5Y*0.98 + P5Z*-0.13 + 0.00, P5X*-0.01 + P5Y*0.14 + P5Z*0.99 + 0.00}, - {P6X*0.99 + P6Y*0.14 + P6Z*-0.01 + 0.00, P6X*-0.14 + P6Y*0.98 + P6Z*-0.13 + 0.00, P6X*-0.01 + P6Y*0.14 + P6Z*0.99 + 0.00}}, - {{P1X*0.98 + P1Y*0.21 + P1Z*-0.03 + 0.00, P1X*-0.21 + P1Y*0.96 + P1Z*-0.17 + 0.00, P1X*-0.01 + P1Y*0.18 + P1Z*0.98 + 0.00}, - {P2X*0.98 + P2Y*0.21 + P2Z*-0.03 + 0.00, P2X*-0.21 + P2Y*0.96 + P2Z*-0.17 + 0.00, P2X*-0.01 + P2Y*0.18 + P2Z*0.98 + 0.00}, - {P3X*0.98 + P3Y*0.21 + P3Z*-0.03 + 0.00, P3X*-0.21 + P3Y*0.96 + P3Z*-0.17 + 0.00, P3X*-0.01 + P3Y*0.18 + P3Z*0.98 + 0.00}, - {P4X*0.98 + P4Y*0.21 + P4Z*-0.03 + 0.00, P4X*-0.21 + P4Y*0.96 + P4Z*-0.17 + 0.00, P4X*-0.01 + P4Y*0.18 + P4Z*0.98 + 0.00}, - {P5X*0.98 + P5Y*0.21 + P5Z*-0.03 + 0.00, P5X*-0.21 + P5Y*0.96 + P5Z*-0.17 + 0.00, P5X*-0.01 + P5Y*0.18 + P5Z*0.98 + 0.00}, - {P6X*0.98 + P6Y*0.21 + P6Z*-0.03 + 0.00, P6X*-0.21 + P6Y*0.96 + P6Z*-0.17 + 0.00, P6X*-0.01 + P6Y*0.18 + P6Z*0.98 + 0.00}}, - {{P1X*0.96 + P1Y*0.27 + P1Z*-0.05 + 0.00, P1X*-0.28 + P1Y*0.94 + P1Z*-0.21 + 0.00, P1X*-0.01 + P1Y*0.22 + P1Z*0.98 + 0.00}, - {P2X*0.96 + P2Y*0.27 + P2Z*-0.05 + 0.00, P2X*-0.28 + P2Y*0.94 + P2Z*-0.21 + 0.00, P2X*-0.01 + P2Y*0.22 + P2Z*0.98 + 0.00}, - {P3X*0.96 + P3Y*0.27 + P3Z*-0.05 + 0.00, P3X*-0.28 + P3Y*0.94 + P3Z*-0.21 + 0.00, P3X*-0.01 + P3Y*0.22 + P3Z*0.98 + 0.00}, - {P4X*0.96 + P4Y*0.27 + P4Z*-0.05 + 0.00, P4X*-0.28 + P4Y*0.94 + P4Z*-0.21 + 0.00, P4X*-0.01 + P4Y*0.22 + P4Z*0.98 + 0.00}, - {P5X*0.96 + P5Y*0.27 + P5Z*-0.05 + 0.00, P5X*-0.28 + P5Y*0.94 + P5Z*-0.21 + 0.00, P5X*-0.01 + P5Y*0.22 + P5Z*0.98 + 0.00}, - {P6X*0.96 + P6Y*0.27 + P6Z*-0.05 + 0.00, P6X*-0.28 + P6Y*0.94 + P6Z*-0.21 + 0.00, P6X*-0.01 + P6Y*0.22 + P6Z*0.98 + 0.00}}, - {{P1X*0.94 + P1Y*0.33 + P1Z*-0.07 + 0.00, P1X*-0.34 + P1Y*0.91 + P1Z*-0.25 + 0.00, P1X*-0.02 + P1Y*0.26 + P1Z*0.97 + 0.00}, - {P2X*0.94 + P2Y*0.33 + P2Z*-0.07 + 0.00, P2X*-0.34 + P2Y*0.91 + P2Z*-0.25 + 0.00, P2X*-0.02 + P2Y*0.26 + P2Z*0.97 + 0.00}, - {P3X*0.94 + P3Y*0.33 + P3Z*-0.07 + 0.00, P3X*-0.34 + P3Y*0.91 + P3Z*-0.25 + 0.00, P3X*-0.02 + P3Y*0.26 + P3Z*0.97 + 0.00}, - {P4X*0.94 + P4Y*0.33 + P4Z*-0.07 + 0.00, P4X*-0.34 + P4Y*0.91 + P4Z*-0.25 + 0.00, P4X*-0.02 + P4Y*0.26 + P4Z*0.97 + 0.00}, - {P5X*0.94 + P5Y*0.33 + P5Z*-0.07 + 0.00, P5X*-0.34 + P5Y*0.91 + P5Z*-0.25 + 0.00, P5X*-0.02 + P5Y*0.26 + P5Z*0.97 + 0.00}, - {P6X*0.94 + P6Y*0.33 + P6Z*-0.07 + 0.00, P6X*-0.34 + P6Y*0.91 + P6Z*-0.25 + 0.00, P6X*-0.02 + P6Y*0.26 + P6Z*0.97 + 0.00}}, - {{P1X*0.96 + P1Y*0.27 + P1Z*-0.05 + 0.00, P1X*-0.28 + P1Y*0.94 + P1Z*-0.21 + 0.00, P1X*-0.01 + P1Y*0.22 + P1Z*0.98 + 0.00}, - {P2X*0.96 + P2Y*0.27 + P2Z*-0.05 + 0.00, P2X*-0.28 + P2Y*0.94 + P2Z*-0.21 + 0.00, P2X*-0.01 + P2Y*0.22 + P2Z*0.98 + 0.00}, - {P3X*0.96 + P3Y*0.27 + P3Z*-0.05 + 0.00, P3X*-0.28 + P3Y*0.94 + P3Z*-0.21 + 0.00, P3X*-0.01 + P3Y*0.22 + P3Z*0.98 + 0.00}, - {P4X*0.96 + P4Y*0.27 + P4Z*-0.05 + 0.00, P4X*-0.28 + P4Y*0.94 + P4Z*-0.21 + 0.00, P4X*-0.01 + P4Y*0.22 + P4Z*0.98 + 0.00}, - {P5X*0.96 + P5Y*0.27 + P5Z*-0.05 + 0.00, P5X*-0.28 + P5Y*0.94 + P5Z*-0.21 + 0.00, P5X*-0.01 + P5Y*0.22 + P5Z*0.98 + 0.00}, - {P6X*0.96 + P6Y*0.27 + P6Z*-0.05 + 0.00, P6X*-0.28 + P6Y*0.94 + P6Z*-0.21 + 0.00, P6X*-0.01 + P6Y*0.22 + P6Z*0.98 + 0.00}}, - {{P1X*0.98 + P1Y*0.21 + P1Z*-0.03 + 0.00, P1X*-0.21 + P1Y*0.96 + P1Z*-0.17 + 0.00, P1X*-0.01 + P1Y*0.18 + P1Z*0.98 + 0.00}, - {P2X*0.98 + P2Y*0.21 + P2Z*-0.03 + 0.00, P2X*-0.21 + P2Y*0.96 + P2Z*-0.17 + 0.00, P2X*-0.01 + P2Y*0.18 + P2Z*0.98 + 0.00}, - {P3X*0.98 + P3Y*0.21 + P3Z*-0.03 + 0.00, P3X*-0.21 + P3Y*0.96 + P3Z*-0.17 + 0.00, P3X*-0.01 + P3Y*0.18 + P3Z*0.98 + 0.00}, - {P4X*0.98 + P4Y*0.21 + P4Z*-0.03 + 0.00, P4X*-0.21 + P4Y*0.96 + P4Z*-0.17 + 0.00, P4X*-0.01 + P4Y*0.18 + P4Z*0.98 + 0.00}, - {P5X*0.98 + P5Y*0.21 + P5Z*-0.03 + 0.00, P5X*-0.21 + P5Y*0.96 + P5Z*-0.17 + 0.00, P5X*-0.01 + P5Y*0.18 + P5Z*0.98 + 0.00}, - {P6X*0.98 + P6Y*0.21 + P6Z*-0.03 + 0.00, P6X*-0.21 + P6Y*0.96 + P6Z*-0.17 + 0.00, P6X*-0.01 + P6Y*0.18 + P6Z*0.98 + 0.00}}, - {{P1X*0.99 + P1Y*0.14 + P1Z*-0.01 + 0.00, P1X*-0.14 + P1Y*0.98 + P1Z*-0.13 + 0.00, P1X*-0.01 + P1Y*0.14 + P1Z*0.99 + 0.00}, - {P2X*0.99 + P2Y*0.14 + P2Z*-0.01 + 0.00, P2X*-0.14 + P2Y*0.98 + P2Z*-0.13 + 0.00, P2X*-0.01 + P2Y*0.14 + P2Z*0.99 + 0.00}, - {P3X*0.99 + P3Y*0.14 + P3Z*-0.01 + 0.00, P3X*-0.14 + P3Y*0.98 + P3Z*-0.13 + 0.00, P3X*-0.01 + P3Y*0.14 + P3Z*0.99 + 0.00}, - {P4X*0.99 + P4Y*0.14 + P4Z*-0.01 + 0.00, P4X*-0.14 + P4Y*0.98 + P4Z*-0.13 + 0.00, P4X*-0.01 + P4Y*0.14 + P4Z*0.99 + 0.00}, - {P5X*0.99 + P5Y*0.14 + P5Z*-0.01 + 0.00, P5X*-0.14 + P5Y*0.98 + P5Z*-0.13 + 0.00, P5X*-0.01 + P5Y*0.14 + P5Z*0.99 + 0.00}, - {P6X*0.99 + P6Y*0.14 + P6Z*-0.01 + 0.00, P6X*-0.14 + P6Y*0.98 + P6Z*-0.13 + 0.00, P6X*-0.01 + P6Y*0.14 + P6Z*0.99 + 0.00}}, - {{P1X*1.00 + P1Y*0.07 + P1Z*-0.00 + 0.00, P1X*-0.07 + P1Y*0.99 + P1Z*-0.09 + 0.00, P1X*-0.00 + P1Y*0.09 + P1Z*1.00 + 0.00}, - {P2X*1.00 + P2Y*0.07 + P2Z*-0.00 + 0.00, P2X*-0.07 + P2Y*0.99 + P2Z*-0.09 + 0.00, P2X*-0.00 + P2Y*0.09 + P2Z*1.00 + 0.00}, - {P3X*1.00 + P3Y*0.07 + P3Z*-0.00 + 0.00, P3X*-0.07 + P3Y*0.99 + P3Z*-0.09 + 0.00, P3X*-0.00 + P3Y*0.09 + P3Z*1.00 + 0.00}, - {P4X*1.00 + P4Y*0.07 + P4Z*-0.00 + 0.00, P4X*-0.07 + P4Y*0.99 + P4Z*-0.09 + 0.00, P4X*-0.00 + P4Y*0.09 + P4Z*1.00 + 0.00}, - {P5X*1.00 + P5Y*0.07 + P5Z*-0.00 + 0.00, P5X*-0.07 + P5Y*0.99 + P5Z*-0.09 + 0.00, P5X*-0.00 + P5Y*0.09 + P5Z*1.00 + 0.00}, - {P6X*1.00 + P6Y*0.07 + P6Z*-0.00 + 0.00, P6X*-0.07 + P6Y*0.99 + P6Z*-0.09 + 0.00, P6X*-0.00 + P6Y*0.09 + P6Z*1.00 + 0.00}}, -}; -const int twist_entries[] { 0,10 }; -const MovementTable twist_table {twist_paths, 20, 50, twist_entries, 2 }; -} - -const MovementTable& backwardTable() { - return backward_table; -} -const MovementTable& climbTable() { - return climb_table; -} -const MovementTable& forwardTable() { - return forward_table; -} -const MovementTable& forwardfastTable() { - return forwardfast_table; -} -const MovementTable& rotatexTable() { - return rotatex_table; -} -const MovementTable& rotateyTable() { - return rotatey_table; -} -const MovementTable& rotatezTable() { - return rotatez_table; -} -const MovementTable& shiftleftTable() { - return shiftleft_table; -} -const MovementTable& shiftrightTable() { - return shiftright_table; -} -const MovementTable& turnleftTable() { - return turnleft_table; -} -const MovementTable& turnrightTable() { - return turnright_table; -} -const MovementTable& twistTable() { - return twist_table; -} diff --git a/software/archive/hexapod7697/src/hexapod/movements.cpp b/software/archive/hexapod7697/src/hexapod/movements.cpp deleted file mode 100644 index b00c6e5..0000000 --- a/software/archive/hexapod7697/src/hexapod/movements.cpp +++ /dev/null @@ -1,59 +0,0 @@ -#include "movement.h" -#include "config.h" - -using namespace hexapod::config; -using namespace hexapod; - -#define SIN30 0.5 -#define COS30 0.866 -#define SIN45 0.7071 -#define COS45 0.7071 -#define SIN15 0.2588 -#define COS15 0.9659 - -#define STANDBY_Z (kLegJoint3ToTip*COS15-kLegJoint2ToJoint3*SIN30) -#define LEFTRIGHT_X (kLegMountLeftRightX+kLegRootToJoint1+kLegJoint1ToJoint2+(kLegJoint2ToJoint3*COS30)+kLegJoint3ToTip*SIN15) -#define OTHER_X (kLegMountOtherX + (kLegRootToJoint1+kLegJoint1ToJoint2+(kLegJoint2ToJoint3*COS30)+kLegJoint3ToTip*SIN15)*COS45) -#define OTHER_Y (kLegMountOtherY + (kLegRootToJoint1+kLegJoint1ToJoint2+(kLegJoint2ToJoint3*COS30)+kLegJoint3ToTip*SIN15)*SIN45) - -#define P1X OTHER_X -#define P1Y OTHER_Y -#define P1Z -STANDBY_Z - -#define P2X LEFTRIGHT_X -#define P2Y 0 -#define P2Z -STANDBY_Z - -#define P3X OTHER_X -#define P3Y -OTHER_Y -#define P3Z -STANDBY_Z - -#define P4X -OTHER_X -#define P4Y -OTHER_Y -#define P4Z -STANDBY_Z - -#define P5X -LEFTRIGHT_X -#define P5Y 0 -#define P5Z -STANDBY_Z - -#define P6X -OTHER_X -#define P6Y OTHER_Y -#define P6Z -STANDBY_Z - -namespace hexapod { - - namespace { - const Locations kStandby { - {P1X, P1Y, P1Z}, {P2X, P2Y, P2Z}, {P3X, P3Y, P3Z}, {P4X, P4Y, P4Z}, {P5X, P5Y, P5Z}, {P6X, P6Y, P6Z} - }; - const int zero = 0; - - const MovementTable standay_table {&kStandby, 1, 20, &zero, 1}; - } - - const MovementTable& standbyTable() { - return standay_table; - } - - #include "movement_table.h" -} diff --git a/software/archive/hexapod7697/src/hexapod/servo.cpp b/software/archive/hexapod7697/src/hexapod/servo.cpp deleted file mode 100644 index f53af97..0000000 --- a/software/archive/hexapod7697/src/hexapod/servo.cpp +++ /dev/null @@ -1,117 +0,0 @@ -#include "servo.h" -#include "debug.h" - -#include "hal/pwm.h" - -namespace hexapod { - - namespace { - // if freq = 240, 1 tick = 1000000 / (240*4096) ~= 1us - // if freq = 120, 1 tick = 1000000 / (120*4096) ~= 2us - const static int kFrequency = 120; - const static int kTickUs = 2; - const static int kServoMiddle = 1400; - const static int kServoMax = 2000; - const static int kServoMin = 800; - const static int kServoRange = kServoMax-kServoMiddle; - - auto pwmLeft = hal::PCA9685(0x41); - auto pwmRight = hal::PCA9685(0x40); - bool pwmInited = false; - - void initPWM(void) { - if (pwmInited) - return; - - pwmLeft.begin(); - pwmLeft.setPWMFreq(kFrequency); - pwmRight.begin(); - pwmRight.setPWMFreq(kFrequency); - pwmInited = true; - } - - int hexapod2pwm(int legIndex, int partIndex) { - switch(legIndex) { - case 0: return 5 + partIndex; - case 1: return 2 + partIndex; - case 2: return 8 + partIndex; - case 3: return 16 + 8 + partIndex; - case 4: return 16 + 2 + partIndex; - case 5: return 16 + 5 + partIndex; - default: return 0; - } - } - - int pwm2hexapod(int pwm) { - if(pwm >= 16+8) - return 9 + pwm - (16+8); - if(pwm >= 16+5) - return 15 + pwm - (16+5); - if(pwm >= 16+2) - return 12 + pwm - (16+2); - if(pwm >= 8) - return 6 + pwm - (8); - if(pwm >= 5) - return 0 + pwm - (5); - if(pwm >= 2) - return 3 + pwm - (2); - return -1; - } - - } - - void Servo::init(void) { - initPWM(); - } - - Servo::Servo(int legIndex, int partIndex) { - pwmIndex_ = hexapod2pwm(legIndex, partIndex); - inverse_ = partIndex == 1 ? true : false; - adjust_angle_ = partIndex == 1 ? 15.0 : 0.0; - range_ = partIndex == 0 ? 45 : 60; - angle_ = 0; - } - - void Servo::setAngle(float angle) { - initPWM(); - - if (angle > range_ + adjust_angle_) { - LOG_INFO("exceed[%d][%f]", pwm2hexapod(pwmIndex_), angle); - angle = range_; - } - else if(angle < -range_ + adjust_angle_) { - LOG_INFO("exceed[%d][%f]", pwm2hexapod(pwmIndex_), angle); - angle = -range_; - } - - angle_ = angle; - - hal::PCA9685* pwm; - int idx; - if (pwmIndex_ < 16) { - pwm = &pwmRight; - idx = pwmIndex_; - } - else { - pwm = &pwmLeft; - idx = pwmIndex_ - 16; - } - angle -= adjust_angle_; - if (inverse_) - angle = -angle; - - int us = kServoMiddle + offset_ + angle*(kServoRange/60)*(1+0.01*scale_); - if (us > kServoMax) - us = kServoMax; - else if(us < kServoMin) - us = kServoMin; - - pwm->setPWM(idx, 0, us/kTickUs); - LOG_DEBUG("setAngle(%.2f, %d)", angle, us); - } - - float Servo::getAngle(void) { - return angle_; - } - -} \ No newline at end of file diff --git a/software/archive/hexapod7697/src/hexapod/servo.h b/software/archive/hexapod7697/src/hexapod/servo.h deleted file mode 100644 index 2058de5..0000000 --- a/software/archive/hexapod7697/src/hexapod/servo.h +++ /dev/null @@ -1,38 +0,0 @@ -#pragma once - -namespace hexapod { - - class Servo { - public: - static void init(void); - - public: - Servo(int legIndex, int partIndex); - - // angle: 0 means center, range is -60~60 - void setAngle(float angle); - float getAngle(void); - - void getParameter(int& offset, int& scale) { - offset = offset_; - scale = scale_; - } - - void setParameter(int offset, int scale, bool update = true) { - offset_ = offset; - scale_ = scale; - if (update) - setAngle(angle_); - } - - private: - float angle_; - int pwmIndex_; - bool inverse_; - int offset_; - int scale_; - int range_; - float adjust_angle_; - }; - -} \ No newline at end of file diff --git a/software/archive/hexapod7697/src/linkit_control/ui_controls.cpp b/software/archive/hexapod7697/src/linkit_control/ui_controls.cpp deleted file mode 100644 index 6f1b386..0000000 --- a/software/archive/hexapod7697/src/linkit_control/ui_controls.cpp +++ /dev/null @@ -1,83 +0,0 @@ -#include -#include "ui_controls.h" - -namespace { - const static int kRepeatPeriod1 = 500; - const static int kRepeatPeriod1Count = 4; - const static int kRepeatPeriod2 = 100; -} - -void ButtonGroup::addControl(Button &button) { - // prevent duplicated entry - for (const auto control : controls_) { - if (control == &button) { - return; - } - } - controls_.push_back(&button); -}; - -void ButtonGroup::addControl(Button *button) { - // prevent duplicated entry - for (const auto control : controls_) { - if (control == button) { - return; - } - } - controls_.push_back(button); -}; - -void ButtonGroup::addControls(std::vector