diff --git a/.cproject b/.cproject new file mode 100644 index 0000000000..b0c8d5a9dd --- /dev/null +++ b/.cproject @@ -0,0 +1,116 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + make + all + true + true + true + + + make + + clean + true + true + true + + + make + + distclean + true + true + true + + + make + + upload + true + true + true + + + make + + install + true + true + true + + + + diff --git a/.gitignore b/.gitignore index a05cd34c8c..3da1c5c7ad 100644 --- a/.gitignore +++ b/.gitignore @@ -33,4 +33,4 @@ nuttx/nuttx.hex .settings Firmware.sublime-workspace .DS_Store -nuttx/configs/px4fmu/include/nsh_romfsimg.h +nsh_romfsimg.h diff --git a/.project b/.project new file mode 100644 index 0000000000..62e37139e4 --- /dev/null +++ b/.project @@ -0,0 +1,135 @@ + + + PX4 Firmware + + + + + + org.eclipse.cdt.managedbuilder.core.genmakebuilder + clean,full,incremental, + + + ?name? + + + + org.eclipse.cdt.make.core.append_environment + true + + + org.eclipse.cdt.make.core.autoBuildTarget + all + + + org.eclipse.cdt.make.core.buildArguments + + + + org.eclipse.cdt.make.core.buildCommand + make + + + org.eclipse.cdt.make.core.cleanBuildTarget + clean + + + org.eclipse.cdt.make.core.contents + org.eclipse.cdt.make.core.activeConfigSettings + + + org.eclipse.cdt.make.core.enableAutoBuild + false + + + org.eclipse.cdt.make.core.enableCleanBuild + true + + + org.eclipse.cdt.make.core.enableFullBuild + true + + + org.eclipse.cdt.make.core.fullBuildTarget + all + + + org.eclipse.cdt.make.core.stopOnError + true + + + org.eclipse.cdt.make.core.useDefaultBuildCmd + true + + + + + org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder + full,incremental, + + + + + + org.eclipse.cdt.core.cnature + org.eclipse.cdt.core.ccnature + org.eclipse.cdt.managedbuilder.core.managedBuildNature + org.eclipse.cdt.managedbuilder.core.ScannerConfigNature + + + + 1344101890673 + + 6 + + org.eclipse.ui.ide.multiFilter + 1.0-name-matches-false-false-*.o + + + + 1344101890683 + + 6 + + org.eclipse.ui.ide.multiFilter + 1.0-name-matches-false-false-.dep + + + + 1344101890687 + + 6 + + org.eclipse.ui.ide.multiFilter + 1.0-name-matches-false-false-.context + + + + 1344101890691 + + 6 + + org.eclipse.ui.ide.multiFilter + 1.0-name-matches-false-false-.depend + + + + 1344101890695 + + 6 + + org.eclipse.ui.ide.multiFilter + 1.0-name-matches-false-false-.built + + + + 1344101890698 + + 6 + + org.eclipse.ui.ide.multiFilter + 1.0-name-matches-false-false-*.a + + + + diff --git a/Firmware.sublime-project b/Firmware.sublime-project index e3a8064c3d..31b924af7c 100644 --- a/Firmware.sublime-project +++ b/Firmware.sublime-project @@ -10,7 +10,10 @@ ".built", ".context", ".depend", - "Make.dep" + "Make.dep", + ".configured", + "*.sublime-project", + "*.sublime-workspace" ] } ], diff --git a/ROMFS/Makefile b/ROMFS/Makefile index cc5a3ccd31..6437a1e974 100644 --- a/ROMFS/Makefile +++ b/ROMFS/Makefile @@ -20,7 +20,12 @@ ROMFS_FSSPEC := $(SRCROOT)/scripts/rcS~init.d/rcS \ $(SRCROOT)/scripts/rc.logging~init.d/rc.logging \ $(SRCROOT)/scripts/rc.standalone~init.d/rc.standalone \ $(SRCROOT)/scripts/rc.PX4IO~init.d/rc.PX4IO \ - $(SRCROOT)/scripts/rc.PX4IOAR~init.d/rc.PX4IOAR + $(SRCROOT)/scripts/rc.PX4IOAR~init.d/rc.PX4IOAR \ + $(SRCROOT)/mixers/FMU_pass.mix~mixers/FMU_pass.mix \ + $(SRCROOT)/mixers/FMU_delta.mix~mixers/FMU_delta.mix \ + $(SRCROOT)/mixers/FMU_AERT.mix~mixers/FMU_AERT.mix \ + $(SRCROOT)/mixers/FMU_AET.mix~mixers/FMU_AET.mix \ + $(SRCROOT)/mixers/FMU_RET.mix~mixers/FMU_ERT.mix # # Add the PX4IO firmware to the spec if someone has dropped it into the diff --git a/ROMFS/mixers/FMU_AERT.mix b/ROMFS/mixers/FMU_AERT.mix new file mode 100644 index 0000000000..eb46da5fa4 --- /dev/null +++ b/ROMFS/mixers/FMU_AERT.mix @@ -0,0 +1,64 @@ +Aileron/rudder/elevator/throttle mixer for PX4FMU +================================================== + +This file defines mixers suitable for controlling a fixed wing aircraft with +aileron, rudder, elevator and throttle controls using PX4FMU. The configuration +assumes the aileron servo(s) are connected to PX4FMU servo output 0, the +elevator to output 1, the rudder to output 2 and the throttle to output 3. + +Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0 +(roll), 1 (pitch) and 3 (thrust). + +Aileron mixer +------------- +Two scalers total (output, roll). + +This mixer assumes that the aileron servos are set up correctly mechanically; +depending on the actual configuration it may be necessary to reverse the scaling +factors (to reverse the servo movement) and adjust the offset, scaling and +endpoints to suit. + +As there is only one output, if using two servos adjustments to compensate for +differences between the servos must be made mechanically. To obtain the correct +motion using a Y cable, the servos can be positioned reversed from one another. + +M: 2 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 0 10000 10000 0 -10000 10000 + +Elevator mixer +------------ +Two scalers total (output, roll). + +This mixer assumes that the elevator servo is set up correctly mechanically; +depending on the actual configuration it may be necessary to reverse the scaling +factors (to reverse the servo movement) and adjust the offset, scaling and +endpoints to suit. + +M: 2 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 1 10000 10000 0 -10000 10000 + +Rudder mixer +------------ +Two scalers total (output, yaw). + +This mixer assumes that the rudder servo is set up correctly mechanically; +depending on the actual configuration it may be necessary to reverse the scaling +factors (to reverse the servo movement) and adjust the offset, scaling and +endpoints to suit. + +M: 2 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 2 10000 10000 0 -10000 10000 + +Motor speed mixer +----------------- +Two scalers total (output, thrust). + +This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1) +range. Inputs below zero are treated as zero. + +M: 2 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 3 0 20000 -10000 -10000 10000 diff --git a/ROMFS/mixers/FMU_AET.mix b/ROMFS/mixers/FMU_AET.mix new file mode 100644 index 0000000000..9ae23f2646 --- /dev/null +++ b/ROMFS/mixers/FMU_AET.mix @@ -0,0 +1,60 @@ +Aileron/elevator/throttle mixer for PX4FMU +================================================== + +This file defines mixers suitable for controlling a fixed wing aircraft with +aileron, elevator and throttle controls using PX4FMU. The configuration assumes +the aileron servo(s) are connected to PX4FMU servo output 0, the elevator to +output 1 and the throttle to output 3. + +Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0 +(roll), 1 (pitch) and 3 (thrust). + +Aileron mixer +------------- +Two scalers total (output, roll). + +This mixer assumes that the aileron servos are set up correctly mechanically; +depending on the actual configuration it may be necessary to reverse the scaling +factors (to reverse the servo movement) and adjust the offset, scaling and +endpoints to suit. + +As there is only one output, if using two servos adjustments to compensate for +differences between the servos must be made mechanically. To obtain the correct +motion using a Y cable, the servos can be positioned reversed from one another. + +Alternatively, output 2 could be used as a second aileron servo output with +separate mixing. + +M: 2 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 0 10000 10000 0 -10000 10000 + +Elevator mixer +------------ +Two scalers total (output, roll). + +This mixer assumes that the elevator servo is set up correctly mechanically; +depending on the actual configuration it may be necessary to reverse the scaling +factors (to reverse the servo movement) and adjust the offset, scaling and +endpoints to suit. + +M: 2 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 1 10000 10000 0 -10000 10000 + +Output 2 +-------- +This mixer is empty. + +M: 0 + +Motor speed mixer +----------------- +Two scalers total (output, thrust). + +This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1) +range. Inputs below zero are treated as zero. + +M: 2 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 3 0 20000 -10000 -10000 10000 diff --git a/ROMFS/mixers/FMU_RET.mix b/ROMFS/mixers/FMU_RET.mix new file mode 100644 index 0000000000..94815b48e8 --- /dev/null +++ b/ROMFS/mixers/FMU_RET.mix @@ -0,0 +1,53 @@ +Rudder/elevator/throttle mixer for PX4FMU +========================================= + +This file defines mixers suitable for controlling a fixed wing aircraft with +rudder, elevator and throttle controls using PX4FMU. The configuration assumes +the rudder servo is connected to PX4FMU servo output 0, the elevator to output 1 +and the throttle to output 3. + +Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0 +(roll), 1 (pitch) and 3 (thrust). + +Rudder mixer +------------ +Two scalers total (output, roll). + +This mixer assumes that the rudder servo is set up correctly mechanically; +depending on the actual configuration it may be necessary to reverse the scaling +factors (to reverse the servo movement) and adjust the offset, scaling and +endpoints to suit. + +M: 2 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 0 10000 10000 0 -10000 10000 + +Elevator mixer +------------ +Two scalers total (output, roll). + +This mixer assumes that the elevator servo is set up correctly mechanically; +depending on the actual configuration it may be necessary to reverse the scaling +factors (to reverse the servo movement) and adjust the offset, scaling and +endpoints to suit. + +M: 2 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 1 10000 10000 0 -10000 10000 + +Output 2 +-------- +This mixer is empty. + +M: 0 + +Motor speed mixer +----------------- +Two scalers total (output, thrust). + +This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1) +range. Inputs below zero are treated as zero. + +M: 2 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 3 0 20000 -10000 -10000 10000 diff --git a/ROMFS/mixers/FMU_delta.mix b/ROMFS/mixers/FMU_delta.mix new file mode 100644 index 0000000000..7b878e40b4 --- /dev/null +++ b/ROMFS/mixers/FMU_delta.mix @@ -0,0 +1,50 @@ +Delta-wing mixer for PX4FMU +=========================== + +This file defines mixers suitable for controlling a delta wing aircraft using +PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU +servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is +assumed to be unused. + +Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0 +(roll), 1 (pitch) and 3 (thrust). + +See the README for more information on the scaler format. + +Elevon mixers +------------- +Three scalers total (output, roll, pitch). + +On the assumption that the two elevon servos are physically reversed, the pitch +input is inverted between the two servos. + +The scaling factor for roll inputs is adjusted to implement differential travel +for the elevons. + +M: 3 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 0 3000 5000 0 -10000 10000 +S: 0 1 5000 5000 0 -10000 10000 + +M: 3 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 0 5000 3000 0 -10000 10000 +S: 0 1 -5000 -5000 0 -10000 10000 + +Output 2 +-------- +This mixer is empty. + +M: 0 + +Motor speed mixer +----------------- +Two scalers total (output, thrust). + +This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1) +range. Inputs below zero are treated as zero. + +M: 2 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 3 0 20000 -10000 -10000 10000 + diff --git a/ROMFS/mixers/FMU_pass.mix b/ROMFS/mixers/FMU_pass.mix new file mode 100644 index 0000000000..0e8e07a072 --- /dev/null +++ b/ROMFS/mixers/FMU_pass.mix @@ -0,0 +1,23 @@ +Passthrough mixer for PX4FMU +============================ + +This file defines passthrough mixers suitable for testing. + +Channel group 0, channels 0-3 are passed directly through to the outputs. + +M: 2 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 0 10000 10000 0 -10000 10000 + +M: 2 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 1 10000 10000 0 -10000 10000 + +M: 2 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 2 10000 10000 0 -10000 10000 + +M: 2 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 3 10000 10000 0 -10000 10000 + diff --git a/ROMFS/mixers/FMU_quad+.mix b/ROMFS/mixers/FMU_quad+.mix new file mode 100644 index 0000000000..1ab38ef6d4 --- /dev/null +++ b/ROMFS/mixers/FMU_quad+.mix @@ -0,0 +1,54 @@ +Quadrotor + mixer for PX4FMU +============================ + +This file defines mixers suitable for controlling a quadrotor in the + +arrangement using PX4FMU. The configuration assumes the motors are connected +starting with the front motor on output 0 and proceeding clockwise. + +Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0 +(roll), 1 (pitch), 2 (yaw) and 3 (thrust). + +See the README for more information on the scaler format. + +Scale values here will definitely need tuning. + +Front +----- + +M: 4 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 0 0 0 0 -10000 10000 +S: 0 1 1000 1000 0 -10000 10000 +S: 0 2 1000 1000 0 -10000 10000 +S: 0 3 0 20000 -10000 -10000 10000 + +Right +----- + +M: 4 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 0 1000 1000 0 -10000 10000 +S: 0 1 0 0 0 -10000 10000 +S: 0 2 -1000 -1000 0 -10000 10000 +S: 0 3 0 20000 -10000 -10000 10000 + +Back +---- + +M: 4 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 0 0 0 0 -10000 10000 +S: 0 1 -1000 -1000 0 -10000 10000 +S: 0 2 1000 1000 0 -10000 10000 +S: 0 3 0 20000 -10000 -10000 10000 + +Left +---- + +M: 4 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 0 -1000 -1000 0 -10000 10000 +S: 0 1 0 0 0 -10000 10000 +S: 0 2 -1000 -1000 0 -10000 10000 +S: 0 3 0 20000 -10000 -10000 10000 + diff --git a/ROMFS/mixers/FMU_quadX.mix b/ROMFS/mixers/FMU_quadX.mix new file mode 100644 index 0000000000..5a8641fa0b --- /dev/null +++ b/ROMFS/mixers/FMU_quadX.mix @@ -0,0 +1,54 @@ +Quadrotor X mixer for PX4FMU +============================ + +This file defines mixers suitable for controlling a quadrotor in the X +arrangement using PX4FMU. The configuration assumes the motors are connected +starting with the front-right motor on output 0 and proceeding clockwise. + +Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0 +(roll), 1 (pitch), 2 (yaw) and 3 (thrust). + +See the README for more information on the scaler format. + +Scale values here will definitely need tuning. + +Front right +----------- + +M: 4 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 0 1000 1000 0 -10000 10000 +S: 0 1 1000 1000 0 -10000 10000 +S: 0 2 1000 1000 0 -10000 10000 +S: 0 3 0 20000 -10000 -10000 10000 + +Back right +---------- + +M: 4 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 0 1000 1000 0 -10000 10000 +S: 0 1 -1000 -1000 0 -10000 10000 +S: 0 2 -1000 -1000 0 -10000 10000 +S: 0 3 0 20000 -10000 -10000 10000 + +Back left +--------- + +M: 4 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 0 -1000 -1000 0 -10000 10000 +S: 0 1 -1000 -1000 0 -10000 10000 +S: 0 2 1000 1000 0 -10000 10000 +S: 0 3 0 20000 -10000 -10000 10000 + +Front left +---------- + +M: 4 +S: 0 0 10000 10000 0 -10000 10000 +S: 0 0 -1000 -1000 0 -10000 10000 +S: 0 1 1000 1000 0 -10000 10000 +S: 0 2 -1000 -1000 0 -10000 10000 +S: 0 3 0 20000 -10000 -10000 10000 + diff --git a/ROMFS/mixers/README b/ROMFS/mixers/README new file mode 100644 index 0000000000..482478fa70 --- /dev/null +++ b/ROMFS/mixers/README @@ -0,0 +1,90 @@ +PX4 mixer definitions +===================== + +Files in this directory implement example mixers that can be used as a basis +for customisation, or for general testing purposes. + +Mixer basics +------------ + +Mixers combine control values from various sources (control tasks, user inputs, +etc.) and produce output values suitable for controlling actuators; servos, +motors, switches and so on. + +An actuator derives its value from the combination of one or more control +values. Each of the control values is scaled according to the actuator's +configuration and then combined to produce the actuator value, which may then be +further scaled to suit the specific output type. + +Internally, all scaling is performed using floating point values. Inputs and +outputs are clamped to the range -1.0 to 1.0. + +control control control + | | | + v v v + scale scale scale + | | | + | v | + +-------> mix <------+ + | + scale + | + v + out + +Scaling +------- + +Basic scalers provide linear scaling of the input to the output. + +Each scaler allows the input value to be scaled independently for inputs +greater/less than zero. An offset can be applied to the output, and lower and +upper boundary constraints can be applied. Negative scaling factors cause the +output to be inverted (negative input produces positive output). + +Scaler pseudocode: + +if (input < 0) + output = (input * NEGATIVE_SCALE) + OFFSET +else + output = (input * POSITIVE_SCALE) + OFFSET + +if (output < LOWER_LIMIT) + output = LOWER_LIMIT +if (output > UPPER_LIMIT) + output = UPPER_LIMIT + +Syntax +------ + +Mixer definitions are text files; lines beginning with a single capital letter +followed by a colon are significant. All other lines are ignored, meaning that +explanatory text can be freely mixed with the definitions. + +Each file may define more than one mixer; the allocation of mixers to actuators +is specific to the device reading the mixer definition. + +A mixer begins with a line of the form + + M: + +If the scaler count is zero, the mixer is a placeholder and the device will not +allocate a mixer for this position. Otherwise, this line is followed by scaler +definitions matching the given count. + +A scaler definition is a line of the form: + + S: <-ve scale> <+ve scale> + +The first scaler definition following the M: line configures the output scaler. +The and fields are ignored in this case. + +For the remaining scalers, the value identifies the control group from +which the scaler will read. Control group 0 is the vehicle attitude control +group; other group numbers may be assigned for other purposes. The value +selects the control within the group that will be scaled. + +The remaining fields on the line represent the scaler parameters as discussed +above. Whilst the calculations are performed as floating-point operations, the +values stored in the definition file are scaled by a factor of 10000; i.e. an +offset of -0.5 is encoded as -5000. diff --git a/apps/px4/fmu/fmu.cpp b/apps/px4/fmu/fmu.cpp index 57eb12f4eb..3021321daf 100644 --- a/apps/px4/fmu/fmu.cpp +++ b/apps/px4/fmu/fmu.cpp @@ -209,6 +209,8 @@ FMUServo::task_main() unsigned num_outputs = (_mode == MODE_2PWM) ? 2 : 4; + log("starting"); + /* loop until killed */ while (!_task_should_exit) { @@ -235,7 +237,6 @@ FMUServo::task_main() /* if the actuator is configured */ if (_mixer[i] != nullptr) { - /* mix controls to the actuator */ float output = mixer_mix(_mixer[i], &controls[0]); @@ -263,6 +264,8 @@ FMUServo::task_main() /* 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 */ @@ -379,13 +382,16 @@ FMUServo::ioctl(struct file *filp, int cmd, unsigned long arg) /* get the caller-supplied mixer and check */ mm = (struct mixer_s *)arg; - if (mixer_check(mm, 1, NUM_ACTUATOR_CONTROLS)) { /* only the attitude group is supported */ - ret = -EINVAL; - break; - } - /* allocate local storage and copy from the caller*/ if (mm != nullptr) { + + if (mixer_check(mm, 1, NUM_ACTUATOR_CONTROLS)) { + /* only the attitude group is supported */ + ret = -EINVAL; + break; + } + + /* allocate a new mixer struct */ tmm = (struct mixer_s *)malloc(MIXER_SIZE(mm->control_count)); memcpy(tmm, mm, MIXER_SIZE(mm->control_count)); @@ -512,6 +518,56 @@ fmu_new_mode(PortMode new_mode) return ret; } +void +test(void) +{ + int fd; + + fd = open(PWM_OUTPUT_DEVICE_PATH, 0); + + if (fd < 0) { + puts("open fail"); + exit(1); + } + + ioctl(fd, PWM_SERVO_ARM, 0); + ioctl(fd, PWM_SERVO_SET(0), 1000); + + close(fd); + + exit(0); +} + +void +fake(int argc, char *argv[]) +{ + if (argc < 5) { + puts("fmu fake (values -100 - 100)"); + exit(1); + } + + struct actuator_controls_s ac; + + ac.control[0] = strtol(argv[1], 0, 0) / 100.0f; + + ac.control[1] = strtol(argv[2], 0, 0) / 100.0f; + + ac.control[2] = strtol(argv[3], 0, 0) / 100.0f; + + ac.control[3] = strtol(argv[4], 0, 0) / 100.0f; + + int handle = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &ac); + + if (handle < 0) { + puts("advertise failed"); + exit(1); + } + + close(handle); + + exit(0); +} + } // namespace extern "C" __EXPORT int fmu_main(int argc, char *argv[]); @@ -521,10 +577,16 @@ fmu_main(int argc, char *argv[]) { PortMode new_mode = PORT_MODE_UNSET; + if (!strcmp(argv[1], "test")) + test(); + + if (!strcmp(argv[1], "fake")) + fake(argc - 1, argv + 1); + /* * Mode switches. * - * XXX use getopt + * XXX use getopt? */ if (!strcmp(argv[1], "mode_gpio")) { new_mode = PORT_FULL_GPIO; diff --git a/apps/systemlib/mixer.c b/apps/systemlib/mixer.c index 8b1dcc054e..b068d39588 100644 --- a/apps/systemlib/mixer.c +++ b/apps/systemlib/mixer.c @@ -163,29 +163,46 @@ mixer_mix(struct mixer_s *mixer, float **controls) static int mixer_getline(int fd, char *line, unsigned maxlen) { - int ret; - char c; + /* reduce line budget by 1 to account for terminal NUL */ + maxlen--; - while (--maxlen) { - ret = read(fd, &c, 1); + /* loop looking for a non-comment line */ + for (;;) { + int ret; + char c; + char *p = line; - if (ret <= 0) - return ret; + /* loop reading characters for this line */ + for (;;) { + ret = read(fd, &c, 1); - if (c == '\r') - continue; + /* on error or EOF, return same */ + if (ret <= 0) + return ret; - if (c == '\n') { - *line = '\0'; - return 1; + /* ignore carriage returns */ + if (c == '\r') + continue; + + /* line termination */ + if (c == '\n') { + /* ignore malformed lines */ + if ((p - line) < 4) + break; + + if (line[1] != ':') + break; + + /* terminate line as string and return */ + *p = '\0'; + return 1; + } + + /* if we have space, accumulate the byte and go on */ + if ((p - line) < maxlen) + *p++ = c; } - - *line++ = c; } - - /* line too long */ - puts("line too long"); - return -1; } static int @@ -214,7 +231,7 @@ mixer_load(int fd, struct mixer_s **mp) { int ret, result = -1; struct mixer_s *mixer = NULL; - char buf[100]; + char buf[60]; unsigned scalers; ret = mixer_getline(fd, buf, sizeof(buf)); diff --git a/nuttx/configs/px4fmu/include/nsh_romfsimg.h b/nuttx/configs/px4fmu/include/nsh_romfsimg.h deleted file mode 100644 index 9965277c74..0000000000 --- a/nuttx/configs/px4fmu/include/nsh_romfsimg.h +++ /dev/null @@ -1,601 +0,0 @@ -unsigned char romfs_img[] = { - 0x2d, 0x72, 0x6f, 0x6d, 0x31, 0x66, 0x73, 0x2d, 0x00, 0x00, 0x18, 0x90, - 0xc0, 0x84, 0x3c, 0x72, 0x4e, 0x53, 0x48, 0x49, 0x6e, 0x69, 0x74, 0x56, - 0x6f, 0x6c, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x49, - 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, 0x00, 0xd1, 0xff, 0xff, 0x97, - 0x2e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, 0x20, - 0x00, 0x00, 0x00, 0x00, 0xd1, 0xd1, 0xff, 0x80, 0x2e, 0x2e, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x09, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, - 0x68, 0x2d, 0x96, 0x03, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xa0, - 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, 0x00, 0xd1, 0xff, 0xff, 0x00, - 0x2e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xc0, 0x00, 0x00, 0x00, 0x20, - 0x00, 0x00, 0x00, 0x00, 0xd1, 0xd1, 0xff, 0x20, 0x2e, 0x2e, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x01, 0x62, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7c, - 0xaf, 0xce, 0x68, 0x4d, 0x72, 0x63, 0x2e, 0x6c, 0x6f, 0x67, 0x67, 0x69, - 0x6e, 0x67, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x23, 0x21, 0x6e, 0x73, - 0x68, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x49, 0x6e, 0x69, 0x74, 0x69, 0x61, - 0x6c, 0x69, 0x73, 0x65, 0x20, 0x6c, 0x6f, 0x67, 0x67, 0x69, 0x6e, 0x67, - 0x20, 0x73, 0x65, 0x72, 0x76, 0x69, 0x63, 0x65, 0x73, 0x2e, 0x0a, 0x23, - 0x0a, 0x0a, 0x69, 0x66, 0x20, 0x5b, 0x20, 0x2d, 0x64, 0x20, 0x2f, 0x66, - 0x73, 0x2f, 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x73, 0x64, 0x20, 0x5d, 0x0a, - 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x09, 0x23, 0x20, 0x58, 0x58, 0x58, 0x20, - 0x74, 0x68, 0x69, 0x73, 0x20, 0x73, 0x68, 0x6f, 0x75, 0x6c, 0x64, 0x20, - 0x62, 0x65, 0x20, 0x27, 0x3c, 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e, 0x64, - 0x3e, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x27, 0x2e, 0x0a, 0x09, 0x23, - 0x20, 0x73, 0x64, 0x6c, 0x6f, 0x67, 0x20, 0x26, 0x0a, 0x66, 0x69, 0x0a, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x05, 0x72, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x03, 0xe9, 0x35, 0x68, 0x7f, 0x06, 0x72, 0x63, 0x2e, 0x50, - 0x58, 0x34, 0x49, 0x4f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x23, 0x21, 0x6e, 0x73, 0x68, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x46, 0x6c, - 0x69, 0x67, 0x68, 0x74, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, - 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x20, 0x66, 0x6f, 0x72, 0x20, - 0x50, 0x58, 0x34, 0x46, 0x4d, 0x55, 0x20, 0x77, 0x69, 0x74, 0x68, 0x20, - 0x50, 0x58, 0x34, 0x49, 0x4f, 0x20, 0x63, 0x61, 0x72, 0x72, 0x69, 0x65, - 0x72, 0x20, 0x62, 0x6f, 0x61, 0x72, 0x64, 0x2e, 0x0a, 0x23, 0x0a, 0x0a, - 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, - 0x20, 0x64, 0x6f, 0x69, 0x6e, 0x67, 0x20, 0x50, 0x58, 0x34, 0x49, 0x4f, - 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, 0x2e, 0x2e, 0x2e, 0x22, - 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, - 0x74, 0x68, 0x65, 0x20, 0x4f, 0x52, 0x42, 0x0a, 0x23, 0x0a, 0x75, 0x6f, - 0x72, 0x62, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x0a, 0x0a, 0x23, 0x0a, - 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, - 0x73, 0x65, 0x6e, 0x73, 0x6f, 0x72, 0x73, 0x2e, 0x0a, 0x23, 0x0a, 0x73, - 0x68, 0x20, 0x2f, 0x65, 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, - 0x64, 0x2f, 0x72, 0x63, 0x2e, 0x73, 0x65, 0x6e, 0x73, 0x6f, 0x72, 0x73, - 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, - 0x4d, 0x41, 0x56, 0x4c, 0x69, 0x6e, 0x6b, 0x0a, 0x23, 0x0a, 0x6d, 0x61, - 0x76, 0x6c, 0x69, 0x6e, 0x6b, 0x20, 0x2d, 0x64, 0x20, 0x2f, 0x64, 0x65, - 0x76, 0x2f, 0x74, 0x74, 0x79, 0x53, 0x30, 0x20, 0x2d, 0x62, 0x20, 0x35, - 0x37, 0x36, 0x30, 0x30, 0x20, 0x26, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, - 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x63, 0x6f, - 0x6d, 0x6d, 0x61, 0x6e, 0x64, 0x65, 0x72, 0x2e, 0x0a, 0x23, 0x0a, 0x23, - 0x20, 0x58, 0x58, 0x58, 0x20, 0x74, 0x68, 0x69, 0x73, 0x20, 0x73, 0x68, - 0x6f, 0x75, 0x6c, 0x64, 0x20, 0x62, 0x65, 0x20, 0x27, 0x3c, 0x63, 0x6f, - 0x6d, 0x6d, 0x61, 0x6e, 0x64, 0x3e, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, - 0x27, 0x2e, 0x0a, 0x23, 0x0a, 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e, 0x64, - 0x65, 0x72, 0x20, 0x26, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, - 0x61, 0x72, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x61, 0x74, 0x74, 0x69, - 0x74, 0x75, 0x64, 0x65, 0x20, 0x65, 0x73, 0x74, 0x69, 0x6d, 0x61, 0x74, - 0x6f, 0x72, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58, 0x58, 0x58, 0x20, 0x74, - 0x68, 0x69, 0x73, 0x20, 0x73, 0x68, 0x6f, 0x75, 0x6c, 0x64, 0x20, 0x62, - 0x65, 0x20, 0x27, 0x3c, 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e, 0x64, 0x3e, - 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x27, 0x2e, 0x0a, 0x23, 0x0a, 0x61, - 0x74, 0x74, 0x69, 0x74, 0x75, 0x64, 0x65, 0x5f, 0x65, 0x73, 0x74, 0x69, - 0x6d, 0x61, 0x74, 0x6f, 0x72, 0x5f, 0x62, 0x6d, 0x20, 0x26, 0x0a, 0x23, - 0x70, 0x6f, 0x73, 0x69, 0x74, 0x69, 0x6f, 0x6e, 0x5f, 0x65, 0x73, 0x74, - 0x69, 0x6d, 0x61, 0x74, 0x6f, 0x72, 0x20, 0x26, 0x0a, 0x0a, 0x23, 0x0a, - 0x23, 0x20, 0x43, 0x6f, 0x6e, 0x66, 0x69, 0x67, 0x75, 0x72, 0x65, 0x20, - 0x50, 0x58, 0x34, 0x46, 0x4d, 0x55, 0x20, 0x66, 0x6f, 0x72, 0x20, 0x6f, - 0x70, 0x65, 0x72, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x20, 0x77, 0x69, 0x74, - 0x68, 0x20, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x0a, 0x23, 0x0a, 0x23, 0x20, - 0x58, 0x58, 0x58, 0x20, 0x61, 0x72, 0x67, 0x75, 0x6d, 0x65, 0x6e, 0x74, - 0x73, 0x3f, 0x0a, 0x23, 0x0a, 0x70, 0x78, 0x34, 0x66, 0x6d, 0x75, 0x20, - 0x73, 0x74, 0x61, 0x72, 0x74, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, - 0x74, 0x61, 0x72, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x66, 0x69, 0x78, - 0x65, 0x64, 0x2d, 0x77, 0x69, 0x6e, 0x67, 0x20, 0x63, 0x6f, 0x6e, 0x74, - 0x72, 0x6f, 0x6c, 0x6c, 0x65, 0x72, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58, - 0x58, 0x58, 0x20, 0x74, 0x68, 0x69, 0x73, 0x20, 0x73, 0x68, 0x6f, 0x75, - 0x6c, 0x64, 0x20, 0x62, 0x65, 0x20, 0x27, 0x3c, 0x63, 0x6f, 0x6d, 0x6d, - 0x61, 0x6e, 0x64, 0x3e, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x27, 0x2e, - 0x0a, 0x23, 0x0a, 0x66, 0x69, 0x78, 0x65, 0x64, 0x77, 0x69, 0x6e, 0x67, - 0x5f, 0x63, 0x6f, 0x6e, 0x74, 0x72, 0x6f, 0x6c, 0x20, 0x26, 0x0a, 0x0a, - 0x23, 0x0a, 0x23, 0x20, 0x46, 0x69, 0x72, 0x65, 0x20, 0x75, 0x70, 0x20, - 0x74, 0x68, 0x65, 0x20, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x20, 0x69, 0x6e, - 0x74, 0x65, 0x72, 0x66, 0x61, 0x63, 0x65, 0x2e, 0x0a, 0x23, 0x0a, 0x70, - 0x78, 0x34, 0x69, 0x6f, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x0a, 0x0a, - 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x6c, 0x6f, - 0x6f, 0x6b, 0x69, 0x6e, 0x67, 0x20, 0x66, 0x6f, 0x72, 0x20, 0x61, 0x20, - 0x47, 0x50, 0x53, 0x2e, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58, 0x58, 0x58, - 0x20, 0x74, 0x68, 0x69, 0x73, 0x20, 0x73, 0x68, 0x6f, 0x75, 0x6c, 0x64, - 0x20, 0x6e, 0x6f, 0x74, 0x20, 0x6e, 0x65, 0x65, 0x64, 0x20, 0x74, 0x6f, - 0x20, 0x62, 0x65, 0x20, 0x62, 0x61, 0x63, 0x6b, 0x67, 0x72, 0x6f, 0x75, - 0x6e, 0x64, 0x65, 0x64, 0x0a, 0x23, 0x0a, 0x67, 0x70, 0x73, 0x20, 0x2d, - 0x64, 0x20, 0x2f, 0x64, 0x65, 0x76, 0x2f, 0x74, 0x74, 0x79, 0x53, 0x33, - 0x20, 0x2d, 0x6d, 0x20, 0x61, 0x6c, 0x6c, 0x20, 0x26, 0x0a, 0x0a, 0x23, - 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x6c, 0x6f, 0x67, - 0x67, 0x69, 0x6e, 0x67, 0x20, 0x74, 0x6f, 0x20, 0x6d, 0x69, 0x63, 0x72, - 0x6f, 0x53, 0x44, 0x20, 0x69, 0x66, 0x20, 0x77, 0x65, 0x20, 0x63, 0x61, - 0x6e, 0x0a, 0x23, 0x0a, 0x73, 0x68, 0x20, 0x2f, 0x65, 0x74, 0x63, 0x2f, - 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f, 0x72, 0x63, 0x2e, 0x6c, 0x6f, - 0x67, 0x67, 0x69, 0x6e, 0x67, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x73, - 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, 0x20, 0x69, 0x73, 0x20, 0x64, 0x6f, - 0x6e, 0x65, 0x3b, 0x20, 0x77, 0x65, 0x20, 0x64, 0x6f, 0x6e, 0x27, 0x74, - 0x20, 0x77, 0x61, 0x6e, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x73, 0x68, - 0x65, 0x6c, 0x6c, 0x20, 0x62, 0x65, 0x63, 0x61, 0x75, 0x73, 0x65, 0x20, - 0x77, 0x65, 0x0a, 0x23, 0x20, 0x75, 0x73, 0x65, 0x20, 0x74, 0x68, 0x65, - 0x20, 0x73, 0x61, 0x6d, 0x65, 0x20, 0x55, 0x41, 0x52, 0x54, 0x20, 0x66, - 0x6f, 0x72, 0x20, 0x74, 0x65, 0x6c, 0x65, 0x6d, 0x65, 0x74, 0x72, 0x79, - 0x20, 0x28, 0x64, 0x75, 0x6d, 0x62, 0x29, 0x2e, 0x0a, 0x23, 0x0a, 0x65, - 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, 0x20, - 0x73, 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, 0x20, 0x64, 0x6f, 0x6e, 0x65, - 0x2c, 0x20, 0x65, 0x78, 0x69, 0x74, 0x69, 0x6e, 0x67, 0x2e, 0x22, 0x0a, - 0x65, 0x78, 0x69, 0x74, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x09, 0x72, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xd6, - 0xf4, 0x16, 0x7b, 0x19, 0x72, 0x63, 0x2e, 0x50, 0x58, 0x34, 0x49, 0x4f, - 0x41, 0x52, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x23, 0x21, 0x6e, 0x73, - 0x68, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x46, 0x6c, 0x69, 0x67, 0x68, 0x74, - 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, 0x20, 0x73, 0x63, 0x72, - 0x69, 0x70, 0x74, 0x20, 0x66, 0x6f, 0x72, 0x20, 0x50, 0x58, 0x34, 0x46, - 0x4d, 0x55, 0x20, 0x6f, 0x6e, 0x20, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x41, - 0x52, 0x20, 0x63, 0x61, 0x72, 0x72, 0x69, 0x65, 0x72, 0x20, 0x62, 0x6f, - 0x61, 0x72, 0x64, 0x2e, 0x0a, 0x23, 0x0a, 0x0a, 0x65, 0x63, 0x68, 0x6f, - 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x64, 0x6f, 0x69, - 0x6e, 0x67, 0x20, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x41, 0x52, 0x20, 0x73, - 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, 0x2e, 0x2e, 0x2e, 0x22, 0x0a, 0x0a, - 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x74, 0x68, - 0x65, 0x20, 0x4f, 0x52, 0x42, 0x0a, 0x23, 0x0a, 0x75, 0x6f, 0x72, 0x62, - 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, - 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x73, 0x65, - 0x6e, 0x73, 0x6f, 0x72, 0x73, 0x2e, 0x0a, 0x23, 0x0a, 0x73, 0x68, 0x20, - 0x2f, 0x65, 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f, - 0x72, 0x63, 0x2e, 0x73, 0x65, 0x6e, 0x73, 0x6f, 0x72, 0x73, 0x0a, 0x0a, - 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x4d, 0x41, - 0x56, 0x4c, 0x69, 0x6e, 0x6b, 0x0a, 0x23, 0x0a, 0x6d, 0x61, 0x76, 0x6c, - 0x69, 0x6e, 0x6b, 0x20, 0x2d, 0x64, 0x20, 0x2f, 0x64, 0x65, 0x76, 0x2f, - 0x74, 0x74, 0x79, 0x53, 0x30, 0x20, 0x2d, 0x62, 0x20, 0x35, 0x37, 0x36, - 0x30, 0x30, 0x20, 0x26, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, - 0x61, 0x72, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x63, 0x6f, 0x6d, 0x6d, - 0x61, 0x6e, 0x64, 0x65, 0x72, 0x2e, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58, - 0x58, 0x58, 0x20, 0x74, 0x68, 0x69, 0x73, 0x20, 0x73, 0x68, 0x6f, 0x75, - 0x6c, 0x64, 0x20, 0x62, 0x65, 0x20, 0x27, 0x3c, 0x63, 0x6f, 0x6d, 0x6d, - 0x61, 0x6e, 0x64, 0x3e, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x27, 0x2e, - 0x0a, 0x23, 0x0a, 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e, 0x64, 0x65, 0x72, - 0x20, 0x26, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, - 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x61, 0x74, 0x74, 0x69, 0x74, 0x75, - 0x64, 0x65, 0x20, 0x65, 0x73, 0x74, 0x69, 0x6d, 0x61, 0x74, 0x6f, 0x72, - 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58, 0x58, 0x58, 0x20, 0x74, 0x68, 0x69, - 0x73, 0x20, 0x73, 0x68, 0x6f, 0x75, 0x6c, 0x64, 0x20, 0x62, 0x65, 0x20, - 0x27, 0x3c, 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e, 0x64, 0x3e, 0x20, 0x73, - 0x74, 0x61, 0x72, 0x74, 0x27, 0x2e, 0x0a, 0x23, 0x0a, 0x61, 0x74, 0x74, - 0x69, 0x74, 0x75, 0x64, 0x65, 0x5f, 0x65, 0x73, 0x74, 0x69, 0x6d, 0x61, - 0x74, 0x6f, 0x72, 0x5f, 0x62, 0x6d, 0x20, 0x26, 0x0a, 0x23, 0x70, 0x6f, - 0x73, 0x69, 0x74, 0x69, 0x6f, 0x6e, 0x5f, 0x65, 0x73, 0x74, 0x69, 0x6d, - 0x61, 0x74, 0x6f, 0x72, 0x20, 0x26, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, - 0x43, 0x6f, 0x6e, 0x66, 0x69, 0x67, 0x75, 0x72, 0x65, 0x20, 0x50, 0x58, - 0x34, 0x46, 0x4d, 0x55, 0x20, 0x66, 0x6f, 0x72, 0x20, 0x6f, 0x70, 0x65, - 0x72, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x20, 0x77, 0x69, 0x74, 0x68, 0x20, - 0x50, 0x58, 0x34, 0x49, 0x4f, 0x41, 0x52, 0x0a, 0x23, 0x0a, 0x23, 0x20, - 0x58, 0x58, 0x58, 0x20, 0x61, 0x72, 0x67, 0x75, 0x6d, 0x65, 0x6e, 0x74, - 0x73, 0x3f, 0x0a, 0x23, 0x0a, 0x70, 0x78, 0x34, 0x66, 0x6d, 0x75, 0x20, - 0x73, 0x74, 0x61, 0x72, 0x74, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x46, - 0x69, 0x72, 0x65, 0x20, 0x75, 0x70, 0x20, 0x74, 0x68, 0x65, 0x20, 0x41, - 0x52, 0x2e, 0x44, 0x72, 0x6f, 0x6e, 0x65, 0x20, 0x63, 0x6f, 0x6e, 0x74, - 0x72, 0x6f, 0x6c, 0x6c, 0x65, 0x72, 0x2e, 0x0a, 0x23, 0x0a, 0x23, 0x20, - 0x58, 0x58, 0x58, 0x20, 0x74, 0x68, 0x69, 0x73, 0x20, 0x73, 0x68, 0x6f, - 0x75, 0x6c, 0x64, 0x20, 0x62, 0x65, 0x20, 0x27, 0x3c, 0x63, 0x6f, 0x6d, - 0x6d, 0x61, 0x6e, 0x64, 0x3e, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x27, - 0x2e, 0x0a, 0x23, 0x0a, 0x61, 0x72, 0x64, 0x72, 0x6f, 0x6e, 0x65, 0x5f, - 0x63, 0x6f, 0x6e, 0x74, 0x72, 0x6f, 0x6c, 0x20, 0x2d, 0x64, 0x20, 0x2f, - 0x64, 0x65, 0x76, 0x2f, 0x74, 0x74, 0x79, 0x53, 0x31, 0x20, 0x2d, 0x6d, - 0x20, 0x61, 0x74, 0x74, 0x69, 0x74, 0x75, 0x64, 0x65, 0x20, 0x26, 0x0a, - 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x6c, - 0x6f, 0x6f, 0x6b, 0x69, 0x6e, 0x67, 0x20, 0x66, 0x6f, 0x72, 0x20, 0x61, - 0x20, 0x47, 0x50, 0x53, 0x2e, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58, 0x58, - 0x58, 0x20, 0x74, 0x68, 0x69, 0x73, 0x20, 0x73, 0x68, 0x6f, 0x75, 0x6c, - 0x64, 0x20, 0x6e, 0x6f, 0x74, 0x20, 0x6e, 0x65, 0x65, 0x64, 0x20, 0x74, - 0x6f, 0x20, 0x62, 0x65, 0x20, 0x62, 0x61, 0x63, 0x6b, 0x67, 0x72, 0x6f, - 0x75, 0x6e, 0x64, 0x65, 0x64, 0x0a, 0x23, 0x0a, 0x67, 0x70, 0x73, 0x20, - 0x2d, 0x64, 0x20, 0x2f, 0x64, 0x65, 0x76, 0x2f, 0x74, 0x74, 0x79, 0x53, - 0x33, 0x20, 0x2d, 0x6d, 0x20, 0x61, 0x6c, 0x6c, 0x20, 0x26, 0x0a, 0x0a, - 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x6c, 0x6f, - 0x67, 0x67, 0x69, 0x6e, 0x67, 0x20, 0x74, 0x6f, 0x20, 0x6d, 0x69, 0x63, - 0x72, 0x6f, 0x53, 0x44, 0x20, 0x69, 0x66, 0x20, 0x77, 0x65, 0x20, 0x63, - 0x61, 0x6e, 0x0a, 0x23, 0x0a, 0x73, 0x68, 0x20, 0x2f, 0x65, 0x74, 0x63, - 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f, 0x72, 0x63, 0x2e, 0x6c, - 0x6f, 0x67, 0x67, 0x69, 0x6e, 0x67, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, - 0x73, 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, 0x20, 0x69, 0x73, 0x20, 0x64, - 0x6f, 0x6e, 0x65, 0x3b, 0x20, 0x77, 0x65, 0x20, 0x64, 0x6f, 0x6e, 0x27, - 0x74, 0x20, 0x77, 0x61, 0x6e, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x73, - 0x68, 0x65, 0x6c, 0x6c, 0x20, 0x62, 0x65, 0x63, 0x61, 0x75, 0x73, 0x65, - 0x20, 0x77, 0x65, 0x0a, 0x23, 0x20, 0x75, 0x73, 0x65, 0x20, 0x74, 0x68, - 0x65, 0x20, 0x73, 0x61, 0x6d, 0x65, 0x20, 0x55, 0x41, 0x52, 0x54, 0x20, - 0x66, 0x6f, 0x72, 0x20, 0x74, 0x65, 0x6c, 0x65, 0x6d, 0x65, 0x74, 0x72, - 0x79, 0x20, 0x28, 0x64, 0x75, 0x6d, 0x62, 0x29, 0x2e, 0x0a, 0x23, 0x0a, - 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, - 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, 0x20, 0x64, 0x6f, 0x6e, - 0x65, 0x2c, 0x20, 0x65, 0x78, 0x69, 0x74, 0x69, 0x6e, 0x67, 0x2e, 0x22, - 0x0a, 0x65, 0x78, 0x69, 0x74, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0b, 0x02, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x01, 0x6e, 0xb5, 0xbb, 0x51, 0xae, 0x72, 0x63, 0x2e, 0x73, - 0x65, 0x6e, 0x73, 0x6f, 0x72, 0x73, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x23, 0x21, 0x6e, 0x73, 0x68, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, - 0x61, 0x6e, 0x64, 0x61, 0x72, 0x64, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, - 0x75, 0x70, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x20, 0x66, 0x6f, - 0x72, 0x20, 0x50, 0x58, 0x34, 0x46, 0x4d, 0x55, 0x20, 0x6f, 0x6e, 0x62, - 0x6f, 0x61, 0x72, 0x64, 0x20, 0x73, 0x65, 0x6e, 0x73, 0x6f, 0x72, 0x20, - 0x64, 0x72, 0x69, 0x76, 0x65, 0x72, 0x73, 0x2e, 0x0a, 0x23, 0x0a, 0x0a, - 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x73, 0x65, - 0x6e, 0x73, 0x6f, 0x72, 0x20, 0x64, 0x72, 0x69, 0x76, 0x65, 0x72, 0x73, - 0x20, 0x68, 0x65, 0x72, 0x65, 0x2e, 0x0a, 0x23, 0x0a, 0x0a, 0x23, 0x6d, - 0x73, 0x35, 0x36, 0x31, 0x31, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x0a, - 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x74, - 0x68, 0x65, 0x20, 0x73, 0x65, 0x6e, 0x73, 0x6f, 0x72, 0x20, 0x63, 0x6f, - 0x6c, 0x6c, 0x65, 0x63, 0x74, 0x69, 0x6f, 0x6e, 0x20, 0x74, 0x61, 0x73, - 0x6b, 0x2e, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58, 0x58, 0x58, 0x20, 0x73, - 0x68, 0x6f, 0x75, 0x6c, 0x64, 0x20, 0x62, 0x65, 0x20, 0x27, 0x73, 0x65, - 0x6e, 0x73, 0x6f, 0x72, 0x73, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x27, - 0x0a, 0x23, 0x0a, 0x73, 0x65, 0x6e, 0x73, 0x6f, 0x72, 0x73, 0x20, 0x26, - 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x54, 0x65, 0x73, 0x74, 0x20, 0x73, - 0x65, 0x6e, 0x73, 0x6f, 0x72, 0x20, 0x66, 0x75, 0x6e, 0x63, 0x74, 0x69, - 0x6f, 0x6e, 0x61, 0x6c, 0x69, 0x74, 0x79, 0x0a, 0x23, 0x0a, 0x23, 0x20, - 0x58, 0x58, 0x58, 0x20, 0x69, 0x6e, 0x74, 0x65, 0x67, 0x72, 0x61, 0x74, - 0x65, 0x20, 0x77, 0x69, 0x74, 0x68, 0x20, 0x27, 0x73, 0x65, 0x6e, 0x73, - 0x6f, 0x72, 0x73, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x27, 0x20, 0x3f, - 0x0a, 0x23, 0x0a, 0x23, 0x69, 0x66, 0x20, 0x73, 0x65, 0x6e, 0x73, 0x6f, - 0x72, 0x73, 0x20, 0x71, 0x75, 0x69, 0x63, 0x6b, 0x74, 0x65, 0x73, 0x74, - 0x0a, 0x23, 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x23, 0x09, 0x65, 0x63, 0x68, - 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x73, 0x65, - 0x6e, 0x73, 0x6f, 0x72, 0x20, 0x69, 0x6e, 0x69, 0x74, 0x69, 0x61, 0x6c, - 0x69, 0x73, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x20, 0x46, 0x41, 0x49, 0x4c, - 0x45, 0x44, 0x2e, 0x22, 0x0a, 0x23, 0x09, 0x72, 0x65, 0x62, 0x6f, 0x6f, - 0x74, 0x0a, 0x23, 0x66, 0x69, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x0e, 0xf2, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xcc, 0x52, 0xce, 0xe0, 0xfd, - 0x72, 0x63, 0x2e, 0x73, 0x74, 0x61, 0x6e, 0x64, 0x61, 0x6c, 0x6f, 0x6e, - 0x65, 0x00, 0x00, 0x00, 0x23, 0x21, 0x6e, 0x73, 0x68, 0x0a, 0x23, 0x0a, - 0x23, 0x20, 0x46, 0x6c, 0x69, 0x67, 0x68, 0x74, 0x20, 0x73, 0x74, 0x61, - 0x72, 0x74, 0x75, 0x70, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x20, - 0x66, 0x6f, 0x72, 0x20, 0x50, 0x58, 0x34, 0x46, 0x4d, 0x55, 0x20, 0x73, - 0x74, 0x61, 0x6e, 0x64, 0x61, 0x6c, 0x6f, 0x6e, 0x65, 0x20, 0x63, 0x6f, - 0x6e, 0x66, 0x69, 0x67, 0x75, 0x72, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x2e, - 0x0a, 0x23, 0x0a, 0x0a, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, - 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x64, 0x6f, 0x69, 0x6e, 0x67, 0x20, 0x73, - 0x74, 0x61, 0x6e, 0x64, 0x61, 0x6c, 0x6f, 0x6e, 0x65, 0x20, 0x50, 0x58, - 0x34, 0x46, 0x4d, 0x55, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, - 0x2e, 0x2e, 0x2e, 0x22, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, - 0x61, 0x72, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x4f, 0x52, 0x42, 0x0a, - 0x23, 0x0a, 0x75, 0x6f, 0x72, 0x62, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, - 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, - 0x74, 0x68, 0x65, 0x20, 0x73, 0x65, 0x6e, 0x73, 0x6f, 0x72, 0x73, 0x2e, - 0x0a, 0x23, 0x0a, 0x23, 0x73, 0x68, 0x20, 0x2f, 0x65, 0x74, 0x63, 0x2f, - 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f, 0x72, 0x63, 0x2e, 0x73, 0x65, - 0x6e, 0x73, 0x6f, 0x72, 0x73, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, - 0x74, 0x61, 0x72, 0x74, 0x20, 0x4d, 0x41, 0x56, 0x4c, 0x69, 0x6e, 0x6b, - 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x6d, 0x61, 0x76, 0x6c, 0x69, 0x6e, 0x6b, - 0x20, 0x2d, 0x64, 0x20, 0x2f, 0x64, 0x65, 0x76, 0x2f, 0x74, 0x74, 0x79, - 0x53, 0x30, 0x20, 0x2d, 0x62, 0x20, 0x35, 0x37, 0x36, 0x30, 0x30, 0x20, - 0x26, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, - 0x20, 0x74, 0x68, 0x65, 0x20, 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e, 0x64, - 0x65, 0x72, 0x2e, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58, 0x58, 0x58, 0x20, - 0x74, 0x68, 0x69, 0x73, 0x20, 0x73, 0x68, 0x6f, 0x75, 0x6c, 0x64, 0x20, - 0x62, 0x65, 0x20, 0x27, 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e, 0x64, 0x65, - 0x72, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x27, 0x2e, 0x0a, 0x23, 0x0a, - 0x23, 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e, 0x64, 0x65, 0x72, 0x20, 0x26, - 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, - 0x74, 0x68, 0x65, 0x20, 0x61, 0x74, 0x74, 0x69, 0x74, 0x75, 0x64, 0x65, - 0x20, 0x65, 0x73, 0x74, 0x69, 0x6d, 0x61, 0x74, 0x6f, 0x72, 0x0a, 0x23, - 0x0a, 0x23, 0x20, 0x58, 0x58, 0x58, 0x20, 0x74, 0x68, 0x69, 0x73, 0x20, - 0x73, 0x68, 0x6f, 0x75, 0x6c, 0x64, 0x20, 0x62, 0x65, 0x20, 0x27, 0x3c, - 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e, 0x64, 0x3e, 0x20, 0x73, 0x74, 0x61, - 0x72, 0x74, 0x27, 0x2e, 0x0a, 0x23, 0x0a, 0x23, 0x61, 0x74, 0x74, 0x69, - 0x74, 0x75, 0x64, 0x65, 0x5f, 0x65, 0x73, 0x74, 0x69, 0x6d, 0x61, 0x74, - 0x6f, 0x72, 0x5f, 0x62, 0x6d, 0x20, 0x26, 0x0a, 0x23, 0x70, 0x6f, 0x73, - 0x69, 0x74, 0x69, 0x6f, 0x6e, 0x5f, 0x65, 0x73, 0x74, 0x69, 0x6d, 0x61, - 0x74, 0x6f, 0x72, 0x20, 0x26, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, - 0x74, 0x61, 0x72, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x66, 0x69, 0x78, - 0x65, 0x64, 0x2d, 0x77, 0x69, 0x6e, 0x67, 0x20, 0x63, 0x6f, 0x6e, 0x74, - 0x72, 0x6f, 0x6c, 0x6c, 0x65, 0x72, 0x2e, 0x0a, 0x23, 0x0a, 0x23, 0x20, - 0x58, 0x58, 0x58, 0x20, 0x73, 0x68, 0x6f, 0x75, 0x6c, 0x64, 0x20, 0x74, - 0x68, 0x69, 0x73, 0x20, 0x62, 0x65, 0x20, 0x6c, 0x6f, 0x6f, 0x6b, 0x69, - 0x6e, 0x67, 0x20, 0x66, 0x6f, 0x72, 0x20, 0x63, 0x6f, 0x6e, 0x66, 0x69, - 0x67, 0x75, 0x72, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x20, 0x74, 0x6f, 0x20, - 0x64, 0x65, 0x63, 0x69, 0x64, 0x65, 0x0a, 0x23, 0x20, 0x77, 0x68, 0x65, - 0x74, 0x68, 0x65, 0x72, 0x20, 0x74, 0x68, 0x65, 0x20, 0x62, 0x6f, 0x61, - 0x72, 0x64, 0x20, 0x69, 0x73, 0x20, 0x63, 0x6f, 0x6e, 0x66, 0x69, 0x67, - 0x75, 0x72, 0x65, 0x64, 0x20, 0x66, 0x6f, 0x72, 0x20, 0x66, 0x69, 0x78, - 0x65, 0x64, 0x2d, 0x77, 0x69, 0x6e, 0x67, 0x20, 0x75, 0x73, 0x65, 0x3f, - 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58, 0x58, 0x58, 0x20, 0x74, 0x68, 0x69, - 0x73, 0x20, 0x73, 0x68, 0x6f, 0x75, 0x6c, 0x64, 0x20, 0x62, 0x65, 0x20, - 0x27, 0x66, 0x69, 0x78, 0x65, 0x64, 0x77, 0x69, 0x6e, 0x67, 0x5f, 0x63, - 0x6f, 0x6e, 0x74, 0x72, 0x6f, 0x6c, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, - 0x27, 0x2e, 0x0a, 0x23, 0x0a, 0x23, 0x66, 0x69, 0x78, 0x65, 0x64, 0x77, - 0x69, 0x6e, 0x67, 0x5f, 0x63, 0x6f, 0x6e, 0x74, 0x72, 0x6f, 0x6c, 0x20, - 0x26, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x43, 0x6f, 0x6e, 0x66, 0x69, - 0x67, 0x75, 0x72, 0x65, 0x20, 0x46, 0x4d, 0x55, 0x20, 0x66, 0x6f, 0x72, - 0x20, 0x73, 0x74, 0x61, 0x6e, 0x64, 0x61, 0x6c, 0x6f, 0x6e, 0x65, 0x20, - 0x6d, 0x6f, 0x64, 0x65, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58, 0x58, 0x58, - 0x20, 0x61, 0x72, 0x67, 0x75, 0x6d, 0x65, 0x6e, 0x74, 0x73, 0x3f, 0x0a, - 0x23, 0x0a, 0x23, 0x70, 0x78, 0x34, 0x66, 0x6d, 0x75, 0x20, 0x73, 0x74, - 0x61, 0x72, 0x74, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, - 0x72, 0x74, 0x20, 0x6c, 0x6f, 0x6f, 0x6b, 0x69, 0x6e, 0x67, 0x20, 0x66, - 0x6f, 0x72, 0x20, 0x61, 0x20, 0x47, 0x50, 0x53, 0x2e, 0x0a, 0x23, 0x0a, - 0x23, 0x20, 0x58, 0x58, 0x58, 0x20, 0x74, 0x68, 0x69, 0x73, 0x20, 0x73, - 0x68, 0x6f, 0x75, 0x6c, 0x64, 0x20, 0x6e, 0x6f, 0x74, 0x20, 0x6e, 0x65, - 0x65, 0x64, 0x20, 0x74, 0x6f, 0x20, 0x62, 0x65, 0x20, 0x62, 0x61, 0x63, - 0x6b, 0x67, 0x72, 0x6f, 0x75, 0x6e, 0x64, 0x65, 0x64, 0x0a, 0x23, 0x0a, - 0x23, 0x67, 0x70, 0x73, 0x20, 0x2d, 0x64, 0x20, 0x2f, 0x64, 0x65, 0x76, - 0x2f, 0x74, 0x74, 0x79, 0x53, 0x33, 0x20, 0x2d, 0x6d, 0x20, 0x61, 0x6c, - 0x6c, 0x20, 0x26, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, - 0x72, 0x74, 0x20, 0x6c, 0x6f, 0x67, 0x67, 0x69, 0x6e, 0x67, 0x20, 0x74, - 0x6f, 0x20, 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x53, 0x44, 0x20, 0x69, 0x66, - 0x20, 0x77, 0x65, 0x20, 0x63, 0x61, 0x6e, 0x0a, 0x23, 0x0a, 0x73, 0x68, - 0x20, 0x2f, 0x65, 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, - 0x2f, 0x72, 0x63, 0x2e, 0x6c, 0x6f, 0x67, 0x67, 0x69, 0x6e, 0x67, 0x0a, - 0x0a, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, - 0x5d, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, 0x20, 0x64, 0x6f, - 0x6e, 0x65, 0x22, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0a, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x09, 0x76, 0x8d, 0x9c, 0xa3, 0x80, - 0x72, 0x63, 0x53, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x23, 0x21, 0x6e, 0x73, 0x68, 0x0a, 0x23, 0x0a, - 0x23, 0x20, 0x50, 0x58, 0x34, 0x46, 0x4d, 0x55, 0x20, 0x73, 0x74, 0x61, - 0x72, 0x74, 0x75, 0x70, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x2e, - 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x54, 0x68, 0x69, 0x73, 0x20, 0x73, 0x63, - 0x72, 0x69, 0x70, 0x74, 0x20, 0x69, 0x73, 0x20, 0x72, 0x65, 0x73, 0x70, - 0x6f, 0x6e, 0x73, 0x69, 0x62, 0x6c, 0x65, 0x20, 0x66, 0x6f, 0x72, 0x3a, - 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x2d, 0x20, 0x6d, 0x6f, 0x75, 0x6e, 0x74, - 0x69, 0x6e, 0x67, 0x20, 0x74, 0x68, 0x65, 0x20, 0x6d, 0x69, 0x63, 0x72, - 0x6f, 0x53, 0x44, 0x20, 0x63, 0x61, 0x72, 0x64, 0x20, 0x28, 0x69, 0x66, - 0x20, 0x70, 0x72, 0x65, 0x73, 0x65, 0x6e, 0x74, 0x29, 0x0a, 0x23, 0x20, - 0x2d, 0x20, 0x72, 0x75, 0x6e, 0x6e, 0x69, 0x6e, 0x67, 0x20, 0x74, 0x68, - 0x65, 0x20, 0x75, 0x73, 0x65, 0x72, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, - 0x75, 0x70, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x20, 0x66, 0x72, - 0x6f, 0x6d, 0x20, 0x74, 0x68, 0x65, 0x20, 0x6d, 0x69, 0x63, 0x72, 0x6f, - 0x53, 0x44, 0x20, 0x63, 0x61, 0x72, 0x64, 0x20, 0x28, 0x69, 0x66, 0x20, - 0x70, 0x72, 0x65, 0x73, 0x65, 0x6e, 0x74, 0x29, 0x0a, 0x23, 0x20, 0x2d, - 0x20, 0x64, 0x65, 0x74, 0x65, 0x63, 0x74, 0x69, 0x6e, 0x67, 0x20, 0x74, - 0x68, 0x65, 0x20, 0x63, 0x6f, 0x6e, 0x66, 0x69, 0x67, 0x75, 0x72, 0x61, - 0x74, 0x69, 0x6f, 0x6e, 0x20, 0x6f, 0x66, 0x20, 0x74, 0x68, 0x65, 0x20, - 0x73, 0x79, 0x73, 0x74, 0x65, 0x6d, 0x20, 0x61, 0x6e, 0x64, 0x20, 0x70, - 0x69, 0x63, 0x6b, 0x69, 0x6e, 0x67, 0x20, 0x61, 0x20, 0x73, 0x75, 0x69, - 0x74, 0x61, 0x62, 0x6c, 0x65, 0x0a, 0x23, 0x20, 0x20, 0x20, 0x73, 0x74, - 0x61, 0x72, 0x74, 0x75, 0x70, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, - 0x20, 0x74, 0x6f, 0x20, 0x63, 0x6f, 0x6e, 0x74, 0x69, 0x6e, 0x75, 0x65, - 0x20, 0x77, 0x69, 0x74, 0x68, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x4e, 0x6f, - 0x74, 0x65, 0x3a, 0x20, 0x44, 0x4f, 0x20, 0x4e, 0x4f, 0x54, 0x20, 0x61, - 0x64, 0x64, 0x20, 0x63, 0x6f, 0x6e, 0x66, 0x69, 0x67, 0x75, 0x72, 0x61, - 0x74, 0x69, 0x6f, 0x6e, 0x2d, 0x73, 0x70, 0x65, 0x63, 0x69, 0x66, 0x69, - 0x63, 0x20, 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e, 0x64, 0x73, 0x20, 0x74, - 0x6f, 0x20, 0x74, 0x68, 0x69, 0x73, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, - 0x74, 0x3b, 0x0a, 0x23, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x61, - 0x64, 0x64, 0x20, 0x74, 0x68, 0x65, 0x6d, 0x20, 0x74, 0x6f, 0x20, 0x74, - 0x68, 0x65, 0x20, 0x70, 0x65, 0x72, 0x2d, 0x63, 0x6f, 0x6e, 0x66, 0x69, - 0x67, 0x75, 0x72, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x20, 0x73, 0x63, 0x72, - 0x69, 0x70, 0x74, 0x73, 0x20, 0x69, 0x6e, 0x73, 0x74, 0x65, 0x61, 0x64, - 0x2e, 0x0a, 0x23, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x44, 0x65, 0x66, - 0x61, 0x75, 0x6c, 0x74, 0x20, 0x74, 0x6f, 0x20, 0x61, 0x75, 0x74, 0x6f, - 0x2d, 0x73, 0x74, 0x61, 0x72, 0x74, 0x20, 0x6d, 0x6f, 0x64, 0x65, 0x2e, - 0x20, 0x20, 0x41, 0x6e, 0x20, 0x69, 0x6e, 0x69, 0x74, 0x20, 0x73, 0x63, - 0x72, 0x69, 0x70, 0x74, 0x20, 0x6f, 0x6e, 0x20, 0x74, 0x68, 0x65, 0x20, - 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x53, 0x44, 0x20, 0x63, 0x61, 0x72, 0x64, - 0x0a, 0x23, 0x20, 0x63, 0x61, 0x6e, 0x20, 0x63, 0x68, 0x61, 0x6e, 0x67, - 0x65, 0x20, 0x74, 0x68, 0x69, 0x73, 0x20, 0x74, 0x6f, 0x20, 0x70, 0x72, - 0x65, 0x76, 0x65, 0x6e, 0x74, 0x20, 0x61, 0x75, 0x74, 0x6f, 0x6d, 0x61, - 0x74, 0x69, 0x63, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, 0x20, - 0x6f, 0x66, 0x20, 0x74, 0x68, 0x65, 0x20, 0x66, 0x6c, 0x69, 0x67, 0x68, - 0x74, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x2e, 0x0a, 0x23, 0x0a, - 0x73, 0x65, 0x74, 0x20, 0x4d, 0x4f, 0x44, 0x45, 0x20, 0x61, 0x75, 0x74, - 0x6f, 0x73, 0x74, 0x61, 0x72, 0x74, 0x0a, 0x73, 0x65, 0x74, 0x20, 0x55, - 0x53, 0x42, 0x5f, 0x41, 0x4c, 0x4c, 0x4f, 0x57, 0x45, 0x44, 0x20, 0x79, - 0x65, 0x73, 0x0a, 0x73, 0x65, 0x74, 0x20, 0x55, 0x53, 0x42, 0x20, 0x6e, - 0x6f, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x54, 0x72, 0x79, 0x20, 0x74, - 0x6f, 0x20, 0x6d, 0x6f, 0x75, 0x6e, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, - 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x53, 0x44, 0x20, 0x63, 0x61, 0x72, 0x64, - 0x2e, 0x0a, 0x23, 0x0a, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, - 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x6c, 0x6f, 0x6f, 0x6b, 0x69, 0x6e, 0x67, - 0x20, 0x66, 0x6f, 0x72, 0x20, 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x53, 0x44, - 0x2e, 0x2e, 0x2e, 0x22, 0x0a, 0x69, 0x66, 0x20, 0x6d, 0x6f, 0x75, 0x6e, - 0x74, 0x20, 0x2d, 0x74, 0x20, 0x76, 0x66, 0x61, 0x74, 0x20, 0x2f, 0x64, - 0x65, 0x76, 0x2f, 0x6d, 0x6d, 0x63, 0x73, 0x64, 0x30, 0x20, 0x2f, 0x66, - 0x73, 0x2f, 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x73, 0x64, 0x0a, 0x74, 0x68, - 0x65, 0x6e, 0x0a, 0x09, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, - 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x63, 0x61, 0x72, 0x64, 0x20, 0x6d, 0x6f, - 0x75, 0x6e, 0x74, 0x65, 0x64, 0x20, 0x61, 0x74, 0x20, 0x2f, 0x66, 0x73, - 0x2f, 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x73, 0x64, 0x22, 0x0a, 0x65, 0x6c, - 0x73, 0x65, 0x0a, 0x09, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, - 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x6e, 0x6f, 0x20, 0x6d, 0x69, 0x63, 0x72, - 0x6f, 0x53, 0x44, 0x20, 0x63, 0x61, 0x72, 0x64, 0x20, 0x66, 0x6f, 0x75, - 0x6e, 0x64, 0x22, 0x0a, 0x66, 0x69, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, - 0x4c, 0x6f, 0x6f, 0x6b, 0x20, 0x66, 0x6f, 0x72, 0x20, 0x61, 0x6e, 0x20, - 0x69, 0x6e, 0x69, 0x74, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x20, - 0x6f, 0x6e, 0x20, 0x74, 0x68, 0x65, 0x20, 0x6d, 0x69, 0x63, 0x72, 0x6f, - 0x53, 0x44, 0x20, 0x63, 0x61, 0x72, 0x64, 0x2e, 0x0a, 0x23, 0x0a, 0x23, - 0x20, 0x54, 0x6f, 0x20, 0x70, 0x72, 0x65, 0x76, 0x65, 0x6e, 0x74, 0x20, - 0x61, 0x75, 0x74, 0x6f, 0x6d, 0x61, 0x74, 0x69, 0x63, 0x20, 0x73, 0x74, - 0x61, 0x72, 0x74, 0x75, 0x70, 0x20, 0x69, 0x6e, 0x20, 0x74, 0x68, 0x65, - 0x20, 0x63, 0x75, 0x72, 0x72, 0x65, 0x6e, 0x74, 0x20, 0x66, 0x6c, 0x69, - 0x67, 0x68, 0x74, 0x20, 0x6d, 0x6f, 0x64, 0x65, 0x2c, 0x0a, 0x23, 0x20, - 0x74, 0x68, 0x65, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x20, 0x73, - 0x68, 0x6f, 0x75, 0x6c, 0x64, 0x20, 0x73, 0x65, 0x74, 0x20, 0x4d, 0x4f, - 0x44, 0x45, 0x20, 0x74, 0x6f, 0x20, 0x73, 0x6f, 0x6d, 0x65, 0x20, 0x6f, - 0x74, 0x68, 0x65, 0x72, 0x20, 0x76, 0x61, 0x6c, 0x75, 0x65, 0x2e, 0x0a, - 0x23, 0x0a, 0x69, 0x66, 0x20, 0x5b, 0x20, 0x2d, 0x66, 0x20, 0x2f, 0x66, - 0x73, 0x2f, 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x73, 0x64, 0x2f, 0x65, 0x74, - 0x63, 0x2f, 0x72, 0x63, 0x20, 0x5d, 0x0a, 0x74, 0x68, 0x65, 0x6e, 0x0a, - 0x09, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, - 0x5d, 0x20, 0x72, 0x65, 0x61, 0x64, 0x69, 0x6e, 0x67, 0x20, 0x2f, 0x66, - 0x73, 0x2f, 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x73, 0x64, 0x2f, 0x65, 0x74, - 0x63, 0x2f, 0x72, 0x63, 0x22, 0x0a, 0x09, 0x73, 0x68, 0x20, 0x2f, 0x66, - 0x73, 0x2f, 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x73, 0x64, 0x2f, 0x65, 0x74, - 0x63, 0x2f, 0x72, 0x63, 0x0a, 0x66, 0x69, 0x0a, 0x0a, 0x23, 0x0a, 0x23, - 0x20, 0x43, 0x68, 0x65, 0x63, 0x6b, 0x20, 0x66, 0x6f, 0x72, 0x20, 0x55, - 0x53, 0x42, 0x20, 0x68, 0x6f, 0x73, 0x74, 0x0a, 0x23, 0x0a, 0x69, 0x66, - 0x20, 0x5b, 0x20, 0x24, 0x55, 0x53, 0x42, 0x5f, 0x41, 0x4c, 0x4c, 0x4f, - 0x57, 0x45, 0x44, 0x20, 0x3d, 0x3d, 0x20, 0x79, 0x65, 0x73, 0x20, 0x5d, - 0x0a, 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x09, 0x69, 0x66, 0x20, 0x73, 0x65, - 0x72, 0x63, 0x6f, 0x6e, 0x0a, 0x09, 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x09, - 0x09, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, - 0x5d, 0x20, 0x55, 0x53, 0x42, 0x20, 0x69, 0x6e, 0x74, 0x65, 0x72, 0x66, - 0x61, 0x63, 0x65, 0x20, 0x63, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74, 0x65, - 0x64, 0x22, 0x0a, 0x09, 0x66, 0x69, 0x0a, 0x66, 0x69, 0x0a, 0x0a, 0x23, - 0x0a, 0x23, 0x20, 0x49, 0x66, 0x20, 0x77, 0x65, 0x20, 0x61, 0x72, 0x65, - 0x20, 0x73, 0x74, 0x69, 0x6c, 0x6c, 0x20, 0x69, 0x6e, 0x20, 0x66, 0x6c, - 0x69, 0x67, 0x68, 0x74, 0x20, 0x6d, 0x6f, 0x64, 0x65, 0x2c, 0x20, 0x77, - 0x6f, 0x72, 0x6b, 0x20, 0x6f, 0x75, 0x74, 0x20, 0x77, 0x68, 0x61, 0x74, - 0x20, 0x61, 0x69, 0x72, 0x66, 0x72, 0x61, 0x6d, 0x65, 0x20, 0x0a, 0x23, - 0x20, 0x63, 0x6f, 0x6e, 0x66, 0x69, 0x67, 0x75, 0x72, 0x61, 0x74, 0x69, - 0x6f, 0x6e, 0x20, 0x77, 0x65, 0x20, 0x68, 0x61, 0x76, 0x65, 0x20, 0x61, - 0x6e, 0x64, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x20, 0x75, 0x70, 0x20, - 0x61, 0x63, 0x63, 0x6f, 0x72, 0x64, 0x69, 0x6e, 0x67, 0x6c, 0x79, 0x2e, - 0x0a, 0x23, 0x0a, 0x69, 0x66, 0x20, 0x5b, 0x20, 0x24, 0x4d, 0x4f, 0x44, - 0x45, 0x20, 0x21, 0x3d, 0x20, 0x61, 0x75, 0x74, 0x6f, 0x73, 0x74, 0x61, - 0x72, 0x74, 0x20, 0x5d, 0x0a, 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x09, 0x65, - 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, 0x20, - 0x61, 0x75, 0x74, 0x6f, 0x6d, 0x61, 0x74, 0x69, 0x63, 0x20, 0x73, 0x74, - 0x61, 0x72, 0x74, 0x75, 0x70, 0x20, 0x63, 0x61, 0x6e, 0x63, 0x65, 0x6c, - 0x6c, 0x65, 0x64, 0x20, 0x62, 0x79, 0x20, 0x75, 0x73, 0x65, 0x72, 0x20, - 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x22, 0x0a, 0x65, 0x6c, 0x73, 0x65, - 0x0a, 0x09, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, - 0x74, 0x5d, 0x20, 0x64, 0x65, 0x74, 0x65, 0x63, 0x74, 0x69, 0x6e, 0x67, - 0x20, 0x61, 0x74, 0x74, 0x61, 0x63, 0x68, 0x65, 0x64, 0x20, 0x68, 0x61, - 0x72, 0x64, 0x77, 0x61, 0x72, 0x65, 0x2e, 0x2e, 0x2e, 0x22, 0x0a, 0x0a, - 0x09, 0x23, 0x0a, 0x09, 0x23, 0x20, 0x41, 0x73, 0x73, 0x75, 0x6d, 0x65, - 0x20, 0x74, 0x68, 0x61, 0x74, 0x20, 0x77, 0x65, 0x20, 0x61, 0x72, 0x65, - 0x20, 0x50, 0x58, 0x34, 0x46, 0x4d, 0x55, 0x20, 0x69, 0x6e, 0x20, 0x73, - 0x74, 0x61, 0x6e, 0x64, 0x61, 0x6c, 0x6f, 0x6e, 0x65, 0x20, 0x6d, 0x6f, - 0x64, 0x65, 0x0a, 0x09, 0x23, 0x0a, 0x09, 0x73, 0x65, 0x74, 0x20, 0x42, - 0x4f, 0x41, 0x52, 0x44, 0x20, 0x50, 0x58, 0x34, 0x46, 0x4d, 0x55, 0x0a, - 0x0a, 0x09, 0x23, 0x0a, 0x09, 0x23, 0x20, 0x41, 0x72, 0x65, 0x20, 0x77, - 0x65, 0x20, 0x61, 0x74, 0x74, 0x61, 0x63, 0x68, 0x65, 0x64, 0x20, 0x74, - 0x6f, 0x20, 0x61, 0x20, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x41, 0x52, 0x20, - 0x28, 0x41, 0x52, 0x2e, 0x44, 0x72, 0x6f, 0x6e, 0x65, 0x20, 0x63, 0x61, - 0x72, 0x72, 0x69, 0x65, 0x72, 0x20, 0x62, 0x6f, 0x61, 0x72, 0x64, 0x29, - 0x3f, 0x0a, 0x09, 0x23, 0x0a, 0x09, 0x69, 0x66, 0x20, 0x62, 0x6f, 0x61, - 0x72, 0x64, 0x69, 0x6e, 0x66, 0x6f, 0x20, 0x2d, 0x74, 0x20, 0x37, 0x0a, - 0x09, 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x09, 0x09, 0x73, 0x65, 0x74, 0x20, - 0x42, 0x4f, 0x41, 0x52, 0x44, 0x20, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x41, - 0x52, 0x0a, 0x09, 0x09, 0x69, 0x66, 0x20, 0x5b, 0x20, 0x2d, 0x66, 0x20, - 0x2f, 0x65, 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f, - 0x72, 0x63, 0x2e, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x41, 0x52, 0x20, 0x5d, - 0x0a, 0x09, 0x09, 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x09, 0x09, 0x09, 0x65, - 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, 0x20, - 0x72, 0x65, 0x61, 0x64, 0x69, 0x6e, 0x67, 0x20, 0x2f, 0x65, 0x74, 0x63, - 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f, 0x72, 0x63, 0x2e, 0x50, - 0x58, 0x34, 0x49, 0x4f, 0x41, 0x52, 0x22, 0x0a, 0x09, 0x09, 0x09, 0x73, - 0x68, 0x20, 0x2f, 0x65, 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, - 0x64, 0x2f, 0x72, 0x63, 0x2e, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x41, 0x52, - 0x0a, 0x09, 0x09, 0x66, 0x69, 0x0a, 0x09, 0x65, 0x6c, 0x73, 0x65, 0x0a, - 0x09, 0x09, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, - 0x74, 0x5d, 0x20, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x41, 0x52, 0x20, 0x6e, - 0x6f, 0x74, 0x20, 0x64, 0x65, 0x74, 0x65, 0x63, 0x74, 0x65, 0x64, 0x22, - 0x0a, 0x09, 0x66, 0x69, 0x0a, 0x0a, 0x09, 0x23, 0x0a, 0x09, 0x23, 0x20, - 0x41, 0x72, 0x65, 0x20, 0x77, 0x65, 0x20, 0x61, 0x74, 0x74, 0x61, 0x63, - 0x68, 0x65, 0x64, 0x20, 0x74, 0x6f, 0x20, 0x61, 0x20, 0x50, 0x58, 0x34, - 0x49, 0x4f, 0x3f, 0x0a, 0x09, 0x23, 0x0a, 0x09, 0x69, 0x66, 0x20, 0x62, - 0x6f, 0x61, 0x72, 0x64, 0x69, 0x6e, 0x66, 0x6f, 0x20, 0x2d, 0x74, 0x20, - 0x36, 0x0a, 0x09, 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x09, 0x09, 0x73, 0x65, - 0x74, 0x20, 0x42, 0x4f, 0x41, 0x52, 0x44, 0x20, 0x50, 0x58, 0x34, 0x49, - 0x4f, 0x0a, 0x09, 0x09, 0x69, 0x66, 0x20, 0x5b, 0x20, 0x2d, 0x66, 0x20, - 0x2f, 0x65, 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f, - 0x72, 0x63, 0x2e, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x20, 0x5d, 0x0a, 0x09, - 0x09, 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x09, 0x09, 0x09, 0x65, 0x63, 0x68, - 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x72, 0x65, - 0x61, 0x64, 0x69, 0x6e, 0x67, 0x20, 0x2f, 0x65, 0x74, 0x63, 0x2f, 0x69, - 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f, 0x72, 0x63, 0x2e, 0x50, 0x58, 0x34, - 0x49, 0x4f, 0x22, 0x0a, 0x09, 0x09, 0x09, 0x73, 0x68, 0x20, 0x2f, 0x65, - 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f, 0x72, 0x63, - 0x2e, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x0a, 0x09, 0x09, 0x66, 0x69, 0x0a, - 0x09, 0x65, 0x6c, 0x73, 0x65, 0x0a, 0x09, 0x09, 0x65, 0x63, 0x68, 0x6f, - 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x50, 0x58, 0x34, - 0x49, 0x4f, 0x20, 0x6e, 0x6f, 0x74, 0x20, 0x64, 0x65, 0x74, 0x65, 0x63, - 0x74, 0x65, 0x64, 0x22, 0x0a, 0x09, 0x66, 0x69, 0x0a, 0x0a, 0x09, 0x23, - 0x0a, 0x09, 0x23, 0x20, 0x4c, 0x6f, 0x6f, 0x6b, 0x73, 0x20, 0x6c, 0x69, - 0x6b, 0x65, 0x20, 0x77, 0x65, 0x20, 0x61, 0x72, 0x65, 0x20, 0x73, 0x74, - 0x61, 0x6e, 0x64, 0x2d, 0x61, 0x6c, 0x6f, 0x6e, 0x65, 0x0a, 0x09, 0x23, - 0x0a, 0x09, 0x69, 0x66, 0x20, 0x5b, 0x20, 0x24, 0x42, 0x4f, 0x41, 0x52, - 0x44, 0x20, 0x3d, 0x3d, 0x20, 0x50, 0x58, 0x34, 0x46, 0x4d, 0x55, 0x20, - 0x5d, 0x0a, 0x09, 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x09, 0x09, 0x65, 0x63, - 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x6e, - 0x6f, 0x20, 0x65, 0x78, 0x70, 0x61, 0x6e, 0x73, 0x69, 0x6f, 0x6e, 0x20, - 0x62, 0x6f, 0x61, 0x72, 0x64, 0x20, 0x64, 0x65, 0x74, 0x65, 0x63, 0x74, - 0x65, 0x64, 0x22, 0x0a, 0x09, 0x09, 0x69, 0x66, 0x20, 0x5b, 0x20, 0x2d, - 0x66, 0x20, 0x2f, 0x65, 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, - 0x64, 0x2f, 0x72, 0x63, 0x2e, 0x73, 0x74, 0x61, 0x6e, 0x64, 0x61, 0x6c, - 0x6f, 0x6e, 0x65, 0x20, 0x5d, 0x0a, 0x09, 0x09, 0x74, 0x68, 0x65, 0x6e, - 0x0a, 0x09, 0x09, 0x09, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, - 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x72, 0x65, 0x61, 0x64, 0x69, 0x6e, 0x67, - 0x20, 0x2f, 0x65, 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, - 0x2f, 0x72, 0x63, 0x2e, 0x73, 0x74, 0x61, 0x6e, 0x64, 0x61, 0x6c, 0x6f, - 0x6e, 0x65, 0x22, 0x0a, 0x09, 0x09, 0x09, 0x73, 0x68, 0x20, 0x2f, 0x65, - 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f, 0x72, 0x63, - 0x2e, 0x73, 0x74, 0x61, 0x6e, 0x64, 0x61, 0x6c, 0x6f, 0x6e, 0x65, 0x0a, - 0x09, 0x09, 0x66, 0x69, 0x0a, 0x09, 0x66, 0x69, 0x0a, 0x0a, 0x09, 0x23, - 0x0a, 0x09, 0x23, 0x20, 0x57, 0x65, 0x20, 0x6d, 0x61, 0x79, 0x20, 0x6e, - 0x6f, 0x74, 0x20, 0x72, 0x65, 0x61, 0x63, 0x68, 0x20, 0x68, 0x65, 0x72, - 0x65, 0x20, 0x69, 0x66, 0x20, 0x74, 0x68, 0x65, 0x20, 0x61, 0x69, 0x72, - 0x66, 0x72, 0x61, 0x6d, 0x65, 0x2d, 0x73, 0x70, 0x65, 0x63, 0x69, 0x66, - 0x69, 0x63, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x20, 0x65, 0x78, - 0x69, 0x74, 0x73, 0x20, 0x74, 0x68, 0x65, 0x20, 0x73, 0x68, 0x65, 0x6c, - 0x6c, 0x2e, 0x0a, 0x09, 0x23, 0x0a, 0x09, 0x65, 0x63, 0x68, 0x6f, 0x20, - 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x73, 0x74, 0x61, 0x72, - 0x74, 0x75, 0x70, 0x20, 0x64, 0x6f, 0x6e, 0x65, 0x2e, 0x22, 0x0a, 0x66, - 0x69, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00 -}; -unsigned int romfs_img_len = 7168; diff --git a/nuttx/configs/px4fmu/src/up_pwm_servo.c b/nuttx/configs/px4fmu/src/up_pwm_servo.c index 05daf1e97c..adb9b50308 100644 --- a/nuttx/configs/px4fmu/src/up_pwm_servo.c +++ b/nuttx/configs/px4fmu/src/up_pwm_servo.c @@ -164,10 +164,10 @@ pwm_timer_init(unsigned timer) rDCR(timer) = 0; /* configure the timer to free-run at 1MHz */ - rPSC(timer) = pwm_timers[timer].clock_freq / 1000000; + rPSC(timer) = (pwm_timers[timer].clock_freq / 1000000) - 1; /* and update at the desired rate */ - rARR(timer) = 1000000 / pwm_update_rate; + rARR(timer) = (1000000 / pwm_update_rate) - 1; /* generate an update event; reloads the counter and all registers */ rEGR(timer) = GTIM_EGR_UG; @@ -234,6 +234,8 @@ up_pwm_servo_set(unsigned channel, servo_position_t value) return -1; /* configure the channel */ + if (value > 0) + value--; switch (pwm_channels[channel].timer_channel) { case 1: rCCR1(timer) = value; diff --git a/nuttx/configs/px4io/src/drv_pwm_servo.c b/nuttx/configs/px4io/src/drv_pwm_servo.c index 7f3238da35..4d821cba60 100644 --- a/nuttx/configs/px4io/src/drv_pwm_servo.c +++ b/nuttx/configs/px4io/src/drv_pwm_servo.c @@ -96,10 +96,10 @@ pwm_timer_init(unsigned timer) rDCR(timer) = 0; /* configure the timer to free-run at 1MHz */ - rPSC(timer) = cfg->timers[timer].clock_freq / 1000000; + rPSC(timer) = (cfg->timers[timer].clock_freq / 1000000) -1; /* and update at the desired rate */ - rARR(timer) = 1000000 / cfg->update_rate; + rARR(timer) = (1000000 / cfg->update_rate) - 1; /* generate an update event; reloads the counter and all registers */ rEGR(timer) = GTIM_EGR_UG; @@ -166,6 +166,8 @@ pwm_channel_set(unsigned channel, servo_position_t value) return; /* configure the channel */ + if (value > 0) + value--; switch (cfg->channels[channel].timer_channel) { case 1: rCCR1(timer) = value;