From 59573e5b69f9afc5dbe00bc165ae8e1f4d457f89 Mon Sep 17 00:00:00 2001 From: marco Date: Wed, 17 Apr 2013 19:46:01 +0200 Subject: [PATCH 01/23] BLCtrl 2.0 testing - currently only 8 Bit resolution - this should fly --- apps/drivers/mkblctrl/Makefile | 44 + apps/drivers/mkblctrl/mkblctrl.cpp | 1403 ++++++++++++++++++++++++++++ nuttx/configs/px4fmu/nsh/appconfig | 1 + 3 files changed, 1448 insertions(+) create mode 100644 apps/drivers/mkblctrl/Makefile create mode 100644 apps/drivers/mkblctrl/mkblctrl.cpp diff --git a/apps/drivers/mkblctrl/Makefile b/apps/drivers/mkblctrl/Makefile new file mode 100644 index 0000000000..b3be2c4687 --- /dev/null +++ b/apps/drivers/mkblctrl/Makefile @@ -0,0 +1,44 @@ +############################################################################ +# +# Copyright (C) 2012 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +# +# Interface driver for the Mikrokopter BLCtrl +# + +APPNAME = mkblctrl +PRIORITY = SCHED_PRIORITY_DEFAULT +STACKSIZE = 2048 + +INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common + +include $(APPDIR)/mk/app.mk diff --git a/apps/drivers/mkblctrl/mkblctrl.cpp b/apps/drivers/mkblctrl/mkblctrl.cpp new file mode 100644 index 0000000000..c14fdfd1d8 --- /dev/null +++ b/apps/drivers/mkblctrl/mkblctrl.cpp @@ -0,0 +1,1403 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file mkblctrl.cpp + * + * Driver/configurator for the Mikrokopter BL-Ctrl. + * Marco Bauer + * + */ + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +#include +#include + +#include +#include +#include +#include + +#include +#include +#include + +#include + +#define I2C_BUS_SPEED 400000 +#define UPDATE_RATE 400 +#define MAX_MOTORS 8 +#define BLCTRL_BASE_ADDR 0x29 +#define BLCTRL_OLD 0 +#define BLCTRL_NEW 1 +#define BLCTRL_MIN_VALUE -0.984F +#define MOTOR_STATE_PRESENT_MASK 0x80 +#define MOTOR_STATE_ERROR_MASK 0x7F +#define MOTOR_SPINUP_COUNTER 2500 + + +class MK : public device::I2C +{ +public: + enum Mode { + MODE_2PWM, + MODE_4PWM, + MODE_NONE + }; + + enum MappingMode { + MAPPING_MK = 0, + MAPPING_PX4, + }; + + enum FrameType { + FRAME_PLUS = 0, + FRAME_X, + }; + + MK(int bus); + ~MK(); + + virtual int ioctl(file *filp, int cmd, unsigned long arg); + virtual int init(unsigned motors); + + int set_mode(Mode mode); + int set_pwm_rate(unsigned rate); + int set_motor_count(unsigned count); + int set_motor_test(bool motortest); + int set_px4mode(int px4mode); + int set_frametype(int frametype); + +private: + static const unsigned _max_actuators = MAX_MOTORS; + static const bool showDebug = false; + + Mode _mode; + int _update_rate; + int _current_update_rate; + int _task; + int _t_actuators; + int _t_armed; + unsigned int _motor; + int _px4mode; + int _frametype; + orb_advert_t _t_outputs; + orb_advert_t _t_actuators_effective; + unsigned int _num_outputs; + bool _primary_pwm_device; + bool _motortest; + + volatile bool _task_should_exit; + bool _armed; + + unsigned long debugCounter; + + MixerGroup *_mixers; + + actuator_controls_s _controls; + + static void task_main_trampoline(int argc, char *argv[]); + void task_main() __attribute__((noreturn)); + + static int control_callback(uintptr_t handle, + uint8_t control_group, + uint8_t control_index, + float &input); + + int pwm_ioctl(file *filp, int cmd, unsigned long arg); + + struct GPIOConfig { + uint32_t input; + uint32_t output; + uint32_t alt; + }; + + static const GPIOConfig _gpio_tab[]; + static const unsigned _ngpio; + + void gpio_reset(void); + void gpio_set_function(uint32_t gpios, int function); + void gpio_write(uint32_t gpios, int function); + uint32_t gpio_read(void); + int gpio_ioctl(file *filp, int cmd, unsigned long arg); + int mk_servo_arm(bool status); + + int mk_check_for_blctrl(unsigned int count); + int mk_servo_set(unsigned int chan, float val); + int mk_servo_set_test(unsigned int chan, float val); + int mk_servo_test(unsigned int chan); + + +}; + +const MK::GPIOConfig MK::_gpio_tab[] = { + {GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0}, + {GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0}, + {GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, GPIO_USART2_CTS_1}, + {GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, GPIO_USART2_RTS_1}, + {GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, GPIO_USART2_TX_1}, + {GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, GPIO_USART2_RX_1}, + {GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, GPIO_CAN2_TX_2}, + {GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, GPIO_CAN2_RX_2}, +}; + +const unsigned MK::_ngpio = sizeof(MK::_gpio_tab) / sizeof(MK::_gpio_tab[0]); + +const int blctrlAddr_quad_plus[] = { 2, 2, -2, -2, 0, 0, 0, 0 }; // Addresstranslator for Quad + configuration +const int blctrlAddr_hexa_plus[] = { 0, 2, 2, -2, 1, -3, 0, 0 }; // Addresstranslator for Hexa + configuration +const int blctrlAddr_octo_plus[] = { 0, 3, -1, 0, 3, 0, 0, -5 }; // Addresstranslator for Octo + configuration + +const int blctrlAddr_quad_x[] = { 2, 2, -2, -2, 0, 0, 0, 0 }; // Addresstranslator for Quad X configuration +const int blctrlAddr_hexa_x[] = { 2, 4, -2, 0, -3, -1, 0, 0 }; // Addresstranslator for Hexa X configuration +const int blctrlAddr_octo_x[] = { 1, 4, 0, 1, -4, 1, 1, -4 }; // Addresstranslator for Octo X configuration + +const int blctrlAddr_px4[] = { 0, 0, 0, 0, 0, 0, 0, 0}; + +int addrTranslator[] = {0,0,0,0,0,0,0,0}; + +struct MotorData_t +{ + unsigned int Version; // the version of the BL (0 = old) + unsigned int SetPoint; // written by attitude controller + unsigned int SetPointLowerBits; // for higher Resolution of new BLs + unsigned int State; // 7 bit for I2C error counter, highest bit indicates if motor is present + unsigned int ReadMode; // select data to read + // the following bytes must be exactly in that order! + unsigned int Current; // in 0.1 A steps, read back from BL + unsigned int MaxPWM; // read back from BL is less than 255 if BL is in current limit + unsigned int Temperature; // old BL-Ctrl will return a 255 here, the new version the temp. in °C + unsigned int RoundCount; +}; + +MotorData_t Motor[MAX_MOTORS]; + + +namespace +{ + +MK *g_mk; + +} // namespace + +MK::MK(int bus) : + I2C("mkblctrl", "/dev/mkblctrl", bus, 0, I2C_BUS_SPEED), + _mode(MODE_NONE), + _update_rate(50), + _task(-1), + _t_actuators(-1), + _t_armed(-1), + _t_outputs(0), + _t_actuators_effective(0), + _num_outputs(0), + _motortest(false), + _motor(-1), + _px4mode(MAPPING_MK), + _frametype(FRAME_PLUS), + _primary_pwm_device(false), + _task_should_exit(false), + _armed(false), + _mixers(nullptr) +{ + _debug_enabled = true; +} + +MK::~MK() +{ + if (_task != -1) { + /* tell the task we want it to go away */ + _task_should_exit = true; + + unsigned i = 10; + + do { + /* wait 50ms - it should wake every 100ms or so worst-case */ + usleep(50000); + + /* if we have given up, kill it */ + if (--i == 0) { + task_delete(_task); + break; + } + + } while (_task != -1); + } + + /* clean up the alternate device node */ + if (_primary_pwm_device) + unregister_driver(PWM_OUTPUT_DEVICE_PATH); + + g_mk = nullptr; +} + +int +MK::init(unsigned motors) +{ + _num_outputs = motors; + debugCounter = 0; + int ret; + ASSERT(_task == -1); + + ret = I2C::init(); + + if (ret != OK) { + warnx("I2C init failed"); + return ret; + } + + usleep(500000); + + /* try to claim the generic PWM output device node as well - it's OK if we fail at this */ + ret = register_driver(PWM_OUTPUT_DEVICE_PATH, &fops, 0666, (void *)this); + + if (ret == OK) { + log("default PWM output device"); + _primary_pwm_device = true; + } + + /* reset GPIOs */ + gpio_reset(); + + /* check for connected blctrls */ + //mk_check_for_blctrl(_num_outputs); + + /* start the IO interface task */ + _task = task_spawn("mkblctrl", + SCHED_DEFAULT, + SCHED_PRIORITY_MAX -20, + 2048, + (main_t)&MK::task_main_trampoline, + nullptr); + + + if (_task < 0) { + debug("task start failed: %d", errno); + return -errno; + } + + return OK; +} + +void +MK::task_main_trampoline(int argc, char *argv[]) +{ + g_mk->task_main(); +} + +int +MK::set_mode(Mode mode) +{ + /* + * Configure for PWM output. + * + * Note that regardless of the configured mode, the task is always + * listening and mixing; the mode just selects which of the channels + * are presented on the output pins. + */ + switch (mode) { + case MODE_2PWM: + if(_num_outputs == 4) { + debug("MODE_QUAD"); + } else if(_num_outputs == 6) { + debug("MODE_HEXA"); + } else if(_num_outputs == 8) { + debug("MODE_OCTO"); + } + //up_pwm_servo_init(0x3); + up_pwm_servo_deinit(); + _update_rate = UPDATE_RATE; /* default output rate */ + break; + + case MODE_4PWM: + if(_num_outputs == 4) { + debug("MODE_QUADRO"); + } else if(_num_outputs == 6) { + debug("MODE_HEXA"); + } else if(_num_outputs == 8) { + debug("MODE_OCTO"); + } + //up_pwm_servo_init(0xf); + up_pwm_servo_deinit(); + _update_rate = UPDATE_RATE; /* default output rate */ + break; + + case MODE_NONE: + debug("MODE_NONE"); + /* disable servo outputs and set a very low update rate */ + up_pwm_servo_deinit(); + _update_rate = UPDATE_RATE; + break; + + default: + return -EINVAL; + } + + _mode = mode; + return OK; +} + +int +MK::set_pwm_rate(unsigned rate) +{ + if ((rate > 500) || (rate < 10)) + return -EINVAL; + + _update_rate = rate; + return OK; +} + +int +MK::set_px4mode(int px4mode) +{ + _px4mode = px4mode; +} + +int +MK::set_frametype(int frametype) +{ + _frametype = frametype; +} + + +int +MK::set_motor_count(unsigned count) +{ + _num_outputs = count; + + if(_px4mode == MAPPING_MK) { + if(_frametype == FRAME_PLUS) { + fprintf(stderr, "[mkblctrl] addresstanslator for Mikrokopter addressing used. Frametype: +\n"); + } else if(_frametype == FRAME_X) { + fprintf(stderr, "[mkblctrl] addresstanslator for Mikrokopter addressing used. Frametype: X\n"); + } + if(_num_outputs == 4) { + if(_frametype == FRAME_PLUS) { + memcpy(&addrTranslator, &blctrlAddr_quad_plus, sizeof(blctrlAddr_quad_plus)); + } else if(_frametype == FRAME_X) { + memcpy(&addrTranslator, &blctrlAddr_quad_x, sizeof(blctrlAddr_quad_x)); + } + } else if(_num_outputs == 6) { + if(_frametype == FRAME_PLUS) { + memcpy(&addrTranslator, &blctrlAddr_hexa_plus, sizeof(blctrlAddr_hexa_plus)); + } else if(_frametype == FRAME_X) { + memcpy(&addrTranslator, &blctrlAddr_hexa_x, sizeof(blctrlAddr_hexa_x)); + } + } else if(_num_outputs == 8) { + if(_frametype == FRAME_PLUS) { + memcpy(&addrTranslator, &blctrlAddr_octo_plus, sizeof(blctrlAddr_octo_plus)); + } else if(_frametype == FRAME_X) { + memcpy(&addrTranslator, &blctrlAddr_octo_x, sizeof(blctrlAddr_octo_x)); + } + } + } else { + fprintf(stderr, "[mkblctrl] PX4 native addressing used.\n"); + memcpy(&addrTranslator, &blctrlAddr_px4, sizeof(blctrlAddr_px4)); + } + + /* check for connected blctrls */ + mk_check_for_blctrl(_num_outputs); + + return OK; +} + +int +MK::set_motor_test(bool motortest) +{ + _motortest = motortest; + return OK; +} + + +void +MK::task_main() +{ + /* + * Subscribe to the appropriate PWM output topic based on whether we are the + * primary PWM output or not. + */ + _t_actuators = orb_subscribe(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS : + ORB_ID(actuator_controls_1)); + /* force a reset of the update rate */ + _current_update_rate = 0; + + _t_armed = orb_subscribe(ORB_ID(actuator_armed)); + orb_set_interval(_t_armed, 200); /* 5Hz update rate */ + + /* advertise the mixed control outputs */ + actuator_outputs_s outputs; + memset(&outputs, 0, sizeof(outputs)); + /* advertise the mixed control outputs */ + _t_outputs = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), + &outputs); + + /* advertise the effective control inputs */ + actuator_controls_effective_s controls_effective; + memset(&controls_effective, 0, sizeof(controls_effective)); + /* advertise the effective control inputs */ + _t_actuators_effective = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_effective_1), + &controls_effective); + + pollfd fds[2]; + fds[0].fd = _t_actuators; + fds[0].events = POLLIN; + fds[1].fd = _t_armed; + fds[1].events = POLLIN; + + log("starting"); + long update_rate_in_us = 0; + + /* loop until killed */ + while (!_task_should_exit) { + + /* handle update rate changes */ + if (_current_update_rate != _update_rate) { + int update_rate_in_ms = int(1000 / _update_rate); + update_rate_in_us = long(1000000 / _update_rate); + + /* reject faster than 500 Hz updates */ + if (update_rate_in_ms < 2) { + update_rate_in_ms = 2; + _update_rate = 500; + } + /* reject slower than 50 Hz updates */ + if (update_rate_in_ms > 20) { + update_rate_in_ms = 20; + _update_rate = 50; + } + + orb_set_interval(_t_actuators, update_rate_in_ms); + up_pwm_servo_set_rate(_update_rate); + _current_update_rate = _update_rate; + } + + /* sleep waiting for data, but no more than a second */ + int ret = ::poll(&fds[0], 2, 1000); + + /* this would be bad... */ + if (ret < 0) { + log("poll error %d", errno); + usleep(1000000); + continue; + } + + /* do we have a control update? */ + if (fds[0].revents & POLLIN) { + + /* get controls - must always do this to avoid spinning */ + orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS : ORB_ID(actuator_controls_1), _t_actuators, &_controls); + + /* can we mix? */ + if (_mixers != nullptr) { + + /* do mixing */ + outputs.noutputs = _mixers->mix(&outputs.output[0], _num_outputs); + outputs.timestamp = hrt_absolute_time(); + + // XXX output actual limited values + memcpy(&controls_effective, &_controls, sizeof(controls_effective)); + + orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_effective_1), _t_actuators_effective, &controls_effective); + + /* iterate actuators */ + for (unsigned int i = 0; i < _num_outputs; i++) { + + /* last resort: catch NaN, INF and out-of-band errors */ + if (i < outputs.noutputs && + isfinite(outputs.output[i]) && + outputs.output[i] >= -1.0f && + outputs.output[i] <= 1.0f) { + /* scale for PWM output 900 - 2100us */ + //outputs.output[i] = 1500 + (600 * outputs.output[i]); + //outputs.output[i] = 127 + (127 * outputs.output[i]); + } else { + /* + * Value is NaN, INF or out of band - set to the minimum value. + * This will be clearly visible on the servo status and will limit the risk of accidentally + * spinning motors. It would be deadly in flight. + */ + if(outputs.output[i] < -1.0f) { + outputs.output[i] = -1.0f; + } else if(outputs.output[i] > 1.0f) { + outputs.output[i] = 1.0f; + } else { + outputs.output[i] = -1.0f; + } + } + + /* don't go under BLCTRL_MIN_VALUE */ + if(outputs.output[i] < BLCTRL_MIN_VALUE) { + outputs.output[i] = BLCTRL_MIN_VALUE; + } + //_motortest = true; + /* output to BLCtrl's */ + if(_motortest == true) { + mk_servo_test(i); + } else { + //mk_servo_set(i, outputs.output[i]); + mk_servo_set_test(i, outputs.output[i]); // 8Bit + } + + + } + + /* and publish for anyone that cares to see */ + orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), _t_outputs, &outputs); + } + } + + /* how about an arming update? */ + if (fds[1].revents & POLLIN) { + actuator_armed_s aa; + + /* get new value */ + orb_copy(ORB_ID(actuator_armed), _t_armed, &aa); + + /* update PWM servo armed status if armed and not locked down */ + ////up_pwm_servo_arm(aa.armed && !aa.lockdown); + mk_servo_arm(aa.armed && !aa.lockdown); + } + } + + ::close(_t_actuators); + ::close(_t_actuators_effective); + ::close(_t_armed); + + + /* make sure servos are off */ + up_pwm_servo_deinit(); + + log("stopping"); + + /* note - someone else is responsible for restoring the GPIO config */ + + /* tell the dtor that we are exiting */ + _task = -1; + _exit(0); +} + + +int +MK::mk_servo_arm(bool status) +{ + _armed = status; + return 0; +} + + +int +MK::mk_check_for_blctrl(unsigned int count) +{ + _retries = 10; + uint8_t foundMotorCount = 0; + + for(unsigned i=0; i 2047) { + tmpVal = 2047; + } + + + Motor[chan].SetPoint = (uint8_t) tmpVal / 3; // divide 8 + Motor[chan].SetPointLowerBits = (uint8_t) tmpVal % 8; // rest of divide 8 + //rod = (uint8_t) tmpVal % 8; + //Motor[chan].SetPointLowerBits = rod<<1; // rest of divide 8 + Motor[chan].SetPointLowerBits = 0; + + if(_armed == false) { + Motor[chan].SetPoint = 0; + Motor[chan].SetPointLowerBits = 0; + } + + //if(Motor[chan].State & MOTOR_STATE_PRESENT_MASK) { + set_address(BLCTRL_BASE_ADDR + (chan + addrTranslator[chan])); + + if(Motor[chan].Version == BLCTRL_OLD) { + /* + * Old BL-Ctrl 8Bit served. Version < 2.0 + */ + msg[0] = Motor[chan].SetPoint; + if(Motor[chan].RoundCount >= 16) { + // on each 16th cyle we read out the status messages from the blctrl + if (OK == transfer(&msg[0], 1, &result[0], 2)) { + Motor[chan].Current = result[0]; + Motor[chan].MaxPWM = result[1]; + Motor[chan].Temperature = 255;; + } else { + if((Motor[chan].State & MOTOR_STATE_ERROR_MASK) < MOTOR_STATE_ERROR_MASK) Motor[chan].State++; // error + } + Motor[chan].RoundCount = 0; + } else { + if (OK != transfer(&msg[0], 1, nullptr, 0)) { + if((Motor[chan].State & MOTOR_STATE_ERROR_MASK) < MOTOR_STATE_ERROR_MASK) Motor[chan].State++; // error + } + } + + } else { + /* + * New BL-Ctrl 11Bit served. Version >= 2.0 + */ + msg[0] = Motor[chan].SetPoint; + msg[1] = Motor[chan].SetPointLowerBits; + + if(Motor[chan].SetPointLowerBits == 0) { + bytesToSendBL2 = 1; // if setpoint lower bits are zero, we send only the higher bits - this saves time + } + + if(Motor[chan].RoundCount >= 16) { + // on each 16th cyle we read out the status messages from the blctrl + if (OK == transfer(&msg[0], bytesToSendBL2, &result[0], 3)) { + Motor[chan].Current = result[0]; + Motor[chan].MaxPWM = result[1]; + Motor[chan].Temperature = result[2]; + } else { + if((Motor[chan].State & MOTOR_STATE_ERROR_MASK) < MOTOR_STATE_ERROR_MASK) Motor[chan].State++; // error + } + Motor[chan].RoundCount = 0; + } else { + if (OK != transfer(&msg[0], bytesToSendBL2, nullptr, 0)) { + if((Motor[chan].State & MOTOR_STATE_ERROR_MASK) < MOTOR_STATE_ERROR_MASK) Motor[chan].State++; // error + } + } + + } + + Motor[chan].RoundCount++; + //} + + if(showDebug == true) { + debugCounter++; + if(debugCounter == 2000) { + debugCounter = 0; + for(int i=0; i<_num_outputs; i++){ + if(Motor[i].State & MOTOR_STATE_PRESENT_MASK) { + fprintf(stderr, "[mkblctrl] #%i:\tVer: %i\tVal: %i\tCurr: %i\tMaxPWM: %i\tTemp: %i\tState: %i\n", i, Motor[i].Version, Motor[i].SetPoint, Motor[i].Current, Motor[i].MaxPWM, Motor[i].Temperature, Motor[i].State); + } + } + fprintf(stderr, "\n"); + } + } + return 0; +} + +int +MK::mk_servo_set_test(unsigned int chan, float val) +{ + _retries = 0; + int ret; + + float tmpVal = 0; + + uint8_t msg[2] = { 0,0 }; + + tmpVal = (1023 + (1023 * val)); + if(tmpVal > 2048) { + tmpVal = 2048; + } + + Motor[chan].SetPoint = (uint8_t) (tmpVal / 8); + + if(_armed == false) { + Motor[chan].SetPoint = 0; + Motor[chan].SetPointLowerBits = 0; + } + + msg[0] = Motor[chan].SetPoint; + + set_address(BLCTRL_BASE_ADDR + (chan + addrTranslator[chan])); + ret = transfer(&msg[0], 1, nullptr, 0); + + ret = OK; + + return ret; +} + + +int +MK::mk_servo_test(unsigned int chan) +{ + int ret=0; + float tmpVal = 0; + float val = -1; + _retries = 0; + uint8_t msg[2] = { 0,0 }; + + if(debugCounter >= MOTOR_SPINUP_COUNTER) { + debugCounter = 0; + _motor++; + + if(_motor < _num_outputs) { + fprintf(stderr, "[mkblctrl] Motortest - #%i:\tspinup\n", _motor); + } + + if(_motor >= _num_outputs) { + _motor = -1; + _motortest = false; + } + + } + debugCounter++; + + if(_motor == chan) { + val = BLCTRL_MIN_VALUE; + } else { + val = -1; + } + + tmpVal = (1023 + (1023 * val)); + if(tmpVal > 2048) { + tmpVal = 2048; + } + + //Motor[chan].SetPoint = (uint8_t) (tmpVal / 8); + //Motor[chan].SetPointLowerBits = (uint8_t) (tmpVal % 8) & 0x07; + Motor[chan].SetPoint = (uint8_t) tmpVal>>3; + Motor[chan].SetPointLowerBits = (uint8_t) tmpVal & 0x07; + + if(_motor != chan) { + Motor[chan].SetPoint = 0; + Motor[chan].SetPointLowerBits = 0; + } + + if(Motor[chan].Version == BLCTRL_OLD) { + msg[0] = Motor[chan].SetPoint; + } else { + msg[0] = Motor[chan].SetPoint; + msg[1] = Motor[chan].SetPointLowerBits; + } + + set_address(BLCTRL_BASE_ADDR + (chan + addrTranslator[chan])); + if(Motor[chan].Version == BLCTRL_OLD) { + ret = transfer(&msg[0], 1, nullptr, 0); + } else { + ret = transfer(&msg[0], 2, nullptr, 0); + } + + return ret; +} + + +int +MK::control_callback(uintptr_t handle, + uint8_t control_group, + uint8_t control_index, + float &input) +{ + const actuator_controls_s *controls = (actuator_controls_s *)handle; + + input = controls->control[control_index]; + return 0; +} + +int +MK::ioctl(file *filp, int cmd, unsigned long arg) +{ + int ret; + + // XXX disabled, confusing users + //debug("ioctl 0x%04x 0x%08x", cmd, arg); + + /* try it as a GPIO ioctl first */ + ret = gpio_ioctl(filp, cmd, arg); + + if (ret != -ENOTTY) + return ret; + + /* if we are in valid PWM mode, try it as a PWM ioctl as well */ + switch (_mode) { + case MODE_2PWM: + case MODE_4PWM: + ret = pwm_ioctl(filp, cmd, arg); + break; + + default: + debug("not in a PWM mode"); + break; + } + + /* if nobody wants it, let CDev have it */ + if (ret == -ENOTTY) + ret = CDev::ioctl(filp, cmd, arg); + + return ret; +} + +int +MK::pwm_ioctl(file *filp, int cmd, unsigned long arg) +{ + int ret = OK; + int channel; + + lock(); + + switch (cmd) { + case PWM_SERVO_ARM: + ////up_pwm_servo_arm(true); + mk_servo_arm(true); + break; + + case PWM_SERVO_DISARM: + ////up_pwm_servo_arm(false); + mk_servo_arm(false); + break; + + case PWM_SERVO_SET_UPDATE_RATE: + set_pwm_rate(arg); + break; + + + case PWM_SERVO_SET(0) ... PWM_SERVO_SET(_max_actuators - 1): + + /* fake an update to the selected 'servo' channel */ + if ((arg >= 0) && (arg <= 255)) { + channel = cmd - PWM_SERVO_SET(0); + //mk_servo_set(channel, arg); + } else { + ret = -EINVAL; + } + + break; + + case PWM_SERVO_GET(0) ... PWM_SERVO_GET(_max_actuators - 1): + /* copy the current output value from the channel */ + *(servo_position_t *)arg = cmd - PWM_SERVO_GET(0); + break; + + case MIXERIOCGETOUTPUTCOUNT: + /* + if (_mode == MODE_4PWM) { + *(unsigned *)arg = 4; + } else { + *(unsigned *)arg = 2; + } + */ + + *(unsigned *)arg = _num_outputs; + + break; + + case MIXERIOCRESET: + if (_mixers != nullptr) { + delete _mixers; + _mixers = nullptr; + } + + break; + + case MIXERIOCADDSIMPLE: { + mixer_simple_s *mixinfo = (mixer_simple_s *)arg; + + SimpleMixer *mixer = new SimpleMixer(control_callback, + (uintptr_t)&_controls, mixinfo); + + if (mixer->check()) { + delete mixer; + ret = -EINVAL; + + } else { + if (_mixers == nullptr) + _mixers = new MixerGroup(control_callback, + (uintptr_t)&_controls); + + _mixers->add_mixer(mixer); + } + + break; + } + + case MIXERIOCLOADBUF: { + const char *buf = (const char *)arg; + unsigned buflen = strnlen(buf, 1024); + + if (_mixers == nullptr) + _mixers = new MixerGroup(control_callback, (uintptr_t)&_controls); + + if (_mixers == nullptr) { + ret = -ENOMEM; + + } else { + + ret = _mixers->load_from_buf(buf, buflen); + + if (ret != 0) { + debug("mixer load failed with %d", ret); + delete _mixers; + _mixers = nullptr; + ret = -EINVAL; + } + } + break; + } + + default: + ret = -ENOTTY; + break; + } + + unlock(); + + return ret; +} + +void +MK::gpio_reset(void) +{ + /* + * Setup default GPIO config - all pins as GPIOs, GPIO driver chip + * to input mode. + */ + for (unsigned i = 0; i < _ngpio; i++) + stm32_configgpio(_gpio_tab[i].input); + + stm32_gpiowrite(GPIO_GPIO_DIR, 0); + stm32_configgpio(GPIO_GPIO_DIR); +} + +void +MK::gpio_set_function(uint32_t gpios, int function) +{ + /* + * GPIOs 0 and 1 must have the same direction as they are buffered + * by a shared 2-port driver. Any attempt to set either sets both. + */ + if (gpios & 3) { + gpios |= 3; + + /* flip the buffer to output mode if required */ + if (GPIO_SET_OUTPUT == function) + stm32_gpiowrite(GPIO_GPIO_DIR, 1); + } + + /* configure selected GPIOs as required */ + for (unsigned i = 0; i < _ngpio; i++) { + if (gpios & (1 << i)) { + switch (function) { + case GPIO_SET_INPUT: + stm32_configgpio(_gpio_tab[i].input); + break; + + case GPIO_SET_OUTPUT: + stm32_configgpio(_gpio_tab[i].output); + break; + + case GPIO_SET_ALT_1: + if (_gpio_tab[i].alt != 0) + stm32_configgpio(_gpio_tab[i].alt); + + break; + } + } + } + + /* flip buffer to input mode if required */ + if ((GPIO_SET_INPUT == function) && (gpios & 3)) + stm32_gpiowrite(GPIO_GPIO_DIR, 0); +} + +void +MK::gpio_write(uint32_t gpios, int function) +{ + int value = (function == GPIO_SET) ? 1 : 0; + + for (unsigned i = 0; i < _ngpio; i++) + if (gpios & (1 << i)) + stm32_gpiowrite(_gpio_tab[i].output, value); +} + +uint32_t +MK::gpio_read(void) +{ + uint32_t bits = 0; + + for (unsigned i = 0; i < _ngpio; i++) + if (stm32_gpioread(_gpio_tab[i].input)) + bits |= (1 << i); + + return bits; +} + +int +MK::gpio_ioctl(struct file *filp, int cmd, unsigned long arg) +{ + int ret = OK; + + lock(); + + switch (cmd) { + + case GPIO_RESET: + gpio_reset(); + break; + + case GPIO_SET_OUTPUT: + case GPIO_SET_INPUT: + case GPIO_SET_ALT_1: + gpio_set_function(arg, cmd); + break; + + case GPIO_SET_ALT_2: + case GPIO_SET_ALT_3: + case GPIO_SET_ALT_4: + ret = -EINVAL; + break; + + case GPIO_SET: + case GPIO_CLEAR: + gpio_write(arg, cmd); + break; + + case GPIO_GET: + *(uint32_t *)arg = gpio_read(); + break; + + default: + ret = -ENOTTY; + } + + unlock(); + + return ret; +} + +namespace +{ + +enum PortMode { + PORT_MODE_UNSET = 0, + PORT_FULL_GPIO, + PORT_FULL_SERIAL, + PORT_FULL_PWM, + PORT_GPIO_AND_SERIAL, + PORT_PWM_AND_SERIAL, + PORT_PWM_AND_GPIO, +}; + +enum MappingMode { + MAPPING_MK = 0, + MAPPING_PX4, +}; + + enum FrameType { + FRAME_PLUS = 0, + FRAME_X, + }; + +PortMode g_port_mode; + +int +mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest, int px4mode, int frametype) +{ + uint32_t gpio_bits; + MK::Mode servo_mode; + + /* reset to all-inputs */ + g_mk->ioctl(0, GPIO_RESET, 0); + + gpio_bits = 0; + servo_mode = MK::MODE_NONE; + + switch (new_mode) { + case PORT_FULL_GPIO: + case PORT_MODE_UNSET: + /* nothing more to do here */ + break; + + case PORT_FULL_SERIAL: + /* set all multi-GPIOs to serial mode */ + gpio_bits = GPIO_MULTI_1 | GPIO_MULTI_2 | GPIO_MULTI_3 | GPIO_MULTI_4; + break; + + case PORT_FULL_PWM: + /* select 4-pin PWM mode */ + servo_mode = MK::MODE_4PWM; + break; + + case PORT_GPIO_AND_SERIAL: + /* set RX/TX multi-GPIOs to serial mode */ + gpio_bits = GPIO_MULTI_3 | GPIO_MULTI_4; + break; + + case PORT_PWM_AND_SERIAL: + /* select 2-pin PWM mode */ + servo_mode = MK::MODE_2PWM; + /* set RX/TX multi-GPIOs to serial mode */ + gpio_bits = GPIO_MULTI_3 | GPIO_MULTI_4; + break; + + case PORT_PWM_AND_GPIO: + /* select 2-pin PWM mode */ + servo_mode = MK::MODE_2PWM; + break; + } + + /* adjust GPIO config for serial mode(s) */ + if (gpio_bits != 0) + g_mk->ioctl(0, GPIO_SET_ALT_1, gpio_bits); + + /* native PX4 addressing) */ + g_mk->set_px4mode(px4mode); + + /* set frametype (geometry) */ + g_mk->set_frametype(frametype); + + /* (re)set count of used motors */ + g_mk->set_motor_count(motorcount); + + /* (re)set the PWM output mode */ + g_mk->set_mode(servo_mode); + + /* motortest if enabled */ + g_mk->set_motor_test(motortest); + + if ((servo_mode != MK::MODE_NONE) && (update_rate != 0)) + g_mk->set_pwm_rate(update_rate); + + return OK; +} + +int +mk_start(unsigned bus, unsigned motors) +{ + int ret = OK; + + if (g_mk == nullptr) { + + g_mk = new MK(bus); + + if (g_mk == nullptr) { + ret = -ENOMEM; + + } else { + ret = g_mk->init(motors); + + if (ret != OK) { + delete g_mk; + g_mk = nullptr; + } + } + } + + return ret; +} + + +} // namespace + +extern "C" __EXPORT int mkblctrl_main(int argc, char *argv[]); + +int +mkblctrl_main(int argc, char *argv[]) +{ + PortMode new_mode = PORT_MODE_UNSET; + int pwm_update_rate_in_hz = UPDATE_RATE; + int motorcount = 0; + int bus = 1; + bool motortest = false; + int px4mode = MAPPING_MK; + int frametype = FRAME_PLUS; // + plus is default + + /* + * Mode switches. + * + * XXX use getopt? + */ + for (int i = 1; i < argc; i++) { /* argv[0] is "mk" */ + if (!strcmp(argv[i], "mode_quad")) { + new_mode = PORT_FULL_PWM; + motorcount = 4; + } else if (!strcmp(argv[i], "mode_hexa")) { + new_mode = PORT_FULL_PWM; + motorcount = 6; + } else if (!strcmp(argv[i], "mode_octo")) { + new_mode = PORT_FULL_PWM; + motorcount = 8; + } + + /* look for the optional update rate for the supported modes */ + if (strcmp(argv[i], "-u") == 0 || strcmp(argv[i], "--update-rate") == 0) { + if (argc > i + 1) { + pwm_update_rate_in_hz = atoi(argv[i + 1]); + } else { + errx(1, "missing argument for update rate (-u)"); + return 1; + } + } + + /* look for the optional i2c bus parameter */ + if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) { + if (argc > i + 1) { + bus = atoi(argv[i + 1]); + } else { + errx(1, "missing argument for i2c bus (-b)"); + return 1; + } + } + + /* look for the optional frame parameter */ + if (strcmp(argv[i], "-f") == 0 || strcmp(argv[i], "--frame") == 0) { + if (argc > i + 1) { + if(strcmp(argv[i + 1], "+") == 0 || strcmp(argv[i + 1], "x") == 0 || strcmp(argv[i + 1], "X") == 0) { + if(strcmp(argv[i + 1], "+") == 0) { + frametype = FRAME_PLUS; + } else { + frametype = FRAME_PLUS; + } + } else { + errx(1, "only + or x for frametype supported !"); + } + } else { + errx(1, "missing argument for frametype (-f)"); + return 1; + } + } + + /* look for the optional geometry parameter */ + if (strcmp(argv[i], "-px4mode") == 0) { + px4mode = MAPPING_PX4; + } + + /* look for the optional test parameter */ + if (strcmp(argv[i], "-t") == 0) { + motortest = true; + } + + } + + if(new_mode == PORT_MODE_UNSET) { + fprintf(stderr, "mkblctrl: unrecognised command, try:\n"); + fprintf(stderr, " mode_quad, mode_hexa, mode_octo [-b i2c_bus_number] [-u update_rate_in_hz] [-t motortest] [-px4mode] [-f frame{+/x}]\n"); + exit(1); + } + + if (mk_start(bus, motorcount) != OK) + errx(1, "failed to start the MK-BLCtrl driver"); + + + /* was a new mode set? */ + if (new_mode != PORT_MODE_UNSET) { + + /* yes but it's the same mode */ + //if (new_mode == g_port_mode) + //return OK; + + /* switch modes */ + fprintf(stderr, "[mkblctrl] %iHz Update Rate\n",pwm_update_rate_in_hz); + return mk_new_mode(new_mode, pwm_update_rate_in_hz, motorcount, motortest, px4mode, frametype); + } + + /* test, etc. here g*/ + + exit(1); +} diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig index 80cf6f312c..5bac6214c9 100644 --- a/nuttx/configs/px4fmu/nsh/appconfig +++ b/nuttx/configs/px4fmu/nsh/appconfig @@ -124,6 +124,7 @@ CONFIGURED_APPS += drivers/blinkm CONFIGURED_APPS += drivers/stm32/tone_alarm CONFIGURED_APPS += drivers/stm32/adc CONFIGURED_APPS += drivers/px4fmu +CONFIGURED_APPS += drivers/mkblctrl CONFIGURED_APPS += drivers/hil CONFIGURED_APPS += drivers/gps CONFIGURED_APPS += drivers/mb12xx From ed9fbbce5946d22ded1519ddec1b5ff6a8f2e511 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 25 Apr 2013 17:25:42 +0200 Subject: [PATCH 02/23] HIL bugfixing --- apps/drivers/gps/ubx.cpp | 18 ++++++++---- apps/examples/kalman_demo/KalmanNav.cpp | 2 ++ apps/mavlink/mavlink_receiver.c | 14 +++++---- apps/uORB/topics/vehicle_gps_position.h | 39 +++++++++++++------------ 4 files changed, 43 insertions(+), 30 deletions(-) diff --git a/apps/drivers/gps/ubx.cpp b/apps/drivers/gps/ubx.cpp index 0d4894b8de..c150f52715 100644 --- a/apps/drivers/gps/ubx.cpp +++ b/apps/drivers/gps/ubx.cpp @@ -33,7 +33,14 @@ * ****************************************************************************/ -/* @file U-Blox protocol implementation */ +/** + * @file ubx.cpp + * + * U-Blox protocol implementation. Following u-blox 6/7 Receiver Description + * including Prototol Specification. + * + * @see http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf + */ #include #include @@ -633,16 +640,17 @@ UBX::handle_message() } case NAV_VELNED: { -// printf("GOT NAV_VELNED MESSAGE\n"); if (!_waiting_for_ack) { + /* 35.15 NAV-VELNED (0x01 0x12) message (page 181 / 210 of reference manual */ gps_bin_nav_velned_packet_t *packet = (gps_bin_nav_velned_packet_t *) _rx_buffer; _gps_position->vel_m_s = (float)packet->speed * 1e-2f; - _gps_position->vel_n_m_s = (float)packet->velN * 1e-2f; - _gps_position->vel_e_m_s = (float)packet->velE * 1e-2f; - _gps_position->vel_d_m_s = (float)packet->velD * 1e-2f; + _gps_position->vel_n_m_s = (float)packet->velN * 1e-2f; /* NED NORTH velocity */ + _gps_position->vel_e_m_s = (float)packet->velE * 1e-2f; /* NED EAST velocity */ + _gps_position->vel_d_m_s = (float)packet->velD * 1e-2f; /* NED DOWN velocity */ _gps_position->cog_rad = (float)packet->heading * M_DEG_TO_RAD_F * 1e-5f; + _gps_position->c_variance_rad = (float)packet->cAcc * M_DEG_TO_RAD_F * 1e-5f; _gps_position->vel_ned_valid = true; _gps_position->timestamp_velocity = hrt_absolute_time(); } diff --git a/apps/examples/kalman_demo/KalmanNav.cpp b/apps/examples/kalman_demo/KalmanNav.cpp index 6df454a555..4ef150da1e 100644 --- a/apps/examples/kalman_demo/KalmanNav.cpp +++ b/apps/examples/kalman_demo/KalmanNav.cpp @@ -355,6 +355,8 @@ int KalmanNav::predictState(float dt) float LDot = vN / R; float lDot = vE / (cosLSing * R); float rotRate = 2 * omega + lDot; + + // XXX position prediction using speed float vNDot = fN - vE * rotRate * sinL + vD * LDot; float vDDot = fD - vE * rotRate * cosL - diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c index a30f0bf3c1..22c2fcdade 100644 --- a/apps/mavlink/mavlink_receiver.c +++ b/apps/mavlink/mavlink_receiver.c @@ -477,25 +477,27 @@ handle_message(mavlink_message_t *msg) /* gps */ hil_gps.timestamp_position = gps.time_usec; -// hil_gps.counter = hil_counter++; hil_gps.time_gps_usec = gps.time_usec; hil_gps.lat = gps.lat; hil_gps.lon = gps.lon; hil_gps.alt = gps.alt; -// hil_gps.counter_pos_valid = hil_counter++; hil_gps.eph_m = (float)gps.eph * 1e-2f; // from cm to m hil_gps.epv_m = (float)gps.epv * 1e-2f; // from cm to m hil_gps.s_variance_m_s = 5.0f; hil_gps.p_variance_m = hil_gps.eph_m * hil_gps.eph_m; hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s - /* gps.cog is in degrees 0..360 * 100, heading is -PI..PI */ - float heading_rad = gps.cog * M_DEG_TO_RAD_F * 1e-2f - M_PI_F; + /* gps.cog is in degrees 0..360 * 100, heading is -PI..+PI */ + float heading_rad = gps.cog * M_DEG_TO_RAD_F * 1e-2f; + /* go back to -PI..PI */ + if (heading_rad > M_PI_F) + heading_rad -= 2.0f * M_PI_F; hil_gps.vel_n_m_s = (float)gps.vel * 1e-2f * cosf(heading_rad); hil_gps.vel_e_m_s = (float)gps.vel * 1e-2f * sinf(heading_rad); hil_gps.vel_d_m_s = 0.0f; - /* COG (course over ground) is speced as 0..360 degrees (compass) */ - hil_gps.cog_rad = heading_rad + M_PI_F; // from deg*100 to rad + hil_gps.vel_ned_valid = true; + /* COG (course over ground) is speced as -PI..+PI */ + hil_gps.cog_rad = heading_rad; hil_gps.fix_type = gps.fix_type; hil_gps.satellites_visible = gps.satellites_visible; diff --git a/apps/uORB/topics/vehicle_gps_position.h b/apps/uORB/topics/vehicle_gps_position.h index 5463a460da..0a7fb4e9da 100644 --- a/apps/uORB/topics/vehicle_gps_position.h +++ b/apps/uORB/topics/vehicle_gps_position.h @@ -55,38 +55,39 @@ */ struct vehicle_gps_position_s { - uint64_t timestamp_position; /**< Timestamp for position information */ - int32_t lat; /**< Latitude in 1E7 degrees */ - int32_t lon; /**< Longitude in 1E7 degrees */ - int32_t alt; /**< Altitude in 1E3 meters (millimeters) above MSL */ + uint64_t timestamp_position; /**< Timestamp for position information */ + int32_t lat; /**< Latitude in 1E7 degrees */ + int32_t lon; /**< Longitude in 1E7 degrees */ + int32_t alt; /**< Altitude in 1E3 meters (millimeters) above MSL */ uint64_t timestamp_variance; float s_variance_m_s; /**< speed accuracy estimate m/s */ - float p_variance_m; /**< position accuracy estimate m */ - uint8_t fix_type; /**< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. */ + float p_variance_m; /**< position accuracy estimate m */ + float c_variance_rad; /**< course accuracy estimate rad */ + uint8_t fix_type; /**< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. */ - float eph_m; /**< GPS HDOP horizontal dilution of position in m */ - float epv_m; /**< GPS VDOP horizontal dilution of position in m */ + float eph_m; /**< GPS HDOP horizontal dilution of position in m */ + float epv_m; /**< GPS VDOP horizontal dilution of position in m */ - uint64_t timestamp_velocity; /**< Timestamp for velocity informations */ - float vel_m_s; /**< GPS ground speed (m/s) */ - float vel_n_m_s; /**< GPS ground speed in m/s */ - float vel_e_m_s; /**< GPS ground speed in m/s */ - float vel_d_m_s; /**< GPS ground speed in m/s */ - float cog_rad; /**< Course over ground (NOT heading, but direction of movement) in rad */ - bool vel_ned_valid; /**< Flag to indicate if NED speed is valid */ + uint64_t timestamp_velocity; /**< Timestamp for velocity informations */ + float vel_m_s; /**< GPS ground speed (m/s) */ + float vel_n_m_s; /**< GPS ground speed in m/s */ + float vel_e_m_s; /**< GPS ground speed in m/s */ + float vel_d_m_s; /**< GPS ground speed in m/s */ + float cog_rad; /**< Course over ground (NOT heading, but direction of movement) in rad, -PI..PI */ + bool vel_ned_valid; /**< Flag to indicate if NED speed is valid */ uint64_t timestamp_time; /**< Timestamp for time information */ uint64_t time_gps_usec; /**< Timestamp (microseconds in GPS format), this is the timestamp which comes from the gps module */ - uint64_t timestamp_satellites; /**< Timestamp for sattelite information */ + uint64_t timestamp_satellites; /**< Timestamp for sattelite information */ uint8_t satellites_visible; /**< Number of satellites visible. If unknown, set to 255 */ uint8_t satellite_prn[20]; /**< Global satellite ID */ uint8_t satellite_used[20]; /**< 0: Satellite not used, 1: used for localization */ - uint8_t satellite_elevation[20]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */ - uint8_t satellite_azimuth[20]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */ + uint8_t satellite_elevation[20]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */ + uint8_t satellite_azimuth[20]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */ uint8_t satellite_snr[20]; /**< Signal to noise ratio of satellite */ - bool satellite_info_available; /**< 0 for no info, 1 for info available */ + bool satellite_info_available; /**< 0 for no info, 1 for info available */ }; /** From e37f471ac4ce52e724b0d89714d9db6e1d16ee8e Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 25 Apr 2013 23:59:46 +0400 Subject: [PATCH 03/23] 6-point accelerometer calibration implemented --- apps/commander/accelerometer_calibration.c | 414 +++++++++++++++++++++ apps/commander/accelerometer_calibration.h | 19 + apps/commander/commander.c | 125 +------ 3 files changed, 435 insertions(+), 123 deletions(-) create mode 100644 apps/commander/accelerometer_calibration.c create mode 100644 apps/commander/accelerometer_calibration.h diff --git a/apps/commander/accelerometer_calibration.c b/apps/commander/accelerometer_calibration.c new file mode 100644 index 0000000000..f950398815 --- /dev/null +++ b/apps/commander/accelerometer_calibration.c @@ -0,0 +1,414 @@ +/* + * accelerometer_calibration.c + * + * Copyright (C) 2013 Anton Babushkin. All rights reserved. + * Author: Anton Babushkin + * + * Transform acceleration vector to true orientation and scale + * + * * * * Model * * * + * accel_corr = accel_T * (accel_raw - accel_offs) + * + * accel_corr[3] - fully corrected acceleration vector in body frame + * accel_T[3][3] - accelerometers transform matrix, rotation and scaling transform + * accel_raw[3] - raw acceleration vector + * accel_offs[3] - acceleration offset vector + * + * * * * Calibration * * * + * + * Reference vectors + * accel_corr_ref[6][3] = [ g 0 0 ] // nose up + * | -g 0 0 | // nose down + * | 0 g 0 | // left side down + * | 0 -g 0 | // right side down + * | 0 0 g | // on back + * [ 0 0 -g ] // level + * accel_raw_ref[6][3] + * + * accel_corr_ref[i] = accel_T * (accel_raw_ref[i] - accel_offs), i = 0...5 + * + * 6 reference vectors * 3 axes = 18 equations + * 9 (accel_T) + 3 (accel_offs) = 12 unknown constants + * + * Find accel_offs + * + * accel_offs[i] = (accel_raw_ref[i*2][i] + accel_raw_ref[i*2+1][i]) / 2 + * + * + * Find accel_T + * + * 9 unknown constants + * need 9 equations -> use 3 of 6 measurements -> 3 * 3 = 9 equations + * + * accel_corr_ref[i*2] = accel_T * (accel_raw_ref[i*2] - accel_offs), i = 0...2 + * + * Solve separate system for each row of accel_T: + * + * accel_corr_ref[j*2][i] = accel_T[i] * (accel_raw_ref[j*2] - accel_offs), j = 0...2 + * + * A * x = b + * + * x = [ accel_T[0][i] ] + * | accel_T[1][i] | + * [ accel_T[2][i] ] + * + * b = [ accel_corr_ref[0][i] ] // One measurement per axis is enough + * | accel_corr_ref[2][i] | + * [ accel_corr_ref[4][i] ] + * + * a[i][j] = accel_raw_ref[i][j] - accel_offs[j], i = 0;2;4, j = 0...2 + * + * Matrix A is common for all three systems: + * A = [ a[0][0] a[0][1] a[0][2] ] + * | a[2][0] a[2][1] a[2][2] | + * [ a[4][0] a[4][1] a[4][2] ] + * + * x = A^-1 * b + * + * accel_T = A^-1 * g + * g = 9.80665 + */ + +#include "accelerometer_calibration.h" + +#include +#include +#include +#include +#include +#include + +void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd) { + /* announce change */ + mavlink_log_info(mavlink_fd, "accelerometer calibration started"); + /* set to accel calibration mode */ + status->flag_preflight_accel_calibration = true; + state_machine_publish(status_pub, status, mavlink_fd); + + float accel_offs_scaled[3]; + float accel_scale[3]; + int res = do_accel_calibration_mesurements(mavlink_fd, accel_offs_scaled, accel_scale); + if (res == OK) { + /* measurements complete successfully, set parameters */ + if (param_set(param_find("SENS_ACC_XOFF"), &(accel_offs_scaled[0])) + || param_set(param_find("SENS_ACC_YOFF"), &(accel_offs_scaled[1])) + || param_set(param_find("SENS_ACC_ZOFF"), &(accel_offs_scaled[2])) + || param_set(param_find("SENS_ACC_XSCALE"), &(accel_scale[0])) + || param_set(param_find("SENS_ACC_YSCALE"), &(accel_scale[1])) + || param_set(param_find("SENS_ACC_ZSCALE"), &(accel_scale[2]))) { + mavlink_log_critical(mavlink_fd, "Setting offs or scale failed!"); + } + + int fd = open(ACCEL_DEVICE_PATH, 0); + struct accel_scale ascale = { + accel_offs_scaled[0], + accel_scale[0], + accel_offs_scaled[1], + accel_scale[1], + accel_offs_scaled[2], + accel_scale[2], + }; + + if (OK != ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&ascale)) + warn("WARNING: failed to set scale / offsets for accel"); + + close(fd); + + /* auto-save to EEPROM */ + int save_ret = param_save_default(); + + if (save_ret != 0) { + warn("WARNING: auto-save of params to storage failed"); + } + + mavlink_log_info(mavlink_fd, "accel calibration done"); + + tune_confirm(); + sleep(2); + tune_confirm(); + sleep(2); + /* third beep by cal end routine */ + } else { + /* measurements error */ + mavlink_log_info(mavlink_fd, "accel calibration aborted"); + tune_error(); + sleep(2); + } + + /* exit accel calibration mode */ + status->flag_preflight_accel_calibration = false; + state_machine_publish(status_pub, status, mavlink_fd); +} + +int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs_scaled[3], float accel_scale[3]) { + const int samples_num = 2500; + + int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined)); + + int16_t accel_raw_ref[6][3]; + bool data_collected[6] = { false, false, false, false, false, false }; + const char *orientation_strs[6] = { "x+", "x-", "y+", "y-", "z+", "z-" }; + while (true) { + bool done = true; + char str[80]; + int str_ptr; + str_ptr = sprintf(str, "keep vehicle still:"); + for (int i = 0; i < 6; i++) { + if (!data_collected[i]) { + str_ptr += sprintf(&(str[str_ptr]), " %s", orientation_strs[i]); + done = false; + } + } + if (done) { + mavlink_log_info(mavlink_fd, "all accel measurements complete"); + break; + } else { + mavlink_log_info(mavlink_fd, str); + int orient = detect_orientation(mavlink_fd, sensor_combined_sub); + if (orient < 0) { + sprintf(str, "orientation detection error: %i", orient); + mavlink_log_info(mavlink_fd, str); + return ERROR; + } + mavlink_log_info(mavlink_fd, "accel measurement started"); + read_accelerometer_raw_avg(sensor_combined_sub, &(accel_raw_ref[orient][0]), samples_num); + //mavlink_log_info(mavlink_fd, "accel measurement complete"); + str_ptr = sprintf(str, "complete: %i [ %i %i %i ]", orient, accel_raw_ref[orient][0], accel_raw_ref[orient][1], accel_raw_ref[orient][2]); + mavlink_log_info(mavlink_fd, str); + data_collected[orient] = true; + tune_confirm(); + } + } + close(sensor_combined_sub); + + /* calculate offsets and rotation+scale matrix */ + int16_t accel_offs[3]; + float accel_T[3][3]; + int res = calculate_calibration_values(accel_raw_ref, accel_T, accel_offs, CONSTANTS_ONE_G); + if (res != 0) { + mavlink_log_info(mavlink_fd, "calibration values calculation error"); + return ERROR; + } + + char str[80]; + sprintf(str, "accel offsets: [ %i %i %i ]", accel_offs[0], accel_offs[1], accel_offs[2]); + mavlink_log_info(mavlink_fd, str); + //mavlink_log_info(mavlink_fd, "accel transform matrix:"); + for (int i = 0; i < 3; i++) { + //sprintf(str, "\t[ %0.6f %0.6f %0.6f ]", accel_T[i][0], accel_T[i][1], accel_T[i][2]); + //mavlink_log_info(mavlink_fd, str); + } + + /* convert raw accel offset to scaled and transform matrix to scales + * rotation part of transform matrix is not used by now */ + for (int i = 0; i < 3; i++) { + accel_offs_scaled[i] = accel_offs[i] * accel_T[i][i]; + accel_scale[i] = accel_T[i][i]; + } + + return OK; +} + +/* + * Wait for vehicle become still and detect it's orientation. + * + * @return 0..5 according to orientation when vehicle is still and ready for measurements, + * ERROR if vehicle is not still after 10s or orientation error is more than 20% + */ +int detect_orientation(int mavlink_fd, int sub_sensor_combined) { + struct sensor_combined_s sensor; + /* exponential moving average of accel */ + float accel_ema[3] = { 0.0f, 0.0f, 0.0f }; + /* max-hold dispersion of accel */ + float accel_disp[3] = { 0.0f, 0.0f, 0.0f }; + float accel_len2 = 0.0f; + /* EMA time constant in seconds*/ + float ema_len = 0.2f; + /* set "still" threshold to 0.005 m/s^2 */ + float still_thr2 = pow(0.05f / CONSTANTS_ONE_G, 2); + /* set accel error threshold to 20% of accel vector length */ + float accel_err_thr = 0.2f; + /* still time required in us */ + int64_t still_time = 2000000; + struct pollfd fds[1] = { { .fd = sub_sensor_combined, .events = POLLIN } }; + + hrt_abstime t_start = hrt_absolute_time(); + /* set deadline to 20s */ + hrt_abstime timeout = 20000000; + hrt_abstime t_timeout = t_start + timeout; + hrt_abstime t = t_start; + hrt_abstime t_prev = t_start; + hrt_abstime t_still = 0; + while (true) { + /* wait blocking for new data */ + int poll_ret = poll(fds, 1, 1000); + if (poll_ret) { + orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &sensor); + t = hrt_absolute_time(); + float dt = (t - t_prev) / 1000000.0f; + t_prev = t; + float w = dt / ema_len; + for (int i = 0; i < 3; i++) { + accel_ema[i] = accel_ema[i] * (1.0f - w) + sensor.accelerometer_raw[i] * w; + float d = (float) sensor.accelerometer_raw[i] - accel_ema[i]; + d = d * d; + accel_disp[i] = accel_disp[i] * (1.0f - w); + if (d > accel_disp[i]) + accel_disp[i] = d; + } + accel_len2 = accel_ema[0] * accel_ema[0] + accel_ema[1] * accel_ema[1] + accel_ema[2] * accel_ema[2]; + float still_thr_raw2 = still_thr2 * accel_len2; + if ( accel_disp[0] < still_thr_raw2 && + accel_disp[1] < still_thr_raw2 && + accel_disp[2] < still_thr_raw2 ) { + /* is still now */ + if (t_still == 0) { + /* first time */ + mavlink_log_info(mavlink_fd, "still"); + t_still = t; + t_timeout = t + timeout; + } else { + /* still since t_still */ + if ((int64_t) t - (int64_t) t_still > still_time) { + /* vehicle is still, exit from the loop to detection of its orientation */ + break; + } + } + } else { + /* not still, reset still start time */ + if (t_still != 0) { + mavlink_log_info(mavlink_fd, "moving"); + t_still = 0; + } + } + } else if (poll_ret == 0) { + /* any poll failure for 1s is a reason to abort */ + mavlink_log_info(mavlink_fd, "ERROR: poll failure"); + return -3; + } + if (t > t_timeout) { + mavlink_log_info(mavlink_fd, "ERROR: timeout"); + return -1; + } + } + float accel_len = sqrt(accel_len2); + float accel_err_thr_raw = accel_len * accel_err_thr; + char str[80]; + sprintf(str, "ema: [ %.1f %.1f %.1f ]", accel_ema[0], accel_ema[1], accel_ema[2]); + mavlink_log_info(mavlink_fd, str); + sprintf(str, "disp: [ %.1f %.1f %.1f ]", accel_disp[0], accel_disp[1], accel_disp[2]); + mavlink_log_info(mavlink_fd, str); + if ( fabs(accel_ema[0] - accel_len) < accel_err_thr_raw && + fabs(accel_ema[1]) < accel_err_thr_raw && + fabs(accel_ema[2]) < accel_err_thr_raw ) + return 0; // [ g, 0, 0 ] + if ( fabs(accel_ema[0] + accel_len) < accel_err_thr_raw && + fabs(accel_ema[1]) < accel_err_thr_raw && + fabs(accel_ema[2]) < accel_err_thr_raw ) + return 1; // [ -g, 0, 0 ] + if ( fabs(accel_ema[0]) < accel_err_thr_raw && + fabs(accel_ema[1] - accel_len) < accel_err_thr_raw && + fabs(accel_ema[2]) < accel_err_thr_raw ) + return 2; // [ 0, g, 0 ] + if ( fabs(accel_ema[0]) < accel_err_thr_raw && + fabs(accel_ema[1] + accel_len) < accel_err_thr_raw && + fabs(accel_ema[2]) < accel_err_thr_raw ) + return 3; // [ 0, -g, 0 ] + if ( abs(accel_ema[0]) < accel_err_thr_raw && + abs(accel_ema[1]) < accel_err_thr_raw && + abs(accel_ema[2] - accel_len) < accel_err_thr_raw ) + return 4; // [ 0, 0, g ] + if ( abs(accel_ema[0]) < accel_err_thr_raw && + abs(accel_ema[1]) < accel_err_thr_raw && + abs(accel_ema[2] + accel_len) < accel_err_thr_raw ) + return 5; // [ 0, 0, -g ] + mavlink_log_info(mavlink_fd, "ERROR: invalid orientation"); + return -2; // Can't detect orientation +} + +/* + * Read specified number of accelerometer samples, calculate average and dispersion. + */ +int read_accelerometer_raw_avg(int sensor_combined_sub, int16_t accel_avg[3], int samples_num) { + struct pollfd fds[1] = { { .fd = sensor_combined_sub, .events = POLLIN } }; + int count = 0; + int32_t accel_sum[3] = { 0, 0, 0 }; + while (count < samples_num) { + int poll_ret = poll(fds, 1, 1000); + if (poll_ret == 1) { + struct sensor_combined_s sensor; + orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor); + for (int i = 0; i < 3; i++) { + accel_sum[i] += sensor.accelerometer_raw[i]; + } + count++; + } else { + return ERROR; + } + } + for (int i = 0; i < 3; i++) { + accel_avg[i] = (accel_sum[i] + count / 2) / count; + } + /* calculate dispersion */ + return OK; +} + +/* + * Convert raw values from accelerometers to m/s^2. + */ +void acceleration_raw_to_m_s2(float accel_corr[3], int16_t accel_raw[3], + float accel_T[3][3], int16_t accel_offs[3]) { + for (int i = 0; i < 3; i++) { + accel_corr[i] = 0.0f; + for (int j = 0; j < 3; j++) { + accel_corr[i] += accel_T[i][j] * (accel_raw[j] - accel_offs[j]); + } + } +} + +int mat_invert3(float src[3][3], float dst[3][3]) { + float det = src[0][0] * (src[1][1] * src[2][2] - src[1][2] * src[2][1]) - + src[0][1] * (src[1][0] * src[2][2] - src[1][2] * src[2][0]) + + src[0][2] * (src[1][0] * src[2][1] - src[1][1] * src[2][0]); + if (det == 0.0) + return -1; // Singular matrix + dst[0][0] = (src[1][1] * src[2][2] - src[1][2] * src[2][1]) / det; + dst[1][0] = (src[1][2] * src[2][0] - src[1][0] * src[2][2]) / det; + dst[2][0] = (src[1][0] * src[2][1] - src[1][1] * src[2][0]) / det; + dst[0][1] = (src[0][2] * src[2][1] - src[0][1] * src[2][2]) / det; + dst[1][1] = (src[0][0] * src[2][2] - src[0][2] * src[2][0]) / det; + dst[2][1] = (src[0][1] * src[2][0] - src[0][0] * src[2][1]) / det; + dst[0][2] = (src[0][1] * src[1][2] - src[0][2] * src[1][1]) / det; + dst[1][2] = (src[0][2] * src[1][0] - src[0][0] * src[1][2]) / det; + dst[2][2] = (src[0][0] * src[1][1] - src[0][1] * src[1][0]) / det; + return 0; +} + +int calculate_calibration_values(int16_t accel_raw_ref[6][3], + float accel_T[3][3], int16_t accel_offs[3], float g) { + /* calculate raw offsets */ + for (int i = 0; i < 3; i++) { + accel_offs[i] = (int16_t) (((int32_t) (accel_raw_ref[i * 2][i]) + + (int32_t) (accel_raw_ref[i * 2 + 1][i])) / 2); + } + /* fill matrix A for linear equations system*/ + float mat_A[3][3]; + memset(mat_A, 0, sizeof(mat_A)); + for (int i = 0; i < 3; i++) { + for (int j = 0; j < 3; j++) { + float a = (accel_raw_ref[i * 2][j] - accel_offs[j]); + mat_A[i][j] = a; + } + } + /* calculate inverse matrix for A */ + float mat_A_inv[3][3]; + mat_invert3(mat_A, mat_A_inv); + for (int i = 0; i < 3; i++) { + /* copy results to accel_T */ + for (int j = 0; j < 3; j++) { + /* simplify matrices mult because b has only one non-zero element == g at index i */ + accel_T[j][i] = mat_A_inv[j][i] * g; + } + } + return 0; +} diff --git a/apps/commander/accelerometer_calibration.h b/apps/commander/accelerometer_calibration.h new file mode 100644 index 0000000000..acf45b6b6e --- /dev/null +++ b/apps/commander/accelerometer_calibration.h @@ -0,0 +1,19 @@ +/* + * accelerometer_calibration.h + * + * Created on: 25.04.2013 + * Author: ton + */ + +#ifndef ACCELEROMETER_CALIBRATION_H_ +#define ACCELEROMETER_CALIBRATION_H_ + +#include +#include + +void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd); +int detect_orientation(int mavlink_fd, int sub_sensor_combined); +int mat_invert3(float src[3][3], float dst[3][3]); +int calculate_calibration_values(int16_t accel_raw_ref[6][3], float accel_T[3][3], int16_t accel_offs[3], float g); + +#endif /* ACCELEROMETER_CALIBRATION_H_ */ diff --git a/apps/commander/commander.c b/apps/commander/commander.c index 7c0a25f862..0f18d6cef5 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -94,7 +94,7 @@ #include #include "calibration_routines.h" - +#include "accelerometer_calibration.h" PARAM_DEFINE_INT32(SYS_FAILSAVE_LL, 0); /**< Go into low-level failsafe after 0 ms */ //PARAM_DEFINE_INT32(SYS_FAILSAVE_HL, 0); /**< Go into high-level failsafe after 0 ms */ @@ -158,7 +158,6 @@ static int led_off(int led); static void do_gyro_calibration(int status_pub, struct vehicle_status_s *status); static void do_mag_calibration(int status_pub, struct vehicle_status_s *status); static void do_rc_calibration(int status_pub, struct vehicle_status_s *status); -static void do_accel_calibration(int status_pub, struct vehicle_status_s *status); static void handle_command(int status_pub, struct vehicle_status_s *current_status, struct vehicle_command_s *cmd); int trigger_audio_alarm(uint8_t old_mode, uint8_t old_state, uint8_t new_mode, uint8_t new_state); @@ -666,126 +665,6 @@ void do_gyro_calibration(int status_pub, struct vehicle_status_s *status) close(sub_sensor_combined); } -void do_accel_calibration(int status_pub, struct vehicle_status_s *status) -{ - /* announce change */ - - mavlink_log_info(mavlink_fd, "keep it level and still"); - /* set to accel calibration mode */ - status->flag_preflight_accel_calibration = true; - state_machine_publish(status_pub, status, mavlink_fd); - - const int calibration_count = 2500; - - int sub_sensor_combined = orb_subscribe(ORB_ID(sensor_combined)); - struct sensor_combined_s raw; - - int calibration_counter = 0; - float accel_offset[3] = {0.0f, 0.0f, 0.0f}; - - int fd = open(ACCEL_DEVICE_PATH, 0); - struct accel_scale ascale_null = { - 0.0f, - 1.0f, - 0.0f, - 1.0f, - 0.0f, - 1.0f, - }; - - if (OK != ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&ascale_null)) - warn("WARNING: failed to set scale / offsets for accel"); - - close(fd); - - while (calibration_counter < calibration_count) { - - /* wait blocking for new data */ - struct pollfd fds[1] = { { .fd = sub_sensor_combined, .events = POLLIN } }; - - int poll_ret = poll(fds, 1, 1000); - - if (poll_ret) { - orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &raw); - accel_offset[0] += raw.accelerometer_m_s2[0]; - accel_offset[1] += raw.accelerometer_m_s2[1]; - accel_offset[2] += raw.accelerometer_m_s2[2]; - calibration_counter++; - - } else if (poll_ret == 0) { - /* any poll failure for 1s is a reason to abort */ - mavlink_log_info(mavlink_fd, "acceleration calibration aborted"); - return; - } - } - - accel_offset[0] = accel_offset[0] / calibration_count; - accel_offset[1] = accel_offset[1] / calibration_count; - accel_offset[2] = accel_offset[2] / calibration_count; - - if (isfinite(accel_offset[0]) && isfinite(accel_offset[1]) && isfinite(accel_offset[2])) { - - /* add the removed length from x / y to z, since we induce a scaling issue else */ - float total_len = sqrtf(accel_offset[0] * accel_offset[0] + accel_offset[1] * accel_offset[1] + accel_offset[2] * accel_offset[2]); - - /* if length is correct, zero results here */ - accel_offset[2] = accel_offset[2] + total_len; - - float scale = 9.80665f / total_len; - - if (param_set(param_find("SENS_ACC_XOFF"), &(accel_offset[0])) - || param_set(param_find("SENS_ACC_YOFF"), &(accel_offset[1])) - || param_set(param_find("SENS_ACC_ZOFF"), &(accel_offset[2])) - || param_set(param_find("SENS_ACC_XSCALE"), &(scale)) - || param_set(param_find("SENS_ACC_YSCALE"), &(scale)) - || param_set(param_find("SENS_ACC_ZSCALE"), &(scale))) { - mavlink_log_critical(mavlink_fd, "Setting offs or scale failed!"); - } - - fd = open(ACCEL_DEVICE_PATH, 0); - struct accel_scale ascale = { - accel_offset[0], - scale, - accel_offset[1], - scale, - accel_offset[2], - scale, - }; - - if (OK != ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&ascale)) - warn("WARNING: failed to set scale / offsets for accel"); - - close(fd); - - /* auto-save to EEPROM */ - int save_ret = param_save_default(); - - if (save_ret != 0) { - warn("WARNING: auto-save of params to storage failed"); - } - - //char buf[50]; - //sprintf(buf, "[cmd] accel cal: x:%8.4f y:%8.4f z:%8.4f\n", (double)accel_offset[0], (double)accel_offset[1], (double)accel_offset[2]); - //mavlink_log_info(mavlink_fd, buf); - mavlink_log_info(mavlink_fd, "accel calibration done"); - - tune_confirm(); - sleep(2); - tune_confirm(); - sleep(2); - /* third beep by cal end routine */ - - } else { - mavlink_log_info(mavlink_fd, "accel calibration FAILED (NaN)"); - } - - /* exit accel calibration mode */ - status->flag_preflight_accel_calibration = false; - state_machine_publish(status_pub, status, mavlink_fd); - - close(sub_sensor_combined); -} - void do_airspeed_calibration(int status_pub, struct vehicle_status_s *status) { /* announce change */ @@ -1040,7 +919,7 @@ void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_sta if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) { mavlink_log_info(mavlink_fd, "CMD starting accel cal"); tune_confirm(); - do_accel_calibration(status_pub, ¤t_status); + do_accel_calibration(status_pub, ¤t_status, mavlink_fd); tune_confirm(); mavlink_log_info(mavlink_fd, "CMD finished accel cal"); do_state_update(status_pub, ¤t_status, mavlink_fd, SYSTEM_STATE_STANDBY); From 593e3252dd90b2437862aba1c8a54b5c6edb5600 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Fri, 26 Apr 2013 13:52:25 +0400 Subject: [PATCH 04/23] Added hysteresis to still detector --- apps/commander/accelerometer_calibration.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/apps/commander/accelerometer_calibration.c b/apps/commander/accelerometer_calibration.c index f950398815..9e7a3b99e0 100644 --- a/apps/commander/accelerometer_calibration.c +++ b/apps/commander/accelerometer_calibration.c @@ -274,7 +274,9 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { break; } } - } else { + } else if ( accel_disp[0] > still_thr_raw2 * 2.0f || + accel_disp[1] > still_thr_raw2 * 2.0f || + accel_disp[2] > still_thr_raw2 * 2.0f) { /* not still, reset still start time */ if (t_still != 0) { mavlink_log_info(mavlink_fd, "moving"); From 26f9a1d42c6402a283a679e66236f247fd274cd2 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Fri, 26 Apr 2013 15:25:17 +0400 Subject: [PATCH 05/23] abs/fabs bugfix, logging cleanup --- apps/commander/accelerometer_calibration.c | 80 ++++++++-------------- 1 file changed, 29 insertions(+), 51 deletions(-) diff --git a/apps/commander/accelerometer_calibration.c b/apps/commander/accelerometer_calibration.c index 9e7a3b99e0..f607b6da69 100644 --- a/apps/commander/accelerometer_calibration.c +++ b/apps/commander/accelerometer_calibration.c @@ -80,7 +80,7 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd) { /* announce change */ - mavlink_log_info(mavlink_fd, "accelerometer calibration started"); + mavlink_log_info(mavlink_fd, "accel calibration started"); /* set to accel calibration mode */ status->flag_preflight_accel_calibration = true; state_machine_publish(status_pub, status, mavlink_fd); @@ -96,7 +96,7 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int m || param_set(param_find("SENS_ACC_XSCALE"), &(accel_scale[0])) || param_set(param_find("SENS_ACC_YSCALE"), &(accel_scale[1])) || param_set(param_find("SENS_ACC_ZSCALE"), &(accel_scale[2]))) { - mavlink_log_critical(mavlink_fd, "Setting offs or scale failed!"); + mavlink_log_critical(mavlink_fd, "ERROR: setting offs or scale failed"); } int fd = open(ACCEL_DEVICE_PATH, 0); @@ -122,7 +122,6 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int m } mavlink_log_info(mavlink_fd, "accel calibration done"); - tune_confirm(); sleep(2); tune_confirm(); @@ -142,12 +141,11 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int m int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs_scaled[3], float accel_scale[3]) { const int samples_num = 2500; - - int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined)); - int16_t accel_raw_ref[6][3]; bool data_collected[6] = { false, false, false, false, false, false }; const char *orientation_strs[6] = { "x+", "x-", "y+", "y-", "z+", "z-" }; + + int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined)); while (true) { bool done = true; char str[80]; @@ -159,25 +157,21 @@ int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs_scaled[3], done = false; } } - if (done) { - mavlink_log_info(mavlink_fd, "all accel measurements complete"); + if (done) break; - } else { - mavlink_log_info(mavlink_fd, str); - int orient = detect_orientation(mavlink_fd, sensor_combined_sub); - if (orient < 0) { - sprintf(str, "orientation detection error: %i", orient); - mavlink_log_info(mavlink_fd, str); - return ERROR; - } - mavlink_log_info(mavlink_fd, "accel measurement started"); - read_accelerometer_raw_avg(sensor_combined_sub, &(accel_raw_ref[orient][0]), samples_num); - //mavlink_log_info(mavlink_fd, "accel measurement complete"); - str_ptr = sprintf(str, "complete: %i [ %i %i %i ]", orient, accel_raw_ref[orient][0], accel_raw_ref[orient][1], accel_raw_ref[orient][2]); - mavlink_log_info(mavlink_fd, str); - data_collected[orient] = true; - tune_confirm(); - } + mavlink_log_info(mavlink_fd, str); + + int orient = detect_orientation(mavlink_fd, sensor_combined_sub); + if (orient < 0) + return ERROR; + + sprintf(str, "meas started: %s", orientation_strs[orient]); + mavlink_log_info(mavlink_fd, str); + read_accelerometer_raw_avg(sensor_combined_sub, &(accel_raw_ref[orient][0]), samples_num); + str_ptr = sprintf(str, "meas result for %s: [ %i %i %i ]", orientation_strs[orient], accel_raw_ref[orient][0], accel_raw_ref[orient][1], accel_raw_ref[orient][2]); + mavlink_log_info(mavlink_fd, str); + data_collected[orient] = true; + tune_confirm(); } close(sensor_combined_sub); @@ -186,26 +180,16 @@ int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs_scaled[3], float accel_T[3][3]; int res = calculate_calibration_values(accel_raw_ref, accel_T, accel_offs, CONSTANTS_ONE_G); if (res != 0) { - mavlink_log_info(mavlink_fd, "calibration values calculation error"); + mavlink_log_info(mavlink_fd, "ERROR: calibration values calc error"); return ERROR; } - char str[80]; - sprintf(str, "accel offsets: [ %i %i %i ]", accel_offs[0], accel_offs[1], accel_offs[2]); - mavlink_log_info(mavlink_fd, str); - //mavlink_log_info(mavlink_fd, "accel transform matrix:"); - for (int i = 0; i < 3; i++) { - //sprintf(str, "\t[ %0.6f %0.6f %0.6f ]", accel_T[i][0], accel_T[i][1], accel_T[i][2]); - //mavlink_log_info(mavlink_fd, str); - } - /* convert raw accel offset to scaled and transform matrix to scales * rotation part of transform matrix is not used by now */ for (int i = 0; i < 3; i++) { accel_offs_scaled[i] = accel_offs[i] * accel_T[i][i]; accel_scale[i] = accel_T[i][i]; } - return OK; } @@ -226,8 +210,8 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { float ema_len = 0.2f; /* set "still" threshold to 0.005 m/s^2 */ float still_thr2 = pow(0.05f / CONSTANTS_ONE_G, 2); - /* set accel error threshold to 20% of accel vector length */ - float accel_err_thr = 0.2f; + /* set accel error threshold to 30% of accel vector length */ + float accel_err_thr = 0.3f; /* still time required in us */ int64_t still_time = 2000000; struct pollfd fds[1] = { { .fd = sub_sensor_combined, .events = POLLIN } }; @@ -264,7 +248,7 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { /* is still now */ if (t_still == 0) { /* first time */ - mavlink_log_info(mavlink_fd, "still"); + mavlink_log_info(mavlink_fd, "still..."); t_still = t; t_timeout = t + timeout; } else { @@ -279,7 +263,7 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { accel_disp[2] > still_thr_raw2 * 2.0f) { /* not still, reset still start time */ if (t_still != 0) { - mavlink_log_info(mavlink_fd, "moving"); + mavlink_log_info(mavlink_fd, "moving..."); t_still = 0; } } @@ -289,17 +273,11 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { return -3; } if (t > t_timeout) { - mavlink_log_info(mavlink_fd, "ERROR: timeout"); return -1; } } float accel_len = sqrt(accel_len2); float accel_err_thr_raw = accel_len * accel_err_thr; - char str[80]; - sprintf(str, "ema: [ %.1f %.1f %.1f ]", accel_ema[0], accel_ema[1], accel_ema[2]); - mavlink_log_info(mavlink_fd, str); - sprintf(str, "disp: [ %.1f %.1f %.1f ]", accel_disp[0], accel_disp[1], accel_disp[2]); - mavlink_log_info(mavlink_fd, str); if ( fabs(accel_ema[0] - accel_len) < accel_err_thr_raw && fabs(accel_ema[1]) < accel_err_thr_raw && fabs(accel_ema[2]) < accel_err_thr_raw ) @@ -316,13 +294,13 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { fabs(accel_ema[1] + accel_len) < accel_err_thr_raw && fabs(accel_ema[2]) < accel_err_thr_raw ) return 3; // [ 0, -g, 0 ] - if ( abs(accel_ema[0]) < accel_err_thr_raw && - abs(accel_ema[1]) < accel_err_thr_raw && - abs(accel_ema[2] - accel_len) < accel_err_thr_raw ) + if ( fabs(accel_ema[0]) < accel_err_thr_raw && + fabs(accel_ema[1]) < accel_err_thr_raw && + fabs(accel_ema[2] - accel_len) < accel_err_thr_raw ) return 4; // [ 0, 0, g ] - if ( abs(accel_ema[0]) < accel_err_thr_raw && - abs(accel_ema[1]) < accel_err_thr_raw && - abs(accel_ema[2] + accel_len) < accel_err_thr_raw ) + if ( fabs(accel_ema[0]) < accel_err_thr_raw && + fabs(accel_ema[1]) < accel_err_thr_raw && + fabs(accel_ema[2] + accel_len) < accel_err_thr_raw ) return 5; // [ 0, 0, -g ] mavlink_log_info(mavlink_fd, "ERROR: invalid orientation"); return -2; // Can't detect orientation From afbb4d55b3fc4e0e2a1fc1a1b052e9f4fb034d51 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 26 Apr 2013 15:13:47 +0200 Subject: [PATCH 06/23] Finished conversion to C++ --- apps/attitude_estimator_ekf/Makefile | 5 +++-- ...f_main.c => attitude_estimator_ekf_main.cpp} | 17 ++++++++++++----- 2 files changed, 15 insertions(+), 7 deletions(-) rename apps/attitude_estimator_ekf/{attitude_estimator_ekf_main.c => attitude_estimator_ekf_main.cpp} (98%) diff --git a/apps/attitude_estimator_ekf/Makefile b/apps/attitude_estimator_ekf/Makefile index 734af7cc1c..46a54c6607 100755 --- a/apps/attitude_estimator_ekf/Makefile +++ b/apps/attitude_estimator_ekf/Makefile @@ -35,8 +35,9 @@ APPNAME = attitude_estimator_ekf PRIORITY = SCHED_PRIORITY_DEFAULT STACKSIZE = 2048 -CSRCS = attitude_estimator_ekf_main.c \ - attitude_estimator_ekf_params.c \ +CXXSRCS = attitude_estimator_ekf_main.cpp + +CSRCS = attitude_estimator_ekf_params.c \ codegen/eye.c \ codegen/attitudeKalmanfilter.c \ codegen/mrdivide.c \ diff --git a/apps/attitude_estimator_ekf/attitude_estimator_ekf_main.c b/apps/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp similarity index 98% rename from apps/attitude_estimator_ekf/attitude_estimator_ekf_main.c rename to apps/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp index bd972f03f3..1a50dde0f4 100755 --- a/apps/attitude_estimator_ekf/attitude_estimator_ekf_main.c +++ b/apps/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp @@ -66,11 +66,17 @@ #include #include +#ifdef __cplusplus +extern "C" { +#endif #include "codegen/attitudeKalmanfilter_initialize.h" #include "codegen/attitudeKalmanfilter.h" #include "attitude_estimator_ekf_params.h" +#ifdef __cplusplus +} +#endif -__EXPORT int attitude_estimator_ekf_main(int argc, char *argv[]); +extern "C" __EXPORT int attitude_estimator_ekf_main(int argc, char *argv[]); static bool thread_should_exit = false; /**< Deamon exit flag */ static bool thread_running = false; /**< Deamon status flag */ @@ -265,10 +271,11 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds /* Main loop*/ while (!thread_should_exit) { - struct pollfd fds[2] = { - { .fd = sub_raw, .events = POLLIN }, - { .fd = sub_params, .events = POLLIN } - }; + struct pollfd fds[2]; + fds[0].fd = sub_raw; + fds[0].events = POLLIN; + fds[1].fd = sub_params; + fds[1].events = POLLIN; int ret = poll(fds, 2, 1000); if (ret < 0) { From 556a017444b809c18e2ce495a2fd00380960e0f4 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 26 Apr 2013 17:41:46 +0200 Subject: [PATCH 07/23] Hotfix: GPS MAVLink transmission fixes --- apps/mavlink/orb_listener.c | 18 +++++++++++++----- 1 file changed, 13 insertions(+), 5 deletions(-) diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c index 1dd3fc2d8e..5f15facf87 100644 --- a/apps/mavlink/orb_listener.c +++ b/apps/mavlink/orb_listener.c @@ -229,6 +229,13 @@ l_vehicle_gps_position(const struct listener *l) /* copy gps data into local buffer */ orb_copy(ORB_ID(vehicle_gps_position), mavlink_subs.gps_sub, &gps); + /* GPS COG is 0..2PI in degrees * 1e2 */ + float cog_deg = gps.cog_rad; + if (cog_deg > M_PI_F) + cog_deg -= 2.0f * M_PI_F; + cog_deg *= M_RAD_TO_DEG_F; + + /* GPS position */ mavlink_msg_gps_raw_int_send(MAVLINK_COMM_0, gps.timestamp_position, @@ -236,13 +243,14 @@ l_vehicle_gps_position(const struct listener *l) gps.lat, gps.lon, gps.alt, - (uint16_t)(gps.eph_m * 1e2f), // from m to cm - (uint16_t)(gps.epv_m * 1e2f), // from m to cm - (uint16_t)(gps.vel_m_s * 1e2f), // from m/s to cm/s - (uint16_t)(gps.cog_rad * M_RAD_TO_DEG_F * 1e2f), // from rad to deg * 100 + gps.eph_m * 1e2f, // from m to cm + gps.epv_m * 1e2f, // from m to cm + gps.vel_m_s * 1e2f, // from m/s to cm/s + cog_deg * 1e2f, // from rad to deg * 100 gps.satellites_visible); - if (gps.satellite_info_available && (gps_counter % 4 == 0)) { + /* update SAT info every 10 seconds */ + if (gps.satellite_info_available && (gps_counter % 50 == 0)) { mavlink_msg_gps_status_send(MAVLINK_COMM_0, gps.satellites_visible, gps.satellite_prn, From ff15efb9c91540303622c3f9c48e22bbc9488ae0 Mon Sep 17 00:00:00 2001 From: px4dev Date: Fri, 26 Apr 2013 12:59:12 -0700 Subject: [PATCH 08/23] Build utility apps -Os to save ROM space. --- apps/examples/nsh/Makefile | 2 ++ apps/nshlib/Makefile | 2 ++ apps/px4/tests/Makefile | 2 ++ apps/system/i2c/Makefile | 1 + apps/systemcmds/bl_update/Makefile | 2 ++ apps/systemcmds/boardinfo/Makefile | 2 ++ apps/systemcmds/calibration/Makefile | 2 ++ apps/systemcmds/delay_test/Makefile | 2 ++ apps/systemcmds/eeprom/Makefile | 2 ++ apps/systemcmds/mixer/Makefile | 2 ++ apps/systemcmds/param/Makefile | 2 ++ apps/systemcmds/perf/Makefile | 2 ++ apps/systemcmds/preflight_check/Makefile | 2 ++ apps/systemcmds/reboot/Makefile | 2 ++ apps/systemcmds/top/Makefile | 2 ++ 15 files changed, 29 insertions(+) diff --git a/apps/examples/nsh/Makefile b/apps/examples/nsh/Makefile index c7d212fc2c..ad687958f6 100644 --- a/apps/examples/nsh/Makefile +++ b/apps/examples/nsh/Makefile @@ -64,6 +64,8 @@ ROOTDEPPATH = --dep-path . VPATH = +MAXOPTIMIZATION = -Os + all: .built .PHONY: clean depend distclean diff --git a/apps/nshlib/Makefile b/apps/nshlib/Makefile index 76cdac40d5..4256a10918 100644 --- a/apps/nshlib/Makefile +++ b/apps/nshlib/Makefile @@ -107,6 +107,8 @@ endif ROOTDEPPATH = --dep-path . VPATH = +MAXOPTIMIZATION = -Os + # Build targets all: .built diff --git a/apps/px4/tests/Makefile b/apps/px4/tests/Makefile index cb1c3c6185..34f058be44 100644 --- a/apps/px4/tests/Makefile +++ b/apps/px4/tests/Makefile @@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT STACKSIZE = 12000 include $(APPDIR)/mk/app.mk + +MAXOPTIMIZATION = -Os diff --git a/apps/system/i2c/Makefile b/apps/system/i2c/Makefile index 1ed7a2faef..c98e2c0e2b 100644 --- a/apps/system/i2c/Makefile +++ b/apps/system/i2c/Makefile @@ -64,6 +64,7 @@ VPATH = APPNAME = i2c PRIORITY = SCHED_PRIORITY_DEFAULT STACKSIZE = 2048 +MAXOPTIMIZATION = -Os # Build targets diff --git a/apps/systemcmds/bl_update/Makefile b/apps/systemcmds/bl_update/Makefile index 9d0e156f60..d05493577a 100644 --- a/apps/systemcmds/bl_update/Makefile +++ b/apps/systemcmds/bl_update/Makefile @@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT STACKSIZE = 4096 include $(APPDIR)/mk/app.mk + +MAXOPTIMIZATION = -Os diff --git a/apps/systemcmds/boardinfo/Makefile b/apps/systemcmds/boardinfo/Makefile index 753a6843e5..6f1be149c6 100644 --- a/apps/systemcmds/boardinfo/Makefile +++ b/apps/systemcmds/boardinfo/Makefile @@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT STACKSIZE = 2048 include $(APPDIR)/mk/app.mk + +MAXOPTIMIZATION = -Os diff --git a/apps/systemcmds/calibration/Makefile b/apps/systemcmds/calibration/Makefile index aa1aa77610..a1735962e1 100644 --- a/apps/systemcmds/calibration/Makefile +++ b/apps/systemcmds/calibration/Makefile @@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_MAX - 1 STACKSIZE = 4096 include $(APPDIR)/mk/app.mk + +MAXOPTIMIZATION = -Os diff --git a/apps/systemcmds/delay_test/Makefile b/apps/systemcmds/delay_test/Makefile index d30fcba27b..e54cf2f4e4 100644 --- a/apps/systemcmds/delay_test/Makefile +++ b/apps/systemcmds/delay_test/Makefile @@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT STACKSIZE = 2048 include $(APPDIR)/mk/app.mk + +MAXOPTIMIZATION = -Os diff --git a/apps/systemcmds/eeprom/Makefile b/apps/systemcmds/eeprom/Makefile index 2f3db0fdce..79a05550ec 100644 --- a/apps/systemcmds/eeprom/Makefile +++ b/apps/systemcmds/eeprom/Makefile @@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT STACKSIZE = 4096 include $(APPDIR)/mk/app.mk + +MAXOPTIMIZATION = -Os diff --git a/apps/systemcmds/mixer/Makefile b/apps/systemcmds/mixer/Makefile index b016ddc578..3d8ac38cb7 100644 --- a/apps/systemcmds/mixer/Makefile +++ b/apps/systemcmds/mixer/Makefile @@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT STACKSIZE = 4096 include $(APPDIR)/mk/app.mk + +MAXOPTIMIZATION = -Os diff --git a/apps/systemcmds/param/Makefile b/apps/systemcmds/param/Makefile index 603746a206..f19cadbb60 100644 --- a/apps/systemcmds/param/Makefile +++ b/apps/systemcmds/param/Makefile @@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT STACKSIZE = 4096 include $(APPDIR)/mk/app.mk + +MAXOPTIMIZATION = -Os diff --git a/apps/systemcmds/perf/Makefile b/apps/systemcmds/perf/Makefile index 0134c9948b..f8bab41b65 100644 --- a/apps/systemcmds/perf/Makefile +++ b/apps/systemcmds/perf/Makefile @@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT STACKSIZE = 2048 include $(APPDIR)/mk/app.mk + +MAXOPTIMIZATION = -Os diff --git a/apps/systemcmds/preflight_check/Makefile b/apps/systemcmds/preflight_check/Makefile index f138e2640b..98aadaa86f 100644 --- a/apps/systemcmds/preflight_check/Makefile +++ b/apps/systemcmds/preflight_check/Makefile @@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT STACKSIZE = 2048 include $(APPDIR)/mk/app.mk + +MAXOPTIMIZATION = -Os diff --git a/apps/systemcmds/reboot/Makefile b/apps/systemcmds/reboot/Makefile index 9609a24fd0..15dd199829 100644 --- a/apps/systemcmds/reboot/Makefile +++ b/apps/systemcmds/reboot/Makefile @@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT STACKSIZE = 2048 include $(APPDIR)/mk/app.mk + +MAXOPTIMIZATION = -Os diff --git a/apps/systemcmds/top/Makefile b/apps/systemcmds/top/Makefile index c45775f4be..f58f9212e7 100644 --- a/apps/systemcmds/top/Makefile +++ b/apps/systemcmds/top/Makefile @@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT - 10 STACKSIZE = 3000 include $(APPDIR)/mk/app.mk + +MAXOPTIMIZATION = -Os From de412b6467378ea5d4e61928f5795f309012a081 Mon Sep 17 00:00:00 2001 From: px4dev Date: Fri, 26 Apr 2013 12:59:35 -0700 Subject: [PATCH 09/23] Pass -g to the link phase for PX4IO the same way we do for FMU --- nuttx/configs/px4io/common/Make.defs | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/nuttx/configs/px4io/common/Make.defs b/nuttx/configs/px4io/common/Make.defs index 4958f70926..7f782b5b22 100644 --- a/nuttx/configs/px4io/common/Make.defs +++ b/nuttx/configs/px4io/common/Make.defs @@ -112,7 +112,6 @@ ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \ ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") ARCHOPTIMIZATION += -g -ARCHSCRIPT += -g endif ARCHCFLAGS = -std=gnu99 @@ -145,7 +144,7 @@ ARCHDEFINES = ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 # this seems to be the only way to add linker flags -ARCHSCRIPT += --warn-common \ +EXTRA_LIBS += --warn-common \ --gc-sections CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common From 74c62a131e34d416ef29436b12d78f961e14807a Mon Sep 17 00:00:00 2001 From: px4dev Date: Fri, 26 Apr 2013 13:00:12 -0700 Subject: [PATCH 10/23] Fix the way that we idle the tone_alarm pin so that the board defines what is the 'safe' state. --- apps/drivers/stm32/tone_alarm/tone_alarm.cpp | 8 ++++---- nuttx/configs/px4fmu/include/board.h | 1 + 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/apps/drivers/stm32/tone_alarm/tone_alarm.cpp b/apps/drivers/stm32/tone_alarm/tone_alarm.cpp index baa652d8ad..ac5511e60a 100644 --- a/apps/drivers/stm32/tone_alarm/tone_alarm.cpp +++ b/apps/drivers/stm32/tone_alarm/tone_alarm.cpp @@ -494,7 +494,7 @@ ToneAlarm::init() return ret; /* configure the GPIO to the idle state */ - stm32_configgpio(GPIO_TONE_ALARM); + stm32_configgpio(GPIO_TONE_ALARM_IDLE); /* clock/power on our timer */ modifyreg32(STM32_RCC_APB1ENR, 0, TONE_ALARM_CLOCK_ENABLE); @@ -606,6 +606,8 @@ ToneAlarm::start_note(unsigned note) rEGR = GTIM_EGR_UG; // force a reload of the period rCCER |= TONE_CCER; // enable the output + // configure the GPIO to enable timer output + stm32_configgpio(GPIO_TONE_ALARM); } void @@ -616,10 +618,8 @@ ToneAlarm::stop_note() /* * Make sure the GPIO is not driving the speaker. - * - * XXX this presumes PX4FMU and the onboard speaker driver FET. */ - stm32_gpiowrite(GPIO_TONE_ALARM, 0); + stm32_configgpio(GPIO_TONE_ALARM_IDLE); } void diff --git a/nuttx/configs/px4fmu/include/board.h b/nuttx/configs/px4fmu/include/board.h index 8ad56a4c6a..0bc0b30216 100755 --- a/nuttx/configs/px4fmu/include/board.h +++ b/nuttx/configs/px4fmu/include/board.h @@ -326,6 +326,7 @@ */ #define TONE_ALARM_TIMER 3 /* timer 3 */ #define TONE_ALARM_CHANNEL 3 /* channel 3 */ +#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN8) #define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8) /************************************************************************************ From 264cf65d0f6b1259c64aad7d7bb45aff155a8e35 Mon Sep 17 00:00:00 2001 From: px4dev Date: Fri, 26 Apr 2013 13:00:27 -0700 Subject: [PATCH 11/23] Fix an error in a #error --- apps/drivers/stm32/drv_hrt.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/apps/drivers/stm32/drv_hrt.c b/apps/drivers/stm32/drv_hrt.c index bb67d5e6d2..cec0c49ffd 100644 --- a/apps/drivers/stm32/drv_hrt.c +++ b/apps/drivers/stm32/drv_hrt.c @@ -125,7 +125,7 @@ # define HRT_TIMER_VECTOR STM32_IRQ_TIM8CC # define HRT_TIMER_CLOCK STM32_APB2_TIM8_CLKIN # if CONFIG_STM32_TIM8 -# error must not set CONFIG_STM32_TIM8=y and HRT_TIMER=6 +# error must not set CONFIG_STM32_TIM8=y and HRT_TIMER=8 # endif #elif HRT_TIMER == 9 # define HRT_TIMER_BASE STM32_TIM9_BASE From 46085b43d14b1ea1237aa176460ff648e0ff2d2a Mon Sep 17 00:00:00 2001 From: px4dev Date: Fri, 26 Apr 2013 13:00:48 -0700 Subject: [PATCH 12/23] Use the I2C bus number from the board config, not a hardcoded value. --- apps/drivers/blinkm/blinkm.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/apps/drivers/blinkm/blinkm.cpp b/apps/drivers/blinkm/blinkm.cpp index 56265995f3..3fabfd9a54 100644 --- a/apps/drivers/blinkm/blinkm.cpp +++ b/apps/drivers/blinkm/blinkm.cpp @@ -92,6 +92,7 @@ #include +#include #include #include @@ -841,7 +842,7 @@ int blinkm_main(int argc, char *argv[]) { - int i2cdevice = 3; + int i2cdevice = PX4_I2C_BUS_EXPANSION; int blinkmadr = 9; int x; From 5514d6879ab3caae0458fe01da574d7e09b1b447 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 27 Apr 2013 14:09:48 +0200 Subject: [PATCH 13/23] Docs changes --- apps/examples/kalman_demo/Makefile | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/apps/examples/kalman_demo/Makefile b/apps/examples/kalman_demo/Makefile index 99c34d934e..6c592d645c 100644 --- a/apps/examples/kalman_demo/Makefile +++ b/apps/examples/kalman_demo/Makefile @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (C) 2012 PX4 Development Team. All rights reserved. +# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions @@ -32,7 +32,7 @@ ############################################################################ # -# Basic example application +# Full attitude / position Extended Kalman Filter # APPNAME = kalman_demo From d9f9ecb084e862bd72528d118c570533deb6eccd Mon Sep 17 00:00:00 2001 From: marco Date: Sat, 27 Apr 2013 14:46:25 +0200 Subject: [PATCH 14/23] BLCtrl 2.0 testing - currently only 8 Bit resolution - ppm added --- apps/drivers/mkblctrl/mkblctrl.cpp | 36 +++++++++++++++++++++++++++--- 1 file changed, 33 insertions(+), 3 deletions(-) diff --git a/apps/drivers/mkblctrl/mkblctrl.cpp b/apps/drivers/mkblctrl/mkblctrl.cpp index c14fdfd1d8..664271bee5 100644 --- a/apps/drivers/mkblctrl/mkblctrl.cpp +++ b/apps/drivers/mkblctrl/mkblctrl.cpp @@ -62,9 +62,9 @@ #include #include #include - #include #include +#include #include #include @@ -76,6 +76,7 @@ #include #include +#include #define I2C_BUS_SPEED 400000 #define UPDATE_RATE 400 @@ -83,7 +84,7 @@ #define BLCTRL_BASE_ADDR 0x29 #define BLCTRL_OLD 0 #define BLCTRL_NEW 1 -#define BLCTRL_MIN_VALUE -0.984F +#define BLCTRL_MIN_VALUE -0.920F #define MOTOR_STATE_PRESENT_MASK 0x80 #define MOTOR_STATE_ERROR_MASK 0x7F #define MOTOR_SPINUP_COUNTER 2500 @@ -494,6 +495,14 @@ MK::task_main() fds[0].events = POLLIN; fds[1].fd = _t_armed; fds[1].events = POLLIN; + + // rc input, published to ORB + struct rc_input_values rc_in; + orb_advert_t to_input_rc = 0; + + memset(&rc_in, 0, sizeof(rc_in)); + rc_in.input_source = RC_INPUT_SOURCE_PX4FMU_PPM; + log("starting"); long update_rate_in_us = 0; @@ -608,6 +617,27 @@ MK::task_main() ////up_pwm_servo_arm(aa.armed && !aa.lockdown); mk_servo_arm(aa.armed && !aa.lockdown); } + + // see if we have new PPM input data + if (ppm_last_valid_decode != rc_in.timestamp) { + // we have a new PPM frame. Publish it. + rc_in.channel_count = ppm_decoded_channels; + if (rc_in.channel_count > RC_INPUT_MAX_CHANNELS) { + rc_in.channel_count = RC_INPUT_MAX_CHANNELS; + } + for (uint8_t i=0; i Date: Sun, 28 Apr 2013 18:04:54 +0400 Subject: [PATCH 15/23] Reset offsets/scales before calibration and use prescaled values in m/s^2 instead of raw values. --- apps/commander/accelerometer_calibration.c | 128 ++++++++++++--------- apps/commander/accelerometer_calibration.h | 3 - 2 files changed, 76 insertions(+), 55 deletions(-) diff --git a/apps/commander/accelerometer_calibration.c b/apps/commander/accelerometer_calibration.c index f607b6da69..1807369080 100644 --- a/apps/commander/accelerometer_calibration.c +++ b/apps/commander/accelerometer_calibration.c @@ -78,6 +78,13 @@ #include #include +void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd); +int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs[3], float accel_scale[3]); +int detect_orientation(int mavlink_fd, int sub_sensor_combined); +int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samples_num); +int mat_invert3(float src[3][3], float dst[3][3]); +int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], float accel_offs[3], float g); + void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd) { /* announce change */ mavlink_log_info(mavlink_fd, "accel calibration started"); @@ -85,14 +92,16 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int m status->flag_preflight_accel_calibration = true; state_machine_publish(status_pub, status, mavlink_fd); - float accel_offs_scaled[3]; + /* measure and calculate offsets & scales */ + float accel_offs[3]; float accel_scale[3]; - int res = do_accel_calibration_mesurements(mavlink_fd, accel_offs_scaled, accel_scale); + int res = do_accel_calibration_mesurements(mavlink_fd, accel_offs, accel_scale); + if (res == OK) { /* measurements complete successfully, set parameters */ - if (param_set(param_find("SENS_ACC_XOFF"), &(accel_offs_scaled[0])) - || param_set(param_find("SENS_ACC_YOFF"), &(accel_offs_scaled[1])) - || param_set(param_find("SENS_ACC_ZOFF"), &(accel_offs_scaled[2])) + if (param_set(param_find("SENS_ACC_XOFF"), &(accel_offs[0])) + || param_set(param_find("SENS_ACC_YOFF"), &(accel_offs[1])) + || param_set(param_find("SENS_ACC_ZOFF"), &(accel_offs[2])) || param_set(param_find("SENS_ACC_XSCALE"), &(accel_scale[0])) || param_set(param_find("SENS_ACC_YSCALE"), &(accel_scale[1])) || param_set(param_find("SENS_ACC_ZSCALE"), &(accel_scale[2]))) { @@ -101,11 +110,11 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int m int fd = open(ACCEL_DEVICE_PATH, 0); struct accel_scale ascale = { - accel_offs_scaled[0], + accel_offs[0], accel_scale[0], - accel_offs_scaled[1], + accel_offs[1], accel_scale[1], - accel_offs_scaled[2], + accel_offs[2], accel_scale[2], }; @@ -139,12 +148,30 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int m state_machine_publish(status_pub, status, mavlink_fd); } -int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs_scaled[3], float accel_scale[3]) { +int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs[3], float accel_scale[3]) { const int samples_num = 2500; - int16_t accel_raw_ref[6][3]; + float accel_ref[6][3]; bool data_collected[6] = { false, false, false, false, false, false }; const char *orientation_strs[6] = { "x+", "x-", "y+", "y-", "z+", "z-" }; + /* reset existing calibration */ + int fd = open(ACCEL_DEVICE_PATH, 0); + struct accel_scale ascale_null = { + 0.0f, + 1.0f, + 0.0f, + 1.0f, + 0.0f, + 1.0f, + }; + int ioctl_res = ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&ascale_null); + close(fd); + + if (OK != ioctl_res) { + warn("ERROR: failed to set scale / offsets for accel"); + return ERROR; + } + int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined)); while (true) { bool done = true; @@ -167,8 +194,8 @@ int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs_scaled[3], sprintf(str, "meas started: %s", orientation_strs[orient]); mavlink_log_info(mavlink_fd, str); - read_accelerometer_raw_avg(sensor_combined_sub, &(accel_raw_ref[orient][0]), samples_num); - str_ptr = sprintf(str, "meas result for %s: [ %i %i %i ]", orientation_strs[orient], accel_raw_ref[orient][0], accel_raw_ref[orient][1], accel_raw_ref[orient][2]); + read_accelerometer_avg(sensor_combined_sub, &(accel_ref[orient][0]), samples_num); + str_ptr = sprintf(str, "meas result for %s: [ %.2f %.2f %.2f ]", orientation_strs[orient], accel_ref[orient][0], accel_ref[orient][1], accel_ref[orient][2]); mavlink_log_info(mavlink_fd, str); data_collected[orient] = true; tune_confirm(); @@ -176,20 +203,20 @@ int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs_scaled[3], close(sensor_combined_sub); /* calculate offsets and rotation+scale matrix */ - int16_t accel_offs[3]; float accel_T[3][3]; - int res = calculate_calibration_values(accel_raw_ref, accel_T, accel_offs, CONSTANTS_ONE_G); + int res = calculate_calibration_values(accel_ref, accel_T, accel_offs, CONSTANTS_ONE_G); if (res != 0) { mavlink_log_info(mavlink_fd, "ERROR: calibration values calc error"); return ERROR; } - /* convert raw accel offset to scaled and transform matrix to scales - * rotation part of transform matrix is not used by now */ + /* convert accel transform matrix to scales, + * rotation part of transform matrix is not used by now + */ for (int i = 0; i < 3; i++) { - accel_offs_scaled[i] = accel_offs[i] * accel_T[i][i]; accel_scale[i] = accel_T[i][i]; } + return OK; } @@ -233,8 +260,8 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { t_prev = t; float w = dt / ema_len; for (int i = 0; i < 3; i++) { - accel_ema[i] = accel_ema[i] * (1.0f - w) + sensor.accelerometer_raw[i] * w; - float d = (float) sensor.accelerometer_raw[i] - accel_ema[i]; + accel_ema[i] = accel_ema[i] * (1.0f - w) + sensor.accelerometer_m_s2[i] * w; + float d = (float) sensor.accelerometer_m_s2[i] - accel_ema[i]; d = d * d; accel_disp[i] = accel_disp[i] * (1.0f - w); if (d > accel_disp[i]) @@ -273,9 +300,11 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { return -3; } if (t > t_timeout) { + mavlink_log_info(mavlink_fd, "ERROR: timeout"); return -1; } } + float accel_len = sqrt(accel_len2); float accel_err_thr_raw = accel_len * accel_err_thr; if ( fabs(accel_ema[0] - accel_len) < accel_err_thr_raw && @@ -302,56 +331,47 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { fabs(accel_ema[1]) < accel_err_thr_raw && fabs(accel_ema[2] + accel_len) < accel_err_thr_raw ) return 5; // [ 0, 0, -g ] + mavlink_log_info(mavlink_fd, "ERROR: invalid orientation"); + return -2; // Can't detect orientation } /* * Read specified number of accelerometer samples, calculate average and dispersion. */ -int read_accelerometer_raw_avg(int sensor_combined_sub, int16_t accel_avg[3], int samples_num) { +int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samples_num) { struct pollfd fds[1] = { { .fd = sensor_combined_sub, .events = POLLIN } }; int count = 0; - int32_t accel_sum[3] = { 0, 0, 0 }; + float accel_sum[3] = { 0.0f, 0.0f, 0.0f }; + while (count < samples_num) { int poll_ret = poll(fds, 1, 1000); if (poll_ret == 1) { struct sensor_combined_s sensor; orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor); - for (int i = 0; i < 3; i++) { - accel_sum[i] += sensor.accelerometer_raw[i]; - } + for (int i = 0; i < 3; i++) + accel_sum[i] += sensor.accelerometer_m_s2[i]; count++; } else { return ERROR; } } - for (int i = 0; i < 3; i++) { - accel_avg[i] = (accel_sum[i] + count / 2) / count; - } - /* calculate dispersion */ - return OK; -} -/* - * Convert raw values from accelerometers to m/s^2. - */ -void acceleration_raw_to_m_s2(float accel_corr[3], int16_t accel_raw[3], - float accel_T[3][3], int16_t accel_offs[3]) { for (int i = 0; i < 3; i++) { - accel_corr[i] = 0.0f; - for (int j = 0; j < 3; j++) { - accel_corr[i] += accel_T[i][j] * (accel_raw[j] - accel_offs[j]); - } + accel_avg[i] = accel_sum[i] / count; } + + return OK; } int mat_invert3(float src[3][3], float dst[3][3]) { float det = src[0][0] * (src[1][1] * src[2][2] - src[1][2] * src[2][1]) - - src[0][1] * (src[1][0] * src[2][2] - src[1][2] * src[2][0]) + - src[0][2] * (src[1][0] * src[2][1] - src[1][1] * src[2][0]); + src[0][1] * (src[1][0] * src[2][2] - src[1][2] * src[2][0]) + + src[0][2] * (src[1][0] * src[2][1] - src[1][1] * src[2][0]); if (det == 0.0) - return -1; // Singular matrix + return ERROR; // Singular matrix + dst[0][0] = (src[1][1] * src[2][2] - src[1][2] * src[2][1]) / det; dst[1][0] = (src[1][2] * src[2][0] - src[1][0] * src[2][2]) / det; dst[2][0] = (src[1][0] * src[2][1] - src[1][1] * src[2][0]) / det; @@ -361,34 +381,38 @@ int mat_invert3(float src[3][3], float dst[3][3]) { dst[0][2] = (src[0][1] * src[1][2] - src[0][2] * src[1][1]) / det; dst[1][2] = (src[0][2] * src[1][0] - src[0][0] * src[1][2]) / det; dst[2][2] = (src[0][0] * src[1][1] - src[0][1] * src[1][0]) / det; - return 0; + + return OK; } -int calculate_calibration_values(int16_t accel_raw_ref[6][3], - float accel_T[3][3], int16_t accel_offs[3], float g) { - /* calculate raw offsets */ +int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], float accel_offs[3], float g) { + /* calculate offsets */ for (int i = 0; i < 3; i++) { - accel_offs[i] = (int16_t) (((int32_t) (accel_raw_ref[i * 2][i]) - + (int32_t) (accel_raw_ref[i * 2 + 1][i])) / 2); + accel_offs[i] = (accel_ref[i * 2][i] + accel_ref[i * 2 + 1][i]) / 2; } + /* fill matrix A for linear equations system*/ float mat_A[3][3]; memset(mat_A, 0, sizeof(mat_A)); for (int i = 0; i < 3; i++) { for (int j = 0; j < 3; j++) { - float a = (accel_raw_ref[i * 2][j] - accel_offs[j]); + float a = accel_ref[i * 2][j] - accel_offs[j]; mat_A[i][j] = a; } } + /* calculate inverse matrix for A */ float mat_A_inv[3][3]; - mat_invert3(mat_A, mat_A_inv); + if (mat_invert3(mat_A, mat_A_inv) != OK) + return ERROR; + + /* copy results to accel_T */ for (int i = 0; i < 3; i++) { - /* copy results to accel_T */ for (int j = 0; j < 3; j++) { /* simplify matrices mult because b has only one non-zero element == g at index i */ accel_T[j][i] = mat_A_inv[j][i] * g; } } - return 0; + + return OK; } diff --git a/apps/commander/accelerometer_calibration.h b/apps/commander/accelerometer_calibration.h index acf45b6b6e..c0169c2a13 100644 --- a/apps/commander/accelerometer_calibration.h +++ b/apps/commander/accelerometer_calibration.h @@ -12,8 +12,5 @@ #include void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd); -int detect_orientation(int mavlink_fd, int sub_sensor_combined); -int mat_invert3(float src[3][3], float dst[3][3]); -int calculate_calibration_values(int16_t accel_raw_ref[6][3], float accel_T[3][3], int16_t accel_offs[3], float g); #endif /* ACCELEROMETER_CALIBRATION_H_ */ From 525cc1a37c0c03edbda1ecbf9fdbc00f1b1bf0f8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 28 Apr 2013 18:21:06 +0200 Subject: [PATCH 16/23] Added docs --- Documentation/control_flow.graffle | 16650 +++++++++++++++++++++++++++ 1 file changed, 16650 insertions(+) create mode 100644 Documentation/control_flow.graffle diff --git a/Documentation/control_flow.graffle b/Documentation/control_flow.graffle new file mode 100644 index 0000000000..2535231108 --- /dev/null +++ b/Documentation/control_flow.graffle @@ -0,0 +1,16650 @@ + + + + + ApplicationVersion + + com.omnigroup.OmniGraffle + 139.16.0.171715 + + CreationDate + 2013-02-22 17:51:02 +0000 + Creator + Lorenz Meier + GraphDocumentVersion + 8 + GuidesLocked + NO + GuidesVisible + YES + ImageCounter + 1 + LinksVisible + NO + MagnetsVisible + NO + MasterSheets + + ModificationDate + 2013-04-20 15:38:47 +0000 + Modifier + Lorenz Meier + NotesVisible + NO + OriginVisible + NO + PageBreaks + YES + PrintInfo + + NSBottomMargin + + float + 41 + + NSHorizonalPagination + + coded + BAtzdHJlYW10eXBlZIHoA4QBQISEhAhOU051bWJlcgCEhAdOU1ZhbHVlAISECE5TT2JqZWN0AIWEASqEhAFxlwCG + + NSLeftMargin + + float + 18 + + NSPaperName + + string + iso-a3 + + NSPaperSize + + size + {842, 1191} + + NSPrintReverseOrientation + + int + 0 + + NSRightMargin + + float + 18 + + NSTopMargin + + float + 18 + + + ReadOnly + NO + Sheets + + + ActiveLayerIndex + 0 + AutoAdjust + + BackgroundGraphic + + Bounds + {{0, 0}, {806, 1132}} + Class + SolidGraphic + ID + 2 + Style + + shadow + + Draws + NO + + stroke + + Draws + NO + + + + BaseZoom + 0 + CanvasOrigin + {0, 0} + ColumnAlign + 1 + ColumnSpacing + 36 + DisplayScale + 1 0/72 in = 1.0000 in + GraphicsList + + + Bounds + {{320.41170773935767, 646.55758982070449}, {100, 24}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + FontInfo + + Color + + w + 0 + + Font + Helvetica + Size + 12 + + ID + 46 + Line + + ID + 45 + Position + 0.49247664213180542 + RotationType + 0 + + Shape + Rectangle + Style + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 limited / checked} + + Wrap + NO + + + Class + LineGraphic + Head + + ID + 44 + + ID + 45 + Points + + {283.47949897905681, 658.66217570036315} + {459.99996984645378, 658.44980851233595} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 29 + + + + Bounds + {{460.49996948242188, 640.30001831054688}, {248.00003051757812, 36}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 44 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\i\fs24 \cf0 ACTUATOR_CONTROLS_EFFECTIVE_0} + + + + Bounds + {{324, 353.1875}, {120, 28}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 43 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Align + 0 + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;\red68\green147\blue53;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural + +\f0\fs24 \cf2 MAVLink:\ +'MANUAL_CONTROL'} + VerticalPad + 0 + + Wrap + NO + + + Bounds + {{324, 174.5}, {129, 28}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 42 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Align + 0 + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;\red68\green147\blue53;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural + +\f0\fs24 \cf2 MAVLink:\ +'RC_CHANNELS_RAW'} + VerticalPad + 0 + + Wrap + NO + + + Bounds + {{114.97958374023438, 786}, {191, 14}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 40 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;\red68\green147\blue53;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf2 MAVLink: 'SERVO_OUTPUT_RAW'} + VerticalPad + 0 + + Wrap + NO + + + Bounds + {{528.5, 689}, {112, 14}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 39 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;\red68\green147\blue53;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf2 MAVLink: 'ctrl eff 0-3'} + VerticalPad + 0 + + Wrap + NO + + + Class + LineGraphic + Head + + ID + 11 + + ID + 38 + Points + + {584.52245687751122, 125.49999965650382} + {584.56069426576869, 157.00000090441219} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 37 + + + + Bounds + {{448.5, 89}, {272, 36}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 37 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\i\fs24 \cf0 VEHICLE_GLOBAL_POSITION_SETPOINT /\ +VEHICLE_LOCAL_POSITION_SETPOINT} + + + + Class + LineGraphic + Head + + ID + 27 + + ID + 34 + Points + + {210.47275259888471, 495.87499981747118} + {210.43193555768113, 543.06250166479344} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 10 + + + + Bounds + {{108, 737.9375}, {205, 36}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 33 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\i\fs24 \cf0 ACTUATOR_OUTPUTS} + + + + Class + LineGraphic + Head + + ID + 29 + + ID + 32 + Points + + {210.46968123779743, 580.06249992316259} + {210.44442316539605, 627.25000030102035} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 27 + + + + Class + LineGraphic + Head + + ID + 33 + + ID + 30 + Points + + {210.48620562018775, 690.25} + {210.49612530146715, 737.4375} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 29 + + + + Bounds + {{137.97958374023438, 627.75}, {145, 62}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 29 + Shape + RoundRect + Style + + fill + + Color + + b + 1 + g + 0.814996 + r + 0.627106 + + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 Actuator Mixer} + VerticalPad + 0 + + + + Bounds + {{107.97958374023438, 543.5625}, {205, 36}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 27 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\i\fs24 \cf0 ACTUATOR_CONTROLS_0} + + + + Bounds + {{394.22506405270201, 452.15000309396282}, {89, 24}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + FontInfo + + Color + + w + 0 + + Font + Helvetica + Size + 12 + + ID + 25 + Line + + ID + 22 + Position + 0.5900501012802124 + RotationType + 0 + + Shape + Rectangle + Style + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 if in auto mode} + + Wrap + NO + + + Bounds + {{152.49994329565658, 397.00120984204113}, {116, 24}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + FontInfo + + Color + + w + 0 + + Font + Helvetica + Size + 12 + + ID + 24 + Line + + ID + 17 + Position + 0.49406537413597107 + RotationType + 0 + + Shape + Rectangle + Style + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 if in stabilized mode} + + Wrap + NO + + + Class + LineGraphic + Head + + ID + 21 + + ID + 23 + OrthogonalBarAutomatic + + OrthogonalBarPoint + {0, 0} + OrthogonalBarPosition + -1 + Points + + {584.49994992834695, 220} + {584.4997453697481, 348.6875000000008} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 2 + TailArrow + 0 + + + Tail + + ID + 11 + + + + Class + LineGraphic + Head + + ID + 10 + + ID + 22 + OrthogonalBarAutomatic + + OrthogonalBarPoint + {0, 0} + OrthogonalBarPosition + 33.206413269042969 + Points + + {583.83119320765968, 385.68717359526977} + {581, 464} + {283.49994000956832, 464.30111342104294} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 2 + Pattern + 2 + TailArrow + 0 + + + Tail + + ID + 21 + + + + Bounds + {{482, 349.1875}, {205, 36}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 21 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\i\fs24 \cf0 VEHICLE_ATTITUDE_SETPOINT} + + + + Class + LineGraphic + Head + + ID + 10 + + ID + 17 + Points + + {210.49997491180866, 385.6875} + {210.49991091996927, 432.875} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + Pattern + 2 + TailArrow + 0 + + + Tail + + ID + 6 + + + + Class + LineGraphic + Head + + ID + 5 + + ID + 16 + Points + + {283.49999999999511, 270.00001907176534} + {339.50000000000028, 270.00001907176534} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 9 + + + + Class + LineGraphic + Head + + ID + 6 + + ID + 15 + Points + + {210.49998770563047, 301.5} + {210.49998770563047, 348.6875} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 9 + + + + Class + LineGraphic + Head + + ID + 9 + + ID + 13 + Points + + {210.49171354592596, 207} + {210.49498558851923, 238.4999999999998} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 4 + + + + Class + LineGraphic + Head + + ID + 4 + + ID + 12 + Points + + {210.49498558851246, 138.5000000000002} + {210.48997117702493, 170.00000000001342} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 8 + + + + Bounds + {{512, 157.5}, {145, 62}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 11 + Shape + RoundRect + Style + + fill + + Color + + b + 0.999136 + g + 0.808554 + r + 0.587078 + + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 Position Controller} + VerticalPad + 0 + + + + Bounds + {{138, 433.375}, {145, 62}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 10 + Shape + RoundRect + Style + + fill + + Color + + b + 1 + g + 0.814996 + r + 0.627106 + + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 Attitude Controller} + VerticalPad + 0 + + + + Bounds + {{138, 239}, {145, 62}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 9 + Shape + RoundRect + Style + + fill + + Color + + b + 0.366082 + g + 0.639788 + r + 1 + + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 RC scaling and function mapping} + VerticalPad + 0 + + + + Bounds + {{138, 76}, {145, 62}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 8 + Shape + RoundRect + Style + + fill + + Color + + b + 0.324773 + g + 0.632962 + r + 0.99252 + + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 RC Input\ +PX4IO or PX4FMU} + VerticalPad + 0 + + + + Bounds + {{108, 349.1875}, {205, 36}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 6 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\i\fs24 \cf0 MANUAL_CONTROL_SETPOINT} + + + + Bounds + {{340, 252}, {115, 36}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 5 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\i\fs24 \cf0 RC_CHANNELS} + + + + Bounds + {{108, 170.5}, {204.97958374023438, 36}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 4 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\i\fs24 \cf0 INPUT_RC} + + + + GridInfo + + HPages + 1 + KeepToScale + + Layers + + + Lock + NO + Name + Layer 1 + Print + YES + View + YES + + + LayoutInfo + + Animate + NO + circoMinDist + 18 + circoSeparation + 0.0 + layoutEngine + dot + neatoSeparation + 0.0 + twopiSeparation + 0.0 + + Orientation + 2 + PrintOnePage + + RowAlign + 1 + RowSpacing + 36 + SheetTitle + Canvas 1 + UniqueID + 1 + VPages + 1 + + + ActiveLayerIndex + 0 + AutoAdjust + + BackgroundGraphic + + Bounds + {{0, 0}, {806, 1132}} + Class + SolidGraphic + ID + 2 + Style + + shadow + + Draws + NO + + stroke + + Draws + NO + + + + BaseZoom + 0 + CanvasOrigin + {0, 0} + ColumnAlign + 1 + ColumnSpacing + 36 + DisplayScale + 1 0/72 in = 1.0000 in + GraphicsList + + + Bounds + {{129, 170}, {83, 44}} + Class + ShapedGraphic + ID + 4 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + + + GridInfo + + HPages + 1 + KeepToScale + + Layers + + + Lock + NO + Name + Layer 1 + Print + YES + View + YES + + + LayoutInfo + + Animate + NO + circoMinDist + 18 + circoSeparation + 0.0 + layoutEngine + dot + neatoSeparation + 0.0 + twopiSeparation + 0.0 + + Orientation + 2 + PrintOnePage + + RowAlign + 1 + RowSpacing + 36 + SheetTitle + Remote Control + UniqueID + 5 + VPages + 1 + + + ActiveLayerIndex + 0 + AutoAdjust + + BackgroundGraphic + + Bounds + {{0, 0}, {806, 1132}} + Class + SolidGraphic + ID + 2 + Style + + shadow + + Draws + NO + + stroke + + Draws + NO + + + + BaseZoom + 0 + CanvasOrigin + {0, 0} + ColumnAlign + 1 + ColumnSpacing + 36 + DisplayScale + 1 0/72 in = 1.0000 in + GraphicsList + + + Class + Group + Graphics + + + Bounds + {{575.98995971679688, 379}, {47, 14}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 1124 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\b\fs24 \cf0 QUAD +\b0 X} + VerticalPad + 0 + + Wrap + NO + + + Class + Group + Graphics + + + Bounds + {{576.13064904528869, 216.6250047923653}, {50.666667938232422, 36}} + Class + ShapedGraphic + ID + 1126 + Rotation + 270 + Shape + HorizontalTriangle + Style + + fill + + Color + + b + 0.13195 + g + 0.165669 + r + 1 + + + + Text + + VerticalPad + 0 + + + + Bounds + {{565.46398168220912, 200.5990128790099}, {72, 72}} + Class + ShapedGraphic + ID + 1127 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + + + ID + 1125 + Rotation + 315 + + + Class + Group + Graphics + + + Bounds + {{684.97877057518497, 320.1208883952101}, {24, 24}} + Class + ShapedGraphic + ID + 1129 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 4} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1131 + Points + + {744.59415627118847, 308.1935744741462} + {742.38444757998036, 309.34262299357425} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{656.69108999710829, 361.8760779997491}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1132 + Rotation + 45 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{646.29122523639319, 281.66198172978545}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1133 + Rotation + 135 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{643.54122523639319, 278.91198172978545}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1134 + Rotation + 135 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1130 + Rotation + 315 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1136 + Points + + {649.54722336322868, 356.21791362626482} + {651.75693205443667, 355.0688651068366} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{721.45028963730863, 284.03541010066203}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1137 + Rotation + 225 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{646.35015439802385, 281.24950637062551}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1138 + Rotation + 315 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{643.60015439802385, 278.49950637062551}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1139 + Rotation + 315 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1135 + Rotation + 315 + + + Bounds + {{646.0670873832953, 281.20919655324775}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1140 + Rotation + 315 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1128 + Rotation + 315 + + + Class + Group + Graphics + + + Bounds + {{494.01518801866729, 320.05486147948341}, {24, 24}} + Class + ShapedGraphic + ID + 1142 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 2} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1144 + Points + + {458.75335031844725, 307.77399956263616} + {460.96305900965541, 308.92304808206421} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{530.65641659252742, 361.45650308823895}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1145 + Rotation + 135 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{455.55628135324292, 281.24240681827519}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1146 + Rotation + 45 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{452.80628135324292, 278.49240681827519}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1147 + Rotation + 45 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1143 + Rotation + 225 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1149 + Points + + {553.44673702887792, 356.15188491228344} + {551.23702833767004, 355.00283639285527} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{465.54367075479814, 283.96938138668088}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1150 + Rotation + 315 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{455.14380599408253, 281.1834776566443}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1151 + Rotation + 225 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{452.39380599408253, 278.4334776566443}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1152 + Rotation + 225 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1148 + Rotation + 225 + VFlip + YES + + + Bounds + {{455.10349617670488, 281.1431681805102}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1153 + Rotation + 225 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1141 + Rotation + 315 + + + Class + Group + Graphics + + + Bounds + {{684.74305392865585, 129.32699556949493}, {24, 24}} + Class + ShapedGraphic + ID + 1155 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 1} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1157 + Points + + {649.48121622843564, 117.04613365264774} + {651.69092491964352, 118.19518217207589} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{721.38428250251582, 170.72863717825052}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1158 + Rotation + 135 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{646.28414726323126, 90.514540908286847}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1159 + Rotation + 45 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{643.53414726323126, 87.764540908286847}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1160 + Rotation + 45 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1156 + Rotation + 225 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1162 + Points + + {744.17460293886643, 165.42401900229501} + {741.96489424765866, 164.27497048286693} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{656.27153666478659, 93.241515476692427}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1163 + Rotation + 315 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{645.87167190407115, 90.455611746655876}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1164 + Rotation + 225 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{643.12167190407115, 87.705611746655876}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1165 + Rotation + 225 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1161 + Rotation + 225 + VFlip + YES + + + Bounds + {{645.83136208669339, 90.415302270521892}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1166 + Rotation + 225 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1154 + Rotation + 315 + + + Class + Group + Graphics + + + Bounds + {{494.00811680064464, 129.15022794494948}, {24, 24}} + Class + ShapedGraphic + ID + 1168 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 3} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1170 + Points + + {553.62350249664826, 117.22291402388569} + {551.41379380544015, 118.37196254331369} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{465.72043622256808, 170.9054175494887}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1171 + Rotation + 45 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{455.32057146185286, 90.691321279524772}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1172 + Rotation + 135 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{452.57057146185286, 87.941321279524772}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1173 + Rotation + 135 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1169 + Rotation + 315 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1175 + Points + + {458.57656958868847, 165.24725317600405} + {460.78627827989641, 164.09820465657594} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{530.47963586276819, 93.064749650401353}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1176 + Rotation + 225 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{455.37950062348352, 90.278845920365001}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1177 + Rotation + 315 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{452.62950062348352, 87.528845920365001}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1178 + Rotation + 315 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1174 + Rotation + 315 + + + Bounds + {{455.09643360875504, 90.238536102987126}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1179 + Rotation + 315 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1167 + Rotation + 315 + + + Bounds + {{547.25939156789127, 219.8035943432547}, {8, 134}} + Class + ShapedGraphic + ID + 1180 + Rotation + 225 + Shape + Rectangle + + + Bounds + {{647.66855809291212, 119.39442062517122}, {8, 134}} + Class + ShapedGraphic + ID + 1181 + Rotation + 225 + Shape + Rectangle + + + Bounds + {{647.66855089985006, 219.80357636059938}, {8, 134}} + Class + ShapedGraphic + ID + 1182 + Rotation + 315 + Shape + Rectangle + + + Bounds + {{547.20046240626141, 119.33550225313491}, {8, 134}} + Class + ShapedGraphic + ID + 1183 + Rotation + 315 + Shape + Rectangle + + + ID + 1123 + + + Bounds + {{287.14883422851562, 373}, {46, 14}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 1121 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\b\fs24 \cf0 QUAD +\b0 +} + VerticalPad + 0 + + Wrap + NO + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{252.93672553699014, 864.96332065264312}, {24, 24}} + Class + ShapedGraphic + ID + 1186 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 6} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1188 + Points + + {248.68672172228349, 826.3749926090228} + {249.43672172228361, 828.7499926090228} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{252.68672172228372, 918.12499260902291}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1189 + Rotation + 180 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{214.43672172228372, 826.3749926090228}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1190 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{211.68672172228372, 823.6249926090228}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1191 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1187 + Rotation + 270 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1193 + Points + + {281.43672680854809, 927.54165927568897} + {280.6867268085482, 925.1666592756892} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{261.43672680854797, 817.2916592756892}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1194 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{214.18672680854797, 826.0416592756892}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1195 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{211.43672680854797, 823.2916592756892}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1196 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1192 + Rotation + 270 + VFlip + YES + + + Bounds + {{214.02503832182103, 826.05162629068673}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1197 + Rotation + 270 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1185 + + + Class + Group + Graphics + + + Bounds + {{255.93671290080545, 636.38001505533919}, {24, 24}} + Class + ShapedGraphic + ID + 1199 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 5} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1201 + Points + + {251.6867090860988, 597.79168701171886} + {252.43670908609892, 600.16668701171886} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{255.68670908609903, 689.54168701171898}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1202 + Rotation + 180 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{217.43670908609903, 597.79168701171886}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1203 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{214.68670908609903, 595.04168701171886}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1204 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1200 + Rotation + 270 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1206 + Points + + {284.43671417236339, 698.95835367838504} + {283.68671417236351, 696.58335367838527} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{264.43671417236328, 588.70835367838527}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1207 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{217.18671417236328, 597.45835367838527}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1208 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{214.43671417236328, 594.70835367838527}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1209 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1205 + Rotation + 270 + VFlip + YES + + + Bounds + {{217.02502568563636, 597.46832069338279}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1210 + Rotation + 270 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1198 + + + Class + Group + Graphics + + + Bounds + {{480.49999872844216, 864.96333555380545}, {24, 24}} + Class + ShapedGraphic + ID + 1212 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 4} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1214 + Points + + {476.24999491373552, 826.37500751018513} + {476.99999491373563, 828.75000751018513} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{480.24999491373575, 918.12500751018524}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1215 + Rotation + 180 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{441.99999491373575, 826.37500751018513}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1216 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{439.24999491373575, 823.62500751018513}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1217 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1213 + Rotation + 270 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1219 + Points + + {509.00000000000011, 927.5416741768513} + {508.25000000000023, 925.16667417685153} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{489, 817.29167417685153}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1220 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{441.75, 826.04167417685153}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1221 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{439, 823.29167417685153}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1222 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1218 + Rotation + 270 + VFlip + YES + + + Bounds + {{441.58831151327308, 826.05164119184906}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1223 + Rotation + 270 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1211 + + + Class + Group + Graphics + + + Bounds + {{480.49999872844216, 636.38001505533896}, {24, 24}} + Class + ShapedGraphic + ID + 1225 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 3} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1227 + Points + + {476.24999491373552, 597.79168701171864} + {476.99999491373563, 600.16668701171864} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{480.24999491373575, 689.54168701171875}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1228 + Rotation + 180 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{441.99999491373575, 597.79168701171864}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1229 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{439.24999491373575, 595.04168701171864}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1230 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1226 + Rotation + 270 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1232 + Points + + {509.00000000000011, 698.95835367838481} + {508.25000000000023, 696.58335367838504} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{489, 588.70835367838504}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1233 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{441.75, 597.45835367838504}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1234 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{439, 594.70835367838504}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1235 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1231 + Rotation + 270 + VFlip + YES + + + Bounds + {{441.58831151327308, 597.46832069338257}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1236 + Rotation + 270 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1224 + + + Bounds + {{452.7625732421875, 947.72591400146473}, {45, 14}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 1237 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\b\fs24 \cf0 OCTO +\b0 +} + VerticalPad + 0 + + Wrap + NO + + + Class + Group + Graphics + + + Bounds + {{353.51001119036124, 739.42163658141953}, {50.666667938232422, 36}} + Class + ShapedGraphic + ID + 1239 + Rotation + 270 + Shape + HorizontalTriangle + Style + + fill + + Color + + b + 0.13195 + g + 0.165669 + r + 1 + + + + Text + + VerticalPad + 0 + + + + Bounds + {{342.8433593880041, 726.66665752440122}, {72, 72}} + Class + ShapedGraphic + ID + 1240 + Rotation + 45 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + + + ID + 1238 + + + Class + Group + Graphics + + + Bounds + {{366.83836873372331, 916.58333714803678}, {24, 24}} + Class + ShapedGraphic + ID + 1242 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 2} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1244 + Points + + {429.42669677734398, 945.3333333333303} + {427.05169677734398, 944.58333333333019} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{320.42669677734375, 924.08333333333019}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1245 + Rotation + 90 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{327.92669677734398, 878.08333333333019}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1246 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{325.17669677734398, 875.33333333333019}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1247 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1243 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1249 + Points + + {328.26003011067723, 912.08333841959472} + {330.63503011067723, 912.83333841959472} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{421.26003011067723, 914.83333841959472}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1250 + Rotation + 270 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{328.26003011067723, 877.83333841959472}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1251 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{325.51003011067723, 875.08333841959472}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1252 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1248 + + + Bounds + {{327.92668660481695, 877.67164993286758}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1253 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1241 + + + Class + Group + Graphics + + + Bounds + {{205.66167195637968, 750.54168065389615}, {24, 24}} + Class + ShapedGraphic + ID + 1255 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 7} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1257 + Points + + {268.25000000000023, 779.29167683918968} + {265.87500000000023, 778.54167683918956} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{159.24999999999994, 758.04167683918956}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1258 + Rotation + 90 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{166.75, 712.04167683918956}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1259 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{164, 709.29167683918956}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1260 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1256 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1262 + Points + + {167.08333333333348, 746.0416819254541} + {169.45833333333348, 746.7916819254541} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{260.08333333333348, 748.7916819254541}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1263 + Rotation + 270 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{167.08333333333348, 711.7916819254541}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1264 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{164.33333333333348, 709.0416819254541}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1265 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1261 + + + Bounds + {{166.74998982747337, 711.62999343872696}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1266 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1254 + + + Class + Group + Graphics + + + Bounds + {{528.01506551106706, 750.54168065389615}, {24, 24}} + Class + ShapedGraphic + ID + 1268 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 8} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1270 + Points + + {590.60339355468773, 779.29167683918968} + {588.22839355468773, 778.54167683918956} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{481.6033935546875, 758.04167683918956}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1271 + Rotation + 90 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{489.10339355468773, 712.04167683918956}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1272 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{486.35339355468773, 709.29167683918956}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1273 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1269 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1275 + Points + + {489.43672688802098, 746.0416819254541} + {491.81172688802098, 746.7916819254541} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{582.43672688802098, 748.7916819254541}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1276 + Rotation + 270 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{489.43672688802098, 711.7916819254541}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1277 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{486.68672688802098, 709.0416819254541}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1278 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1274 + + + Bounds + {{489.10338338216064, 711.62999343872696}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1279 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1267 + + + Bounds + {{306.14882584901056, 766.45459545146662}, {8, 134}} + Class + ShapedGraphic + ID + 1280 + Rotation + 225 + Shape + Rectangle + + + Bounds + {{468.3533935546875, 695.66666666666504}, {8, 134}} + Class + ShapedGraphic + ID + 1281 + Rotation + 270 + Shape + Rectangle + + + Bounds + {{440.55795213074884, 760.88380015384382}, {8, 134}} + Class + ShapedGraphic + ID + 1282 + Rotation + 135 + Shape + Rectangle + + + Class + Group + Graphics + + + Bounds + {{366.83834838867119, 584.49999872844194}, {24, 24}} + Class + ShapedGraphic + ID + 1284 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 1} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1286 + Points + + {429.42667643229174, 613.24999491373558} + {427.05167643229174, 612.49999491373546} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{320.42667643229152, 591.99999491373546}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1287 + Rotation + 90 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{327.92667643229174, 545.99999491373546}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1288 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{325.17667643229174, 543.24999491373546}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1289 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1285 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1291 + Points + + {328.26000976562511, 579.99999999999977} + {330.63500976562511, 580.74999999999977} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{421.260009765625, 582.74999999999977}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1292 + Rotation + 270 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{328.26000976562523, 545.74999999999977}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1293 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{325.51000976562523, 542.99999999999977}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1294 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1290 + + + Bounds + {{327.92666625976494, 545.58831151327263}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1295 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1283 + + + Bounds + {{281.3533935546875, 695.66666666666504}, {8, 134}} + Class + ShapedGraphic + ID + 1296 + Rotation + 270 + Shape + Rectangle + + + Bounds + {{442.5579845556756, 629.04542696963983}, {8, 134}} + Class + ShapedGraphic + ID + 1297 + Rotation + 225 + Shape + Rectangle + + + Bounds + {{374.84336344400776, 790.58333841959472}, {8, 134}} + Class + ShapedGraphic + ID + 1298 + Shape + Rectangle + + + Bounds + {{374.84335708617891, 600.24999491373535}, {8, 134}} + Class + ShapedGraphic + ID + 1299 + Shape + Rectangle + + + Bounds + {{309.12873002381525, 629.45457637798029}, {8, 134}} + Class + ShapedGraphic + ID + 1300 + Rotation + 135 + Shape + Rectangle + + + ID + 1184 + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{181.15661763567644, 222.11968549092626}, {50.666667938232422, 36}} + Class + ShapedGraphic + ID + 1024 + Rotation + 270 + Shape + HorizontalTriangle + Style + + fill + + Color + + b + 0.13195 + g + 0.165669 + r + 1 + + + + Text + + VerticalPad + 0 + + + + Bounds + {{170.4899658333193, 209.364706433908}, {72, 72}} + Class + ShapedGraphic + ID + 1025 + Rotation + 45 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + + + ID + 1023 + + + Class + Group + Graphics + + + Bounds + {{194.48495483398159, 368.44802729289523}, {24, 24}} + Class + ShapedGraphic + ID + 1027 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 4} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1029 + Points + + {257.0732828776022, 397.19802347818882} + {254.69828287760208, 396.4480234781887} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{148.07328287760188, 375.9480234781887}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1030 + Rotation + 90 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{155.57328287760205, 329.9480234781887}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1031 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{152.82328287760205, 327.1980234781887}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1032 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1028 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1034 + Points + + {155.90661621093548, 363.94802856445312} + {158.28161621093548, 364.69802856445312} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{248.90661621093545, 366.69802856445312}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1035 + Rotation + 270 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{155.90661621093548, 329.69802856445312}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1036 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{153.15661621093548, 326.94802856445312}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1037 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1033 + + + Bounds + {{155.57327270507534, 329.53634007772598}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1038 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1026 + + + Class + Group + Graphics + + + Bounds + {{59.499998728441994, 233.36969502765339}, {24, 24}} + Class + ShapedGraphic + ID + 1040 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 2} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1042 + Points + + {55.249994913735321, 194.78136698403296} + {55.999994913735435, 197.1563669840329} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{59.249994913735435, 286.53136698403307}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1043 + Rotation + 180 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{20.999994913735549, 194.78136698403301}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1044 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{18.249994913735549, 192.03136698403301}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1045 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1041 + Rotation + 270 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1047 + Points + + {87.999999999999915, 295.9480336506993} + {87.250000000000028, 293.57303365069941} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{67.999999999999915, 185.69803365069959}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1048 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{20.749999999999915, 194.44803365069947}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1049 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{17.999999999999915, 191.69803365069947}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1050 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1046 + Rotation + 270 + VFlip + YES + + + Bounds + {{20.588311513272686, 194.45800066569694}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1051 + Rotation + 270 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1039 + + + Class + Group + Graphics + + + Bounds + {{329.22993342082486, 233.36969502765339}, {24, 24}} + Class + ShapedGraphic + ID + 1053 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 1} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1055 + Points + + {324.97992960611816, 194.7813669840329} + {325.72992960611828, 197.15636698403287} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{328.97992960611828, 286.53136698403307}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1056 + Rotation + 180 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{290.72992960611839, 194.78136698403301}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1057 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{287.97992960611839, 192.03136698403301}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1058 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1054 + Rotation + 270 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1060 + Points + + {357.72993469238281, 295.9480336506993} + {356.97993469238293, 293.57303365069941} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{337.72993469238281, 185.69803365069953}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1061 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{290.47993469238281, 194.44803365069947}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1062 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{287.72993469238281, 191.69803365069947}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1063 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1059 + Rotation + 270 + VFlip + YES + + + Bounds + {{290.31824620565556, 194.45800066569686}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1064 + Rotation + 270 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1052 + + + Class + Group + Graphics + + + Bounds + {{194.48495483398159, 92.448027292895233}, {24, 24}} + Class + ShapedGraphic + ID + 1066 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 3} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1068 + Points + + {257.0732828776022, 121.19802347818882} + {254.69828287760208, 120.4480234781887} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{148.07328287760188, 99.948023478188702}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1069 + Rotation + 90 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{155.57328287760205, 53.948023478188688}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1070 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{152.82328287760205, 51.198023478188688}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1071 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1067 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1073 + Points + + {155.90661621093548, 87.948028564453111} + {158.28161621093548, 88.698028564453111} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{248.90661621093545, 90.698028564453111}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1074 + Rotation + 270 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{155.90661621093548, 53.698028564453111}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1075 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{153.15661621093548, 50.948028564453111}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1076 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1072 + + + Bounds + {{155.57327270507534, 53.536340077725967}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1077 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1065 + + + Bounds + {{131.48995971679412, 178.36470031738281}, {8, 134}} + Class + ShapedGraphic + ID + 1078 + Rotation + 270 + Shape + Rectangle + + + Bounds + {{273.48996988932043, 178.36469523111947}, {8, 134}} + Class + ShapedGraphic + ID + 1079 + Rotation + 270 + Shape + Rectangle + + + Bounds + {{202.48996988932029, 249.36468505859375}, {8, 134}} + Class + ShapedGraphic + ID + 1080 + Shape + Rectangle + + + Bounds + {{202.48995971679412, 107.28136189778644}, {8, 134}} + Class + ShapedGraphic + ID + 1081 + Shape + Rectangle + + + ID + 1022 + + + GridInfo + + HPages + 1 + KeepToScale + + Layers + + + Lock + NO + Name + Layer 1 + Print + YES + View + YES + + + LayoutInfo + + Animate + NO + circoMinDist + 18 + circoSeparation + 0.0 + layoutEngine + dot + neatoSeparation + 0.0 + twopiSeparation + 0.0 + + Orientation + 2 + PrintOnePage + + RowAlign + 1 + RowSpacing + 36 + SheetTitle + Rotor Assignments + UniqueID + 2 + VPages + 1 + + + ActiveLayerIndex + 0 + AutoAdjust + + BackgroundGraphic + + Bounds + {{0, 0}, {806, 1132}} + Class + SolidGraphic + ID + 2 + Style + + shadow + + Draws + NO + + stroke + + Draws + NO + + + + BaseZoom + 0 + CanvasOrigin + {0, 0} + ColumnAlign + 1 + ColumnSpacing + 36 + DisplayScale + 1 0/72 in = 1.0000 in + GraphicsList + + + Bounds + {{479, 926}, {45, 14}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 1210 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\b\fs24 \cf0 HEXA +\b0 X} + VerticalPad + 0 + + Wrap + NO + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{323.13577025880016, 749.76557170439401}, {50.666667938232422, 36}} + Class + ShapedGraphic + ID + 1124 + Rotation + 270 + Shape + HorizontalTriangle + Style + + fill + + Color + + b + 0.13195 + g + 0.165669 + r + 1 + + + + Text + + VerticalPad + 0 + + + + Bounds + {{312.46911845644303, 737.01059264737569}, {72, 72}} + Class + ShapedGraphic + ID + 1125 + Rotation + 45 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + + + ID + 1123 + + + Class + Group + Graphics + + + Bounds + {{407.17230315305846, 883.72204834096681}, {24, 24}} + Class + ShapedGraphic + ID + 1127 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 4} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1129 + Points + + {379.80522301611819, 860.03627302756399} + {381.64224206895665, 861.71808336155198} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{432.69752786153174, 932.25483880979243}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1130 + Rotation + 150 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{368.7196421785618, 844.9870622696244}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1131 + Rotation + 60 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{365.9696421785618, 842.2370622696244}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1132 + Rotation + 60 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1128 + Rotation + 240 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1134 + Points + + {458.75089272822612, 931.27417383395721} + {456.91387367538789, 929.59236349996911} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{389.85858788281303, 840.55560805172911}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1135 + Rotation + 330 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{368.33647356578285, 844.82338459189691}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1136 + Rotation + 240 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{365.58647356578285, 842.07338459189691}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1137 + Rotation + 240 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1133 + Rotation + 240 + VFlip + YES + + + Bounds + {{368.26061274159781, 844.81035428333826}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1138 + Rotation + 240 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1126 + Rotation + 330 + + + Class + Group + Graphics + + + Bounds + {{267.75726457856609, 881.27816449485533}, {24, 24}} + Class + ShapedGraphic + ID + 1140 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 6} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1142 + Points + + {331.94303989196902, 882.48992268280176} + {329.51122955798087, 883.02790362996325} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{230.47447410974044, 913.3476178373885}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1143 + Rotation + 60 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{228.99225064990861, 842.82550352035832}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1144 + Rotation + 150 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{226.24225064990861, 840.07550352035832}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1145 + Rotation + 150 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1141 + Rotation + 330 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1147 + Points + + {227.70513908557558, 904.27791574513662} + {230.13694941956365, 903.73993479797491} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{313.17370486780385, 854.92022059054989}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1148 + Rotation + 240 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{229.15592832763582, 842.44233490757972}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1149 + Rotation + 330 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{226.40592832763582, 839.69233490757972}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1150 + Rotation + 330 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1146 + Rotation + 330 + + + Bounds + {{228.84558214533197, 842.36647408339456}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1151 + Rotation + 330 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1139 + Rotation + 330 + + + Class + Group + Graphics + + + Bounds + {{474.97119637474935, 761.64314519248808}, {24, 24}} + Class + ShapedGraphic + ID + 1153 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 1} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1155 + Points + + {539.15697168815223, 762.85490338043462} + {536.72516135416413, 763.39288432759611} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{437.68840590592367, 793.71259853502136}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1156 + Rotation + 60 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{436.20618244609187, 723.19048421799118}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1157 + Rotation + 150 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{433.45618244609187, 720.44048421799118}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1158 + Rotation + 150 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1154 + Rotation + 330 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1160 + Points + + {434.91907088175884, 784.64289644276937} + {437.35088121574688, 784.10491549560766} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{520.38763666398711, 735.28520128818252}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1161 + Rotation + 240 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{436.36986012381902, 722.80731560521247}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1162 + Rotation + 330 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{433.61986012381902, 720.05731560521247}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1163 + Rotation + 330 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1159 + Rotation + 330 + + + Bounds + {{436.05951394151521, 722.73145478102731}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1164 + Rotation + 330 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1152 + Rotation + 330 + + + Class + Group + Graphics + + + Bounds + {{197.82245308809811, 760.38763453076365}, {24, 24}} + Class + ShapedGraphic + ID + 1166 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 2} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1168 + Points + + {170.45537295115798, 736.70185921736106} + {172.29239200399638, 738.38366955134893} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{223.34767779657142, 808.92042499958939}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1169 + Rotation + 150 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{159.36979211360145, 721.65264845942124}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1170 + Rotation + 60 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{156.61979211360145, 718.90264845942124}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1171 + Rotation + 60 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1167 + Rotation + 240 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1173 + Points + + {249.4010426632658, 807.93976002375393} + {247.56402361042768, 806.25794968976606} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{180.50873781785265, 717.22119424152584}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1174 + Rotation + 330 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{158.98662350082267, 721.48897078169387}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1175 + Rotation + 240 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{156.23662350082267, 718.73897078169387}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1176 + Rotation + 240 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1172 + Rotation + 240 + VFlip + YES + + + Bounds + {{158.91076267663743, 721.47594047313521}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1177 + Rotation + 240 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1165 + Rotation + 330 + + + Class + Group + Graphics + + + Bounds + {{405.7864385681853, 642.051622339657}, {24, 24}} + Class + ShapedGraphic + ID + 1179 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 5} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1181 + Points + + {378.41935843124503, 618.36584702625407} + {380.25637748408349, 620.04765736024217} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{431.31166327665852, 690.58441280848263}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1182 + Rotation + 150 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{367.33377759368858, 603.3166362683146}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1183 + Rotation + 60 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{364.58377759368858, 600.5666362683146}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1184 + Rotation + 60 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1180 + Rotation + 240 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1186 + Points + + {457.36502814335307, 689.6037478326474} + {455.52800909051496, 687.92193749865953} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{388.47272329793987, 598.8851820504193}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1187 + Rotation + 330 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{366.95060898090981, 603.15295859058722}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1188 + Rotation + 240 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{364.20060898090981, 600.40295859058722}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1189 + Rotation + 240 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1185 + Rotation + 240 + VFlip + YES + + + Bounds + {{366.87474815672459, 603.13992828202845}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1190 + Rotation + 240 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1178 + Rotation + 330 + + + Bounds + {{416.05401025695778, 706.97194681357246}, {8, 134}} + Class + ShapedGraphic + ID + 1191 + Rotation + 270 + Shape + Rectangle + + + Bounds + {{273.20840928884093, 706.24568349439642}, {8, 134}} + Class + ShapedGraphic + ID + 1192 + Rotation + 270 + Shape + Rectangle + + + Bounds + {{309.23428435411637, 768.64435011115415}, {8, 134}} + Class + ShapedGraphic + ID + 1193 + Rotation + 30 + Shape + Rectangle + + + Bounds + {{380.02813770004576, 644.57328454142464}, {8, 134}} + Class + ShapedGraphic + ID + 1194 + Rotation + 30 + Shape + Rectangle + + + Class + Group + Graphics + + + Bounds + {{268.61421230672084, 643.49244485638758}, {24, 24}} + Class + ShapedGraphic + ID + 1196 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 3} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1198 + Points + + {332.79998762012377, 644.70420304433412} + {330.36817728613562, 645.24218399149561} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{231.33142183789516, 675.56189819892086}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1199 + Rotation + 60 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{229.84919837806336, 605.03978388189068}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1200 + Rotation + 150 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{227.09919837806336, 602.28978388189068}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1201 + Rotation + 150 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1197 + Rotation + 330 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1203 + Points + + {228.56208681373033, 666.49219610666887} + {230.99389714771837, 665.95421515950716} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{314.03065259595854, 617.13450095208213}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1204 + Rotation + 240 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{230.01287605579051, 604.65661526911197}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1205 + Rotation + 330 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{227.26287605579051, 601.90661526911197}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1206 + Rotation + 330 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1202 + Rotation + 330 + + + Bounds + {{229.7025298734867, 604.58075444492681}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1207 + Rotation + 330 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1195 + Rotation + 330 + + + Bounds + {{380.57688435489479, 768.55104482376805}, {8, 134}} + Class + ShapedGraphic + ID + 1208 + Rotation + 330 + Shape + Rectangle + + + Bounds + {{309.53521396482506, 645.50328259865807}, {8, 134}} + Class + ShapedGraphic + ID + 1209 + Rotation + 330 + Shape + Rectangle + + + ID + 1122 + Rotation + 330 + + + Bounds + {{431, 450}, {44, 14}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 1121 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\b\fs24 \cf0 HEXA +\b0 +} + VerticalPad + 0 + + Wrap + NO + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{326.15660523791308, 258.95613225301122}, {50.666667938232422, 36}} + Class + ShapedGraphic + ID + 320 + Rotation + 270 + Shape + HorizontalTriangle + Style + + fill + + Color + + b + 0.13195 + g + 0.165669 + r + 1 + + + + Text + + VerticalPad + 0 + + + + Bounds + {{315.48995343555595, 246.20115319599296}, {72, 72}} + Class + ShapedGraphic + ID + 321 + Rotation + 45 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + + + ID + 319 + + + Class + Group + Graphics + + + Bounds + {{339.36497966449247, 411.82398351031941}, {24, 24}} + Class + ShapedGraphic + ID + 323 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 2} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 325 + Points + + {335.11497584978588, 373.23565546669897} + {335.86497584978599, 375.61065546669897} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{339.11497584978599, 464.98565546669914}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 326 + Rotation + 180 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{300.86497584978611, 373.23565546669909}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 327 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{298.11497584978611, 370.48565546669909}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 328 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 324 + Rotation + 270 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 330 + Points + + {367.86498093605042, 474.40232213336532} + {367.11498093605053, 472.02732213336543} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{347.86498093605042, 364.15232213336554}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 331 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{300.61498093605042, 372.90232213336543}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 332 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{297.86498093605042, 370.15232213336543}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 333 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 329 + Rotation + 270 + VFlip + YES + + + Bounds + {{300.45329244932327, 372.91228914836296}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 334 + Rotation + 270 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 322 + + + Class + Group + Graphics + + + Bounds + {{219.84995651245046, 339.99999872844211}, {24, 24}} + Class + ShapedGraphic + ID + 336 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 3} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 338 + Points + + {282.43828455607104, 368.74999491373569} + {280.06328455607098, 367.99999491373558} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{173.43828455607076, 347.49999491373558}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 339 + Rotation + 90 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{180.93828455607093, 301.49999491373558}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 340 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{178.18828455607093, 298.74999491373558}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 341 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 337 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 343 + Points + + {181.27161788940435, 335.5} + {183.64661788940435, 336.25} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{274.2716178894043, 338.25}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 344 + Rotation + 270 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{181.27161788940435, 301.25}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 345 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{178.52161788940435, 298.5}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 346 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 342 + + + Bounds + {{180.93827438354421, 301.08831151327286}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 347 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 335 + + + Class + Group + Graphics + + + Bounds + {{459.11999511718477, 339.99999872844211}, {24, 24}} + Class + ShapedGraphic + ID + 349 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 6} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 351 + Points + + {521.70832316080532, 368.74999491373569} + {519.33332316080532, 367.99999491373558} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{412.70832316080504, 347.49999491373558}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 352 + Rotation + 90 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{420.20832316080521, 301.49999491373558}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 353 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{417.45832316080521, 298.74999491373558}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 354 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 350 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 356 + Points + + {420.54165649413864, 335.5} + {422.91665649413864, 336.25} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{513.54165649413858, 338.25}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 357 + Rotation + 270 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{420.54165649413864, 301.25}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 358 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{417.79165649413864, 298.5}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 359 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 355 + + + Bounds + {{420.20831298827852, 301.08831151327286}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 360 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 348 + + + Class + Group + Graphics + + + Bounds + {{219.72989813487507, 200.33832295734095}, {24, 24}} + Class + ShapedGraphic + ID + 362 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 5} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 364 + Points + + {215.47989432016846, 161.74999491372051} + {216.22989432016857, 164.12499491372046} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{219.47989432016857, 253.49999491372063}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 365 + Rotation + 180 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{181.22989432016868, 161.74999491372057}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 366 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{178.47989432016868, 158.99999491372057}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 367 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 363 + Rotation + 270 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 369 + Points + + {248.22989940643305, 262.91666158038686} + {247.47989940643316, 260.54166158038697} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{228.22989940643305, 152.66666158038709}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 370 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{180.97989940643305, 161.41666158038697}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 371 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{178.22989940643305, 158.66666158038697}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 372 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 368 + Rotation + 270 + VFlip + YES + + + Bounds + {{180.81821091970582, 161.42662859538444}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 373 + Rotation + 270 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 361 + + + Class + Group + Graphics + + + Bounds + {{458.99999872844205, 201.83832295734095}, {24, 24}} + Class + ShapedGraphic + ID + 375 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 4} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 377 + Points + + {454.74999491373541, 163.24999491372051} + {455.49999491373552, 165.62499491372046} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{458.74999491373552, 254.99999491372063}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 378 + Rotation + 180 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{420.49999491373563, 163.24999491372057}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 379 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{417.74999491373563, 160.49999491372057}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 380 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 376 + Rotation + 270 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 382 + Points + + {487.5, 264.41666158038686} + {486.75000000000011, 262.04166158038697} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{467.5, 154.16666158038709}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 383 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{420.25, 162.91666158038697}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 384 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{417.5, 160.16666158038697}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 385 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 381 + Rotation + 270 + VFlip + YES + + + Bounds + {{420.0883115132728, 162.92662859538444}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 386 + Rotation + 270 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 374 + + + Bounds + {{409.00361117886365, 251.82615622621091}, {8, 134}} + Class + ShapedGraphic + ID + 387 + Rotation + 300 + Shape + Rectangle + + + Bounds + {{285.65882358120746, 179.77439325790914}, {8, 134}} + Class + ShapedGraphic + ID + 388 + Rotation + 300 + Shape + Rectangle + + + Bounds + {{285.65881327292152, 251.82616124293514}, {8, 134}} + Class + ShapedGraphic + ID + 389 + Rotation + 60 + Shape + Rectangle + + + Bounds + {{409.00362148715112, 179.77439325790914}, {8, 134}} + Class + ShapedGraphic + ID + 390 + Rotation + 60 + Shape + Rectangle + + + Class + Group + Graphics + + + Bounds + {{339.48495483398165, 134.49999872844211}, {24, 24}} + Class + ShapedGraphic + ID + 392 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 1} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 394 + Points + + {402.0732828776022, 163.24999491373569} + {399.69828287760214, 162.49999491373558} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{293.07328287760191, 141.99999491373558}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 395 + Rotation + 90 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{300.57328287760208, 95.999994913735577}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 396 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{297.82328287760208, 93.249994913735577}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 397 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 393 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 399 + Points + + {300.90661621093551, 130} + {303.28161621093551, 130.75} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{393.90661621093545, 132.75}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 400 + Rotation + 270 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{300.90661621093551, 95.75}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 401 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{298.15661621093551, 93}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 402 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 398 + + + Bounds + {{300.5732727050754, 95.588311513272842}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 403 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 391 + + + Bounds + {{347.48996988932038, 287.41665649414062}, {8, 134}} + Class + ShapedGraphic + ID + 404 + Shape + Rectangle + + + Bounds + {{347.4899597167942, 145.33333333333331}, {8, 134}} + Class + ShapedGraphic + ID + 405 + Shape + Rectangle + + + ID + 318 + + + GridInfo + + HPages + 1 + KeepToScale + + Layers + + + Lock + NO + Name + Layer 1 + Print + YES + View + YES + + + LayoutInfo + + Animate + NO + circoMinDist + 18 + circoSeparation + 0.0 + layoutEngine + dot + neatoSeparation + 0.0 + twopiSeparation + 0.0 + + Orientation + 2 + PrintOnePage + + RowAlign + 1 + RowSpacing + 36 + SheetTitle + Rotor Assignment 2 + UniqueID + 3 + VPages + 1 + + + ActiveLayerIndex + 0 + AutoAdjust + + BackgroundGraphic + + Bounds + {{0, 0}, {806, 1132}} + Class + SolidGraphic + ID + 2 + Style + + shadow + + Draws + NO + + stroke + + Draws + NO + + + + BaseZoom + 0 + CanvasOrigin + {0, 0} + ColumnAlign + 1 + ColumnSpacing + 36 + DisplayScale + 1 0/72 in = 1.0000 in + GraphicsList + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{317.51000800051321, 240.42163882949882}, {50.666667938232422, 36}} + Class + ShapedGraphic + ID + 1417 + Rotation + 270 + Shape + HorizontalTriangle + Style + + fill + + Color + + b + 0.13195 + g + 0.165669 + r + 1 + + + + Text + + VerticalPad + 0 + + + + Bounds + {{306.84335619815613, 227.6666597724805}, {72, 72}} + Class + ShapedGraphic + ID + 1418 + Rotation + 45 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + + + ID + 1416 + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{181.87174317649047, 313.76849034719959}, {24, 24}} + Class + ShapedGraphic + ID + 1421 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 6} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1423 + Points + + {159.49938242361688, 285.249576623557} + {161.10116522486757, 287.15677793899749} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{201.23696348262672, 364.71920821881605}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1424 + Rotation + 157.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{143.41457890258161, 275.07218626448082}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1425 + Rotation + 67.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{140.66457890258161, 272.32218626448082}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1426 + Rotation + 67.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1422 + Rotation + 247.5 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1428 + Points + + {228.47124867019181, 366.1825051496383} + {226.8694658689414, 364.27530383419804} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{170.73366761118237, 268.21287355437971}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1429 + Rotation + 337.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{143.05605219122737, 274.85989550871483}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1430 + Rotation + 247.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{140.30605219122737, 272.10989550871483}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1431 + Rotation + 247.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1427 + Rotation + 247.5 + VFlip + YES + + + Bounds + {{142.96005354220407, 274.85679605657162}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1432 + Rotation + 247.5 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1420 + Rotation + 337.5 + + + Class + Group + Graphics + + + Bounds + {{272.11841406704639, 103.73309829351469}, {24, 24}} + Class + ShapedGraphic + ID + 1434 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 5} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1436 + Points + + {249.74605331417285, 75.214184569872145} + {251.34783611542343, 77.121385885312606} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{291.48363437318255, 154.68381616513099}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1437 + Rotation + 157.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{233.66124979313764, 65.036794210795819}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1438 + Rotation + 67.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{230.91124979313764, 62.286794210795819}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1439 + Rotation + 67.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1435 + Rotation + 247.5 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1441 + Points + + {318.71791956074799, 156.14711309595339} + {317.11613675949758, 154.23991178051318} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{260.98033850173846, 58.177481500694711}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1442 + Rotation + 337.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{233.30272308178348, 64.824503455029671}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1443 + Rotation + 247.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{230.55272308178348, 62.074503455029671}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1444 + Rotation + 247.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1440 + Rotation + 247.5 + VFlip + YES + + + Bounds + {{233.20672443276007, 64.821404002886837}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1445 + Rotation + 247.5 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1433 + Rotation + 337.5 + + + Class + Group + Graphics + + + Bounds + {{392.11278792691934, 400.85319857921803}, {24, 24}} + Class + ShapedGraphic + ID + 1447 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 4} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1449 + Points + + {369.74042717404592, 372.33428485557562} + {371.34220997529656, 374.24148617101616} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{411.47800823305562, 451.80391645083449}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1450 + Rotation + 157.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{353.65562365301071, 362.15689449649926}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1451 + Rotation + 67.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{350.90562365301071, 359.40689449649926}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1452 + Rotation + 67.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1448 + Rotation + 247.5 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1454 + Points + + {438.71229342062088, 453.26721338165692} + {437.11051061937059, 451.36001206621654} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{380.97471236161118, 355.29758178639815}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1455 + Rotation + 337.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{353.29709694165621, 361.94460374073327}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1456 + Rotation + 247.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{350.54709694165621, 359.19460374073327}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1457 + Rotation + 247.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1453 + Rotation + 247.5 + VFlip + YES + + + Bounds + {{353.20109829263305, 361.94150428859024}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1458 + Rotation + 247.5 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1446 + Rotation + 337.5 + + + Class + Group + Graphics + + + Bounds + {{479.58783759318999, 189.66974728965576}, {24, 24}} + Class + ShapedGraphic + ID + 1460 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 3} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1462 + Points + + {457.21547665220845, 161.15083366194582} + {458.81725945345897, 163.05803497738634} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{498.95305771121809, 240.62046525720473}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1463 + Rotation + 157.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{441.13067313117307, 150.9734433028697}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1464 + Rotation + 67.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{438.38067313117307, 148.2234433028697}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1465 + Rotation + 67.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1461 + Rotation + 247.5 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1467 + Points + + {526.18734328198354, 242.08376201128482} + {524.58556048073308, 240.17656069584442} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{468.44976222297396, 144.11413041602617}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1468 + Rotation + 337.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{440.77214680301904, 150.76115237036112}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1469 + Rotation + 247.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{438.02214680301904, 148.01115237036112}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1470 + Rotation + 247.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1466 + Rotation + 247.5 + VFlip + YES + + + Bounds + {{440.67614795890404, 150.75805299902771}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1471 + Rotation + 247.5 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1459 + Rotation + 337.5 + + + Bounds + {{324.9947377700048, 478.76189426912856}, {46, 14}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 1472 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\b\fs24 \cf0 OCTO +\b0 X} + VerticalPad + 0 + + Wrap + NO + + + Class + Group + Graphics + + + Bounds + {{267.24952227247923, 404.95559172255122}, {24, 24}} + Class + ShapedGraphic + ID + 1474 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 2} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1476 + Points + + {332.396988909622, 413.07125181593568} + {329.91576246001244, 413.28721548361688} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{226.49295677281663, 431.38573061302958}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1477 + Rotation + 67.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{228.4458262787623, 366.49842726410935}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1478 + Rotation + 157.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{225.6958262787623, 363.74842726410935}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1479 + Rotation + 157.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1475 + Rotation + 337.5 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1481 + Points + + {226.20695455654064, 421.06707636999505} + {228.68818100615007, 420.8511127023138} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{316.11098669334581, 384.25259757290121}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1482 + Rotation + 247.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{228.65811718740025, 366.13990092182132}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1483 + Rotation + 337.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{225.90811718740025, 363.38990092182132}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1484 + Rotation + 337.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1480 + Rotation + 337.5 + + + Bounds + {{228.33784007224426, 366.04390208826476}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1485 + Rotation + 337.5 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1473 + Rotation + 337.5 + + + Class + Group + Graphics + + + Bounds + {{181.88306202487647, 189.87345220332375}, {24, 24}} + Class + ShapedGraphic + ID + 1487 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 7} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1489 + Points + + {247.03052866201915, 197.98911229670802} + {244.5493022124096, 198.20507596438921} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{141.12649652521372, 216.30359109380208}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1490 + Rotation + 67.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{143.07936603115925, 151.41628774488177}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1491 + Rotation + 157.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{140.32936603115925, 148.66628774488177}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1492 + Rotation + 157.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1488 + Rotation + 337.5 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1494 + Points + + {140.84049430893771, 205.98493685076758} + {143.32172075854714, 205.76897318308625} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{230.74452644574279, 169.17045805367366}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1495 + Rotation + 247.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{143.29165693979732, 151.05776140259383}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1496 + Rotation + 337.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{140.54165693979732, 148.30776140259383}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1497 + Rotation + 337.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1493 + Rotation + 337.5 + + + Bounds + {{142.97137982464162, 150.96176256903718}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1498 + Rotation + 337.5 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1486 + Rotation + 337.5 + + + Class + Group + Graphics + + + Bounds + {{479.69876456560792, 313.23275528336626}, {24, 24}} + Class + ShapedGraphic + ID + 1500 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 8} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1502 + Points + + {544.84623120275069, 321.34841537675055} + {542.36500475314142, 321.56437904443163} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{438.94219906594537, 339.66289417384445}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1503 + Rotation + 67.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{440.89506857189104, 274.77559082492428}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1504 + Rotation + 157.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{438.14506857189104, 272.02559082492428}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1505 + Rotation + 157.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1501 + Rotation + 337.5 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1507 + Points + + {438.65619684966936, 329.34423993081015} + {441.13742329927879, 329.12827626312878} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{528.56022898647439, 292.52976113371614}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1508 + Rotation + 247.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{441.107359480529, 274.41706448263619}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1509 + Rotation + 337.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{438.357359480529, 271.66706448263619}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1510 + Rotation + 337.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1506 + Rotation + 337.5 + + + Bounds + {{440.78708236537307, 274.3210656490798}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1511 + Rotation + 337.5 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1499 + Rotation + 337.5 + + + Bounds + {{248.28852278518417, 235.77792148758147}, {8, 134}} + Class + ShapedGraphic + ID + 1512 + Rotation + 247.5 + Shape + Rectangle + + + Bounds + {{425.23537052568395, 232.45140364934065}, {8, 134}} + Class + ShapedGraphic + ID + 1513 + Rotation + 292.50006103515625 + Shape + Rectangle + + + Bounds + {{374.59821460510483, 282.06732351898592}, {8, 134}} + Class + ShapedGraphic + ID + 1514 + Rotation + 157.5 + Shape + Rectangle + + + Class + Group + Graphics + + + Bounds + {{394.33229525377027, 98.150584482954116}, {24, 24}} + Class + ShapedGraphic + ID + 1516 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 1} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1518 + Points + + {459.47976189091298, 106.26624457633855} + {456.99853544130355, 106.48220824401977} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{353.57572975410767, 124.58072337343253}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1519 + Rotation + 67.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{355.52859926005328, 59.693420024512235}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1520 + Rotation + 157.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{352.77859926005328, 56.943420024512235}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1521 + Rotation + 157.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1517 + Rotation + 337.5 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1523 + Points + + {353.28972753783154, 114.26206913039776} + {355.77095398744109, 114.04610546271654} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{443.19375967463657, 77.447590333303964}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1524 + Rotation + 247.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{355.74089016869129, 59.33489368222402}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1525 + Rotation + 337.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{352.99089016869129, 56.58489368222402}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1526 + Rotation + 337.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1522 + Rotation + 337.5 + + + Bounds + {{355.42061305353548, 59.238894848667528}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1527 + Rotation + 337.5 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1515 + Rotation + 337.5 + + + Bounds + {{252.46989794607327, 160.88960179706885}, {8, 134}} + Class + ShapedGraphic + ID + 1528 + Rotation + 292.50006103515625 + Shape + Rectangle + + + Bounds + {{426.89836479441431, 161.02992820772749}, {8, 134}} + Class + ShapedGraphic + ID + 1529 + Rotation + 247.5 + Shape + Rectangle + + + Bounds + {{302.52032988683095, 284.35823469264687}, {8, 134}} + Class + ShapedGraphic + ID + 1530 + Rotation + 22.500026702880859 + Shape + Rectangle + + + Bounds + {{375.35774119930903, 108.51315184010758}, {8, 134}} + Class + ShapedGraphic + ID + 1531 + Rotation + 22.500026702880859 + Shape + Rectangle + + + Bounds + {{303.4692327942559, 110.3467678696648}, {8, 134}} + Class + ShapedGraphic + ID + 1532 + Rotation + 157.5 + Shape + Rectangle + + + ID + 1419 + Rotation + 45 + + + ID + 1415 + + + GridInfo + + HPages + 1 + KeepToScale + + Layers + + + Lock + NO + Name + Layer 1 + Print + YES + View + YES + + + LayoutInfo + + Animate + NO + circoMinDist + 18 + circoSeparation + 0.0 + layoutEngine + dot + neatoSeparation + 0.0 + twopiSeparation + 0.0 + + Orientation + 2 + PrintOnePage + + RowAlign + 1 + RowSpacing + 36 + SheetTitle + Rotor Assignment 3 + UniqueID + 4 + VPages + 1 + + + SmartAlignmentGuidesActive + YES + SmartDistanceGuidesActive + YES + UseEntirePage + + WindowInfo + + CurrentSheet + 4 + ExpandedCanvases + + + name + Canvas 1 + + + Frame + {{96, 56}, {1043, 822}} + ListView + + OutlineWidth + 142 + RightSidebar + + ShowRuler + + Sidebar + + SidebarWidth + 120 + VisibleRegion + {{-51, -33}, {908, 683}} + Zoom + 1 + ZoomValues + + + Canvas 1 + 1 + 0.5 + + + Rotor Assignments + 1 + 4 + + + Rotor Assignment 2 + 1 + 4 + + + Rotor Assignment 3 + 1 + 1 + + + Remote Control + 1 + 1 + + + + + From ca5dcc11a7754d38e3b5f63bcb708e106fb2a3cd Mon Sep 17 00:00:00 2001 From: marco Date: Mon, 29 Apr 2013 18:32:30 +0200 Subject: [PATCH 17/23] BLCtrl 2.0 testing - currently only 8 Bit resolution - motor detection and px4 mode as default --- apps/drivers/mkblctrl/mkblctrl.cpp | 83 ++++++++++++++++++++---------- 1 file changed, 55 insertions(+), 28 deletions(-) diff --git a/apps/drivers/mkblctrl/mkblctrl.cpp b/apps/drivers/mkblctrl/mkblctrl.cpp index 664271bee5..bcdb80b5d0 100644 --- a/apps/drivers/mkblctrl/mkblctrl.cpp +++ b/apps/drivers/mkblctrl/mkblctrl.cpp @@ -121,6 +121,7 @@ public: int set_motor_test(bool motortest); int set_px4mode(int px4mode); int set_frametype(int frametype); + unsigned int mk_check_for_blctrl(unsigned int count, unsigned int showOutput); private: static const unsigned _max_actuators = MAX_MOTORS; @@ -176,7 +177,6 @@ private: int gpio_ioctl(file *filp, int cmd, unsigned long arg); int mk_servo_arm(bool status); - int mk_check_for_blctrl(unsigned int count); int mk_servo_set(unsigned int chan, float val); int mk_servo_set_test(unsigned int chan, float val); int mk_servo_test(unsigned int chan); @@ -350,11 +350,11 @@ MK::set_mode(Mode mode) switch (mode) { case MODE_2PWM: if(_num_outputs == 4) { - debug("MODE_QUAD"); + //debug("MODE_QUAD"); } else if(_num_outputs == 6) { - debug("MODE_HEXA"); + //debug("MODE_HEXA"); } else if(_num_outputs == 8) { - debug("MODE_OCTO"); + //debug("MODE_OCTO"); } //up_pwm_servo_init(0x3); up_pwm_servo_deinit(); @@ -363,11 +363,11 @@ MK::set_mode(Mode mode) case MODE_4PWM: if(_num_outputs == 4) { - debug("MODE_QUADRO"); + //debug("MODE_QUADRO"); } else if(_num_outputs == 6) { - debug("MODE_HEXA"); + //debug("MODE_HEXA"); } else if(_num_outputs == 8) { - debug("MODE_OCTO"); + //debug("MODE_OCTO"); } //up_pwm_servo_init(0xf); up_pwm_servo_deinit(); @@ -447,8 +447,13 @@ MK::set_motor_count(unsigned count) memcpy(&addrTranslator, &blctrlAddr_px4, sizeof(blctrlAddr_px4)); } - /* check for connected blctrls */ - mk_check_for_blctrl(_num_outputs); + if(_num_outputs == 4) { + fprintf(stderr, "[mkblctrl] Quadrocopter Mode (4)\n"); + } else if(_num_outputs == 6) { + fprintf(stderr, "[mkblctrl] Hexacopter Mode (6)\n"); + } else if(_num_outputs == 8) { + fprintf(stderr, "[mkblctrl] Octocopter Mode (8)\n"); + } return OK; } @@ -502,7 +507,6 @@ MK::task_main() memset(&rc_in, 0, sizeof(rc_in)); rc_in.input_source = RC_INPUT_SOURCE_PX4FMU_PPM; - log("starting"); long update_rate_in_us = 0; @@ -666,10 +670,10 @@ MK::mk_servo_arm(bool status) } -int -MK::mk_check_for_blctrl(unsigned int count) +unsigned int +MK::mk_check_for_blctrl(unsigned int count, unsigned int showOutput) { - _retries = 10; + _retries = 50; uint8_t foundMotorCount = 0; for(unsigned i=0; iset_frametype(frametype); + /* motortest if enabled */ + g_mk->set_motor_test(motortest); + + /* (re)set count of used motors */ - g_mk->set_motor_count(motorcount); + ////g_mk->set_motor_count(motorcount); + /* count used motors */ + + do { + if(g_mk->mk_check_for_blctrl(8, 0) != 0) { + shouldStop = 3; + } else { + shouldStop++; + } + sleep(1); + } while ( shouldStop != 3); + + g_mk->set_motor_count(g_mk->mk_check_for_blctrl(8, 1)); /* (re)set the PWM output mode */ g_mk->set_mode(servo_mode); - /* motortest if enabled */ - g_mk->set_motor_test(motortest); if ((servo_mode != MK::MODE_NONE) && (update_rate != 0)) g_mk->set_pwm_rate(update_rate); @@ -1335,15 +1359,19 @@ mkblctrl_main(int argc, char *argv[]) int motorcount = 0; int bus = 1; bool motortest = false; - int px4mode = MAPPING_MK; + int px4mode = MAPPING_PX4; int frametype = FRAME_PLUS; // + plus is default + new_mode = PORT_FULL_PWM; + motorcount = 8; + /* * Mode switches. * * XXX use getopt? */ for (int i = 1; i < argc; i++) { /* argv[0] is "mk" */ + /* if (!strcmp(argv[i], "mode_quad")) { new_mode = PORT_FULL_PWM; motorcount = 4; @@ -1354,8 +1382,10 @@ mkblctrl_main(int argc, char *argv[]) new_mode = PORT_FULL_PWM; motorcount = 8; } + */ /* look for the optional update rate for the supported modes */ + /* if (strcmp(argv[i], "-u") == 0 || strcmp(argv[i], "--update-rate") == 0) { if (argc > i + 1) { pwm_update_rate_in_hz = atoi(argv[i + 1]); @@ -1365,6 +1395,7 @@ mkblctrl_main(int argc, char *argv[]) } } + */ /* look for the optional i2c bus parameter */ if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) { if (argc > i + 1) { @@ -1376,9 +1407,10 @@ mkblctrl_main(int argc, char *argv[]) } /* look for the optional frame parameter */ - if (strcmp(argv[i], "-f") == 0 || strcmp(argv[i], "--frame") == 0) { + if (strcmp(argv[i], "-mkmode") == 0 || strcmp(argv[i], "--mkmode") == 0) { if (argc > i + 1) { if(strcmp(argv[i + 1], "+") == 0 || strcmp(argv[i + 1], "x") == 0 || strcmp(argv[i + 1], "X") == 0) { + px4mode = MAPPING_MK; if(strcmp(argv[i + 1], "+") == 0) { frametype = FRAME_PLUS; } else { @@ -1388,16 +1420,11 @@ mkblctrl_main(int argc, char *argv[]) errx(1, "only + or x for frametype supported !"); } } else { - errx(1, "missing argument for frametype (-f)"); + errx(1, "missing argument for mkmode (-mkmode)"); return 1; } } - /* look for the optional geometry parameter */ - if (strcmp(argv[i], "-px4mode") == 0) { - px4mode = MAPPING_PX4; - } - /* look for the optional test parameter */ if (strcmp(argv[i], "-t") == 0) { motortest = true; @@ -1407,7 +1434,7 @@ mkblctrl_main(int argc, char *argv[]) if(new_mode == PORT_MODE_UNSET) { fprintf(stderr, "mkblctrl: unrecognised command, try:\n"); - fprintf(stderr, " mode_quad, mode_hexa, mode_octo [-b i2c_bus_number] [-u update_rate_in_hz] [-t motortest] [-px4mode] [-f frame{+/x}]\n"); + fprintf(stderr, " [-mkmode frame{+/x}] [-b i2c_bus_number] [-t motortest]\n"); exit(1); } From 130c7a353055da628518f6de1bbd58c855fad5bd Mon Sep 17 00:00:00 2001 From: marco Date: Mon, 29 Apr 2013 19:56:50 +0200 Subject: [PATCH 18/23] BLCtrl 2.0 testing - currently only 8 Bit resolution - motor detection and px4 mode as default - with safety shutdown --- apps/drivers/mkblctrl/mkblctrl.cpp | 42 +++++------------------------- 1 file changed, 6 insertions(+), 36 deletions(-) diff --git a/apps/drivers/mkblctrl/mkblctrl.cpp b/apps/drivers/mkblctrl/mkblctrl.cpp index bcdb80b5d0..057ee2128d 100644 --- a/apps/drivers/mkblctrl/mkblctrl.cpp +++ b/apps/drivers/mkblctrl/mkblctrl.cpp @@ -311,9 +311,6 @@ MK::init(unsigned motors) /* reset GPIOs */ gpio_reset(); - /* check for connected blctrls */ - //mk_check_for_blctrl(_num_outputs); - /* start the IO interface task */ _task = task_spawn("mkblctrl", SCHED_DEFAULT, @@ -717,16 +714,13 @@ MK::mk_check_for_blctrl(unsigned int count, unsigned int showOutput) for(unsigned i=0; i< count; i++) { fprintf(stderr, "[mkblctrl] blctrl[%i] : found=%i\tversion=%i\tcurrent=%i\tmaxpwm=%i\ttemperature=%i\n", i,Motor[i].State, Motor[i].Version, Motor[i].Current, Motor[i].MaxPWM, Motor[i].Temperature); } + + if(foundMotorCount == 0) { + _task_should_exit = true; + } } return foundMotorCount; - /* - if(foundMotorCount == count) { - return true; - } else { - return false; - } - */ } @@ -1302,12 +1296,12 @@ mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest, do { if(g_mk->mk_check_for_blctrl(8, 0) != 0) { - shouldStop = 3; + shouldStop = 4; } else { shouldStop++; } sleep(1); - } while ( shouldStop != 3); + } while ( shouldStop < 3); g_mk->set_motor_count(g_mk->mk_check_for_blctrl(8, 1)); @@ -1371,31 +1365,7 @@ mkblctrl_main(int argc, char *argv[]) * XXX use getopt? */ for (int i = 1; i < argc; i++) { /* argv[0] is "mk" */ - /* - if (!strcmp(argv[i], "mode_quad")) { - new_mode = PORT_FULL_PWM; - motorcount = 4; - } else if (!strcmp(argv[i], "mode_hexa")) { - new_mode = PORT_FULL_PWM; - motorcount = 6; - } else if (!strcmp(argv[i], "mode_octo")) { - new_mode = PORT_FULL_PWM; - motorcount = 8; - } - */ - /* look for the optional update rate for the supported modes */ - /* - if (strcmp(argv[i], "-u") == 0 || strcmp(argv[i], "--update-rate") == 0) { - if (argc > i + 1) { - pwm_update_rate_in_hz = atoi(argv[i + 1]); - } else { - errx(1, "missing argument for update rate (-u)"); - return 1; - } - } - - */ /* look for the optional i2c bus parameter */ if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) { if (argc > i + 1) { From ee4a93d668540dea3b7b33eafb94a888f802f466 Mon Sep 17 00:00:00 2001 From: marco Date: Mon, 29 Apr 2013 20:42:06 +0200 Subject: [PATCH 19/23] BLCtrl 2.0 testing - currently only 8 Bit resolution - motor detection and px4 mode as default - with safety shutdown - fix --- apps/drivers/mkblctrl/mkblctrl.cpp | 89 ++++++++++++++++-------------- 1 file changed, 48 insertions(+), 41 deletions(-) diff --git a/apps/drivers/mkblctrl/mkblctrl.cpp b/apps/drivers/mkblctrl/mkblctrl.cpp index 057ee2128d..e70bd16945 100644 --- a/apps/drivers/mkblctrl/mkblctrl.cpp +++ b/apps/drivers/mkblctrl/mkblctrl.cpp @@ -121,7 +121,7 @@ public: int set_motor_test(bool motortest); int set_px4mode(int px4mode); int set_frametype(int frametype); - unsigned int mk_check_for_blctrl(unsigned int count, unsigned int showOutput); + unsigned int mk_check_for_blctrl(unsigned int count, bool showOutput); private: static const unsigned _max_actuators = MAX_MOTORS; @@ -412,47 +412,54 @@ MK::set_frametype(int frametype) int MK::set_motor_count(unsigned count) { - _num_outputs = count; + if(count > 0) { - if(_px4mode == MAPPING_MK) { - if(_frametype == FRAME_PLUS) { - fprintf(stderr, "[mkblctrl] addresstanslator for Mikrokopter addressing used. Frametype: +\n"); - } else if(_frametype == FRAME_X) { - fprintf(stderr, "[mkblctrl] addresstanslator for Mikrokopter addressing used. Frametype: X\n"); + _num_outputs = count; + + if(_px4mode == MAPPING_MK) { + if(_frametype == FRAME_PLUS) { + fprintf(stderr, "[mkblctrl] addresstanslator for Mikrokopter addressing used. Frametype: +\n"); + } else if(_frametype == FRAME_X) { + fprintf(stderr, "[mkblctrl] addresstanslator for Mikrokopter addressing used. Frametype: X\n"); + } + if(_num_outputs == 4) { + if(_frametype == FRAME_PLUS) { + memcpy(&addrTranslator, &blctrlAddr_quad_plus, sizeof(blctrlAddr_quad_plus)); + } else if(_frametype == FRAME_X) { + memcpy(&addrTranslator, &blctrlAddr_quad_x, sizeof(blctrlAddr_quad_x)); + } + } else if(_num_outputs == 6) { + if(_frametype == FRAME_PLUS) { + memcpy(&addrTranslator, &blctrlAddr_hexa_plus, sizeof(blctrlAddr_hexa_plus)); + } else if(_frametype == FRAME_X) { + memcpy(&addrTranslator, &blctrlAddr_hexa_x, sizeof(blctrlAddr_hexa_x)); + } + } else if(_num_outputs == 8) { + if(_frametype == FRAME_PLUS) { + memcpy(&addrTranslator, &blctrlAddr_octo_plus, sizeof(blctrlAddr_octo_plus)); + } else if(_frametype == FRAME_X) { + memcpy(&addrTranslator, &blctrlAddr_octo_x, sizeof(blctrlAddr_octo_x)); + } + } + } else { + fprintf(stderr, "[mkblctrl] PX4 native addressing used.\n"); + memcpy(&addrTranslator, &blctrlAddr_px4, sizeof(blctrlAddr_px4)); } + if(_num_outputs == 4) { - if(_frametype == FRAME_PLUS) { - memcpy(&addrTranslator, &blctrlAddr_quad_plus, sizeof(blctrlAddr_quad_plus)); - } else if(_frametype == FRAME_X) { - memcpy(&addrTranslator, &blctrlAddr_quad_x, sizeof(blctrlAddr_quad_x)); - } - } else if(_num_outputs == 6) { - if(_frametype == FRAME_PLUS) { - memcpy(&addrTranslator, &blctrlAddr_hexa_plus, sizeof(blctrlAddr_hexa_plus)); - } else if(_frametype == FRAME_X) { - memcpy(&addrTranslator, &blctrlAddr_hexa_x, sizeof(blctrlAddr_hexa_x)); - } - } else if(_num_outputs == 8) { - if(_frametype == FRAME_PLUS) { - memcpy(&addrTranslator, &blctrlAddr_octo_plus, sizeof(blctrlAddr_octo_plus)); - } else if(_frametype == FRAME_X) { - memcpy(&addrTranslator, &blctrlAddr_octo_x, sizeof(blctrlAddr_octo_x)); - } + fprintf(stderr, "[mkblctrl] Quadrocopter Mode (4)\n"); + } else if(_num_outputs == 6) { + fprintf(stderr, "[mkblctrl] Hexacopter Mode (6)\n"); + } else if(_num_outputs == 8) { + fprintf(stderr, "[mkblctrl] Octocopter Mode (8)\n"); } + + return OK; + } else { - fprintf(stderr, "[mkblctrl] PX4 native addressing used.\n"); - memcpy(&addrTranslator, &blctrlAddr_px4, sizeof(blctrlAddr_px4)); + return -1; } - if(_num_outputs == 4) { - fprintf(stderr, "[mkblctrl] Quadrocopter Mode (4)\n"); - } else if(_num_outputs == 6) { - fprintf(stderr, "[mkblctrl] Hexacopter Mode (6)\n"); - } else if(_num_outputs == 8) { - fprintf(stderr, "[mkblctrl] Octocopter Mode (8)\n"); - } - - return OK; } int @@ -668,7 +675,7 @@ MK::mk_servo_arm(bool status) unsigned int -MK::mk_check_for_blctrl(unsigned int count, unsigned int showOutput) +MK::mk_check_for_blctrl(unsigned int count, bool showOutput) { _retries = 50; uint8_t foundMotorCount = 0; @@ -709,13 +716,13 @@ MK::mk_check_for_blctrl(unsigned int count, unsigned int showOutput) } } - if(showOutput == 1) { + if(showOutput) { fprintf(stderr, "[mkblctrl] MotorsFound: %i\n",foundMotorCount); - for(unsigned i=0; i< count; i++) { + for(unsigned i=0; i< foundMotorCount; i++) { fprintf(stderr, "[mkblctrl] blctrl[%i] : found=%i\tversion=%i\tcurrent=%i\tmaxpwm=%i\ttemperature=%i\n", i,Motor[i].State, Motor[i].Version, Motor[i].Current, Motor[i].MaxPWM, Motor[i].Temperature); } - if(foundMotorCount == 0) { + if(foundMotorCount != 4 && foundMotorCount != 6 && foundMotorCount != 8) { _task_should_exit = true; } } @@ -1295,7 +1302,7 @@ mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest, /* count used motors */ do { - if(g_mk->mk_check_for_blctrl(8, 0) != 0) { + if(g_mk->mk_check_for_blctrl(8, false) != 0) { shouldStop = 4; } else { shouldStop++; @@ -1303,7 +1310,7 @@ mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest, sleep(1); } while ( shouldStop < 3); - g_mk->set_motor_count(g_mk->mk_check_for_blctrl(8, 1)); + g_mk->set_motor_count(g_mk->mk_check_for_blctrl(8, true)); /* (re)set the PWM output mode */ g_mk->set_mode(servo_mode); From b9b75a24045da332644ce397d2777d9d554ff39f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 2 May 2013 22:35:16 +0200 Subject: [PATCH 20/23] Hotfix: Provide a FMU + IO on quad start script --- ROMFS/Makefile | 3 +- ROMFS/scripts/rc.IO_QUAD | 107 +++++++++++++++++++++++++++++++++++++++ 2 files changed, 109 insertions(+), 1 deletion(-) create mode 100644 ROMFS/scripts/rc.IO_QUAD diff --git a/ROMFS/Makefile b/ROMFS/Makefile index 11a4650fa6..5ff079a930 100644 --- a/ROMFS/Makefile +++ b/ROMFS/Makefile @@ -24,6 +24,7 @@ ROMFS_FSSPEC := $(SRCROOT)/scripts/rcS~init.d/rcS \ $(SRCROOT)/scripts/rc.FMU_quad_x~init.d/rc.FMU_quad_x \ $(SRCROOT)/scripts/rc.usb~init.d/rc.usb \ $(SRCROOT)/scripts/rc.hil~init.d/rc.hil \ + $(SRCROOT)/scripts/rc.IO_QUAD~scripts/rc.IO_QUAD \ $(SRCROOT)/mixers/FMU_pass.mix~mixers/FMU_pass.mix \ $(SRCROOT)/mixers/FMU_Q.mix~mixers/FMU_Q.mix \ $(SRCROOT)/mixers/FMU_X5.mix~mixers/FMU_X5.mix \ @@ -32,7 +33,7 @@ ROMFS_FSSPEC := $(SRCROOT)/scripts/rcS~init.d/rcS \ $(SRCROOT)/mixers/FMU_RET.mix~mixers/FMU_ERT.mix \ $(SRCROOT)/mixers/FMU_quad_x.mix~mixers/FMU_quad_x.mix \ $(SRCROOT)/mixers/FMU_quad_+.mix~mixers/FMU_quad_+.mix \ - $(SRCROOT)/mixers/FMU_quad_v.mix~mixers/FMU_quad_v.mix \ + $(SRCROOT)/mixers/FMU_quad_v.mix~mixers/FMU_quad_v.mix \ $(SRCROOT)/mixers/FMU_hex_x.mix~mixers/FMU_hex_x.mix \ $(SRCROOT)/mixers/FMU_hex_+.mix~mixers/FMU_hex_+.mix \ $(SRCROOT)/mixers/FMU_octo_x.mix~mixers/FMU_octo_x.mix \ diff --git a/ROMFS/scripts/rc.IO_QUAD b/ROMFS/scripts/rc.IO_QUAD new file mode 100644 index 0000000000..287cb0483b --- /dev/null +++ b/ROMFS/scripts/rc.IO_QUAD @@ -0,0 +1,107 @@ +#!nsh + +# Disable USB and autostart +set USB no +set MODE quad + +# +# Start the ORB (first app to start) +# +uorb start + +# +# Load microSD params +# +echo "[init] loading microSD params" +param select /fs/microsd/parameters +if [ -f /fs/microsd/parameters ] +then + param load /fs/microsd/parameters +fi + +# +# Force some key parameters to sane values +# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor +# see https://pixhawk.ethz.ch/mavlink/ +# +param set MAV_TYPE 2 + +# +# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell) +# +if [ -f /fs/microsd/px4io.bin ] +then + echo "PX4IO Firmware found. Checking Upgrade.." + if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current + then + echo "No newer version, skipping upgrade." + else + echo "Loading /fs/microsd/px4io.bin" + if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log + then + cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current + echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log + else + echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log + echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode" + fi + fi +fi + +# +# Start MAVLink (depends on orb) +# +mavlink start -d /dev/ttyS1 -b 57600 +usleep 5000 + +# +# Start the commander (depends on orb, mavlink) +# +commander start + +# +# Start PX4IO interface (depends on orb, commander) +# +px4io start + +# +# Allow PX4IO to recover from midair restarts. +# this is very unlikely, but quite safe and robust. +px4io recovery + +# +# Start the sensors (depends on orb, px4io) +# +sh /etc/init.d/rc.sensors + +# +# Start GPS interface (depends on orb) +# +gps start + +# +# Start the attitude estimator (depends on orb) +# +attitude_estimator_ekf start + +# +# Load mixer and start controllers (depends on px4io) +# +mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix +multirotor_att_control start + +# +# Start logging +# +#sdlog start -s 4 + +# +# Start system state +# +if blinkm start +then + echo "using BlinkM for state indication" + blinkm systemstate +else + echo "no BlinkM found, OK." +fi \ No newline at end of file From 1c4fc6cfb0b5d417011df11a0c8705dc344077b8 Mon Sep 17 00:00:00 2001 From: marco Date: Sat, 4 May 2013 20:37:22 +0200 Subject: [PATCH 21/23] Help Parameter added and some small fixes. This Version was flown several Hours without any Problems. --- apps/drivers/mkblctrl/mkblctrl.cpp | 59 ++++++++++++++++-------------- 1 file changed, 32 insertions(+), 27 deletions(-) diff --git a/apps/drivers/mkblctrl/mkblctrl.cpp b/apps/drivers/mkblctrl/mkblctrl.cpp index e70bd16945..3a735e26fb 100644 --- a/apps/drivers/mkblctrl/mkblctrl.cpp +++ b/apps/drivers/mkblctrl/mkblctrl.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Copyright (C) 2012,2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -219,7 +219,7 @@ struct MotorData_t // the following bytes must be exactly in that order! unsigned int Current; // in 0.1 A steps, read back from BL unsigned int MaxPWM; // read back from BL is less than 255 if BL is in current limit - unsigned int Temperature; // old BL-Ctrl will return a 255 here, the new version the temp. in °C + unsigned int Temperature; // old BL-Ctrl will return a 255 here, the new version the temp. in unsigned int RoundCount; }; @@ -1355,28 +1355,26 @@ extern "C" __EXPORT int mkblctrl_main(int argc, char *argv[]); int mkblctrl_main(int argc, char *argv[]) { - PortMode new_mode = PORT_MODE_UNSET; + PortMode port_mode = PORT_FULL_PWM; int pwm_update_rate_in_hz = UPDATE_RATE; - int motorcount = 0; + int motorcount = 8; int bus = 1; - bool motortest = false; int px4mode = MAPPING_PX4; int frametype = FRAME_PLUS; // + plus is default - - new_mode = PORT_FULL_PWM; - motorcount = 8; + bool motortest = false; + bool showHelp = false; + bool newMode = false; /* - * Mode switches. - * - * XXX use getopt? + * optional parameters */ - for (int i = 1; i < argc; i++) { /* argv[0] is "mk" */ + for (int i = 1; i < argc; i++) { /* look for the optional i2c bus parameter */ if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) { if (argc > i + 1) { bus = atoi(argv[i + 1]); + newMode = true; } else { errx(1, "missing argument for i2c bus (-b)"); return 1; @@ -1388,6 +1386,7 @@ mkblctrl_main(int argc, char *argv[]) if (argc > i + 1) { if(strcmp(argv[i + 1], "+") == 0 || strcmp(argv[i + 1], "x") == 0 || strcmp(argv[i + 1], "X") == 0) { px4mode = MAPPING_MK; + newMode = true; if(strcmp(argv[i + 1], "+") == 0) { frametype = FRAME_PLUS; } else { @@ -1405,30 +1404,36 @@ mkblctrl_main(int argc, char *argv[]) /* look for the optional test parameter */ if (strcmp(argv[i], "-t") == 0) { motortest = true; + newMode = true; + } + + /* look for the optional -h --help parameter */ + if (strcmp(argv[i], "-h") == 0 || strcmp(argv[i], "--help") == 0) { + showHelp == true; } } - if(new_mode == PORT_MODE_UNSET) { - fprintf(stderr, "mkblctrl: unrecognised command, try:\n"); - fprintf(stderr, " [-mkmode frame{+/x}] [-b i2c_bus_number] [-t motortest]\n"); + if(showHelp) { + fprintf(stderr, "mkblctrl: help:\n"); + fprintf(stderr, " [-mkmode frame{+/x}] [-b i2c_bus_number] [-t motortest] [-h / --help]\n"); exit(1); } - if (mk_start(bus, motorcount) != OK) - errx(1, "failed to start the MK-BLCtrl driver"); + + if (g_mk == nullptr) { + if (mk_start(bus, motorcount) != OK) { + errx(1, "failed to start the MK-BLCtrl driver"); + } else { + newMode = true; + } + } - /* was a new mode set? */ - if (new_mode != PORT_MODE_UNSET) { - - /* yes but it's the same mode */ - //if (new_mode == g_port_mode) - //return OK; - - /* switch modes */ - fprintf(stderr, "[mkblctrl] %iHz Update Rate\n",pwm_update_rate_in_hz); - return mk_new_mode(new_mode, pwm_update_rate_in_hz, motorcount, motortest, px4mode, frametype); + /* parameter set ? */ + if (newMode) { + /* switch parameter */ + return mk_new_mode(port_mode, pwm_update_rate_in_hz, motorcount, motortest, px4mode, frametype); } /* test, etc. here g*/ From 1f800edc7676a6ea13127746ce38787a1e98b935 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 5 May 2013 15:51:16 +0400 Subject: [PATCH 22/23] Still threshold increased to 0.1m/s^2, and orientation error threshold to 5m/s^2. Timeout increased to 30s. --- apps/commander/accelerometer_calibration.c | 66 +++++++++++----------- 1 file changed, 32 insertions(+), 34 deletions(-) diff --git a/apps/commander/accelerometer_calibration.c b/apps/commander/accelerometer_calibration.c index 1807369080..991145d73c 100644 --- a/apps/commander/accelerometer_calibration.c +++ b/apps/commander/accelerometer_calibration.c @@ -224,7 +224,7 @@ int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs[3], float * Wait for vehicle become still and detect it's orientation. * * @return 0..5 according to orientation when vehicle is still and ready for measurements, - * ERROR if vehicle is not still after 10s or orientation error is more than 20% + * ERROR if vehicle is not still after 30s or orientation error is more than 5m/s^2 */ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { struct sensor_combined_s sensor; @@ -235,17 +235,17 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { float accel_len2 = 0.0f; /* EMA time constant in seconds*/ float ema_len = 0.2f; - /* set "still" threshold to 0.005 m/s^2 */ - float still_thr2 = pow(0.05f / CONSTANTS_ONE_G, 2); - /* set accel error threshold to 30% of accel vector length */ - float accel_err_thr = 0.3f; + /* set "still" threshold to 0.1 m/s^2 */ + float still_thr2 = pow(0.1f, 2); + /* set accel error threshold to 5m/s^2 */ + float accel_err_thr = 5.0f; /* still time required in us */ int64_t still_time = 2000000; struct pollfd fds[1] = { { .fd = sub_sensor_combined, .events = POLLIN } }; hrt_abstime t_start = hrt_absolute_time(); - /* set deadline to 20s */ - hrt_abstime timeout = 20000000; + /* set timeout to 30s */ + hrt_abstime timeout = 30000000; hrt_abstime t_timeout = t_start + timeout; hrt_abstime t = t_start; hrt_abstime t_prev = t_start; @@ -267,11 +267,10 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { if (d > accel_disp[i]) accel_disp[i] = d; } - accel_len2 = accel_ema[0] * accel_ema[0] + accel_ema[1] * accel_ema[1] + accel_ema[2] * accel_ema[2]; - float still_thr_raw2 = still_thr2 * accel_len2; - if ( accel_disp[0] < still_thr_raw2 && - accel_disp[1] < still_thr_raw2 && - accel_disp[2] < still_thr_raw2 ) { + /* still detector with hysteresis */ + if ( accel_disp[0] < still_thr2 && + accel_disp[1] < still_thr2 && + accel_disp[2] < still_thr2 ) { /* is still now */ if (t_still == 0) { /* first time */ @@ -285,9 +284,9 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { break; } } - } else if ( accel_disp[0] > still_thr_raw2 * 2.0f || - accel_disp[1] > still_thr_raw2 * 2.0f || - accel_disp[2] > still_thr_raw2 * 2.0f) { + } else if ( accel_disp[0] > still_thr2 * 2.0f || + accel_disp[1] > still_thr2 * 2.0f || + accel_disp[2] > still_thr2 * 2.0f) { /* not still, reset still start time */ if (t_still != 0) { mavlink_log_info(mavlink_fd, "moving..."); @@ -306,30 +305,29 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { } float accel_len = sqrt(accel_len2); - float accel_err_thr_raw = accel_len * accel_err_thr; - if ( fabs(accel_ema[0] - accel_len) < accel_err_thr_raw && - fabs(accel_ema[1]) < accel_err_thr_raw && - fabs(accel_ema[2]) < accel_err_thr_raw ) + if ( fabs(accel_ema[0] - accel_len) < accel_err_thr && + fabs(accel_ema[1]) < accel_err_thr && + fabs(accel_ema[2]) < accel_err_thr ) return 0; // [ g, 0, 0 ] - if ( fabs(accel_ema[0] + accel_len) < accel_err_thr_raw && - fabs(accel_ema[1]) < accel_err_thr_raw && - fabs(accel_ema[2]) < accel_err_thr_raw ) + if ( fabs(accel_ema[0] + accel_len) < accel_err_thr && + fabs(accel_ema[1]) < accel_err_thr && + fabs(accel_ema[2]) < accel_err_thr ) return 1; // [ -g, 0, 0 ] - if ( fabs(accel_ema[0]) < accel_err_thr_raw && - fabs(accel_ema[1] - accel_len) < accel_err_thr_raw && - fabs(accel_ema[2]) < accel_err_thr_raw ) + if ( fabs(accel_ema[0]) < accel_err_thr && + fabs(accel_ema[1] - accel_len) < accel_err_thr && + fabs(accel_ema[2]) < accel_err_thr ) return 2; // [ 0, g, 0 ] - if ( fabs(accel_ema[0]) < accel_err_thr_raw && - fabs(accel_ema[1] + accel_len) < accel_err_thr_raw && - fabs(accel_ema[2]) < accel_err_thr_raw ) + if ( fabs(accel_ema[0]) < accel_err_thr && + fabs(accel_ema[1] + accel_len) < accel_err_thr && + fabs(accel_ema[2]) < accel_err_thr ) return 3; // [ 0, -g, 0 ] - if ( fabs(accel_ema[0]) < accel_err_thr_raw && - fabs(accel_ema[1]) < accel_err_thr_raw && - fabs(accel_ema[2] - accel_len) < accel_err_thr_raw ) + if ( fabs(accel_ema[0]) < accel_err_thr && + fabs(accel_ema[1]) < accel_err_thr && + fabs(accel_ema[2] - accel_len) < accel_err_thr ) return 4; // [ 0, 0, g ] - if ( fabs(accel_ema[0]) < accel_err_thr_raw && - fabs(accel_ema[1]) < accel_err_thr_raw && - fabs(accel_ema[2] + accel_len) < accel_err_thr_raw ) + if ( fabs(accel_ema[0]) < accel_err_thr && + fabs(accel_ema[1]) < accel_err_thr && + fabs(accel_ema[2] + accel_len) < accel_err_thr ) return 5; // [ 0, 0, -g ] mavlink_log_info(mavlink_fd, "ERROR: invalid orientation"); From 41ec41cf8cc16309cf6f7e949d3ddad78e5f44a2 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 6 May 2013 18:21:56 +0400 Subject: [PATCH 23/23] Accelerometer calibration bugfix --- apps/commander/accelerometer_calibration.c | 14 ++++++-------- apps/commander/accelerometer_calibration.h | 4 ++-- 2 files changed, 8 insertions(+), 10 deletions(-) diff --git a/apps/commander/accelerometer_calibration.c b/apps/commander/accelerometer_calibration.c index 991145d73c..d79dd93dd0 100644 --- a/apps/commander/accelerometer_calibration.c +++ b/apps/commander/accelerometer_calibration.c @@ -232,7 +232,6 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { float accel_ema[3] = { 0.0f, 0.0f, 0.0f }; /* max-hold dispersion of accel */ float accel_disp[3] = { 0.0f, 0.0f, 0.0f }; - float accel_len2 = 0.0f; /* EMA time constant in seconds*/ float ema_len = 0.2f; /* set "still" threshold to 0.1 m/s^2 */ @@ -304,30 +303,29 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { } } - float accel_len = sqrt(accel_len2); - if ( fabs(accel_ema[0] - accel_len) < accel_err_thr && + if ( fabs(accel_ema[0] - CONSTANTS_ONE_G) < accel_err_thr && fabs(accel_ema[1]) < accel_err_thr && fabs(accel_ema[2]) < accel_err_thr ) return 0; // [ g, 0, 0 ] - if ( fabs(accel_ema[0] + accel_len) < accel_err_thr && + if ( fabs(accel_ema[0] + CONSTANTS_ONE_G) < accel_err_thr && fabs(accel_ema[1]) < accel_err_thr && fabs(accel_ema[2]) < accel_err_thr ) return 1; // [ -g, 0, 0 ] if ( fabs(accel_ema[0]) < accel_err_thr && - fabs(accel_ema[1] - accel_len) < accel_err_thr && + fabs(accel_ema[1] - CONSTANTS_ONE_G) < accel_err_thr && fabs(accel_ema[2]) < accel_err_thr ) return 2; // [ 0, g, 0 ] if ( fabs(accel_ema[0]) < accel_err_thr && - fabs(accel_ema[1] + accel_len) < accel_err_thr && + fabs(accel_ema[1] + CONSTANTS_ONE_G) < accel_err_thr && fabs(accel_ema[2]) < accel_err_thr ) return 3; // [ 0, -g, 0 ] if ( fabs(accel_ema[0]) < accel_err_thr && fabs(accel_ema[1]) < accel_err_thr && - fabs(accel_ema[2] - accel_len) < accel_err_thr ) + fabs(accel_ema[2] - CONSTANTS_ONE_G) < accel_err_thr ) return 4; // [ 0, 0, g ] if ( fabs(accel_ema[0]) < accel_err_thr && fabs(accel_ema[1]) < accel_err_thr && - fabs(accel_ema[2] + accel_len) < accel_err_thr ) + fabs(accel_ema[2] + CONSTANTS_ONE_G) < accel_err_thr ) return 5; // [ 0, 0, -g ] mavlink_log_info(mavlink_fd, "ERROR: invalid orientation"); diff --git a/apps/commander/accelerometer_calibration.h b/apps/commander/accelerometer_calibration.h index c0169c2a13..a11cf93d3c 100644 --- a/apps/commander/accelerometer_calibration.h +++ b/apps/commander/accelerometer_calibration.h @@ -1,8 +1,8 @@ /* * accelerometer_calibration.h * - * Created on: 25.04.2013 - * Author: ton + * Copyright (C) 2013 Anton Babushkin. All rights reserved. + * Author: Anton Babushkin */ #ifndef ACCELEROMETER_CALIBRATION_H_