mirror of https://github.com/sebmillet/RF433any
Manages compact integers in the test plan
*WARNING* Actual code *DOES NOT PASS* tests 3 and above. It only passes test 1 and 2 - In order to save memory during the test plan, the read durations are saved in 'compact' form, using compact() to reduce their size and uncompact() to get their 'original' value (not exactly 'original' as some precision is lost on the way). Durations (without compact) are typically uint16_t whereas in compact form, it is uint8_t, saving 50% of space. The precision loss (see comment written on top of compact()) is fine with the code logic.
This commit is contained in:
parent
9dff51891f
commit
9071e2d9d2
57
RF433any.cpp
57
RF433any.cpp
|
@ -141,6 +141,59 @@ static void rf433any_assert_failed(int line) {
|
|||
}
|
||||
|
||||
|
||||
// * ****************** *******************************************************
|
||||
// * compact, uncompact *******************************************************
|
||||
// * ****************** *******************************************************
|
||||
|
||||
// compact() aims to represent 16-bit integers in 8-bit, to the cost of
|
||||
// precision.
|
||||
// The three sets (first one looses 4 bits, middle looses 7, last looses 12)
|
||||
// have been chosen so that smaller durations don't loose too much precision.
|
||||
// The higher the number, the more precision gets lost. This could be seen as
|
||||
// 'the floating point number representation of the (very) poor man' (or,
|
||||
// floating point numbers without... a floating point!)
|
||||
//
|
||||
// Any way, keep in mind Arduino timer produces values always multiple of 4,
|
||||
// that shifts bit-loss by 2.
|
||||
// For example, the first set (that looses 4 bits) actually really looses 2 bits
|
||||
// of precision.
|
||||
duration_t compact(uint16_t u) {
|
||||
#ifdef RF433ANY_DBG_NO_COMPACT_DURATIONS
|
||||
// compact not activated -> compact() is a no-op
|
||||
return u;
|
||||
#else
|
||||
if (u < 2048) {
|
||||
return u >> 4;
|
||||
}
|
||||
if (u < 17408) {
|
||||
return 128 + ((u - 2048) >> 7);
|
||||
}
|
||||
if (u < 46080)
|
||||
return 248 + ((u - 17408) >> 12);
|
||||
return 255;
|
||||
#endif
|
||||
}
|
||||
|
||||
// uncompact() is the opposite of compact(), yes!
|
||||
// Left here in case tests are needed (it is not used in release code).
|
||||
uint16_t uncompact(duration_t b) {
|
||||
#ifdef RF433ANY_DBG_NO_COMPACT_DURATIONS
|
||||
// compact not activated -> uncompact() is a no-op
|
||||
return b;
|
||||
#else
|
||||
uint16_t u = b;
|
||||
if (u < 128) {
|
||||
return u << 4;
|
||||
}
|
||||
u &= 0x7f;
|
||||
if (u < 120) {
|
||||
return (u << 7) + 2048;
|
||||
}
|
||||
return ((u - 120) << 12) + 17408;
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
// * **** *********************************************************************
|
||||
// * Band *********************************************************************
|
||||
// * **** *********************************************************************
|
||||
|
@ -1106,7 +1159,7 @@ void DecoderManchester::dbg_decoder(byte disp_level, byte seq) const {
|
|||
RF433SerialLine sl;
|
||||
char buffer[RF433SERIAL_LINE_BUF_LEN];
|
||||
|
||||
uint16_t sim_timings[SIM_TIMINGS_LEN];
|
||||
duration_t sim_timings[SIM_TIMINGS_LEN];
|
||||
|
||||
uint16_t sim_timings_count = 0;
|
||||
|
||||
|
@ -1159,7 +1212,7 @@ void Track::ih_handle_interrupt() {
|
|||
d = 100;
|
||||
sim_int_count = sim_timings_count + 1;
|
||||
} else {
|
||||
d = sim_timings[sim_int_count++];
|
||||
d = uncompact(sim_timings[sim_int_count++]);
|
||||
}
|
||||
(void)last_t;
|
||||
(void)t;
|
||||
|
|
12
RF433any.h
12
RF433any.h
|
@ -96,6 +96,18 @@
|
|||
|
||||
#include <Arduino.h>
|
||||
|
||||
// Don't uncomment the below unless you know what you are doing!
|
||||
//#define RF433ANY_DBG_NO_COMPACT_DURATIONS
|
||||
|
||||
#ifdef RF433ANY_DBG_NO_COMPACT_DURATIONS
|
||||
#define duration_t uint16_t
|
||||
#else
|
||||
#define duration_t byte
|
||||
#endif
|
||||
|
||||
duration_t compact(uint16_t u);
|
||||
uint16_t uncompact(duration_t b);
|
||||
|
||||
#define RF433ANY_MAX_DURATION 65535
|
||||
#define RF433ANY_MAX_SEP_DURATION 65535
|
||||
#ifndef RF433ANY_MAX_SECTIONS
|
||||
|
|
|
@ -1,8 +1,8 @@
|
|||
#!/usr/bin/bash
|
||||
|
||||
# am
|
||||
# am2
|
||||
|
||||
# Copyright 2019, 2020, 2021 Sébastien Millet
|
||||
# Copyright 2019, 2020, 2021, 2022 Sébastien Millet
|
||||
|
||||
# Can perform the following:
|
||||
# 1. Compile the code
|
||||
|
@ -20,10 +20,12 @@
|
|||
# installed (from tar.gz source) package used so far.
|
||||
# 1.7 Renames archlinux-arduino back to arduino, and created corresponding
|
||||
# symlink (was cleaner to do s).
|
||||
# 2.0 Replaces arduino-builder with arduino-cli
|
||||
# 2.1 Output warning if ARDUINO_USER_LIBS environment variable is not set
|
||||
|
||||
set -euo pipefail
|
||||
|
||||
VERSION=1.7
|
||||
VERSION=2.1
|
||||
|
||||
PORT=
|
||||
BOARD=
|
||||
|
@ -41,6 +43,7 @@ STTY="no"
|
|||
RECORDUSB="no"
|
||||
COMPILE="yes"
|
||||
TESTPLAN=
|
||||
NOCOLOR=
|
||||
|
||||
DISPLAYSEP=no
|
||||
|
||||
|
@ -88,6 +91,7 @@ function usage {
|
|||
echo " (-c or --stty option set)"
|
||||
echo " -t --testplan Set TESTPLAN macro value"
|
||||
echo " (as if #define TESTPLAN VALUE)"
|
||||
echo " --no-color Pass on the --no-color option to arduino-cli"
|
||||
exit 1
|
||||
}
|
||||
|
||||
|
@ -96,7 +100,7 @@ function version {
|
|||
exit
|
||||
}
|
||||
|
||||
OPTS=$(getopt -o hVvub:p:s:B:d:crnt: --long help,version,verbose,upload,board:,port:,speed:,fqbn:,builddir:,catusb,stty,recordusb,nocompile,readspeed:,recordfile:,testplan: -n 'am' -- "$@")
|
||||
OPTS=$(getopt -o hVvub:p:s:B:d:crnt: --long help,version,verbose,upload,board:,port:,speed:,fqbn:,builddir:,catusb,stty,no-color,recordusb,nocompile,readspeed:,recordfile:,testplan: -n 'am' -- "$@")
|
||||
|
||||
eval set -- "$OPTS"
|
||||
|
||||
|
@ -117,6 +121,7 @@ while true; do
|
|||
--readspeed ) READSPEED="$2"; shift 2 ;;
|
||||
--recordfile ) RECORDFILE="$2"; shift 2 ;;
|
||||
--stty ) STTY="yes"; shift ;;
|
||||
--no-color ) NOCOLOR="--no-color"; shift ;;
|
||||
-t | --testplan ) TESTPLAN="$2"; shift 2 ;;
|
||||
-- ) shift; break ;;
|
||||
* ) break ;;
|
||||
|
@ -144,12 +149,6 @@ if [ -n "${BOARD}" ]; then
|
|||
fi
|
||||
fi
|
||||
|
||||
#ARDUINODIR=$(LANG='' type -a arduino \
|
||||
# | tail -n 1 \
|
||||
# | sed 's/\S\+\sis\s//')
|
||||
#ARDUINODIR=$(readlink -f "${ARDUINODIR}")
|
||||
#ARDUINODIR=$(dirname "${ARDUINODIR}")
|
||||
|
||||
ARDUINODIR=/usr/share/arduino
|
||||
|
||||
COUNTUNO=$(compgen -G '/dev/ttyACM*' | wc -l)
|
||||
|
@ -277,35 +276,31 @@ if [ "${COMPILE}" == "yes" ]; then
|
|||
OPT_LIB=
|
||||
TMP_ULIB=${ARDUINO_USER_LIBS:-}
|
||||
if [ -n "${TMP_ULIB}" ]; then
|
||||
OPT_LIB="-libraries ""${TMP_ULIB}"""
|
||||
OPT_LIB="--libraries ""${TMP_ULIB}"""
|
||||
else
|
||||
echo
|
||||
echo "***********************************************************"
|
||||
echo "* WARNING *"
|
||||
echo "* The environment variable ARDUINO_USER_LIBS is not set *"
|
||||
echo "***********************************************************"
|
||||
echo
|
||||
fi
|
||||
|
||||
TESTPLAN_OPT=""
|
||||
if [ -n "${TESTPLAN}" ]; then
|
||||
TESTPLAN_OPT="-prefs=build.extra_flags=-DTESTPLAN=${TESTPLAN}"
|
||||
TESTPLAN_OPT="--build-property build.extra_flags=-DRF433ANY_TESTPLAN=${TESTPLAN}"
|
||||
fi
|
||||
|
||||
# shellcheck disable=SC2086
|
||||
# (We don't want to quote OPT_LIB as it can contain multiple options.)
|
||||
"${ARDUINODIR}/arduino-builder" \
|
||||
-hardware "${ARDUINODIR}/hardware" \
|
||||
-tools "${ARDUINODIR}/hardware/tools/avr" \
|
||||
-tools "${ARDUINODIR}/tools-builder" \
|
||||
-built-in-libraries "${ARDUINODIR}/libraries" \
|
||||
${OPT_LIB} \
|
||||
-fqbn "${FQBN}" \
|
||||
-build-path "${BUILDDIR}" \
|
||||
${TESTPLAN_OPT} \
|
||||
"${FILE}"
|
||||
arduino-cli compile -b "${FQBN}" ${NOCOLOR} --build-path "${BUILDDIR}" ${OPT_LIB} ${TESTPLAN_OPT} "${FILE}"
|
||||
fi
|
||||
|
||||
FILEBASENAME=${FILE##*/}
|
||||
|
||||
if [ "${UPLOAD}" == "yes" ]; then
|
||||
echo "-- Upload"
|
||||
"/usr/bin/avrdude" \
|
||||
-q -q -patmega328p -carduino -P"${PORT}" -b"${SPEED}" -D \
|
||||
-Uflash:w:"${BUILDDIR}/${FILEBASENAME}".hex:i
|
||||
arduino-cli upload -v -b "${FQBN}" --input-dir "${BUILDDIR}" -p "${PORT}"
|
||||
fi
|
||||
|
||||
if [ "${CATUSB}" == "yes" ] || [ "${STTY}" == "yes" ]; then
|
|
@ -0,0 +1,100 @@
|
|||
How to install arduino-cli on Ubuntu
|
||||
====================================
|
||||
|
||||
From this URL: https://arduino.github.io/arduino-cli/0.21/installation/
|
||||
|
||||
```
|
||||
# The below installs arduino-cli in ~/bin
|
||||
curl -O -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh
|
||||
sh install.sh
|
||||
|
||||
# the below downloads what it takes to manage arduino:avr boards
|
||||
arduino-cli core install arduino:avr
|
||||
```
|
||||
|
||||
Example for 01_generic.ino (example of RF433recv library):
|
||||
|
||||
```
|
||||
# Compilation
|
||||
|
||||
$ arduino-cli compile -b arduino:avr:nano:cpu=atmega328old --build-path build --libraries /home/sebastien/travail/cpp/seb/arduino/libraries 01_generic.ino
|
||||
|
||||
Le croquis utilise 7950 octets (25%) de l'espace de stockage de programmes. Le maximum est de 30720 octets.
|
||||
Les variables globales utilisent 243 octets (11%) de mémoire dynamique, ce qui laisse 1805 octets pour les variables locales. Le maximum est de 2048 octets.
|
||||
|
||||
Used library Version Path
|
||||
RF433recv 0.3.0 /home/sebastien/travail/cpp/seb/arduino/libraries/RF433recv
|
||||
|
||||
Used platform Version Path
|
||||
arduino:avr 1.8.5 /home/sebastien/.arduino15/packages/arduino/hardware/avr/1.8.5
|
||||
|
||||
# Upload
|
||||
|
||||
$ arduino-cli upload -v -b arduino:avr:nano:cpu=atmega328old --input-dir build -p /dev/ttyUSB0
|
||||
|
||||
"/home/sebastien/.arduino15/packages/arduino/tools/avrdude/6.3.0-arduino17/bin/avrdude" "-C/home/sebastien/.arduino15/packages/arduino/tools/avrdude/6.3.0-arduino17/etc/avrdude.conf" -v -V -patmega328p -carduino "-P/dev/ttyUSB0" -b57600 -D "-Uflash:w:build/01_generic.ino.hex:i"
|
||||
|
||||
avrdude: Version 6.3-20190619
|
||||
Copyright (c) 2000-2005 Brian Dean, http://www.bdmicro.com/
|
||||
Copyright (c) 2007-2014 Joerg Wunsch
|
||||
|
||||
System wide configuration file is "/home/sebastien/.arduino15/packages/arduino/tools/avrdude/6.3.0-arduino17/etc/avrdude.conf"
|
||||
User configuration file is "/home/sebastien/.avrduderc"
|
||||
User configuration file does not exist or is not a regular file, skipping
|
||||
|
||||
Using Port : /dev/ttyUSB0
|
||||
Using Programmer : arduino
|
||||
Overriding Baud Rate : 57600
|
||||
AVR Part : ATmega328P
|
||||
Chip Erase delay : 9000 us
|
||||
PAGEL : PD7
|
||||
BS2 : PC2
|
||||
RESET disposition : dedicated
|
||||
RETRY pulse : SCK
|
||||
serial program mode : yes
|
||||
parallel program mode : yes
|
||||
Timeout : 200
|
||||
StabDelay : 100
|
||||
CmdexeDelay : 25
|
||||
SyncLoops : 32
|
||||
ByteDelay : 0
|
||||
PollIndex : 3
|
||||
PollValue : 0x53
|
||||
Memory Detail :
|
||||
|
||||
Block Poll Page Polled
|
||||
Memory Type Mode Delay Size Indx Paged Size Size #Pages MinW MaxW ReadBack
|
||||
----------- ---- ----- ----- ---- ------ ------ ---- ------ ----- ----- ---------
|
||||
eeprom 65 20 4 0 no 1024 4 0 3600 3600 0xff 0xff
|
||||
flash 65 6 128 0 yes 32768 128 256 4500 4500 0xff 0xff
|
||||
lfuse 0 0 0 0 no 1 0 0 4500 4500 0x00 0x00
|
||||
hfuse 0 0 0 0 no 1 0 0 4500 4500 0x00 0x00
|
||||
efuse 0 0 0 0 no 1 0 0 4500 4500 0x00 0x00
|
||||
lock 0 0 0 0 no 1 0 0 4500 4500 0x00 0x00
|
||||
calibration 0 0 0 0 no 1 0 0 0 0 0x00 0x00
|
||||
signature 0 0 0 0 no 3 0 0 0 0 0x00 0x00
|
||||
|
||||
Programmer Type : Arduino
|
||||
Description : Arduino
|
||||
Hardware Version: 2
|
||||
Firmware Version: 1.16
|
||||
Vtarget : 0.0 V
|
||||
Varef : 0.0 V
|
||||
Oscillator : Off
|
||||
SCK period : 0.1 us
|
||||
|
||||
avrdude: AVR device initialized and ready to accept instructions
|
||||
|
||||
Reading | ################################################## | 100% 0.00s
|
||||
|
||||
avrdude: Device signature = 0x1e950f (probably m328p)
|
||||
avrdude: reading input file "build/01_generic.ino.hex"
|
||||
avrdude: writing flash (7950 bytes):
|
||||
|
||||
Writing | ################################################## | 100% 2.35s
|
||||
|
||||
avrdude: 7950 bytes of flash written
|
||||
|
||||
avrdude done. Thank you.
|
||||
```
|
||||
|
|
@ -1,10 +0,0 @@
|
|||
ARDUINO_DIR = /usr/share/arduino
|
||||
ARDUINO_LIBS = RF433any
|
||||
ARDMK_DIR = /home/sebastien/.arduino_mk
|
||||
|
||||
# USER_LIB_PATH = /home/sebastien/travail/cpp/seb/arduino/libraries
|
||||
|
||||
BOARD_TAG = uno
|
||||
MCU = atmega328
|
||||
|
||||
include $(ARDMK_DIR)/Arduino.mk
|
|
@ -0,0 +1 @@
|
|||
../Makefile
|
|
@ -0,0 +1 @@
|
|||
../../am2
|
|
@ -54,8 +54,13 @@ void loop() {
|
|||
Serial.print(pdec->get_repeats() + 1);
|
||||
Serial.print("): ");
|
||||
char *buf = pdec->get_pdata()->to_str();
|
||||
Serial.println(buf);
|
||||
free(buf);
|
||||
// DEFENSIVE PROGRAMMING
|
||||
// The option RF433ANY_FD_DECODED above guarantees there's always
|
||||
// something decoded. Test done though, just in case.
|
||||
if (buf) {
|
||||
Serial.println(buf);
|
||||
free(buf);
|
||||
}
|
||||
}
|
||||
delete pdec0;
|
||||
}
|
||||
|
|
|
@ -1,10 +0,0 @@
|
|||
ARDUINO_DIR = /usr/share/arduino
|
||||
ARDUINO_LIBS = RF433any
|
||||
ARDMK_DIR = /home/sebastien/.arduino_mk
|
||||
|
||||
# USER_LIB_PATH = /home/sebastien/travail/cpp/seb/arduino/libraries
|
||||
|
||||
BOARD_TAG = uno
|
||||
MCU = atmega328
|
||||
|
||||
include $(ARDMK_DIR)/Arduino.mk
|
|
@ -0,0 +1 @@
|
|||
../Makefile
|
|
@ -1,343 +0,0 @@
|
|||
#!/usr/bin/bash
|
||||
|
||||
# am
|
||||
|
||||
# Copyright 2019, 2020, 2021 Sébastien Millet
|
||||
|
||||
# Can perform the following:
|
||||
# 1. Compile the code
|
||||
# 2. Upload to Arduino
|
||||
# 3. Read (continually) what is arriving from the USB port the Arduino is
|
||||
# connected to
|
||||
|
||||
# Versions history (as of 1.3)
|
||||
# 1.3 Output from Arduino is recorded in files named with numbers instead of
|
||||
# date-time string.
|
||||
# 1.4 Adds -t (--testplan) option, to set TESTPLAN macro
|
||||
# 1.5 -t (or --testplan) now comes with a value, so as to manage multiple test
|
||||
# plans.
|
||||
# 1.6 Updated to work fine with Arch arduino package instead of the manually
|
||||
# installed (from tar.gz source) package used so far.
|
||||
# 1.7 Renames archlinux-arduino back to arduino, and created corresponding
|
||||
# symlink (was cleaner to do s).
|
||||
|
||||
set -euo pipefail
|
||||
|
||||
VERSION=1.7
|
||||
|
||||
PORT=
|
||||
BOARD=
|
||||
SPEED=
|
||||
FQBN=
|
||||
BUILDDIR=
|
||||
RECORDDIR=out
|
||||
READSPEED=
|
||||
RECORDFILE=
|
||||
|
||||
UPLOAD="no"
|
||||
VERBOSE="no"
|
||||
CATUSB="no"
|
||||
STTY="no"
|
||||
RECORDUSB="no"
|
||||
COMPILE="yes"
|
||||
TESTPLAN=
|
||||
|
||||
DISPLAYSEP=no
|
||||
|
||||
function finish {
|
||||
if [ "${DISPLAYSEP}" == "yes" ]; then
|
||||
echo "-----END ARDUINO OUTPUT-----" | tee -a "${RECORDFILE}"
|
||||
fi
|
||||
}
|
||||
|
||||
trap finish EXIT
|
||||
|
||||
function usage {
|
||||
echo "Usage:"
|
||||
echo " am [OPTIONS...] FILE"
|
||||
echo "Compile FILE using arduino-builder."
|
||||
echo "Example: am sketch.ino"
|
||||
echo ""
|
||||
echo "ENVIRONMENT VARIABLES"
|
||||
echo " If ARDUINO_USER_LIBS is defined and non empty, then arduino-builder"
|
||||
echo " is called with the supplementary option -libraries followed by"
|
||||
echo " ARDUINO_USER_LIBS' value."
|
||||
echo ""
|
||||
echo "OPTIONS"
|
||||
echo " -h --help Display this help screen"
|
||||
echo " -V --version Output version information and quit"
|
||||
echo " -v --verbose Be more talkative"
|
||||
echo " -u --upload Upload compiled code into Arduino"
|
||||
echo " -b --board Board, either 'uno' or 'nano'"
|
||||
echo " -p --port Port, for ex. '/dev/ttyUSB0'"
|
||||
echo " -s --speed Upload speed, for ex. 115200"
|
||||
echo " Normally, speed is infered from device type:"
|
||||
echo " 115200 for Uno, 57600 for Nano"
|
||||
echo " -B --fqbn Board Fully Qualified Name, like 'arduino:avr:uno'"
|
||||
echo " -d --builddir Build directory"
|
||||
echo " -c --catusb Display (continually) what Arduino writes on USB"
|
||||
echo " --stty Tune stty properly for later communication (implied"
|
||||
echo " by --catusb)"
|
||||
echo " -r --recordusb Write USB (continually) to a file (implies -c)"
|
||||
echo " --recordfile Output file if -r option is set"
|
||||
echo " -n --nocompile Don't compile code"
|
||||
echo " --readspeed Read speed of USB. If not specified, this script"
|
||||
echo " will try to infere it from source file. If it"
|
||||
echo " fails, it'll fallback to 9600."
|
||||
echo " This option is useful only if USB is read"
|
||||
echo " (-c or --stty option set)"
|
||||
echo " -t --testplan Set TESTPLAN macro value"
|
||||
echo " (as if #define TESTPLAN VALUE)"
|
||||
exit 1
|
||||
}
|
||||
|
||||
function version {
|
||||
echo "am version ${VERSION}"
|
||||
exit
|
||||
}
|
||||
|
||||
OPTS=$(getopt -o hVvub:p:s:B:d:crnt: --long help,version,verbose,upload,board:,port:,speed:,fqbn:,builddir:,catusb,stty,recordusb,nocompile,readspeed:,recordfile:,testplan: -n 'am' -- "$@")
|
||||
|
||||
eval set -- "$OPTS"
|
||||
|
||||
while true; do
|
||||
case "$1" in
|
||||
-h | --help ) usage; shift ;;
|
||||
-V | --version ) version; shift ;;
|
||||
-v | --verbose ) VERBOSE="yes"; shift ;;
|
||||
-u | --upload ) UPLOAD="yes"; shift ;;
|
||||
-b | --board ) BOARD="$2"; shift 2 ;;
|
||||
-p | --port ) PORT="$2"; shift 2 ;;
|
||||
-s | --speed ) SPEED="$2"; shift 2 ;;
|
||||
-B | --fqbn ) FQBN="$2"; shift 2 ;;
|
||||
-d | --builddir ) BUILDDIR="$2"; shift 2 ;;
|
||||
-c | --catusb ) CATUSB="yes"; shift ;;
|
||||
-r | --recordusb ) RECORDUSB="yes"; CATUSB="yes"; shift ;;
|
||||
-n | --nocompile ) COMPILE="no"; shift ;;
|
||||
--readspeed ) READSPEED="$2"; shift 2 ;;
|
||||
--recordfile ) RECORDFILE="$2"; shift 2 ;;
|
||||
--stty ) STTY="yes"; shift ;;
|
||||
-t | --testplan ) TESTPLAN="$2"; shift 2 ;;
|
||||
-- ) shift; break ;;
|
||||
* ) break ;;
|
||||
esac
|
||||
done
|
||||
|
||||
FILE=${1:-}
|
||||
TRAILINGOPTS=${2:-}
|
||||
|
||||
if [ -n "${TRAILINGOPTS}" ]; then
|
||||
echo "Error: trailing options"
|
||||
exit 1;
|
||||
fi
|
||||
if [ -z "${FILE}" ]; then
|
||||
echo "Error: no input file"
|
||||
exit 1;
|
||||
fi
|
||||
|
||||
set +e
|
||||
|
||||
if [ -n "${BOARD}" ]; then
|
||||
if [ "${BOARD}" != "uno" ] && [ "${BOARD}" != "nano" ]; then
|
||||
echo "Error: board '${BOARD}' unknown"
|
||||
exit 1
|
||||
fi
|
||||
fi
|
||||
|
||||
#ARDUINODIR=$(LANG='' type -a arduino \
|
||||
# | tail -n 1 \
|
||||
# | sed 's/\S\+\sis\s//')
|
||||
#ARDUINODIR=$(readlink -f "${ARDUINODIR}")
|
||||
#ARDUINODIR=$(dirname "${ARDUINODIR}")
|
||||
|
||||
ARDUINODIR=/usr/share/arduino
|
||||
|
||||
COUNTUNO=$(compgen -G '/dev/ttyACM*' | wc -l)
|
||||
COUNTNANO=$(compgen -G '/dev/ttyUSB*' | wc -l)
|
||||
|
||||
if [ -z "${BOARD}" ]; then
|
||||
if [ "${COUNTUNO}" -ge 1 ] && [ "${COUNTNANO}" -ge 1 ]; then
|
||||
echo "Error: cannot guess board, found ${COUNTUNO} uno(s), ${COUNTNANO} nano(s)"
|
||||
exit 10
|
||||
fi
|
||||
if [ "${COUNTUNO}" -ge 1 ]; then
|
||||
BOARD=uno
|
||||
elif [ "${COUNTNANO}" -ge 1 ]; then
|
||||
BOARD=nano
|
||||
fi
|
||||
if [ -z "${BOARD}" ]; then
|
||||
echo "Error: cannot guess board, none found";
|
||||
exit 10
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ "${UPLOAD}" == "yes" ] || [ "${CATUSB}" == "yes" ]; then
|
||||
if [ -z "${PORT}" ]; then
|
||||
if [ "${BOARD}" == "uno" ]; then
|
||||
COUNT=${COUNTUNO}
|
||||
PORT=$(compgen -G '/dev/ttyACM*')
|
||||
elif [ "${BOARD}" == "nano" ]; then
|
||||
COUNT=${COUNTNANO}
|
||||
PORT=$(compgen -G '/dev/ttyUSB*')
|
||||
else
|
||||
echo "FATAL #001, CHECK THIS CODE"
|
||||
exit 99
|
||||
fi
|
||||
|
||||
if [ "${COUNT}" -ge 2 ]; then
|
||||
echo "Error: cannot guess port, more than 1 board '${BOARD}' found"
|
||||
exit 10
|
||||
fi
|
||||
if [ -z "${PORT}" ]; then
|
||||
echo "Error: cannot guess port, none found"
|
||||
exit 10
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ -z "${SPEED}" ]; then
|
||||
if [ "${BOARD}" == "uno" ]; then
|
||||
SPEED=115200
|
||||
elif [ "${BOARD}" == "nano" ]; then
|
||||
SPEED=57600
|
||||
else
|
||||
echo "FATAL #002, CHECK THIS CODE"
|
||||
exit 99
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ ! -e "${PORT}" ]; then
|
||||
echo "Error: port not found"
|
||||
exit 10
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ -z "${FQBN}" ]; then
|
||||
if [ "${BOARD}" == "uno" ]; then
|
||||
FQBN="arduino:avr:uno"
|
||||
elif [ "${BOARD}" == "nano" ]; then
|
||||
FQBN="arduino:avr:nano:cpu=atmega328old"
|
||||
else
|
||||
echo "FATAL #003, CHECK THIS CODE"
|
||||
exit 99
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ -z "${BUILDDIR}" ]; then
|
||||
if [[ "${FILE}" == */* ]]; then
|
||||
BUILDDIR=${FILE%/*}
|
||||
BUILDDIR="${BUILDDIR%/}/build"
|
||||
else
|
||||
BUILDDIR=build
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ "${RECORDUSB}" == "yes" ]; then
|
||||
if [ -z "${RECORDFILE}" ]; then
|
||||
V=${FILE##*/}
|
||||
V=${V%.*}
|
||||
V=${V:-out}
|
||||
PREV=
|
||||
for i in {15..00}; do
|
||||
F="${RECORDDIR}/${V}-$i.txt"
|
||||
if [ -e "${F}" ] && [ -n "${PREV}" ]; then
|
||||
mv "${F}" "${PREV}"
|
||||
fi
|
||||
PREV="${F}"
|
||||
done
|
||||
RECORDFILE="${F}"
|
||||
mkdir -p "${RECORDDIR}"
|
||||
fi
|
||||
else
|
||||
RECORDFILE="/dev/null"
|
||||
fi
|
||||
|
||||
if [ "${VERBOSE}" == "yes" ]; then
|
||||
echo "-- Settings"
|
||||
echo "Arduino dir: ${ARDUINODIR}"
|
||||
echo "Board: ${BOARD}"
|
||||
echo "Port: ${PORT}"
|
||||
echo "Speed: ${SPEED}"
|
||||
echo "Fqbn: ${FQBN}"
|
||||
echo "Upload: ${UPLOAD}"
|
||||
echo "Catusb: ${CATUSB}"
|
||||
echo "Recordusb: ${RECORDUSB}"
|
||||
echo "Record file: ${RECORDFILE}"
|
||||
echo "Verbose: ${VERBOSE}"
|
||||
echo "File: ${FILE}"
|
||||
echo "Build dir: ${BUILDDIR}"
|
||||
fi
|
||||
|
||||
set -e
|
||||
|
||||
if [ "${COMPILE}" == "yes" ]; then
|
||||
echo "-- Compile"
|
||||
|
||||
mkdir -p "${BUILDDIR}"
|
||||
|
||||
OPT_LIB=
|
||||
TMP_ULIB=${ARDUINO_USER_LIBS:-}
|
||||
if [ -n "${TMP_ULIB}" ]; then
|
||||
OPT_LIB="-libraries ""${TMP_ULIB}"""
|
||||
fi
|
||||
|
||||
TESTPLAN_OPT=""
|
||||
if [ -n "${TESTPLAN}" ]; then
|
||||
TESTPLAN_OPT="-prefs=build.extra_flags=-DTESTPLAN=${TESTPLAN}"
|
||||
fi
|
||||
|
||||
# shellcheck disable=SC2086
|
||||
# (We don't want to quote OPT_LIB as it can contain multiple options.)
|
||||
"${ARDUINODIR}/arduino-builder" \
|
||||
-hardware "${ARDUINODIR}/hardware" \
|
||||
-tools "${ARDUINODIR}/hardware/tools/avr" \
|
||||
-tools "${ARDUINODIR}/tools-builder" \
|
||||
-built-in-libraries "${ARDUINODIR}/libraries" \
|
||||
${OPT_LIB} \
|
||||
-fqbn "${FQBN}" \
|
||||
-build-path "${BUILDDIR}" \
|
||||
${TESTPLAN_OPT} \
|
||||
"${FILE}"
|
||||
fi
|
||||
|
||||
FILEBASENAME=${FILE##*/}
|
||||
|
||||
if [ "${UPLOAD}" == "yes" ]; then
|
||||
echo "-- Upload"
|
||||
"/usr/bin/avrdude" \
|
||||
-q -q -patmega328p -carduino -P"${PORT}" -b"${SPEED}" -D \
|
||||
-Uflash:w:"${BUILDDIR}/${FILEBASENAME}".hex:i
|
||||
fi
|
||||
|
||||
if [ "${CATUSB}" == "yes" ] || [ "${STTY}" == "yes" ]; then
|
||||
if [ -z "${READSPEED}" ]; then
|
||||
TFILE=$(mktemp)
|
||||
gcc -fpreprocessed -dD -x c++ -E "${FILE}" > "${TFILE}"
|
||||
for sp in 9600 19200 28800 38400 57600 115200; do
|
||||
if grep ${sp} "${TFILE}" > /dev/null; then
|
||||
READSPEED=${sp}
|
||||
fi
|
||||
done
|
||||
READSPEED=${READSPEED:-9600}
|
||||
rm "${TFILE}"
|
||||
fi
|
||||
|
||||
stty -F "${PORT}" -hupcl -echo "${READSPEED}"
|
||||
echo "-- usb setup with speed ${READSPEED}"
|
||||
fi
|
||||
|
||||
if [ "${CATUSB}" == "yes" ]; then
|
||||
echo "-- Read usb (Ctrl-C to quit)"
|
||||
DISPLAYSEP=yes
|
||||
{
|
||||
echo "speed=${READSPEED}"
|
||||
echo "fqbn=${FQBN}"
|
||||
echo "port=${PORT}"
|
||||
echo "file=${FILE}"
|
||||
echo "filedate=$(date +"%Y-%m-%dT%H:%M:%SZ" -d @$(stat -c '%Y' "${FILE}"))"
|
||||
echo "date=$(date +'%Y-%m-%dT%H:%M:%SZ')"
|
||||
echo ""
|
||||
echo "-----BEGIN ARDUINO OUTPUT-----"
|
||||
} | tee "${RECORDFILE}"
|
||||
tee -a "${RECORDFILE}" < "${PORT}"
|
||||
fi
|
||||
|
|
@ -0,0 +1 @@
|
|||
../../am2
|
|
@ -0,0 +1,85 @@
|
|||
// 02_output-received-code.ino
|
||||
|
||||
// Example sketch that comes along with RF433any library
|
||||
// Simply displays received codes
|
||||
|
||||
/*
|
||||
Copyright 2021 Sébastien Millet
|
||||
|
||||
`RF433any' is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU Lesser General Public License as
|
||||
published by the Free Software Foundation, either version 3 of the
|
||||
License, or (at your option) any later version.
|
||||
|
||||
`RF433any' is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General Public
|
||||
License along with this program. If not, see
|
||||
<https://www.gnu.org/licenses>.
|
||||
*/
|
||||
|
||||
//
|
||||
// Schematic: Radio Frequencies RECEIVER plugged on D2
|
||||
//
|
||||
|
||||
#include "RF433any.h"
|
||||
#include <Arduino.h>
|
||||
|
||||
#define PIN_RFINPUT 2
|
||||
|
||||
void setup() {
|
||||
pinMode(PIN_RFINPUT, INPUT);
|
||||
Serial.begin(115200);
|
||||
Serial.print("Waiting for signal\n");
|
||||
}
|
||||
|
||||
Track track(PIN_RFINPUT);
|
||||
|
||||
// NOTE
|
||||
// One could also create a child class, it is cleaner, but I find it overkill
|
||||
char* my_BitVector_to_str(const BitVector *bv) {
|
||||
if (!bv->get_nb_bits())
|
||||
return nullptr;
|
||||
|
||||
byte nb_bytes = bv->get_nb_bytes();
|
||||
|
||||
char *ret = (char*)malloc(nb_bytes * 3);
|
||||
char tmp[3];
|
||||
int j = 0;
|
||||
for (int i = nb_bytes - 1; i >= 0 ; --i) {
|
||||
snprintf(tmp, sizeof(tmp), "%02X", bv->get_nth_byte(i));
|
||||
ret[j] = tmp[0];
|
||||
ret[j + 1] = tmp[1];
|
||||
ret[j + 2] = (i > 0 ? ' ' : '\0');
|
||||
j += 3;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
void loop() {
|
||||
track.treset();
|
||||
|
||||
while (!track.do_events())
|
||||
delay(1);
|
||||
|
||||
Decoder *pdec0 = track.get_data(
|
||||
RF433ANY_FD_DECODED | RF433ANY_FD_DEDUP | RF433ANY_FD_NO_ERROR
|
||||
);
|
||||
for (Decoder *pdec = pdec0; pdec != nullptr; pdec = pdec->get_next()) {
|
||||
Serial.print("Received ");
|
||||
Serial.print(pdec->get_nb_bits());
|
||||
Serial.print(" bits (x");
|
||||
Serial.print(pdec->get_repeats() + 1);
|
||||
Serial.print("): ");
|
||||
char *buf = my_BitVector_to_str(pdec->get_pdata());
|
||||
Serial.println(buf);
|
||||
free(buf);
|
||||
}
|
||||
delete pdec0;
|
||||
}
|
||||
|
||||
// vim: ts=4:sw=4:tw=80:et
|
|
@ -1,10 +0,0 @@
|
|||
ARDUINO_DIR = /usr/share/arduino
|
||||
ARDUINO_LIBS = RF433any
|
||||
ARDMK_DIR = /home/sebastien/.arduino_mk
|
||||
|
||||
# USER_LIB_PATH = /home/sebastien/travail/cpp/seb/arduino/libraries
|
||||
|
||||
BOARD_TAG = uno
|
||||
MCU = atmega328
|
||||
|
||||
include $(ARDMK_DIR)/Arduino.mk
|
|
@ -0,0 +1 @@
|
|||
../Makefile
|
|
@ -1,343 +0,0 @@
|
|||
#!/usr/bin/bash
|
||||
|
||||
# am
|
||||
|
||||
# Copyright 2019, 2020, 2021 Sébastien Millet
|
||||
|
||||
# Can perform the following:
|
||||
# 1. Compile the code
|
||||
# 2. Upload to Arduino
|
||||
# 3. Read (continually) what is arriving from the USB port the Arduino is
|
||||
# connected to
|
||||
|
||||
# Versions history (as of 1.3)
|
||||
# 1.3 Output from Arduino is recorded in files named with numbers instead of
|
||||
# date-time string.
|
||||
# 1.4 Adds -t (--testplan) option, to set TESTPLAN macro
|
||||
# 1.5 -t (or --testplan) now comes with a value, so as to manage multiple test
|
||||
# plans.
|
||||
# 1.6 Updated to work fine with Arch arduino package instead of the manually
|
||||
# installed (from tar.gz source) package used so far.
|
||||
# 1.7 Renames archlinux-arduino back to arduino, and created corresponding
|
||||
# symlink (was cleaner to do s).
|
||||
|
||||
set -euo pipefail
|
||||
|
||||
VERSION=1.7
|
||||
|
||||
PORT=
|
||||
BOARD=
|
||||
SPEED=
|
||||
FQBN=
|
||||
BUILDDIR=
|
||||
RECORDDIR=out
|
||||
READSPEED=
|
||||
RECORDFILE=
|
||||
|
||||
UPLOAD="no"
|
||||
VERBOSE="no"
|
||||
CATUSB="no"
|
||||
STTY="no"
|
||||
RECORDUSB="no"
|
||||
COMPILE="yes"
|
||||
TESTPLAN=
|
||||
|
||||
DISPLAYSEP=no
|
||||
|
||||
function finish {
|
||||
if [ "${DISPLAYSEP}" == "yes" ]; then
|
||||
echo "-----END ARDUINO OUTPUT-----" | tee -a "${RECORDFILE}"
|
||||
fi
|
||||
}
|
||||
|
||||
trap finish EXIT
|
||||
|
||||
function usage {
|
||||
echo "Usage:"
|
||||
echo " am [OPTIONS...] FILE"
|
||||
echo "Compile FILE using arduino-builder."
|
||||
echo "Example: am sketch.ino"
|
||||
echo ""
|
||||
echo "ENVIRONMENT VARIABLES"
|
||||
echo " If ARDUINO_USER_LIBS is defined and non empty, then arduino-builder"
|
||||
echo " is called with the supplementary option -libraries followed by"
|
||||
echo " ARDUINO_USER_LIBS' value."
|
||||
echo ""
|
||||
echo "OPTIONS"
|
||||
echo " -h --help Display this help screen"
|
||||
echo " -V --version Output version information and quit"
|
||||
echo " -v --verbose Be more talkative"
|
||||
echo " -u --upload Upload compiled code into Arduino"
|
||||
echo " -b --board Board, either 'uno' or 'nano'"
|
||||
echo " -p --port Port, for ex. '/dev/ttyUSB0'"
|
||||
echo " -s --speed Upload speed, for ex. 115200"
|
||||
echo " Normally, speed is infered from device type:"
|
||||
echo " 115200 for Uno, 57600 for Nano"
|
||||
echo " -B --fqbn Board Fully Qualified Name, like 'arduino:avr:uno'"
|
||||
echo " -d --builddir Build directory"
|
||||
echo " -c --catusb Display (continually) what Arduino writes on USB"
|
||||
echo " --stty Tune stty properly for later communication (implied"
|
||||
echo " by --catusb)"
|
||||
echo " -r --recordusb Write USB (continually) to a file (implies -c)"
|
||||
echo " --recordfile Output file if -r option is set"
|
||||
echo " -n --nocompile Don't compile code"
|
||||
echo " --readspeed Read speed of USB. If not specified, this script"
|
||||
echo " will try to infere it from source file. If it"
|
||||
echo " fails, it'll fallback to 9600."
|
||||
echo " This option is useful only if USB is read"
|
||||
echo " (-c or --stty option set)"
|
||||
echo " -t --testplan Set TESTPLAN macro value"
|
||||
echo " (as if #define TESTPLAN VALUE)"
|
||||
exit 1
|
||||
}
|
||||
|
||||
function version {
|
||||
echo "am version ${VERSION}"
|
||||
exit
|
||||
}
|
||||
|
||||
OPTS=$(getopt -o hVvub:p:s:B:d:crnt: --long help,version,verbose,upload,board:,port:,speed:,fqbn:,builddir:,catusb,stty,recordusb,nocompile,readspeed:,recordfile:,testplan: -n 'am' -- "$@")
|
||||
|
||||
eval set -- "$OPTS"
|
||||
|
||||
while true; do
|
||||
case "$1" in
|
||||
-h | --help ) usage; shift ;;
|
||||
-V | --version ) version; shift ;;
|
||||
-v | --verbose ) VERBOSE="yes"; shift ;;
|
||||
-u | --upload ) UPLOAD="yes"; shift ;;
|
||||
-b | --board ) BOARD="$2"; shift 2 ;;
|
||||
-p | --port ) PORT="$2"; shift 2 ;;
|
||||
-s | --speed ) SPEED="$2"; shift 2 ;;
|
||||
-B | --fqbn ) FQBN="$2"; shift 2 ;;
|
||||
-d | --builddir ) BUILDDIR="$2"; shift 2 ;;
|
||||
-c | --catusb ) CATUSB="yes"; shift ;;
|
||||
-r | --recordusb ) RECORDUSB="yes"; CATUSB="yes"; shift ;;
|
||||
-n | --nocompile ) COMPILE="no"; shift ;;
|
||||
--readspeed ) READSPEED="$2"; shift 2 ;;
|
||||
--recordfile ) RECORDFILE="$2"; shift 2 ;;
|
||||
--stty ) STTY="yes"; shift ;;
|
||||
-t | --testplan ) TESTPLAN="$2"; shift 2 ;;
|
||||
-- ) shift; break ;;
|
||||
* ) break ;;
|
||||
esac
|
||||
done
|
||||
|
||||
FILE=${1:-}
|
||||
TRAILINGOPTS=${2:-}
|
||||
|
||||
if [ -n "${TRAILINGOPTS}" ]; then
|
||||
echo "Error: trailing options"
|
||||
exit 1;
|
||||
fi
|
||||
if [ -z "${FILE}" ]; then
|
||||
echo "Error: no input file"
|
||||
exit 1;
|
||||
fi
|
||||
|
||||
set +e
|
||||
|
||||
if [ -n "${BOARD}" ]; then
|
||||
if [ "${BOARD}" != "uno" ] && [ "${BOARD}" != "nano" ]; then
|
||||
echo "Error: board '${BOARD}' unknown"
|
||||
exit 1
|
||||
fi
|
||||
fi
|
||||
|
||||
#ARDUINODIR=$(LANG='' type -a arduino \
|
||||
# | tail -n 1 \
|
||||
# | sed 's/\S\+\sis\s//')
|
||||
#ARDUINODIR=$(readlink -f "${ARDUINODIR}")
|
||||
#ARDUINODIR=$(dirname "${ARDUINODIR}")
|
||||
|
||||
ARDUINODIR=/usr/share/arduino
|
||||
|
||||
COUNTUNO=$(compgen -G '/dev/ttyACM*' | wc -l)
|
||||
COUNTNANO=$(compgen -G '/dev/ttyUSB*' | wc -l)
|
||||
|
||||
if [ -z "${BOARD}" ]; then
|
||||
if [ "${COUNTUNO}" -ge 1 ] && [ "${COUNTNANO}" -ge 1 ]; then
|
||||
echo "Error: cannot guess board, found ${COUNTUNO} uno(s), ${COUNTNANO} nano(s)"
|
||||
exit 10
|
||||
fi
|
||||
if [ "${COUNTUNO}" -ge 1 ]; then
|
||||
BOARD=uno
|
||||
elif [ "${COUNTNANO}" -ge 1 ]; then
|
||||
BOARD=nano
|
||||
fi
|
||||
if [ -z "${BOARD}" ]; then
|
||||
echo "Error: cannot guess board, none found";
|
||||
exit 10
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ "${UPLOAD}" == "yes" ] || [ "${CATUSB}" == "yes" ]; then
|
||||
if [ -z "${PORT}" ]; then
|
||||
if [ "${BOARD}" == "uno" ]; then
|
||||
COUNT=${COUNTUNO}
|
||||
PORT=$(compgen -G '/dev/ttyACM*')
|
||||
elif [ "${BOARD}" == "nano" ]; then
|
||||
COUNT=${COUNTNANO}
|
||||
PORT=$(compgen -G '/dev/ttyUSB*')
|
||||
else
|
||||
echo "FATAL #001, CHECK THIS CODE"
|
||||
exit 99
|
||||
fi
|
||||
|
||||
if [ "${COUNT}" -ge 2 ]; then
|
||||
echo "Error: cannot guess port, more than 1 board '${BOARD}' found"
|
||||
exit 10
|
||||
fi
|
||||
if [ -z "${PORT}" ]; then
|
||||
echo "Error: cannot guess port, none found"
|
||||
exit 10
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ -z "${SPEED}" ]; then
|
||||
if [ "${BOARD}" == "uno" ]; then
|
||||
SPEED=115200
|
||||
elif [ "${BOARD}" == "nano" ]; then
|
||||
SPEED=57600
|
||||
else
|
||||
echo "FATAL #002, CHECK THIS CODE"
|
||||
exit 99
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ ! -e "${PORT}" ]; then
|
||||
echo "Error: port not found"
|
||||
exit 10
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ -z "${FQBN}" ]; then
|
||||
if [ "${BOARD}" == "uno" ]; then
|
||||
FQBN="arduino:avr:uno"
|
||||
elif [ "${BOARD}" == "nano" ]; then
|
||||
FQBN="arduino:avr:nano:cpu=atmega328old"
|
||||
else
|
||||
echo "FATAL #003, CHECK THIS CODE"
|
||||
exit 99
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ -z "${BUILDDIR}" ]; then
|
||||
if [[ "${FILE}" == */* ]]; then
|
||||
BUILDDIR=${FILE%/*}
|
||||
BUILDDIR="${BUILDDIR%/}/build"
|
||||
else
|
||||
BUILDDIR=build
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ "${RECORDUSB}" == "yes" ]; then
|
||||
if [ -z "${RECORDFILE}" ]; then
|
||||
V=${FILE##*/}
|
||||
V=${V%.*}
|
||||
V=${V:-out}
|
||||
PREV=
|
||||
for i in {15..00}; do
|
||||
F="${RECORDDIR}/${V}-$i.txt"
|
||||
if [ -e "${F}" ] && [ -n "${PREV}" ]; then
|
||||
mv "${F}" "${PREV}"
|
||||
fi
|
||||
PREV="${F}"
|
||||
done
|
||||
RECORDFILE="${F}"
|
||||
mkdir -p "${RECORDDIR}"
|
||||
fi
|
||||
else
|
||||
RECORDFILE="/dev/null"
|
||||
fi
|
||||
|
||||
if [ "${VERBOSE}" == "yes" ]; then
|
||||
echo "-- Settings"
|
||||
echo "Arduino dir: ${ARDUINODIR}"
|
||||
echo "Board: ${BOARD}"
|
||||
echo "Port: ${PORT}"
|
||||
echo "Speed: ${SPEED}"
|
||||
echo "Fqbn: ${FQBN}"
|
||||
echo "Upload: ${UPLOAD}"
|
||||
echo "Catusb: ${CATUSB}"
|
||||
echo "Recordusb: ${RECORDUSB}"
|
||||
echo "Record file: ${RECORDFILE}"
|
||||
echo "Verbose: ${VERBOSE}"
|
||||
echo "File: ${FILE}"
|
||||
echo "Build dir: ${BUILDDIR}"
|
||||
fi
|
||||
|
||||
set -e
|
||||
|
||||
if [ "${COMPILE}" == "yes" ]; then
|
||||
echo "-- Compile"
|
||||
|
||||
mkdir -p "${BUILDDIR}"
|
||||
|
||||
OPT_LIB=
|
||||
TMP_ULIB=${ARDUINO_USER_LIBS:-}
|
||||
if [ -n "${TMP_ULIB}" ]; then
|
||||
OPT_LIB="-libraries ""${TMP_ULIB}"""
|
||||
fi
|
||||
|
||||
TESTPLAN_OPT=""
|
||||
if [ -n "${TESTPLAN}" ]; then
|
||||
TESTPLAN_OPT="-prefs=build.extra_flags=-DTESTPLAN=${TESTPLAN}"
|
||||
fi
|
||||
|
||||
# shellcheck disable=SC2086
|
||||
# (We don't want to quote OPT_LIB as it can contain multiple options.)
|
||||
"${ARDUINODIR}/arduino-builder" \
|
||||
-hardware "${ARDUINODIR}/hardware" \
|
||||
-tools "${ARDUINODIR}/hardware/tools/avr" \
|
||||
-tools "${ARDUINODIR}/tools-builder" \
|
||||
-built-in-libraries "${ARDUINODIR}/libraries" \
|
||||
${OPT_LIB} \
|
||||
-fqbn "${FQBN}" \
|
||||
-build-path "${BUILDDIR}" \
|
||||
${TESTPLAN_OPT} \
|
||||
"${FILE}"
|
||||
fi
|
||||
|
||||
FILEBASENAME=${FILE##*/}
|
||||
|
||||
if [ "${UPLOAD}" == "yes" ]; then
|
||||
echo "-- Upload"
|
||||
"/usr/bin/avrdude" \
|
||||
-q -q -patmega328p -carduino -P"${PORT}" -b"${SPEED}" -D \
|
||||
-Uflash:w:"${BUILDDIR}/${FILEBASENAME}".hex:i
|
||||
fi
|
||||
|
||||
if [ "${CATUSB}" == "yes" ] || [ "${STTY}" == "yes" ]; then
|
||||
if [ -z "${READSPEED}" ]; then
|
||||
TFILE=$(mktemp)
|
||||
gcc -fpreprocessed -dD -x c++ -E "${FILE}" > "${TFILE}"
|
||||
for sp in 9600 19200 28800 38400 57600 115200; do
|
||||
if grep ${sp} "${TFILE}" > /dev/null; then
|
||||
READSPEED=${sp}
|
||||
fi
|
||||
done
|
||||
READSPEED=${READSPEED:-9600}
|
||||
rm "${TFILE}"
|
||||
fi
|
||||
|
||||
stty -F "${PORT}" -hupcl -echo "${READSPEED}"
|
||||
echo "-- usb setup with speed ${READSPEED}"
|
||||
fi
|
||||
|
||||
if [ "${CATUSB}" == "yes" ]; then
|
||||
echo "-- Read usb (Ctrl-C to quit)"
|
||||
DISPLAYSEP=yes
|
||||
{
|
||||
echo "speed=${READSPEED}"
|
||||
echo "fqbn=${FQBN}"
|
||||
echo "port=${PORT}"
|
||||
echo "file=${FILE}"
|
||||
echo "filedate=$(date +"%Y-%m-%dT%H:%M:%SZ" -d @$(stat -c '%Y' "${FILE}"))"
|
||||
echo "date=$(date +'%Y-%m-%dT%H:%M:%SZ')"
|
||||
echo ""
|
||||
echo "-----BEGIN ARDUINO OUTPUT-----"
|
||||
} | tee "${RECORDFILE}"
|
||||
tee -a "${RECORDFILE}" < "${PORT}"
|
||||
fi
|
||||
|
|
@ -0,0 +1 @@
|
|||
../../am2
|
|
@ -1,10 +0,0 @@
|
|||
ARDUINO_DIR = /usr/share/arduino
|
||||
ARDUINO_LIBS = RF433any
|
||||
ARDMK_DIR = /home/sebastien/.arduino_mk
|
||||
|
||||
# USER_LIB_PATH = /home/sebastien/travail/cpp/seb/arduino/libraries
|
||||
|
||||
BOARD_TAG = uno
|
||||
MCU = atmega328
|
||||
|
||||
include $(ARDMK_DIR)/Arduino.mk
|
|
@ -0,0 +1 @@
|
|||
../Makefile
|
|
@ -1,343 +0,0 @@
|
|||
#!/usr/bin/bash
|
||||
|
||||
# am
|
||||
|
||||
# Copyright 2019, 2020, 2021 Sébastien Millet
|
||||
|
||||
# Can perform the following:
|
||||
# 1. Compile the code
|
||||
# 2. Upload to Arduino
|
||||
# 3. Read (continually) what is arriving from the USB port the Arduino is
|
||||
# connected to
|
||||
|
||||
# Versions history (as of 1.3)
|
||||
# 1.3 Output from Arduino is recorded in files named with numbers instead of
|
||||
# date-time string.
|
||||
# 1.4 Adds -t (--testplan) option, to set TESTPLAN macro
|
||||
# 1.5 -t (or --testplan) now comes with a value, so as to manage multiple test
|
||||
# plans.
|
||||
# 1.6 Updated to work fine with Arch arduino package instead of the manually
|
||||
# installed (from tar.gz source) package used so far.
|
||||
# 1.7 Renames archlinux-arduino back to arduino, and created corresponding
|
||||
# symlink (was cleaner to do s).
|
||||
|
||||
set -euo pipefail
|
||||
|
||||
VERSION=1.7
|
||||
|
||||
PORT=
|
||||
BOARD=
|
||||
SPEED=
|
||||
FQBN=
|
||||
BUILDDIR=
|
||||
RECORDDIR=out
|
||||
READSPEED=
|
||||
RECORDFILE=
|
||||
|
||||
UPLOAD="no"
|
||||
VERBOSE="no"
|
||||
CATUSB="no"
|
||||
STTY="no"
|
||||
RECORDUSB="no"
|
||||
COMPILE="yes"
|
||||
TESTPLAN=
|
||||
|
||||
DISPLAYSEP=no
|
||||
|
||||
function finish {
|
||||
if [ "${DISPLAYSEP}" == "yes" ]; then
|
||||
echo "-----END ARDUINO OUTPUT-----" | tee -a "${RECORDFILE}"
|
||||
fi
|
||||
}
|
||||
|
||||
trap finish EXIT
|
||||
|
||||
function usage {
|
||||
echo "Usage:"
|
||||
echo " am [OPTIONS...] FILE"
|
||||
echo "Compile FILE using arduino-builder."
|
||||
echo "Example: am sketch.ino"
|
||||
echo ""
|
||||
echo "ENVIRONMENT VARIABLES"
|
||||
echo " If ARDUINO_USER_LIBS is defined and non empty, then arduino-builder"
|
||||
echo " is called with the supplementary option -libraries followed by"
|
||||
echo " ARDUINO_USER_LIBS' value."
|
||||
echo ""
|
||||
echo "OPTIONS"
|
||||
echo " -h --help Display this help screen"
|
||||
echo " -V --version Output version information and quit"
|
||||
echo " -v --verbose Be more talkative"
|
||||
echo " -u --upload Upload compiled code into Arduino"
|
||||
echo " -b --board Board, either 'uno' or 'nano'"
|
||||
echo " -p --port Port, for ex. '/dev/ttyUSB0'"
|
||||
echo " -s --speed Upload speed, for ex. 115200"
|
||||
echo " Normally, speed is infered from device type:"
|
||||
echo " 115200 for Uno, 57600 for Nano"
|
||||
echo " -B --fqbn Board Fully Qualified Name, like 'arduino:avr:uno'"
|
||||
echo " -d --builddir Build directory"
|
||||
echo " -c --catusb Display (continually) what Arduino writes on USB"
|
||||
echo " --stty Tune stty properly for later communication (implied"
|
||||
echo " by --catusb)"
|
||||
echo " -r --recordusb Write USB (continually) to a file (implies -c)"
|
||||
echo " --recordfile Output file if -r option is set"
|
||||
echo " -n --nocompile Don't compile code"
|
||||
echo " --readspeed Read speed of USB. If not specified, this script"
|
||||
echo " will try to infere it from source file. If it"
|
||||
echo " fails, it'll fallback to 9600."
|
||||
echo " This option is useful only if USB is read"
|
||||
echo " (-c or --stty option set)"
|
||||
echo " -t --testplan Set TESTPLAN macro value"
|
||||
echo " (as if #define TESTPLAN VALUE)"
|
||||
exit 1
|
||||
}
|
||||
|
||||
function version {
|
||||
echo "am version ${VERSION}"
|
||||
exit
|
||||
}
|
||||
|
||||
OPTS=$(getopt -o hVvub:p:s:B:d:crnt: --long help,version,verbose,upload,board:,port:,speed:,fqbn:,builddir:,catusb,stty,recordusb,nocompile,readspeed:,recordfile:,testplan: -n 'am' -- "$@")
|
||||
|
||||
eval set -- "$OPTS"
|
||||
|
||||
while true; do
|
||||
case "$1" in
|
||||
-h | --help ) usage; shift ;;
|
||||
-V | --version ) version; shift ;;
|
||||
-v | --verbose ) VERBOSE="yes"; shift ;;
|
||||
-u | --upload ) UPLOAD="yes"; shift ;;
|
||||
-b | --board ) BOARD="$2"; shift 2 ;;
|
||||
-p | --port ) PORT="$2"; shift 2 ;;
|
||||
-s | --speed ) SPEED="$2"; shift 2 ;;
|
||||
-B | --fqbn ) FQBN="$2"; shift 2 ;;
|
||||
-d | --builddir ) BUILDDIR="$2"; shift 2 ;;
|
||||
-c | --catusb ) CATUSB="yes"; shift ;;
|
||||
-r | --recordusb ) RECORDUSB="yes"; CATUSB="yes"; shift ;;
|
||||
-n | --nocompile ) COMPILE="no"; shift ;;
|
||||
--readspeed ) READSPEED="$2"; shift 2 ;;
|
||||
--recordfile ) RECORDFILE="$2"; shift 2 ;;
|
||||
--stty ) STTY="yes"; shift ;;
|
||||
-t | --testplan ) TESTPLAN="$2"; shift 2 ;;
|
||||
-- ) shift; break ;;
|
||||
* ) break ;;
|
||||
esac
|
||||
done
|
||||
|
||||
FILE=${1:-}
|
||||
TRAILINGOPTS=${2:-}
|
||||
|
||||
if [ -n "${TRAILINGOPTS}" ]; then
|
||||
echo "Error: trailing options"
|
||||
exit 1;
|
||||
fi
|
||||
if [ -z "${FILE}" ]; then
|
||||
echo "Error: no input file"
|
||||
exit 1;
|
||||
fi
|
||||
|
||||
set +e
|
||||
|
||||
if [ -n "${BOARD}" ]; then
|
||||
if [ "${BOARD}" != "uno" ] && [ "${BOARD}" != "nano" ]; then
|
||||
echo "Error: board '${BOARD}' unknown"
|
||||
exit 1
|
||||
fi
|
||||
fi
|
||||
|
||||
#ARDUINODIR=$(LANG='' type -a arduino \
|
||||
# | tail -n 1 \
|
||||
# | sed 's/\S\+\sis\s//')
|
||||
#ARDUINODIR=$(readlink -f "${ARDUINODIR}")
|
||||
#ARDUINODIR=$(dirname "${ARDUINODIR}")
|
||||
|
||||
ARDUINODIR=/usr/share/arduino
|
||||
|
||||
COUNTUNO=$(compgen -G '/dev/ttyACM*' | wc -l)
|
||||
COUNTNANO=$(compgen -G '/dev/ttyUSB*' | wc -l)
|
||||
|
||||
if [ -z "${BOARD}" ]; then
|
||||
if [ "${COUNTUNO}" -ge 1 ] && [ "${COUNTNANO}" -ge 1 ]; then
|
||||
echo "Error: cannot guess board, found ${COUNTUNO} uno(s), ${COUNTNANO} nano(s)"
|
||||
exit 10
|
||||
fi
|
||||
if [ "${COUNTUNO}" -ge 1 ]; then
|
||||
BOARD=uno
|
||||
elif [ "${COUNTNANO}" -ge 1 ]; then
|
||||
BOARD=nano
|
||||
fi
|
||||
if [ -z "${BOARD}" ]; then
|
||||
echo "Error: cannot guess board, none found";
|
||||
exit 10
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ "${UPLOAD}" == "yes" ] || [ "${CATUSB}" == "yes" ]; then
|
||||
if [ -z "${PORT}" ]; then
|
||||
if [ "${BOARD}" == "uno" ]; then
|
||||
COUNT=${COUNTUNO}
|
||||
PORT=$(compgen -G '/dev/ttyACM*')
|
||||
elif [ "${BOARD}" == "nano" ]; then
|
||||
COUNT=${COUNTNANO}
|
||||
PORT=$(compgen -G '/dev/ttyUSB*')
|
||||
else
|
||||
echo "FATAL #001, CHECK THIS CODE"
|
||||
exit 99
|
||||
fi
|
||||
|
||||
if [ "${COUNT}" -ge 2 ]; then
|
||||
echo "Error: cannot guess port, more than 1 board '${BOARD}' found"
|
||||
exit 10
|
||||
fi
|
||||
if [ -z "${PORT}" ]; then
|
||||
echo "Error: cannot guess port, none found"
|
||||
exit 10
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ -z "${SPEED}" ]; then
|
||||
if [ "${BOARD}" == "uno" ]; then
|
||||
SPEED=115200
|
||||
elif [ "${BOARD}" == "nano" ]; then
|
||||
SPEED=57600
|
||||
else
|
||||
echo "FATAL #002, CHECK THIS CODE"
|
||||
exit 99
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ ! -e "${PORT}" ]; then
|
||||
echo "Error: port not found"
|
||||
exit 10
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ -z "${FQBN}" ]; then
|
||||
if [ "${BOARD}" == "uno" ]; then
|
||||
FQBN="arduino:avr:uno"
|
||||
elif [ "${BOARD}" == "nano" ]; then
|
||||
FQBN="arduino:avr:nano:cpu=atmega328old"
|
||||
else
|
||||
echo "FATAL #003, CHECK THIS CODE"
|
||||
exit 99
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ -z "${BUILDDIR}" ]; then
|
||||
if [[ "${FILE}" == */* ]]; then
|
||||
BUILDDIR=${FILE%/*}
|
||||
BUILDDIR="${BUILDDIR%/}/build"
|
||||
else
|
||||
BUILDDIR=build
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ "${RECORDUSB}" == "yes" ]; then
|
||||
if [ -z "${RECORDFILE}" ]; then
|
||||
V=${FILE##*/}
|
||||
V=${V%.*}
|
||||
V=${V:-out}
|
||||
PREV=
|
||||
for i in {15..00}; do
|
||||
F="${RECORDDIR}/${V}-$i.txt"
|
||||
if [ -e "${F}" ] && [ -n "${PREV}" ]; then
|
||||
mv "${F}" "${PREV}"
|
||||
fi
|
||||
PREV="${F}"
|
||||
done
|
||||
RECORDFILE="${F}"
|
||||
mkdir -p "${RECORDDIR}"
|
||||
fi
|
||||
else
|
||||
RECORDFILE="/dev/null"
|
||||
fi
|
||||
|
||||
if [ "${VERBOSE}" == "yes" ]; then
|
||||
echo "-- Settings"
|
||||
echo "Arduino dir: ${ARDUINODIR}"
|
||||
echo "Board: ${BOARD}"
|
||||
echo "Port: ${PORT}"
|
||||
echo "Speed: ${SPEED}"
|
||||
echo "Fqbn: ${FQBN}"
|
||||
echo "Upload: ${UPLOAD}"
|
||||
echo "Catusb: ${CATUSB}"
|
||||
echo "Recordusb: ${RECORDUSB}"
|
||||
echo "Record file: ${RECORDFILE}"
|
||||
echo "Verbose: ${VERBOSE}"
|
||||
echo "File: ${FILE}"
|
||||
echo "Build dir: ${BUILDDIR}"
|
||||
fi
|
||||
|
||||
set -e
|
||||
|
||||
if [ "${COMPILE}" == "yes" ]; then
|
||||
echo "-- Compile"
|
||||
|
||||
mkdir -p "${BUILDDIR}"
|
||||
|
||||
OPT_LIB=
|
||||
TMP_ULIB=${ARDUINO_USER_LIBS:-}
|
||||
if [ -n "${TMP_ULIB}" ]; then
|
||||
OPT_LIB="-libraries ""${TMP_ULIB}"""
|
||||
fi
|
||||
|
||||
TESTPLAN_OPT=""
|
||||
if [ -n "${TESTPLAN}" ]; then
|
||||
TESTPLAN_OPT="-prefs=build.extra_flags=-DTESTPLAN=${TESTPLAN}"
|
||||
fi
|
||||
|
||||
# shellcheck disable=SC2086
|
||||
# (We don't want to quote OPT_LIB as it can contain multiple options.)
|
||||
"${ARDUINODIR}/arduino-builder" \
|
||||
-hardware "${ARDUINODIR}/hardware" \
|
||||
-tools "${ARDUINODIR}/hardware/tools/avr" \
|
||||
-tools "${ARDUINODIR}/tools-builder" \
|
||||
-built-in-libraries "${ARDUINODIR}/libraries" \
|
||||
${OPT_LIB} \
|
||||
-fqbn "${FQBN}" \
|
||||
-build-path "${BUILDDIR}" \
|
||||
${TESTPLAN_OPT} \
|
||||
"${FILE}"
|
||||
fi
|
||||
|
||||
FILEBASENAME=${FILE##*/}
|
||||
|
||||
if [ "${UPLOAD}" == "yes" ]; then
|
||||
echo "-- Upload"
|
||||
"/usr/bin/avrdude" \
|
||||
-q -q -patmega328p -carduino -P"${PORT}" -b"${SPEED}" -D \
|
||||
-Uflash:w:"${BUILDDIR}/${FILEBASENAME}".hex:i
|
||||
fi
|
||||
|
||||
if [ "${CATUSB}" == "yes" ] || [ "${STTY}" == "yes" ]; then
|
||||
if [ -z "${READSPEED}" ]; then
|
||||
TFILE=$(mktemp)
|
||||
gcc -fpreprocessed -dD -x c++ -E "${FILE}" > "${TFILE}"
|
||||
for sp in 9600 19200 28800 38400 57600 115200; do
|
||||
if grep ${sp} "${TFILE}" > /dev/null; then
|
||||
READSPEED=${sp}
|
||||
fi
|
||||
done
|
||||
READSPEED=${READSPEED:-9600}
|
||||
rm "${TFILE}"
|
||||
fi
|
||||
|
||||
stty -F "${PORT}" -hupcl -echo "${READSPEED}"
|
||||
echo "-- usb setup with speed ${READSPEED}"
|
||||
fi
|
||||
|
||||
if [ "${CATUSB}" == "yes" ]; then
|
||||
echo "-- Read usb (Ctrl-C to quit)"
|
||||
DISPLAYSEP=yes
|
||||
{
|
||||
echo "speed=${READSPEED}"
|
||||
echo "fqbn=${FQBN}"
|
||||
echo "port=${PORT}"
|
||||
echo "file=${FILE}"
|
||||
echo "filedate=$(date +"%Y-%m-%dT%H:%M:%SZ" -d @$(stat -c '%Y' "${FILE}"))"
|
||||
echo "date=$(date +'%Y-%m-%dT%H:%M:%SZ')"
|
||||
echo ""
|
||||
echo "-----BEGIN ARDUINO OUTPUT-----"
|
||||
} | tee "${RECORDFILE}"
|
||||
tee -a "${RECORDFILE}" < "${PORT}"
|
||||
fi
|
||||
|
|
@ -0,0 +1 @@
|
|||
../../am2
|
|
@ -1,10 +0,0 @@
|
|||
ARDUINO_DIR = /usr/share/arduino
|
||||
ARDUINO_LIBS = RF433any
|
||||
ARDMK_DIR = /home/sebastien/.arduino_mk
|
||||
|
||||
# USER_LIB_PATH = /home/sebastien/travail/cpp/seb/arduino/libraries
|
||||
|
||||
BOARD_TAG = uno
|
||||
MCU = atmega328
|
||||
|
||||
include $(ARDMK_DIR)/Arduino.mk
|
|
@ -0,0 +1 @@
|
|||
../Makefile
|
|
@ -1,343 +0,0 @@
|
|||
#!/usr/bin/bash
|
||||
|
||||
# am
|
||||
|
||||
# Copyright 2019, 2020, 2021 Sébastien Millet
|
||||
|
||||
# Can perform the following:
|
||||
# 1. Compile the code
|
||||
# 2. Upload to Arduino
|
||||
# 3. Read (continually) what is arriving from the USB port the Arduino is
|
||||
# connected to
|
||||
|
||||
# Versions history (as of 1.3)
|
||||
# 1.3 Output from Arduino is recorded in files named with numbers instead of
|
||||
# date-time string.
|
||||
# 1.4 Adds -t (--testplan) option, to set TESTPLAN macro
|
||||
# 1.5 -t (or --testplan) now comes with a value, so as to manage multiple test
|
||||
# plans.
|
||||
# 1.6 Updated to work fine with Arch arduino package instead of the manually
|
||||
# installed (from tar.gz source) package used so far.
|
||||
# 1.7 Renames archlinux-arduino back to arduino, and created corresponding
|
||||
# symlink (was cleaner to do s).
|
||||
|
||||
set -euo pipefail
|
||||
|
||||
VERSION=1.7
|
||||
|
||||
PORT=
|
||||
BOARD=
|
||||
SPEED=
|
||||
FQBN=
|
||||
BUILDDIR=
|
||||
RECORDDIR=out
|
||||
READSPEED=
|
||||
RECORDFILE=
|
||||
|
||||
UPLOAD="no"
|
||||
VERBOSE="no"
|
||||
CATUSB="no"
|
||||
STTY="no"
|
||||
RECORDUSB="no"
|
||||
COMPILE="yes"
|
||||
TESTPLAN=
|
||||
|
||||
DISPLAYSEP=no
|
||||
|
||||
function finish {
|
||||
if [ "${DISPLAYSEP}" == "yes" ]; then
|
||||
echo "-----END ARDUINO OUTPUT-----" | tee -a "${RECORDFILE}"
|
||||
fi
|
||||
}
|
||||
|
||||
trap finish EXIT
|
||||
|
||||
function usage {
|
||||
echo "Usage:"
|
||||
echo " am [OPTIONS...] FILE"
|
||||
echo "Compile FILE using arduino-builder."
|
||||
echo "Example: am sketch.ino"
|
||||
echo ""
|
||||
echo "ENVIRONMENT VARIABLES"
|
||||
echo " If ARDUINO_USER_LIBS is defined and non empty, then arduino-builder"
|
||||
echo " is called with the supplementary option -libraries followed by"
|
||||
echo " ARDUINO_USER_LIBS' value."
|
||||
echo ""
|
||||
echo "OPTIONS"
|
||||
echo " -h --help Display this help screen"
|
||||
echo " -V --version Output version information and quit"
|
||||
echo " -v --verbose Be more talkative"
|
||||
echo " -u --upload Upload compiled code into Arduino"
|
||||
echo " -b --board Board, either 'uno' or 'nano'"
|
||||
echo " -p --port Port, for ex. '/dev/ttyUSB0'"
|
||||
echo " -s --speed Upload speed, for ex. 115200"
|
||||
echo " Normally, speed is infered from device type:"
|
||||
echo " 115200 for Uno, 57600 for Nano"
|
||||
echo " -B --fqbn Board Fully Qualified Name, like 'arduino:avr:uno'"
|
||||
echo " -d --builddir Build directory"
|
||||
echo " -c --catusb Display (continually) what Arduino writes on USB"
|
||||
echo " --stty Tune stty properly for later communication (implied"
|
||||
echo " by --catusb)"
|
||||
echo " -r --recordusb Write USB (continually) to a file (implies -c)"
|
||||
echo " --recordfile Output file if -r option is set"
|
||||
echo " -n --nocompile Don't compile code"
|
||||
echo " --readspeed Read speed of USB. If not specified, this script"
|
||||
echo " will try to infere it from source file. If it"
|
||||
echo " fails, it'll fallback to 9600."
|
||||
echo " This option is useful only if USB is read"
|
||||
echo " (-c or --stty option set)"
|
||||
echo " -t --testplan Set TESTPLAN macro value"
|
||||
echo " (as if #define TESTPLAN VALUE)"
|
||||
exit 1
|
||||
}
|
||||
|
||||
function version {
|
||||
echo "am version ${VERSION}"
|
||||
exit
|
||||
}
|
||||
|
||||
OPTS=$(getopt -o hVvub:p:s:B:d:crnt: --long help,version,verbose,upload,board:,port:,speed:,fqbn:,builddir:,catusb,stty,recordusb,nocompile,readspeed:,recordfile:,testplan: -n 'am' -- "$@")
|
||||
|
||||
eval set -- "$OPTS"
|
||||
|
||||
while true; do
|
||||
case "$1" in
|
||||
-h | --help ) usage; shift ;;
|
||||
-V | --version ) version; shift ;;
|
||||
-v | --verbose ) VERBOSE="yes"; shift ;;
|
||||
-u | --upload ) UPLOAD="yes"; shift ;;
|
||||
-b | --board ) BOARD="$2"; shift 2 ;;
|
||||
-p | --port ) PORT="$2"; shift 2 ;;
|
||||
-s | --speed ) SPEED="$2"; shift 2 ;;
|
||||
-B | --fqbn ) FQBN="$2"; shift 2 ;;
|
||||
-d | --builddir ) BUILDDIR="$2"; shift 2 ;;
|
||||
-c | --catusb ) CATUSB="yes"; shift ;;
|
||||
-r | --recordusb ) RECORDUSB="yes"; CATUSB="yes"; shift ;;
|
||||
-n | --nocompile ) COMPILE="no"; shift ;;
|
||||
--readspeed ) READSPEED="$2"; shift 2 ;;
|
||||
--recordfile ) RECORDFILE="$2"; shift 2 ;;
|
||||
--stty ) STTY="yes"; shift ;;
|
||||
-t | --testplan ) TESTPLAN="$2"; shift 2 ;;
|
||||
-- ) shift; break ;;
|
||||
* ) break ;;
|
||||
esac
|
||||
done
|
||||
|
||||
FILE=${1:-}
|
||||
TRAILINGOPTS=${2:-}
|
||||
|
||||
if [ -n "${TRAILINGOPTS}" ]; then
|
||||
echo "Error: trailing options"
|
||||
exit 1;
|
||||
fi
|
||||
if [ -z "${FILE}" ]; then
|
||||
echo "Error: no input file"
|
||||
exit 1;
|
||||
fi
|
||||
|
||||
set +e
|
||||
|
||||
if [ -n "${BOARD}" ]; then
|
||||
if [ "${BOARD}" != "uno" ] && [ "${BOARD}" != "nano" ]; then
|
||||
echo "Error: board '${BOARD}' unknown"
|
||||
exit 1
|
||||
fi
|
||||
fi
|
||||
|
||||
#ARDUINODIR=$(LANG='' type -a arduino \
|
||||
# | tail -n 1 \
|
||||
# | sed 's/\S\+\sis\s//')
|
||||
#ARDUINODIR=$(readlink -f "${ARDUINODIR}")
|
||||
#ARDUINODIR=$(dirname "${ARDUINODIR}")
|
||||
|
||||
ARDUINODIR=/usr/share/arduino
|
||||
|
||||
COUNTUNO=$(compgen -G '/dev/ttyACM*' | wc -l)
|
||||
COUNTNANO=$(compgen -G '/dev/ttyUSB*' | wc -l)
|
||||
|
||||
if [ -z "${BOARD}" ]; then
|
||||
if [ "${COUNTUNO}" -ge 1 ] && [ "${COUNTNANO}" -ge 1 ]; then
|
||||
echo "Error: cannot guess board, found ${COUNTUNO} uno(s), ${COUNTNANO} nano(s)"
|
||||
exit 10
|
||||
fi
|
||||
if [ "${COUNTUNO}" -ge 1 ]; then
|
||||
BOARD=uno
|
||||
elif [ "${COUNTNANO}" -ge 1 ]; then
|
||||
BOARD=nano
|
||||
fi
|
||||
if [ -z "${BOARD}" ]; then
|
||||
echo "Error: cannot guess board, none found";
|
||||
exit 10
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ "${UPLOAD}" == "yes" ] || [ "${CATUSB}" == "yes" ]; then
|
||||
if [ -z "${PORT}" ]; then
|
||||
if [ "${BOARD}" == "uno" ]; then
|
||||
COUNT=${COUNTUNO}
|
||||
PORT=$(compgen -G '/dev/ttyACM*')
|
||||
elif [ "${BOARD}" == "nano" ]; then
|
||||
COUNT=${COUNTNANO}
|
||||
PORT=$(compgen -G '/dev/ttyUSB*')
|
||||
else
|
||||
echo "FATAL #001, CHECK THIS CODE"
|
||||
exit 99
|
||||
fi
|
||||
|
||||
if [ "${COUNT}" -ge 2 ]; then
|
||||
echo "Error: cannot guess port, more than 1 board '${BOARD}' found"
|
||||
exit 10
|
||||
fi
|
||||
if [ -z "${PORT}" ]; then
|
||||
echo "Error: cannot guess port, none found"
|
||||
exit 10
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ -z "${SPEED}" ]; then
|
||||
if [ "${BOARD}" == "uno" ]; then
|
||||
SPEED=115200
|
||||
elif [ "${BOARD}" == "nano" ]; then
|
||||
SPEED=57600
|
||||
else
|
||||
echo "FATAL #002, CHECK THIS CODE"
|
||||
exit 99
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ ! -e "${PORT}" ]; then
|
||||
echo "Error: port not found"
|
||||
exit 10
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ -z "${FQBN}" ]; then
|
||||
if [ "${BOARD}" == "uno" ]; then
|
||||
FQBN="arduino:avr:uno"
|
||||
elif [ "${BOARD}" == "nano" ]; then
|
||||
FQBN="arduino:avr:nano:cpu=atmega328old"
|
||||
else
|
||||
echo "FATAL #003, CHECK THIS CODE"
|
||||
exit 99
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ -z "${BUILDDIR}" ]; then
|
||||
if [[ "${FILE}" == */* ]]; then
|
||||
BUILDDIR=${FILE%/*}
|
||||
BUILDDIR="${BUILDDIR%/}/build"
|
||||
else
|
||||
BUILDDIR=build
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ "${RECORDUSB}" == "yes" ]; then
|
||||
if [ -z "${RECORDFILE}" ]; then
|
||||
V=${FILE##*/}
|
||||
V=${V%.*}
|
||||
V=${V:-out}
|
||||
PREV=
|
||||
for i in {15..00}; do
|
||||
F="${RECORDDIR}/${V}-$i.txt"
|
||||
if [ -e "${F}" ] && [ -n "${PREV}" ]; then
|
||||
mv "${F}" "${PREV}"
|
||||
fi
|
||||
PREV="${F}"
|
||||
done
|
||||
RECORDFILE="${F}"
|
||||
mkdir -p "${RECORDDIR}"
|
||||
fi
|
||||
else
|
||||
RECORDFILE="/dev/null"
|
||||
fi
|
||||
|
||||
if [ "${VERBOSE}" == "yes" ]; then
|
||||
echo "-- Settings"
|
||||
echo "Arduino dir: ${ARDUINODIR}"
|
||||
echo "Board: ${BOARD}"
|
||||
echo "Port: ${PORT}"
|
||||
echo "Speed: ${SPEED}"
|
||||
echo "Fqbn: ${FQBN}"
|
||||
echo "Upload: ${UPLOAD}"
|
||||
echo "Catusb: ${CATUSB}"
|
||||
echo "Recordusb: ${RECORDUSB}"
|
||||
echo "Record file: ${RECORDFILE}"
|
||||
echo "Verbose: ${VERBOSE}"
|
||||
echo "File: ${FILE}"
|
||||
echo "Build dir: ${BUILDDIR}"
|
||||
fi
|
||||
|
||||
set -e
|
||||
|
||||
if [ "${COMPILE}" == "yes" ]; then
|
||||
echo "-- Compile"
|
||||
|
||||
mkdir -p "${BUILDDIR}"
|
||||
|
||||
OPT_LIB=
|
||||
TMP_ULIB=${ARDUINO_USER_LIBS:-}
|
||||
if [ -n "${TMP_ULIB}" ]; then
|
||||
OPT_LIB="-libraries ""${TMP_ULIB}"""
|
||||
fi
|
||||
|
||||
TESTPLAN_OPT=""
|
||||
if [ -n "${TESTPLAN}" ]; then
|
||||
TESTPLAN_OPT="-prefs=build.extra_flags=-DTESTPLAN=${TESTPLAN}"
|
||||
fi
|
||||
|
||||
# shellcheck disable=SC2086
|
||||
# (We don't want to quote OPT_LIB as it can contain multiple options.)
|
||||
"${ARDUINODIR}/arduino-builder" \
|
||||
-hardware "${ARDUINODIR}/hardware" \
|
||||
-tools "${ARDUINODIR}/hardware/tools/avr" \
|
||||
-tools "${ARDUINODIR}/tools-builder" \
|
||||
-built-in-libraries "${ARDUINODIR}/libraries" \
|
||||
${OPT_LIB} \
|
||||
-fqbn "${FQBN}" \
|
||||
-build-path "${BUILDDIR}" \
|
||||
${TESTPLAN_OPT} \
|
||||
"${FILE}"
|
||||
fi
|
||||
|
||||
FILEBASENAME=${FILE##*/}
|
||||
|
||||
if [ "${UPLOAD}" == "yes" ]; then
|
||||
echo "-- Upload"
|
||||
"/usr/bin/avrdude" \
|
||||
-q -q -patmega328p -carduino -P"${PORT}" -b"${SPEED}" -D \
|
||||
-Uflash:w:"${BUILDDIR}/${FILEBASENAME}".hex:i
|
||||
fi
|
||||
|
||||
if [ "${CATUSB}" == "yes" ] || [ "${STTY}" == "yes" ]; then
|
||||
if [ -z "${READSPEED}" ]; then
|
||||
TFILE=$(mktemp)
|
||||
gcc -fpreprocessed -dD -x c++ -E "${FILE}" > "${TFILE}"
|
||||
for sp in 9600 19200 28800 38400 57600 115200; do
|
||||
if grep ${sp} "${TFILE}" > /dev/null; then
|
||||
READSPEED=${sp}
|
||||
fi
|
||||
done
|
||||
READSPEED=${READSPEED:-9600}
|
||||
rm "${TFILE}"
|
||||
fi
|
||||
|
||||
stty -F "${PORT}" -hupcl -echo "${READSPEED}"
|
||||
echo "-- usb setup with speed ${READSPEED}"
|
||||
fi
|
||||
|
||||
if [ "${CATUSB}" == "yes" ]; then
|
||||
echo "-- Read usb (Ctrl-C to quit)"
|
||||
DISPLAYSEP=yes
|
||||
{
|
||||
echo "speed=${READSPEED}"
|
||||
echo "fqbn=${FQBN}"
|
||||
echo "port=${PORT}"
|
||||
echo "file=${FILE}"
|
||||
echo "filedate=$(date +"%Y-%m-%dT%H:%M:%SZ" -d @$(stat -c '%Y' "${FILE}"))"
|
||||
echo "date=$(date +'%Y-%m-%dT%H:%M:%SZ')"
|
||||
echo ""
|
||||
echo "-----BEGIN ARDUINO OUTPUT-----"
|
||||
} | tee "${RECORDFILE}"
|
||||
tee -a "${RECORDFILE}" < "${PORT}"
|
||||
fi
|
||||
|
|
@ -0,0 +1 @@
|
|||
../../am2
|
|
@ -0,0 +1,22 @@
|
|||
# This Makefile is to be symbolic-linked inside subfolders.
|
||||
# It is generic enough that, to the asumption the subfolder contains one .ino
|
||||
# file and only one, it'll work as expected.
|
||||
|
||||
source = $(wildcard *.ino)
|
||||
target = build/$(source).with_bootloader.hex
|
||||
opt =
|
||||
|
||||
ALL: $(target)
|
||||
|
||||
$(target): $(source)
|
||||
ifdef color
|
||||
./am2 $(opt) $<
|
||||
else
|
||||
GCC_COLORS="" ./am2 --no-color $(opt) $<
|
||||
endif
|
||||
|
||||
clean:
|
||||
rm -rf build
|
||||
|
||||
mrproper:
|
||||
rm -rf build out
|
|
@ -1,10 +1,22 @@
|
|||
ARDUINO_DIR = /usr/share/arduino
|
||||
ARDUINO_LIBS = RF433any
|
||||
ARDMK_DIR = /home/sebastien/.arduino_mk
|
||||
# This Makefile is to be symbolic-linked inside subfolders.
|
||||
# It is generic enough that, to the asumption the subfolder contains one .ino
|
||||
# file and only one, it'll work as expected.
|
||||
|
||||
# USER_LIB_PATH = /home/sebastien/travail/cpp/seb/arduino/libraries
|
||||
source = $(wildcard *.ino)
|
||||
target = build/$(source).with_bootloader.hex
|
||||
opt = -t 1
|
||||
|
||||
BOARD_TAG = uno
|
||||
MCU = atmega328
|
||||
ALL: $(target)
|
||||
|
||||
include $(ARDMK_DIR)/Arduino.mk
|
||||
$(target): $(source)
|
||||
ifdef color
|
||||
./am2 $(opt) $<
|
||||
else
|
||||
GCC_COLORS="" ./am2 --no-color $(opt) $<
|
||||
endif
|
||||
|
||||
clean:
|
||||
rm -rf build
|
||||
|
||||
mrproper:
|
||||
rm -rf build out
|
||||
|
|
|
@ -1,345 +0,0 @@
|
|||
#!/usr/bin/bash
|
||||
|
||||
# am
|
||||
# Has an update specific to RF433any library (RF433ANY_TESTPLAN macro used
|
||||
# instead of TESTPLAN).
|
||||
|
||||
# Copyright 2019, 2020, 2021 Sébastien Millet
|
||||
|
||||
# Can perform the following:
|
||||
# 1. Compile the code
|
||||
# 2. Upload to Arduino
|
||||
# 3. Read (continually) what is arriving from the USB port the Arduino is
|
||||
# connected to
|
||||
|
||||
# Versions history (as of 1.3)
|
||||
# 1.3 Output from Arduino is recorded in files named with numbers instead of
|
||||
# date-time string.
|
||||
# 1.4 Adds -t (--testplan) option, to set TESTPLAN macro
|
||||
# 1.5 -t (or --testplan) now comes with a value, so as to manage multiple test
|
||||
# plans.
|
||||
# 1.6 Updated to work fine with Arch arduino package instead of the manually
|
||||
# installed (from tar.gz source) package used so far.
|
||||
# 1.7 Renames archlinux-arduino back to arduino, and created corresponding
|
||||
# symlink (was cleaner to do s).
|
||||
|
||||
set -euo pipefail
|
||||
|
||||
VERSION=1.7
|
||||
|
||||
PORT=
|
||||
BOARD=
|
||||
SPEED=
|
||||
FQBN=
|
||||
BUILDDIR=
|
||||
RECORDDIR=out
|
||||
READSPEED=
|
||||
RECORDFILE=
|
||||
|
||||
UPLOAD="no"
|
||||
VERBOSE="no"
|
||||
CATUSB="no"
|
||||
STTY="no"
|
||||
RECORDUSB="no"
|
||||
COMPILE="yes"
|
||||
TESTPLAN=
|
||||
|
||||
DISPLAYSEP=no
|
||||
|
||||
function finish {
|
||||
if [ "${DISPLAYSEP}" == "yes" ]; then
|
||||
echo "-----END ARDUINO OUTPUT-----" | tee -a "${RECORDFILE}"
|
||||
fi
|
||||
}
|
||||
|
||||
trap finish EXIT
|
||||
|
||||
function usage {
|
||||
echo "Usage:"
|
||||
echo " am [OPTIONS...] FILE"
|
||||
echo "Compile FILE using arduino-builder."
|
||||
echo "Example: am sketch.ino"
|
||||
echo ""
|
||||
echo "ENVIRONMENT VARIABLES"
|
||||
echo " If ARDUINO_USER_LIBS is defined and non empty, then arduino-builder"
|
||||
echo " is called with the supplementary option -libraries followed by"
|
||||
echo " ARDUINO_USER_LIBS' value."
|
||||
echo ""
|
||||
echo "OPTIONS"
|
||||
echo " -h --help Display this help screen"
|
||||
echo " -V --version Output version information and quit"
|
||||
echo " -v --verbose Be more talkative"
|
||||
echo " -u --upload Upload compiled code into Arduino"
|
||||
echo " -b --board Board, either 'uno' or 'nano'"
|
||||
echo " -p --port Port, for ex. '/dev/ttyUSB0'"
|
||||
echo " -s --speed Upload speed, for ex. 115200"
|
||||
echo " Normally, speed is infered from device type:"
|
||||
echo " 115200 for Uno, 57600 for Nano"
|
||||
echo " -B --fqbn Board Fully Qualified Name, like 'arduino:avr:uno'"
|
||||
echo " -d --builddir Build directory"
|
||||
echo " -c --catusb Display (continually) what Arduino writes on USB"
|
||||
echo " --stty Tune stty properly for later communication (implied"
|
||||
echo " by --catusb)"
|
||||
echo " -r --recordusb Write USB (continually) to a file (implies -c)"
|
||||
echo " --recordfile Output file if -r option is set"
|
||||
echo " -n --nocompile Don't compile code"
|
||||
echo " --readspeed Read speed of USB. If not specified, this script"
|
||||
echo " will try to infere it from source file. If it"
|
||||
echo " fails, it'll fallback to 9600."
|
||||
echo " This option is useful only if USB is read"
|
||||
echo " (-c or --stty option set)"
|
||||
echo " -t --testplan Set TESTPLAN macro value"
|
||||
echo " (as if #define TESTPLAN VALUE)"
|
||||
exit 1
|
||||
}
|
||||
|
||||
function version {
|
||||
echo "am version ${VERSION}"
|
||||
exit
|
||||
}
|
||||
|
||||
OPTS=$(getopt -o hVvub:p:s:B:d:crnt: --long help,version,verbose,upload,board:,port:,speed:,fqbn:,builddir:,catusb,stty,recordusb,nocompile,readspeed:,recordfile:,testplan: -n 'am' -- "$@")
|
||||
|
||||
eval set -- "$OPTS"
|
||||
|
||||
while true; do
|
||||
case "$1" in
|
||||
-h | --help ) usage; shift ;;
|
||||
-V | --version ) version; shift ;;
|
||||
-v | --verbose ) VERBOSE="yes"; shift ;;
|
||||
-u | --upload ) UPLOAD="yes"; shift ;;
|
||||
-b | --board ) BOARD="$2"; shift 2 ;;
|
||||
-p | --port ) PORT="$2"; shift 2 ;;
|
||||
-s | --speed ) SPEED="$2"; shift 2 ;;
|
||||
-B | --fqbn ) FQBN="$2"; shift 2 ;;
|
||||
-d | --builddir ) BUILDDIR="$2"; shift 2 ;;
|
||||
-c | --catusb ) CATUSB="yes"; shift ;;
|
||||
-r | --recordusb ) RECORDUSB="yes"; CATUSB="yes"; shift ;;
|
||||
-n | --nocompile ) COMPILE="no"; shift ;;
|
||||
--readspeed ) READSPEED="$2"; shift 2 ;;
|
||||
--recordfile ) RECORDFILE="$2"; shift 2 ;;
|
||||
--stty ) STTY="yes"; shift ;;
|
||||
-t | --testplan ) TESTPLAN="$2"; shift 2 ;;
|
||||
-- ) shift; break ;;
|
||||
* ) break ;;
|
||||
esac
|
||||
done
|
||||
|
||||
FILE=${1:-}
|
||||
TRAILINGOPTS=${2:-}
|
||||
|
||||
if [ -n "${TRAILINGOPTS}" ]; then
|
||||
echo "Error: trailing options"
|
||||
exit 1;
|
||||
fi
|
||||
if [ -z "${FILE}" ]; then
|
||||
echo "Error: no input file"
|
||||
exit 1;
|
||||
fi
|
||||
|
||||
set +e
|
||||
|
||||
if [ -n "${BOARD}" ]; then
|
||||
if [ "${BOARD}" != "uno" ] && [ "${BOARD}" != "nano" ]; then
|
||||
echo "Error: board '${BOARD}' unknown"
|
||||
exit 1
|
||||
fi
|
||||
fi
|
||||
|
||||
#ARDUINODIR=$(LANG='' type -a arduino \
|
||||
# | tail -n 1 \
|
||||
# | sed 's/\S\+\sis\s//')
|
||||
#ARDUINODIR=$(readlink -f "${ARDUINODIR}")
|
||||
#ARDUINODIR=$(dirname "${ARDUINODIR}")
|
||||
|
||||
ARDUINODIR=/usr/share/arduino
|
||||
|
||||
COUNTUNO=$(compgen -G '/dev/ttyACM*' | wc -l)
|
||||
COUNTNANO=$(compgen -G '/dev/ttyUSB*' | wc -l)
|
||||
|
||||
if [ -z "${BOARD}" ]; then
|
||||
if [ "${COUNTUNO}" -ge 1 ] && [ "${COUNTNANO}" -ge 1 ]; then
|
||||
echo "Error: cannot guess board, found ${COUNTUNO} uno(s), ${COUNTNANO} nano(s)"
|
||||
exit 10
|
||||
fi
|
||||
if [ "${COUNTUNO}" -ge 1 ]; then
|
||||
BOARD=uno
|
||||
elif [ "${COUNTNANO}" -ge 1 ]; then
|
||||
BOARD=nano
|
||||
fi
|
||||
if [ -z "${BOARD}" ]; then
|
||||
echo "Error: cannot guess board, none found";
|
||||
exit 10
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ "${UPLOAD}" == "yes" ] || [ "${CATUSB}" == "yes" ]; then
|
||||
if [ -z "${PORT}" ]; then
|
||||
if [ "${BOARD}" == "uno" ]; then
|
||||
COUNT=${COUNTUNO}
|
||||
PORT=$(compgen -G '/dev/ttyACM*')
|
||||
elif [ "${BOARD}" == "nano" ]; then
|
||||
COUNT=${COUNTNANO}
|
||||
PORT=$(compgen -G '/dev/ttyUSB*')
|
||||
else
|
||||
echo "FATAL #001, CHECK THIS CODE"
|
||||
exit 99
|
||||
fi
|
||||
|
||||
if [ "${COUNT}" -ge 2 ]; then
|
||||
echo "Error: cannot guess port, more than 1 board '${BOARD}' found"
|
||||
exit 10
|
||||
fi
|
||||
if [ -z "${PORT}" ]; then
|
||||
echo "Error: cannot guess port, none found"
|
||||
exit 10
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ -z "${SPEED}" ]; then
|
||||
if [ "${BOARD}" == "uno" ]; then
|
||||
SPEED=115200
|
||||
elif [ "${BOARD}" == "nano" ]; then
|
||||
SPEED=57600
|
||||
else
|
||||
echo "FATAL #002, CHECK THIS CODE"
|
||||
exit 99
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ ! -e "${PORT}" ]; then
|
||||
echo "Error: port not found"
|
||||
exit 10
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ -z "${FQBN}" ]; then
|
||||
if [ "${BOARD}" == "uno" ]; then
|
||||
FQBN="arduino:avr:uno"
|
||||
elif [ "${BOARD}" == "nano" ]; then
|
||||
FQBN="arduino:avr:nano:cpu=atmega328old"
|
||||
else
|
||||
echo "FATAL #003, CHECK THIS CODE"
|
||||
exit 99
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ -z "${BUILDDIR}" ]; then
|
||||
if [[ "${FILE}" == */* ]]; then
|
||||
BUILDDIR=${FILE%/*}
|
||||
BUILDDIR="${BUILDDIR%/}/build"
|
||||
else
|
||||
BUILDDIR=build
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ "${RECORDUSB}" == "yes" ]; then
|
||||
if [ -z "${RECORDFILE}" ]; then
|
||||
V=${FILE##*/}
|
||||
V=${V%.*}
|
||||
V=${V:-out}
|
||||
PREV=
|
||||
for i in {15..00}; do
|
||||
F="${RECORDDIR}/${V}-$i.txt"
|
||||
if [ -e "${F}" ] && [ -n "${PREV}" ]; then
|
||||
mv "${F}" "${PREV}"
|
||||
fi
|
||||
PREV="${F}"
|
||||
done
|
||||
RECORDFILE="${F}"
|
||||
mkdir -p "${RECORDDIR}"
|
||||
fi
|
||||
else
|
||||
RECORDFILE="/dev/null"
|
||||
fi
|
||||
|
||||
if [ "${VERBOSE}" == "yes" ]; then
|
||||
echo "-- Settings"
|
||||
echo "Arduino dir: ${ARDUINODIR}"
|
||||
echo "Board: ${BOARD}"
|
||||
echo "Port: ${PORT}"
|
||||
echo "Speed: ${SPEED}"
|
||||
echo "Fqbn: ${FQBN}"
|
||||
echo "Upload: ${UPLOAD}"
|
||||
echo "Catusb: ${CATUSB}"
|
||||
echo "Recordusb: ${RECORDUSB}"
|
||||
echo "Record file: ${RECORDFILE}"
|
||||
echo "Verbose: ${VERBOSE}"
|
||||
echo "File: ${FILE}"
|
||||
echo "Build dir: ${BUILDDIR}"
|
||||
fi
|
||||
|
||||
set -e
|
||||
|
||||
if [ "${COMPILE}" == "yes" ]; then
|
||||
echo "-- Compile"
|
||||
|
||||
mkdir -p "${BUILDDIR}"
|
||||
|
||||
OPT_LIB=
|
||||
TMP_ULIB=${ARDUINO_USER_LIBS:-}
|
||||
if [ -n "${TMP_ULIB}" ]; then
|
||||
OPT_LIB="-libraries ""${TMP_ULIB}"""
|
||||
fi
|
||||
|
||||
TESTPLAN_OPT=""
|
||||
if [ -n "${TESTPLAN}" ]; then
|
||||
TESTPLAN_OPT="-prefs=build.extra_flags=-DRF433ANY_TESTPLAN=${TESTPLAN}"
|
||||
fi
|
||||
|
||||
# shellcheck disable=SC2086
|
||||
# (We don't want to quote OPT_LIB as it can contain multiple options.)
|
||||
"${ARDUINODIR}/arduino-builder" \
|
||||
-hardware "${ARDUINODIR}/hardware" \
|
||||
-tools "${ARDUINODIR}/hardware/tools/avr" \
|
||||
-tools "${ARDUINODIR}/tools-builder" \
|
||||
-built-in-libraries "${ARDUINODIR}/libraries" \
|
||||
${OPT_LIB} \
|
||||
-fqbn "${FQBN}" \
|
||||
-build-path "${BUILDDIR}" \
|
||||
${TESTPLAN_OPT} \
|
||||
"${FILE}"
|
||||
fi
|
||||
|
||||
FILEBASENAME=${FILE##*/}
|
||||
|
||||
if [ "${UPLOAD}" == "yes" ]; then
|
||||
echo "-- Upload"
|
||||
"/usr/bin/avrdude" \
|
||||
-q -q -patmega328p -carduino -P"${PORT}" -b"${SPEED}" -D \
|
||||
-Uflash:w:"${BUILDDIR}/${FILEBASENAME}".hex:i
|
||||
fi
|
||||
|
||||
if [ "${CATUSB}" == "yes" ] || [ "${STTY}" == "yes" ]; then
|
||||
if [ -z "${READSPEED}" ]; then
|
||||
TFILE=$(mktemp)
|
||||
gcc -fpreprocessed -dD -x c++ -E "${FILE}" > "${TFILE}"
|
||||
for sp in 9600 19200 28800 38400 57600 115200; do
|
||||
if grep ${sp} "${TFILE}" > /dev/null; then
|
||||
READSPEED=${sp}
|
||||
fi
|
||||
done
|
||||
READSPEED=${READSPEED:-9600}
|
||||
rm "${TFILE}"
|
||||
fi
|
||||
|
||||
stty -F "${PORT}" -hupcl -echo "${READSPEED}"
|
||||
echo "-- usb setup with speed ${READSPEED}"
|
||||
fi
|
||||
|
||||
if [ "${CATUSB}" == "yes" ]; then
|
||||
echo "-- Read usb (Ctrl-C to quit)"
|
||||
DISPLAYSEP=yes
|
||||
{
|
||||
echo "speed=${READSPEED}"
|
||||
echo "fqbn=${FQBN}"
|
||||
echo "port=${PORT}"
|
||||
echo "file=${FILE}"
|
||||
echo "filedate=$(date +"%Y-%m-%dT%H:%M:%SZ" -d @$(stat -c '%Y' "${FILE}"))"
|
||||
echo "date=$(date +'%Y-%m-%dT%H:%M:%SZ')"
|
||||
echo ""
|
||||
echo "-----BEGIN ARDUINO OUTPUT-----"
|
||||
} | tee "${RECORDFILE}"
|
||||
tee -a "${RECORDFILE}" < "${PORT}"
|
||||
fi
|
||||
|
|
@ -0,0 +1 @@
|
|||
../../../am2
|
|
@ -35,7 +35,7 @@ extern unsigned int counter;
|
|||
extern unsigned int sim_int_count;
|
||||
extern char buffer[RF433SERIAL_LINE_BUF_LEN];
|
||||
extern RF433SerialLine sl;
|
||||
extern uint16_t sim_timings[SIM_TIMINGS_LEN];
|
||||
extern duration_t sim_timings[SIM_TIMINGS_LEN];
|
||||
extern unsigned int sim_int_count_svg;
|
||||
|
||||
bool filter_mask_set;
|
||||
|
@ -103,12 +103,12 @@ void read_simulated_timings_from_usb() {
|
|||
filter_mask_set = true;
|
||||
filter_mask = l;
|
||||
} else {
|
||||
sim_timings[sim_timings_count++] = l;
|
||||
sim_timings[sim_timings_count++] = h;
|
||||
sim_timings[sim_timings_count++] = compact(l);
|
||||
sim_timings[sim_timings_count++] = compact(h);
|
||||
}
|
||||
#else
|
||||
sim_timings[sim_timings_count++] = l;
|
||||
sim_timings[sim_timings_count++] = h;
|
||||
sim_timings[sim_timings_count++] = compact(l);
|
||||
sim_timings[sim_timings_count++] = compact(h);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
|
|
@ -4,15 +4,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x244048FF,
|
||||
"r_low":{
|
||||
"bits":32,"v":0x6D2ADA00,"railstatus":"full","n":2,
|
||||
"b_short":{"inf":201,"mid":536,"sup":884},
|
||||
"b_long":{"inf":885,"mid":1232,"sup":2002},
|
||||
"b_short":{"inf":198,"mid":528,"sup":880},
|
||||
"b_long":{"inf":881,"mid":1232,"sup":2002},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":31,"v":0x496A92FF,"railstatus":"stop received","n":2,
|
||||
"b_short":{"inf":228,"mid":608,"sup":944},
|
||||
"b_long":{"inf":945,"mid":1280,"sup":2080},
|
||||
"b_sep":{"inf":4387,"mid":7020,"sup":65535}
|
||||
"b_sep":{"inf":4320,"mid":6912,"sup":65535}
|
||||
}
|
||||
}
|
||||
]
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
IH_max_pending_timings = 2
|
||||
> nb_sections = 1, initseq = 9604
|
||||
> nb_sections = 1, initseq = 9600
|
||||
00 SSEP
|
||||
sep = 7020
|
||||
sep = 6912
|
||||
low: [2] n = 32, v = 0x6D2ADA00
|
||||
high: [2] n = 31, v = 0x496A92FF
|
||||
|
|
|
@ -4,15 +4,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00000000,
|
||||
"r_low":{
|
||||
"bits":8,"v":0x00000000,"railstatus":"closed","n":1,
|
||||
"b_short":{"inf":186,"mid":248,"sup":310},
|
||||
"b_long":{"inf":186,"mid":248,"sup":310},
|
||||
"b_short":{"inf":180,"mid":240,"sup":300},
|
||||
"b_long":{"inf":180,"mid":240,"sup":300},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":7,"v":0x00000000,"railstatus":"stop received","n":1,
|
||||
"b_short":{"inf":372,"mid":496,"sup":620},
|
||||
"b_long":{"inf":372,"mid":496,"sup":620},
|
||||
"b_sep":{"inf":2417,"mid":3868,"sup":65535}
|
||||
"b_sep":{"inf":2400,"mid":3840,"sup":65535}
|
||||
}
|
||||
}
|
||||
]
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
IH_max_pending_timings = 2
|
||||
> nb_sections = 1, initseq = 9464
|
||||
> nb_sections = 1, initseq = 9344
|
||||
00 SSEP
|
||||
sep = 3868
|
||||
sep = 3840
|
||||
low: [1] n = 8, v = 0x00000000
|
||||
high: [1] n = 7, v = 0x00000000
|
||||
|
|
|
@ -4,15 +4,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00000002,
|
||||
"r_low":{
|
||||
"bits":7,"v":0x00000002,"railstatus":"stop received","n":2,
|
||||
"b_short":{"inf":93,"mid":248,"sup":324},
|
||||
"b_long":{"inf":325,"mid":400,"sup":650},
|
||||
"b_sep":{"inf":562,"mid":900,"sup":65535}
|
||||
"b_short":{"inf":90,"mid":240,"sup":320},
|
||||
"b_long":{"inf":321,"mid":400,"sup":650},
|
||||
"b_sep":{"inf":560,"mid":896,"sup":65535}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":7,"v":0x00000000,"railstatus":"stop received","n":1,
|
||||
"b_short":{"inf":372,"mid":496,"sup":620},
|
||||
"b_long":{"inf":372,"mid":496,"sup":620},
|
||||
"b_sep":{"inf":2417,"mid":3868,"sup":65535}
|
||||
"b_sep":{"inf":2400,"mid":3840,"sup":65535}
|
||||
}
|
||||
}
|
||||
]
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
IH_max_pending_timings = 3
|
||||
> nb_sections = 1, initseq = 65000
|
||||
> nb_sections = 1, initseq = 46080
|
||||
00 2SEP
|
||||
sep = 3868
|
||||
sep = 3840
|
||||
low: [2] n = 7, v = 0x00000002
|
||||
high: [1] n = 7, v = 0x00000000
|
||||
|
|
|
@ -4,15 +4,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00000000,
|
||||
"r_low":{
|
||||
"bits":8,"v":0x00000000,"railstatus":"closed","n":1,
|
||||
"b_short":{"inf":186,"mid":248,"sup":310},
|
||||
"b_long":{"inf":186,"mid":248,"sup":310},
|
||||
"b_short":{"inf":180,"mid":240,"sup":300},
|
||||
"b_long":{"inf":180,"mid":240,"sup":300},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":7,"v":0x00000000,"railstatus":"stop received","n":1,
|
||||
"b_short":{"inf":372,"mid":496,"sup":620},
|
||||
"b_long":{"inf":372,"mid":496,"sup":620},
|
||||
"b_sep":{"inf":2417,"mid":3868,"sup":65535}
|
||||
"b_sep":{"inf":2400,"mid":3840,"sup":65535}
|
||||
}
|
||||
}
|
||||
,
|
||||
|
@ -21,15 +21,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00000008,
|
||||
"r_low":{
|
||||
"bits":7,"v":0x00000008,"railstatus":"stop received","n":2,
|
||||
"b_short":{"inf":93,"mid":248,"sup":324},
|
||||
"b_long":{"inf":325,"mid":400,"sup":650},
|
||||
"b_sep":{"inf":587,"mid":940,"sup":65535}
|
||||
"b_short":{"inf":90,"mid":240,"sup":320},
|
||||
"b_long":{"inf":321,"mid":400,"sup":650},
|
||||
"b_sep":{"inf":580,"mid":928,"sup":65535}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":7,"v":0x00000000,"railstatus":"stop received","n":1,
|
||||
"b_short":{"inf":372,"mid":496,"sup":620},
|
||||
"b_long":{"inf":372,"mid":496,"sup":620},
|
||||
"b_sep":{"inf":2417,"mid":3868,"sup":65535}
|
||||
"b_sep":{"inf":2400,"mid":3840,"sup":65535}
|
||||
}
|
||||
}
|
||||
,
|
||||
|
@ -38,9 +38,9 @@
|
|||
"trk":TRK_RECV,"xorval":0x0000000E,
|
||||
"r_low":{
|
||||
"bits":7,"v":0x0000000E,"railstatus":"stop received","n":2,
|
||||
"b_short":{"inf":93,"mid":248,"sup":324},
|
||||
"b_long":{"inf":325,"mid":400,"sup":650},
|
||||
"b_sep":{"inf":587,"mid":940,"sup":65535}
|
||||
"b_short":{"inf":90,"mid":240,"sup":320},
|
||||
"b_long":{"inf":321,"mid":400,"sup":650},
|
||||
"b_sep":{"inf":580,"mid":928,"sup":65535}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":7,"v":0x00000000,"railstatus":"error","n":1,
|
||||
|
@ -55,9 +55,9 @@
|
|||
"trk":TRK_RECV,"xorval":0x00000002,
|
||||
"r_low":{
|
||||
"bits":7,"v":0x00000002,"railstatus":"stop received","n":2,
|
||||
"b_short":{"inf":93,"mid":248,"sup":324},
|
||||
"b_long":{"inf":325,"mid":400,"sup":650},
|
||||
"b_sep":{"inf":562,"mid":900,"sup":65535}
|
||||
"b_short":{"inf":90,"mid":240,"sup":320},
|
||||
"b_long":{"inf":321,"mid":400,"sup":650},
|
||||
"b_sep":{"inf":560,"mid":896,"sup":65535}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":8,"v":0x00000000,"railstatus":"closed","n":1,
|
||||
|
@ -72,8 +72,8 @@
|
|||
"trk":TRK_RECV,"xorval":0x00000001,
|
||||
"r_low":{
|
||||
"bits":7,"v":0x00000000,"railstatus":"stop received","n":1,
|
||||
"b_short":{"inf":186,"mid":248,"sup":310},
|
||||
"b_long":{"inf":186,"mid":248,"sup":310},
|
||||
"b_short":{"inf":180,"mid":240,"sup":300},
|
||||
"b_long":{"inf":180,"mid":240,"sup":300},
|
||||
"b_sep":{"inf":1250,"mid":2000,"sup":65535}
|
||||
},
|
||||
"r_high":{
|
||||
|
|
|
@ -1,12 +1,12 @@
|
|||
IH_max_pending_timings = 3
|
||||
> nb_sections = 1, initseq = 15000
|
||||
> nb_sections = 1, initseq = 14976
|
||||
00 SSEP
|
||||
sep = 3868
|
||||
sep = 3840
|
||||
low: [1] n = 8, v = 0x00000000
|
||||
high: [1] n = 7, v = 0x00000000
|
||||
IH_max_pending_timings = 3
|
||||
> nb_sections = 1, initseq = 15000
|
||||
> nb_sections = 1, initseq = 14976
|
||||
00 2SEP
|
||||
sep = 3868
|
||||
sep = 3840
|
||||
low: [2] n = 7, v = 0x00000008
|
||||
high: [1] n = 7, v = 0x00000000
|
||||
|
|
|
@ -4,15 +4,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00000000,
|
||||
"r_low":{
|
||||
"bits":8,"v":0x00000000,"railstatus":"closed","n":1,
|
||||
"b_short":{"inf":186,"mid":248,"sup":310},
|
||||
"b_long":{"inf":186,"mid":248,"sup":310},
|
||||
"b_short":{"inf":180,"mid":240,"sup":300},
|
||||
"b_long":{"inf":180,"mid":240,"sup":300},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":7,"v":0x00000000,"railstatus":"stop received","n":1,
|
||||
"b_short":{"inf":375,"mid":500,"sup":625},
|
||||
"b_long":{"inf":375,"mid":500,"sup":625},
|
||||
"b_sep":{"inf":2417,"mid":3868,"sup":65535}
|
||||
"b_short":{"inf":372,"mid":496,"sup":620},
|
||||
"b_long":{"inf":372,"mid":496,"sup":620},
|
||||
"b_sep":{"inf":2400,"mid":3840,"sup":65535}
|
||||
}
|
||||
}
|
||||
]
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
IH_max_pending_timings = 3
|
||||
> nb_sections = 1, initseq = 45000
|
||||
> nb_sections = 1, initseq = 41984
|
||||
00 SSEP
|
||||
sep = 3868
|
||||
sep = 3840
|
||||
low: [1] n = 8, v = 0x00000000
|
||||
high: [1] n = 7, v = 0x00000000
|
||||
|
|
|
@ -4,15 +4,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00000000,
|
||||
"r_low":{
|
||||
"bits":8,"v":0x00000000,"railstatus":"closed","n":1,
|
||||
"b_short":{"inf":186,"mid":248,"sup":310},
|
||||
"b_long":{"inf":186,"mid":248,"sup":310},
|
||||
"b_short":{"inf":180,"mid":240,"sup":300},
|
||||
"b_long":{"inf":180,"mid":240,"sup":300},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":7,"v":0x00000000,"railstatus":"stop received","n":1,
|
||||
"b_short":{"inf":375,"mid":500,"sup":625},
|
||||
"b_long":{"inf":375,"mid":500,"sup":625},
|
||||
"b_sep":{"inf":2417,"mid":3868,"sup":65535}
|
||||
"b_short":{"inf":372,"mid":496,"sup":620},
|
||||
"b_long":{"inf":372,"mid":496,"sup":620},
|
||||
"b_sep":{"inf":2400,"mid":3840,"sup":65535}
|
||||
}
|
||||
}
|
||||
]
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
IH_max_pending_timings = 3
|
||||
> nb_sections = 1, initseq = 15000
|
||||
> nb_sections = 1, initseq = 14976
|
||||
00 SSEP
|
||||
sep = 3868
|
||||
sep = 3840
|
||||
low: [1] n = 8, v = 0x00000000
|
||||
high: [1] n = 7, v = 0x00000000
|
||||
|
|
|
@ -4,14 +4,14 @@
|
|||
"trk":TRK_RECV,"xorval":0x00000000,
|
||||
"r_low":{
|
||||
"bits":7,"v":0x00000000,"railstatus":"stop received","n":1,
|
||||
"b_short":{"inf":186,"mid":248,"sup":310},
|
||||
"b_long":{"inf":186,"mid":248,"sup":310},
|
||||
"b_sep":{"inf":1500,"mid":2400,"sup":65535}
|
||||
"b_short":{"inf":180,"mid":240,"sup":300},
|
||||
"b_long":{"inf":180,"mid":240,"sup":300},
|
||||
"b_sep":{"inf":1440,"mid":2304,"sup":65535}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":8,"v":0x00000000,"railstatus":"closed","n":1,
|
||||
"b_short":{"inf":375,"mid":500,"sup":625},
|
||||
"b_long":{"inf":375,"mid":500,"sup":625},
|
||||
"b_short":{"inf":372,"mid":496,"sup":620},
|
||||
"b_long":{"inf":372,"mid":496,"sup":620},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -4,15 +4,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00000B97,
|
||||
"r_low":{
|
||||
"bits":12,"v":0x00000D1A,"railstatus":"closed","n":2,
|
||||
"b_short":{"inf":234,"mid":624,"sup":958},
|
||||
"b_long":{"inf":959,"mid":1292,"sup":2099},
|
||||
"b_short":{"inf":234,"mid":624,"sup":952},
|
||||
"b_long":{"inf":953,"mid":1280,"sup":2080},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":11,"v":0x0000068D,"railstatus":"stop received","n":2,
|
||||
"b_short":{"inf":269,"mid":716,"sup":1056},
|
||||
"b_long":{"inf":1057,"mid":1396,"sup":2268},
|
||||
"b_sep":{"inf":15017,"mid":24028,"sup":65535}
|
||||
"b_short":{"inf":264,"mid":704,"sup":1048},
|
||||
"b_long":{"inf":1049,"mid":1392,"sup":2262},
|
||||
"b_sep":{"inf":13440,"mid":21504,"sup":65535}
|
||||
}
|
||||
}
|
||||
{
|
||||
|
@ -20,15 +20,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00000FFF,
|
||||
"r_low":{
|
||||
"bits":12,"v":0x00000AAA,"railstatus":"closed","n":2,
|
||||
"b_short":{"inf":234,"mid":624,"sup":958},
|
||||
"b_long":{"inf":959,"mid":1292,"sup":2099},
|
||||
"b_short":{"inf":234,"mid":624,"sup":952},
|
||||
"b_long":{"inf":953,"mid":1280,"sup":2080},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":11,"v":0x00000555,"railstatus":"stop received","n":2,
|
||||
"b_short":{"inf":269,"mid":716,"sup":1056},
|
||||
"b_long":{"inf":1057,"mid":1396,"sup":2268},
|
||||
"b_sep":{"inf":15017,"mid":24028,"sup":65535}
|
||||
"b_short":{"inf":264,"mid":704,"sup":1048},
|
||||
"b_long":{"inf":1049,"mid":1392,"sup":2262},
|
||||
"b_sep":{"inf":13440,"mid":21504,"sup":65535}
|
||||
}
|
||||
}
|
||||
{
|
||||
|
@ -36,15 +36,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00000FFF,
|
||||
"r_low":{
|
||||
"bits":12,"v":0x00000AAA,"railstatus":"closed","n":2,
|
||||
"b_short":{"inf":234,"mid":624,"sup":958},
|
||||
"b_long":{"inf":959,"mid":1292,"sup":2099},
|
||||
"b_short":{"inf":234,"mid":624,"sup":952},
|
||||
"b_long":{"inf":953,"mid":1280,"sup":2080},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":11,"v":0x00000555,"railstatus":"stop received","n":2,
|
||||
"b_short":{"inf":269,"mid":716,"sup":1056},
|
||||
"b_long":{"inf":1057,"mid":1396,"sup":2268},
|
||||
"b_sep":{"inf":15017,"mid":24028,"sup":65535}
|
||||
"b_short":{"inf":264,"mid":704,"sup":1048},
|
||||
"b_long":{"inf":1049,"mid":1392,"sup":2262},
|
||||
"b_sep":{"inf":13440,"mid":21504,"sup":65535}
|
||||
}
|
||||
}
|
||||
{
|
||||
|
@ -52,15 +52,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00000FFF,
|
||||
"r_low":{
|
||||
"bits":12,"v":0x00000AAA,"railstatus":"closed","n":2,
|
||||
"b_short":{"inf":234,"mid":624,"sup":958},
|
||||
"b_long":{"inf":959,"mid":1292,"sup":2099},
|
||||
"b_short":{"inf":234,"mid":624,"sup":952},
|
||||
"b_long":{"inf":953,"mid":1280,"sup":2080},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":11,"v":0x00000555,"railstatus":"stop received","n":2,
|
||||
"b_short":{"inf":269,"mid":716,"sup":1056},
|
||||
"b_long":{"inf":1057,"mid":1396,"sup":2268},
|
||||
"b_sep":{"inf":15017,"mid":24028,"sup":65535}
|
||||
"b_short":{"inf":264,"mid":704,"sup":1048},
|
||||
"b_long":{"inf":1049,"mid":1392,"sup":2262},
|
||||
"b_sep":{"inf":13440,"mid":21504,"sup":65535}
|
||||
}
|
||||
}
|
||||
{
|
||||
|
@ -68,15 +68,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00000FFF,
|
||||
"r_low":{
|
||||
"bits":12,"v":0x00000AAA,"railstatus":"closed","n":2,
|
||||
"b_short":{"inf":234,"mid":624,"sup":958},
|
||||
"b_long":{"inf":959,"mid":1292,"sup":2099},
|
||||
"b_short":{"inf":234,"mid":624,"sup":952},
|
||||
"b_long":{"inf":953,"mid":1280,"sup":2080},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":11,"v":0x00000555,"railstatus":"stop received","n":2,
|
||||
"b_short":{"inf":269,"mid":716,"sup":1056},
|
||||
"b_long":{"inf":1057,"mid":1396,"sup":2268},
|
||||
"b_sep":{"inf":15017,"mid":24028,"sup":65535}
|
||||
"b_short":{"inf":264,"mid":704,"sup":1048},
|
||||
"b_long":{"inf":1049,"mid":1392,"sup":2262},
|
||||
"b_sep":{"inf":13440,"mid":21504,"sup":65535}
|
||||
}
|
||||
}
|
||||
]
|
||||
|
|
|
@ -1,22 +1,22 @@
|
|||
IH_max_pending_timings = 3
|
||||
> nb_sections = 5, initseq = 8484
|
||||
> nb_sections = 5, initseq = 8448
|
||||
00 SSEP
|
||||
sep = 24028
|
||||
sep = 21504
|
||||
low: [2] n = 12, v = 0x00000D1A
|
||||
high: [2] n = 11, v = 0x0000068D
|
||||
01 SSEP
|
||||
sep = 24052
|
||||
sep = 21504
|
||||
low: [2] n = 12, v = 0x00000AAA
|
||||
high: [2] n = 11, v = 0x00000555
|
||||
02 SSEP
|
||||
sep = 24048
|
||||
sep = 21504
|
||||
low: [2] n = 12, v = 0x00000AAA
|
||||
high: [2] n = 11, v = 0x00000555
|
||||
03 SSEP
|
||||
sep = 24056
|
||||
sep = 21504
|
||||
low: [2] n = 12, v = 0x00000AAA
|
||||
high: [2] n = 11, v = 0x00000555
|
||||
04 SSEP
|
||||
sep = 24040
|
||||
sep = 21504
|
||||
low: [2] n = 12, v = 0x00000AAA
|
||||
high: [2] n = 11, v = 0x00000555
|
||||
|
|
|
@ -4,15 +4,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00000000,
|
||||
"r_low":{
|
||||
"bits":11,"v":0x00000000,"railstatus":"closed","n":1,
|
||||
"b_short":{"inf":222,"mid":296,"sup":370},
|
||||
"b_long":{"inf":222,"mid":296,"sup":370},
|
||||
"b_short":{"inf":216,"mid":288,"sup":360},
|
||||
"b_long":{"inf":216,"mid":288,"sup":360},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":10,"v":0x00000000,"railstatus":"stop received","n":1,
|
||||
"b_short":{"inf":315,"mid":420,"sup":525},
|
||||
"b_long":{"inf":315,"mid":420,"sup":525},
|
||||
"b_sep":{"inf":2352,"mid":3764,"sup":65535}
|
||||
"b_short":{"inf":312,"mid":416,"sup":520},
|
||||
"b_long":{"inf":312,"mid":416,"sup":520},
|
||||
"b_sep":{"inf":2320,"mid":3712,"sup":65535}
|
||||
}
|
||||
}
|
||||
{
|
||||
|
@ -20,15 +20,15 @@
|
|||
"trk":TRK_RECV,"xorval":0xFFFFFFFF,
|
||||
"r_low":{
|
||||
"bits":32,"v":0xB251EC9E,"railstatus":"full","n":2,
|
||||
"b_short":{"inf":111,"mid":296,"sup":486},
|
||||
"b_long":{"inf":487,"mid":676,"sup":1098},
|
||||
"b_short":{"inf":108,"mid":288,"sup":480},
|
||||
"b_long":{"inf":481,"mid":672,"sup":1092},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":32,"v":0x4DAE1361,"railstatus":"full","n":2,
|
||||
"b_short":{"inf":158,"mid":420,"sup":604},
|
||||
"b_long":{"inf":605,"mid":788,"sup":1280},
|
||||
"b_sep":{"inf":2352,"mid":3764,"sup":65535}
|
||||
"b_short":{"inf":156,"mid":416,"sup":600},
|
||||
"b_long":{"inf":601,"mid":784,"sup":1274},
|
||||
"b_sep":{"inf":2320,"mid":3712,"sup":65535}
|
||||
}
|
||||
}
|
||||
{
|
||||
|
@ -36,15 +36,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x007FFFFF,
|
||||
"r_low":{
|
||||
"bits":23,"v":0x0011319F,"railstatus":"error","n":2,
|
||||
"b_short":{"inf":111,"mid":296,"sup":486},
|
||||
"b_long":{"inf":487,"mid":676,"sup":1098},
|
||||
"b_short":{"inf":108,"mid":288,"sup":480},
|
||||
"b_long":{"inf":481,"mid":672,"sup":1092},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":23,"v":0x006ECE60,"railstatus":"error","n":2,
|
||||
"b_short":{"inf":158,"mid":420,"sup":604},
|
||||
"b_long":{"inf":605,"mid":788,"sup":1280},
|
||||
"b_sep":{"inf":2352,"mid":3764,"sup":65535}
|
||||
"b_short":{"inf":156,"mid":416,"sup":600},
|
||||
"b_long":{"inf":601,"mid":784,"sup":1274},
|
||||
"b_sep":{"inf":2320,"mid":3712,"sup":65535}
|
||||
}
|
||||
}
|
||||
]
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
IH_max_pending_timings = 3
|
||||
> nb_sections = 2, initseq = 5656
|
||||
> nb_sections = 2, initseq = 5632
|
||||
00 SSEP
|
||||
sep = 3764
|
||||
sep = 3712
|
||||
low: [1] n = 11, v = 0x00000000
|
||||
high: [1] n = 10, v = 0x00000000
|
||||
01 CONT
|
||||
|
|
|
@ -4,15 +4,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00001407,
|
||||
"r_low":{
|
||||
"bits":26,"v":0x010004B2,"railstatus":"closed","n":2,
|
||||
"b_short":{"inf":476,"mid":1268,"sup":1904},
|
||||
"b_long":{"inf":1905,"mid":2540,"sup":4127},
|
||||
"b_short":{"inf":474,"mid":1264,"sup":1848},
|
||||
"b_long":{"inf":1849,"mid":2432,"sup":3952},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":25,"v":0x010010B5,"railstatus":"stop received","n":2,
|
||||
"b_short":{"inf":452,"mid":1204,"sup":1820},
|
||||
"b_long":{"inf":1821,"mid":2436,"sup":3958},
|
||||
"b_sep":{"inf":3315,"mid":5304,"sup":65535}
|
||||
"b_short":{"inf":450,"mid":1200,"sup":1816},
|
||||
"b_long":{"inf":1817,"mid":2432,"sup":3952},
|
||||
"b_sep":{"inf":3280,"mid":5248,"sup":65535}
|
||||
}
|
||||
}
|
||||
{
|
||||
|
@ -20,15 +20,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00001407,
|
||||
"r_low":{
|
||||
"bits":26,"v":0x010004B2,"railstatus":"closed","n":2,
|
||||
"b_short":{"inf":476,"mid":1268,"sup":1904},
|
||||
"b_long":{"inf":1905,"mid":2540,"sup":4127},
|
||||
"b_short":{"inf":474,"mid":1264,"sup":1848},
|
||||
"b_long":{"inf":1849,"mid":2432,"sup":3952},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":25,"v":0x010010B5,"railstatus":"stop received","n":2,
|
||||
"b_short":{"inf":452,"mid":1204,"sup":1820},
|
||||
"b_long":{"inf":1821,"mid":2436,"sup":3958},
|
||||
"b_sep":{"inf":3315,"mid":5304,"sup":65535}
|
||||
"b_short":{"inf":450,"mid":1200,"sup":1816},
|
||||
"b_long":{"inf":1817,"mid":2432,"sup":3952},
|
||||
"b_sep":{"inf":3280,"mid":5248,"sup":65535}
|
||||
}
|
||||
}
|
||||
]
|
||||
|
|
|
@ -1,10 +1,10 @@
|
|||
IH_max_pending_timings = 3
|
||||
> nb_sections = 2, initseq = 5288
|
||||
> nb_sections = 2, initseq = 5248
|
||||
00 SSEP
|
||||
sep = 5304
|
||||
sep = 5248
|
||||
low: [2] n = 26, v = 0x010004B2
|
||||
high: [2] n = 25, v = 0x010010B5
|
||||
01 SSEP
|
||||
sep = 5324
|
||||
sep = 5248
|
||||
low: [2] n = 26, v = 0x010004B2
|
||||
high: [2] n = 25, v = 0x010010B5
|
||||
|
|
|
@ -4,15 +4,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00001407,
|
||||
"r_low":{
|
||||
"bits":25,"v":0x008004B2,"railstatus":"closed","n":2,
|
||||
"b_short":{"inf":476,"mid":1268,"sup":1904},
|
||||
"b_long":{"inf":1905,"mid":2540,"sup":4127},
|
||||
"b_short":{"inf":474,"mid":1264,"sup":1848},
|
||||
"b_long":{"inf":1849,"mid":2432,"sup":3952},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":24,"v":0x008010B5,"railstatus":"stop received","n":2,
|
||||
"b_short":{"inf":452,"mid":1204,"sup":1820},
|
||||
"b_long":{"inf":1821,"mid":2436,"sup":3958},
|
||||
"b_sep":{"inf":3315,"mid":5304,"sup":65535}
|
||||
"b_short":{"inf":450,"mid":1200,"sup":1816},
|
||||
"b_long":{"inf":1817,"mid":2432,"sup":3952},
|
||||
"b_sep":{"inf":3280,"mid":5248,"sup":65535}
|
||||
}
|
||||
}
|
||||
{
|
||||
|
@ -20,15 +20,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00001407,
|
||||
"r_low":{
|
||||
"bits":26,"v":0x010004B2,"railstatus":"closed","n":2,
|
||||
"b_short":{"inf":476,"mid":1268,"sup":1904},
|
||||
"b_long":{"inf":1905,"mid":2540,"sup":4127},
|
||||
"b_short":{"inf":474,"mid":1264,"sup":1848},
|
||||
"b_long":{"inf":1849,"mid":2432,"sup":3952},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":25,"v":0x010010B5,"railstatus":"stop received","n":2,
|
||||
"b_short":{"inf":452,"mid":1204,"sup":1820},
|
||||
"b_long":{"inf":1821,"mid":2436,"sup":3958},
|
||||
"b_sep":{"inf":3315,"mid":5304,"sup":65535}
|
||||
"b_short":{"inf":450,"mid":1200,"sup":1816},
|
||||
"b_long":{"inf":1817,"mid":2432,"sup":3952},
|
||||
"b_sep":{"inf":3280,"mid":5248,"sup":65535}
|
||||
}
|
||||
}
|
||||
]
|
||||
|
|
|
@ -1,10 +1,10 @@
|
|||
IH_max_pending_timings = 3
|
||||
> nb_sections = 2, initseq = 5288
|
||||
> nb_sections = 2, initseq = 5248
|
||||
00 SSEP
|
||||
sep = 5304
|
||||
sep = 5248
|
||||
low: [2] n = 25, v = 0x008004B2
|
||||
high: [2] n = 24, v = 0x008010B5
|
||||
01 SSEP
|
||||
sep = 5324
|
||||
sep = 5248
|
||||
low: [2] n = 26, v = 0x010004B2
|
||||
high: [2] n = 25, v = 0x010010B5
|
||||
|
|
|
@ -4,15 +4,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00001407,
|
||||
"r_low":{
|
||||
"bits":24,"v":0x004004B2,"railstatus":"closed","n":2,
|
||||
"b_short":{"inf":476,"mid":1268,"sup":1904},
|
||||
"b_long":{"inf":1905,"mid":2540,"sup":4127},
|
||||
"b_short":{"inf":474,"mid":1264,"sup":1848},
|
||||
"b_long":{"inf":1849,"mid":2432,"sup":3952},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":23,"v":0x004010B5,"railstatus":"stop received","n":2,
|
||||
"b_short":{"inf":452,"mid":1204,"sup":1820},
|
||||
"b_long":{"inf":1821,"mid":2436,"sup":3958},
|
||||
"b_sep":{"inf":3315,"mid":5304,"sup":65535}
|
||||
"b_short":{"inf":450,"mid":1200,"sup":1816},
|
||||
"b_long":{"inf":1817,"mid":2432,"sup":3952},
|
||||
"b_sep":{"inf":3280,"mid":5248,"sup":65535}
|
||||
}
|
||||
}
|
||||
{
|
||||
|
@ -20,15 +20,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00001407,
|
||||
"r_low":{
|
||||
"bits":26,"v":0x010004B2,"railstatus":"closed","n":2,
|
||||
"b_short":{"inf":476,"mid":1268,"sup":1904},
|
||||
"b_long":{"inf":1905,"mid":2540,"sup":4127},
|
||||
"b_short":{"inf":474,"mid":1264,"sup":1848},
|
||||
"b_long":{"inf":1849,"mid":2432,"sup":3952},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":25,"v":0x010010B5,"railstatus":"stop received","n":2,
|
||||
"b_short":{"inf":452,"mid":1204,"sup":1820},
|
||||
"b_long":{"inf":1821,"mid":2436,"sup":3958},
|
||||
"b_sep":{"inf":3315,"mid":5304,"sup":65535}
|
||||
"b_short":{"inf":450,"mid":1200,"sup":1816},
|
||||
"b_long":{"inf":1817,"mid":2432,"sup":3952},
|
||||
"b_sep":{"inf":3280,"mid":5248,"sup":65535}
|
||||
}
|
||||
}
|
||||
]
|
||||
|
|
|
@ -1,10 +1,10 @@
|
|||
IH_max_pending_timings = 3
|
||||
> nb_sections = 2, initseq = 5288
|
||||
> nb_sections = 2, initseq = 5248
|
||||
00 SSEP
|
||||
sep = 5304
|
||||
sep = 5248
|
||||
low: [2] n = 24, v = 0x004004B2
|
||||
high: [2] n = 23, v = 0x004010B5
|
||||
01 SSEP
|
||||
sep = 5324
|
||||
sep = 5248
|
||||
low: [2] n = 26, v = 0x010004B2
|
||||
high: [2] n = 25, v = 0x010010B5
|
||||
|
|
|
@ -4,15 +4,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00001407,
|
||||
"r_low":{
|
||||
"bits":23,"v":0x002004B2,"railstatus":"closed","n":2,
|
||||
"b_short":{"inf":476,"mid":1268,"sup":1904},
|
||||
"b_long":{"inf":1905,"mid":2540,"sup":4127},
|
||||
"b_short":{"inf":474,"mid":1264,"sup":1848},
|
||||
"b_long":{"inf":1849,"mid":2432,"sup":3952},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":22,"v":0x002010B5,"railstatus":"stop received","n":2,
|
||||
"b_short":{"inf":452,"mid":1204,"sup":1820},
|
||||
"b_long":{"inf":1821,"mid":2436,"sup":3958},
|
||||
"b_sep":{"inf":3315,"mid":5304,"sup":65535}
|
||||
"b_short":{"inf":450,"mid":1200,"sup":1816},
|
||||
"b_long":{"inf":1817,"mid":2432,"sup":3952},
|
||||
"b_sep":{"inf":3280,"mid":5248,"sup":65535}
|
||||
}
|
||||
}
|
||||
{
|
||||
|
@ -20,15 +20,15 @@
|
|||
"trk":TRK_RECV,"xorval":0x00001407,
|
||||
"r_low":{
|
||||
"bits":26,"v":0x010004B2,"railstatus":"closed","n":2,
|
||||
"b_short":{"inf":476,"mid":1268,"sup":1904},
|
||||
"b_long":{"inf":1905,"mid":2540,"sup":4127},
|
||||
"b_short":{"inf":474,"mid":1264,"sup":1848},
|
||||
"b_long":{"inf":1849,"mid":2432,"sup":3952},
|
||||
"b_sep":{"inf":0,"mid":0,"sup":0}
|
||||
},
|
||||
"r_high":{
|
||||
"bits":25,"v":0x010010B5,"railstatus":"stop received","n":2,
|
||||
"b_short":{"inf":452,"mid":1204,"sup":1820},
|
||||
"b_long":{"inf":1821,"mid":2436,"sup":3958},
|
||||
"b_sep":{"inf":3315,"mid":5304,"sup":65535}
|
||||
"b_short":{"inf":450,"mid":1200,"sup":1816},
|
||||
"b_long":{"inf":1817,"mid":2432,"sup":3952},
|
||||
"b_sep":{"inf":3280,"mid":5248,"sup":65535}
|
||||
}
|
||||
}
|
||||
]
|
||||
|
|
|
@ -1,10 +1,10 @@
|
|||
IH_max_pending_timings = 3
|
||||
> nb_sections = 2, initseq = 5288
|
||||
> nb_sections = 2, initseq = 5248
|
||||
00 SSEP
|
||||
sep = 5304
|
||||
sep = 5248
|
||||
low: [2] n = 23, v = 0x002004B2
|
||||
high: [2] n = 22, v = 0x002010B5
|
||||
01 SSEP
|
||||
sep = 5324
|
||||
sep = 5248
|
||||
low: [2] n = 26, v = 0x010004B2
|
||||
high: [2] n = 25, v = 0x010010B5
|
||||
|
|
|
@ -44,7 +44,7 @@ for ((i=START; i<=STOP; i++)); do
|
|||
|
||||
echo "== ROUND $i"
|
||||
|
||||
testplan/test/am testplan/test/test.ino -u --stty -t "${i}"
|
||||
testplan/test/am2 testplan/test/test.ino -u --stty -t "${i}"
|
||||
|
||||
sleep 2
|
||||
|
||||
|
|
Loading…
Reference in New Issue