diff --git a/libs/mavlink_skyward_lib b/libs/mavlink_skyward_lib index 00a22f01347688d08464eafcbb86998a0690a8f8..00b5e98f28a1476587974dc623377af42883e6f0 160000 --- a/libs/mavlink_skyward_lib +++ b/libs/mavlink_skyward_lib @@ -1 +1 @@ -Subproject commit 00a22f01347688d08464eafcbb86998a0690a8f8 +Subproject commit 00b5e98f28a1476587974dc623377af42883e6f0 diff --git a/libs/miosix-kernel b/libs/miosix-kernel index 38bea2878c5470f8dd4cdd5792c969a5bf5ab660..ed0ed118e979bee276efa0e19af295dc53fc62d1 160000 --- a/libs/miosix-kernel +++ b/libs/miosix-kernel @@ -1 +1 @@ -Subproject commit 38bea2878c5470f8dd4cdd5792c969a5bf5ab660 +Subproject commit ed0ed118e979bee276efa0e19af295dc53fc62d1 diff --git a/sbs.conf b/sbs.conf index a1e257e21ca3e424eae9c05fdfc5fe9d890917e6..dda21f77fe9e1ee94b8ff4105cfd4e719d0d8901 100644 --- a/sbs.conf +++ b/sbs.conf @@ -142,6 +142,11 @@ Files: src/shared/logger/Logger.cpp libs/tscpp/buffer.cpp libs/tscpp/stream.cpp +[sensormanager] +Type: srcfiles +Files: src/shared/sensors/SensorManager.cpp + src/shared/sensors/SensorSampler.cpp + [gamma868] Type: srcfiles Files: src/shared/drivers/gamma868/Gamma868.cpp @@ -162,7 +167,7 @@ Files: src/shared/drivers/servo/servo.cpp Type: srcfiles Files: src/shared/utils/testutils/TestHelper.cpp -[tests] +[tests-boardcore] Type: srcfiles Files: src/tests/catch/test-aero.cpp src/tests/catch/test-buttonhandler.cpp @@ -173,7 +178,8 @@ Files: src/tests/catch/test-aero.cpp src/tests/catch/test-matrix.cpp src/tests/catch/test-packetqueue.cpp src/tests/catch/spidriver/test-spidriver - + src/tests/catch/test-sensormanager.cpp + #-------------------------------# # Entrypoints # @@ -218,7 +224,7 @@ Main: kernel-testsuite Type: test BoardId: stm32f429zi_stm32f4discovery BinName: tests-catch -Include: %tests %shared %test-utils %spi +Include: %tests-boardcore %shared %test-utils %spi %sensormanager Defines: Main: catch/catch-tests-entry @@ -278,6 +284,14 @@ Include: %shared Defines: Main: test-pinobserver +[test-sensormanager] +Type: test +BoardId: stm32f407vg_skyward_tortellino +BinName: test-sensormanager +Include: %shared %sensormanager +Defines: -DSTANDALONE_CATCH1_TEST -DDEBUG +Main: catch/test-sensormanager + ## Drivers @@ -293,7 +307,7 @@ Main: drivers/test-dsgamma Type: test BoardId: stm32f429zi_skyward_death_stack BinName: test-imu-adis -Include: %shared +Include: %shared %sensormanager Defines: Main: drivers/test-imu-adis @@ -301,7 +315,7 @@ Main: drivers/test-imu-adis Type: test BoardId: stm32f429zi_skyward_homeone BinName: test-mpu9250 -Include: %shared +Include: %shared %sensormanager Defines: Main: drivers/test-mpu9250 @@ -309,7 +323,7 @@ Main: drivers/test-mpu9250 Type: test BoardId: stm32f429zi_skyward_death_stack BinName: test-lsm -Include: %shared +Include: %shared %sensormanager Defines: Main: drivers/test-lsm @@ -398,7 +412,7 @@ Main: drivers/test-ad7994 # Type: test # BoardId: stm32f429zi_stm32f4discovery # BinName: test-circularbuffer -# Include: %shared %test-utils +# Include: %shared %test-utils # Defines: -DSTANDALONE_CATCH1_TEST # Main: catch/test-circularbuffer @@ -455,7 +469,7 @@ Main: drivers/test-servo Type: test BoardId: stm32f429zi_skyward_death_stack BinName: calibrate-mpu9250 -Include: %shared +Include: %shared %sensormanager Defines: Main: drivers/calibrate-mpu9250 @@ -463,7 +477,7 @@ Main: drivers/calibrate-mpu9250 Type: test BoardId: stm32f429zi_skyward_death_stack BinName: test-ms5803 -Include: %shared %spi +Include: %shared %spi %sensormanager Defines: Main: drivers/test-ms5803 @@ -477,7 +491,7 @@ Main: drivers/test-l3gd20 [test-lsm9ds1] Type: test -BoardId: stm32f407vg_stm32f4discovery +BoardId: stm32f407vg_skyward_tortellino BinName: test-lsm9ds1 Include: %shared %spi Defines: -DDEBUG @@ -501,8 +515,16 @@ Main: test-rls [test-lsm9ds1-fifo] Type: test -BoardId: stm32f407vg_stm32f4discovery +BoardId: stm32f407vg_skyward_tortellino BinName: test-lsm9ds1-fifo Include: %shared %spi Defines: -DDEBUG Main: drivers/test-lsm9ds1-fifo + +[test-lis3dsh] +Type: test +BoardId: stm32f407vg_skyward_tortellino +BinName: test-lis3dsh +Include: %shared %spi +Defines: +Main: drivers/test-lis3dsh diff --git a/scripts/eventgen/EventFunctions.cpp.template b/scripts/eventgen/EventStrings.cpp.template similarity index 99% rename from scripts/eventgen/EventFunctions.cpp.template rename to scripts/eventgen/EventStrings.cpp.template index 1611abafb11180cdadeafae5294f45acc4f85f78..ac394d77ae88f40eaf621b4122d3552610f7ac0a 100644 --- a/scripts/eventgen/EventFunctions.cpp.template +++ b/scripts/eventgen/EventStrings.cpp.template @@ -33,6 +33,7 @@ #include "Topics.h" #include <map> +using std::map; string getEventString(uint8_t event) {{ diff --git a/scripts/eventgen/Events.h.template b/scripts/eventgen/Events.h.template index bd9cc25367ec63690cfc588a877778f110f09791..6ba4c21b2157b67e17b18d7ddfcfdcd818cc7225 100644 --- a/scripts/eventgen/Events.h.template +++ b/scripts/eventgen/Events.h.template @@ -32,22 +32,25 @@ #include <cstdint> #include <string> +#include <vector> #include "events/Event.h" #include "events/EventBroker.h" -#include "EventClasses.h" #include "Topics.h" using std::string; -using std::map; /** - * Definition of all events signals. + * Definition of all events in the Homeone Board software + * Refer to section 5.1.1 of the Software Design Document. + */ enum Events : uint8_t {{ {enum_data} }}; +const std::vector<uint8_t> EVENT_LIST {{{event_list}}}; + /** * @brief Returns the name of the provided event * diff --git a/scripts/eventgen/README.md b/scripts/eventgen/README.md index 7bfb1c9b0625ffdfc86794475246b92e6251e586..478c8fb83cf7efa97b80a13f033d3fa43760166c 100644 --- a/scripts/eventgen/README.md +++ b/scripts/eventgen/README.md @@ -1,10 +1,10 @@ # Events Generator Script -This script generates Events.h, Topics.h and EventFunctions.cpp from a list of -SCXML files representing the state machines of a project. +This script generates the enums for all Events and Topics handled in a project, given a list of `scxml` files that describe all states and transitions. To execute the script: -To execute the script: +`eventgen.py <LIST_OF_SCXML_FILES>` -`./eventgen.py <LIST_OF_SCXML_FILES>` +The header files will be generated in the `generated/` folder. + +Note that the SCXML files should contain transitions with the following form: *< TOPIC >.< EVENT >*. -The files will be generated in the generated/ folder. \ No newline at end of file diff --git a/scripts/eventgen/Topics.h.template b/scripts/eventgen/Topics.h.template index 2ce2c2c536a6ba099b7c72ab2df987ccf9449fd3..ca3f1288407f927b6cc462f22cf4ec1c7bb443fd 100644 --- a/scripts/eventgen/Topics.h.template +++ b/scripts/eventgen/Topics.h.template @@ -32,8 +32,8 @@ #include <stdint.h> #include <string> +#include <vector> -using std::map; using std::string; /** @@ -44,11 +44,12 @@ enum Topics : uint8_t {enum_data} }}; +const std::vector<uint8_t> TOPIC_LIST {{{topic_list}}}; + /** * @brief Returns the name of the provided event * * @param event * @return string */ -string getTopicString(uint8_t topic); - +string getTopicString(uint8_t topic); \ No newline at end of file diff --git a/scripts/eventgen/eventgen.py b/scripts/eventgen/eventgen.py index 9c36223a3266a22a65961776074efcfc0bd14656..9061dba58668f3ac101cae87c690985647c2d565 100755 --- a/scripts/eventgen/eventgen.py +++ b/scripts/eventgen/eventgen.py @@ -23,7 +23,7 @@ # import re import datetime -from os.path import join +from os.path import join, dirname import os import xml.etree.ElementTree as ET @@ -32,6 +32,10 @@ from collections import OrderedDict OUTPUT_FOLDER = "generated" +EVENTS_TEMPLATE_FILE = os.path.dirname(sys.argv[0]) + '/Events.h.template' +TOPICS_TEMPLATE_FILE = os.path.dirname(sys.argv[0]) + '/Topics.h.template' +STRINGS_TEMPLATE_FILE = os.path.dirname(sys.argv[0]) + '/EventStrings.cpp.template' + # # ASCII art banner # @@ -94,6 +98,7 @@ def parse_scxml(files): def generate_events(events, date): enum_str = "" event_map_str = "" + event_list_str = "" # generate string for e in events: @@ -102,14 +107,14 @@ def generate_events(events, date): (" = EV_FIRST_SIGNAL" if e == events[0] else "") + endl event_map_str += " {{ {event}, {string} }}{endl}".format( event=e, string='"' + e + '"', endl=endl) + event_list_str += e + (", " if e != events[-1] else "") # read template - with open('Events.h.template', 'r') as template_file: + with open( EVENTS_TEMPLATE_FILE, 'r') as template_file: template = template_file.read() # write template - template = template.format(date=date, enum_data=enum_str) - + template = template.format(date=date, enum_data=enum_str, event_list=event_list_str) with open(join(OUTPUT_FOLDER, 'Events.h'), 'w') as header_file: header_file.write(template) @@ -121,17 +126,19 @@ def generate_events(events, date): def generate_topics(topics, date): enum_str = "" topic_map_str = "" + topic_list_str = "" for t in topics: endl = ",\n" if t != topics[-1] else "" enum_str += " " + t + endl topic_map_str += " {{ {topics}, {string} }}{endl}".format( topics=t, string='"' + t + '"', endl=endl) + topic_list_str += t + (", " if t != topics[-1] else "") - with open('Topics.h.template', 'r') as template_file: + with open( TOPICS_TEMPLATE_FILE, 'r') as template_file: template = template_file.read() - template = template.format(date=date, enum_data=enum_str) + template = template.format(date=date, enum_data=enum_str, topic_list=topic_list_str) with open(join(OUTPUT_FOLDER, 'Topics.h'), 'w') as header_file: header_file.write(template) @@ -142,12 +149,12 @@ def generate_topics(topics, date): # Generate EventFunctions.cpp # def generate_functions(event_map_str, topic_map_str, date): - with open('EventFunctions.cpp.template', 'r') as cpp_template_file: + with open( STRINGS_TEMPLATE_FILE, 'r') as cpp_template_file: cpp = cpp_template_file.read() cpp = cpp.format(date=date, event_map_data=event_map_str, topic_map_data=topic_map_str) - with open(join(OUTPUT_FOLDER, 'EventFunctions.cpp'), 'w') as cpp_file: + with open(join(OUTPUT_FOLDER, 'EventStrings.cpp'), 'w') as cpp_file: cpp_file.write(cpp) # diff --git a/scripts/linter.sh b/scripts/linter.sh index 70dd0adb8d12a393cc67d72cc2051353b27c2b22..ae9e1e73a401e5debf1f3377e8676e5fc95f29a4 100755 --- a/scripts/linter.sh +++ b/scripts/linter.sh @@ -1,18 +1,83 @@ #!/bin/bash +# +# Usage: grepcheck <FOLDER_TO_CHECK> <STRING_TO_FIND> <EGREP_ARGS> +# +function grepcheck { + + FILES=$(grep -rl "$2" $1 | egrep "$3") + + for f in $FILES + do + # Print name of the file in red + echo -ne '\033\x5b\x33\x33\x6d' + + echo $f + echo -ne '\033\x5b\x30\x6d' + + if [[ $verbose -eq 1 ]]; then + grep --color=always -r "$2" $f -C3 + echo '' + fi + done + + echo '' + + # If VERBOSE is defined then also print the context in the file +} + +# Horrifying way of checking if -v or --verbose is enabled +verbose=0 + +case "$1" in +-v|--verbose) + verbose=1 + shift ;; +esac + +case "$2" in +-v|--verbose) + verbose=1 +esac + +# Execute checks +echo '--------------------------- CPPCHECK' echo '[Linter] Executing cppcheck' -cppcheck --template=gcc -q --std=c++11 --enable=all \ +echo '' +cppcheck -U "RCC_APB1ENR_CAN2EN" --template=gcc -q --std=c++11 --enable=all \ --suppress=unusedFunction --suppress=missingInclude --suppress=noExplicitConstructor \ - "$@" 2>&1 | awk ' + "$1" 2>&1 | awk ' function color(c,s) { printf("\033[%dm%s\033[0m\n",30+c,s) } - /warning/ {color(1,$0);next} + /error/ {color(1,$0);next} + /warning/ {color(3,$0);next} /style/ {color(2,$0);next} - /performance/ {color(3,$0);next} + /performance/ {color(6,$0);next} /information/ {color(4,$0);next} /portability/ {color(5,$0);next} {print} ' +echo '' + +echo '--------------------------- USING NAMESPACE' +echo '[Linter] Checking for using namespace in .h(pp) files' + +grepcheck $1 'using namespace' '.h(pp)?$' + +echo '--------------------------- GREP PRINTF' +echo '[Linter] Checking for printf instead of TRACE' + +grepcheck $1 "printf" '.*' + +echo '--------------------------- GREP ASSERT' +echo '[Linter] Checking if there are asserts in the code' + +grepcheck $1 "assert" '.*' + +echo '--------------------------- GREP THROW' +echo '[Linter] Checking if there are exceptions in the code' + +grepcheck $1 "throw" '~*catch.hpp' #exit 0 diff --git a/scripts/mavlink_client/README.md b/scripts/mavlink_client/README.md index 4a3c225d75fc187df6b0ac5550cb8bad7f174c9b..e8cd75de7fbd87bf075a2506218e1de6d4be6a3c 100644 --- a/scripts/mavlink_client/README.md +++ b/scripts/mavlink_client/README.md @@ -1,14 +1,14 @@ -# Mavlink Clinet +# Mavlink Client These scripts can be used to transmit and receive mavlink data from a PC, either connected via serial port to a transceiver or directly connected to one of the boards. -`make` compiles the 3 `.c` files: +Use `make` to compile the 3 `.c` files: * continuous_tx: sends a message of raw bytes with a given length at a certain frequency. This was used to test the LoRa modules. * mavlink_demo_tx: sends a message whenever it receives a char on stdin -* mavlink_demo_rx: receives and prints packets, eventually sending back ana ACK. +* mavlink_demo_rx: receives and prints packets, eventually sending back an ACK. -`plot.py`: reads value on stdin and plots them. Can be used piping in the output -of mavlink_demo_rx \ No newline at end of file +`plot.py`: reads value on stdin and plots them. Can be used piped with the output +of mavlink_demo_rx. \ No newline at end of file diff --git a/scripts/old/anakin.sh b/scripts/old/anakin.sh deleted file mode 100755 index 52d32b6107f171f011925e0da0f9f215ff9caf98..0000000000000000000000000000000000000000 --- a/scripts/old/anakin.sh +++ /dev/null @@ -1,8 +0,0 @@ -#!/bin/bash - -if [ $# -ne 1 ]; then - echo "Usage: $0 <filename.bin>" - exit -1 -fi; - -stm32flash -b 500000 -w $1 -v /dev/ttyUSB0 diff --git a/scripts/old/anakin_client_curses/.gitignore b/scripts/old/anakin_client_curses/.gitignore deleted file mode 100644 index b051c6c57fa8b6cc588a3ebad860005ec6fcf7cc..0000000000000000000000000000000000000000 --- a/scripts/old/anakin_client_curses/.gitignore +++ /dev/null @@ -1 +0,0 @@ -client diff --git a/scripts/old/anakin_client_curses/Makefile b/scripts/old/anakin_client_curses/Makefile deleted file mode 100644 index f97ef085b53c809ca0363276bbae66fbf22e6ded..0000000000000000000000000000000000000000 --- a/scripts/old/anakin_client_curses/Makefile +++ /dev/null @@ -1,2 +0,0 @@ -all: - gcc -o client client.c -lcurses diff --git a/scripts/old/anakin_client_curses/client.c b/scripts/old/anakin_client_curses/client.c deleted file mode 100644 index 5c45227bddf8b8aa5ced0341a9cb56e0ce624d63..0000000000000000000000000000000000000000 --- a/scripts/old/anakin_client_curses/client.c +++ /dev/null @@ -1,319 +0,0 @@ -#include <stdio.h> -#include <stdlib.h> -#include <string.h> -#include <errno.h> -#include <fcntl.h> -#include <ncurses.h> -#include <signal.h> -#include <stdint.h> -#include <termios.h> -#include <unistd.h> - -volatile int stop = 0; -uint8_t buf[8192] = {0}; -uint16_t rptr = 0, wptr = 0; - -#pragma pack(1) -struct vec3_t { - float x; - float y; - float z; -}; -#pragma pack() - -enum DataType -{ - DATA_VEC3 = 0, - DATA_QUAT = 1, - DATA_FLOAT = 2, - DATA_INT = 3, - DATA_STRING= 4, - DATA_LIMITED_INT = 5, - DATA_UINT32 = 6 -}; - -const char* sensor_names[] = -{ - "ACCEL_MPU9250", - "ACCEL_INEMO", - "ACCEL_MAX21105", - - "GYRO_MPU9250", - "GYRO_INEMO", - "GYRO_FXAS21002", - "GYRO_MAX21105", - - "COMPASS_MPU9250", - "COMPASS_INEMO", - - "TEMP_MPU9250", - "TEMP_INEMO", - "TEMP_LPS331AP", - "TEMP_MAX21105", - "TEMP_MS580", - - "PRESS_LPS331AP", - "PRESS_MS580", - - "UNUSED_16", - "DMA_TX_FIFOSZ", - "DMA_RX_FIFOSZ", - "DMA_FIFO_ERR", - "CPU%", - "LOG_QUEUE_SZ" -}; - -uint8_t sensor_type[] = -{ - DATA_VEC3, - DATA_VEC3, - DATA_VEC3, - - DATA_VEC3, - DATA_VEC3, - DATA_VEC3, - DATA_VEC3, - - DATA_VEC3, - DATA_VEC3, - - DATA_FLOAT, - DATA_FLOAT, - DATA_FLOAT, - DATA_FLOAT, - DATA_FLOAT, - - DATA_FLOAT, - DATA_FLOAT, - - DATA_INT, - DATA_LIMITED_INT, - DATA_LIMITED_INT, - DATA_UINT32, - DATA_UINT32, - DATA_LIMITED_INT -}; - -#define NUM_SENSORS ((int)((sizeof(sensor_names) / sizeof(sensor_names[0])))) - - -void on_signal(int s) -{ - if(!stop) - { - signal(s, on_signal); - stop = 1; - } -} - -int logline = 0; -void log_string(const char* data, int len) -{ - if(len <= 0) - return; - - move(NUM_SENSORS + 2 + logline, 10); - attron(COLOR_PAIR(1)); - printw(data); - if(len < 30) - for(int i=len;i<30;i++) - printw(" "); - refresh(); - logline = (logline+1)%20; -} - -void draw_sensor(int id, int type, const void* data) -{ - char tmp[256] = {0}; - - if(id >= (int)NUM_SENSORS) - { - sprintf(tmp, "Got packet for invalid sensor %d\n", id); - log_string(tmp, strlen(tmp)); - return; - } - - if(type < 0 || type > 6 || type == 4) - { - sprintf(tmp, "Got packet for invalid type %d\n", type); - log_string(tmp, strlen(tmp)); - return; - } - - move(1+id, 10); - sprintf(tmp, "%20s : ", sensor_names[id]); - - uint8_t color = (type != 5) ? (type + 1) : 2; - attron(COLOR_PAIR(color)); - printw(tmp); - attroff(COLOR_PAIR(color)); - - int all_null = 1; - for(int i=0;i<NUM_SENSORS && all_null == 1;i++) - if(((const char *)data)[i] != 0) - all_null = 0; - if((data == NULL || all_null == 1) && type != 5) - { - attron(COLOR_PAIR(5)); - attron(A_BOLD); - printw("[NULL] "); - attroff(A_BOLD); - attroff(COLOR_PAIR(5)); - return; - } - - const uint8_t* i = (const uint8_t*) data; - const struct vec3_t* v = (const struct vec3_t*) data; - const float* f = (const float*) data; - const uint8_t* ui = (const uint8_t*) data; - const uint32_t* ui32 = (const uint32_t*) data; - - switch(type) - { - case DATA_FLOAT: - sprintf(tmp, "%7.4f ", *f); - printw(tmp); - break; - case DATA_INT: - sprintf(tmp, "%d ", *i); - printw(tmp); - break; - case DATA_UINT32: - sprintf(tmp, "%d ", *ui32); - printw(tmp); - break; - case DATA_VEC3: - sprintf(tmp, "(%7.4f, %7.4f, %7.4f)", v->x, v->y, v->z); - printw(tmp); - break; - case DATA_LIMITED_INT: - { - uint32_t vv = (*ui * 27) / 256; - for(uint32_t i=0;i<27;i++) - { - if(i < vv) - printw("#"); - else - printw("."); - } - break; - } - default: - printw("[NOT IMPLEMENTED]"); - break; - } -} - -int sfd; -int init_serial(const char *device) -{ - sfd = open(device, O_RDWR | O_NOCTTY | O_SYNC); - if(sfd < 0) - { - printf("Cannot open ttyUSB0\n"); - return 1; - } - - struct termios tty; - memset(&tty, 0, sizeof(tty)); - if(tcgetattr(sfd, &tty) != 0) - { - printf("Cannot get attributes\n"); - return 1; - } - cfmakeraw(&tty); - cfsetospeed(&tty, B115200); - cfsetispeed(&tty, B115200); - tcsetattr(sfd, TCSANOW, &tty); - - return 0; -} - -void parse(int len) -{ - if(len == 0) - return; - - uint8_t type = buf[0]; - if(type == DATA_STRING) - log_string((const char *)&buf[1], len-1); - else - { - uint8_t id = buf[1]; - draw_sensor(id, type, &buf[2]); - } -} - -int fromHex(char l) -{ - if(l >= '0' && l <= '9') - return l - '0'; - if(l >= 'a' && l <= 'f') - return 10 + l - 'a'; - if(l >= 'A' && l <= 'F') - return 10 + l - 'A'; - return 0; -} - -int read_and_draw() -{ - memset(buf, 0, sizeof(buf)); - int bpos = 0; - char b; - char tmp = 0; - do { - read(sfd, &b, 1); - if(b == '\n' || b == '\r') - break; - else { - if(tmp == 0) - tmp = b; - else { - buf[bpos++] = (fromHex(tmp) << 4) | fromHex(b); - tmp = 0; - } - } - } while(1); - parse(bpos); - return 0; -} - -int main(int argc, char *argv[]) -{ - if(argc < 2) - { - printf("Usage: %s <PORT>\n", argv[0]); - return -1; - } - if(init_serial(argv[1])) - return -1; - - signal(SIGINT, on_signal); - signal(SIGTERM, on_signal); - - initscr(); - start_color(); - init_pair(1, COLOR_BLUE, COLOR_BLACK); - init_pair(2, COLOR_GREEN, COLOR_BLACK); - init_pair(3, COLOR_CYAN, COLOR_BLACK); - init_pair(4, COLOR_WHITE, COLOR_BLACK); - init_pair(5, COLOR_RED, COLOR_BLACK); - init_pair(7, COLOR_MAGENTA, COLOR_BLACK); - erase(); - refresh(); - - log_string("Ready...", 8); - while(!stop) - { - if(read_and_draw() == 1) - stop = 1; - refresh(); - } - - endwin(); - - signal(SIGINT, 0); - signal(SIGTERM, 0); - - return 0; -} diff --git a/scripts/old/excel_eventgen/Events.h.template b/scripts/old/excel_eventgen/Events.h.template deleted file mode 100644 index 2c4937a1fdd509e3307baf666120b77fdd067fec..0000000000000000000000000000000000000000 --- a/scripts/old/excel_eventgen/Events.h.template +++ /dev/null @@ -1,67 +0,0 @@ -/* Copyright (c) 2018 Skyward Experimental Rocketry - * Authors: Luca Erbetta - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - */ - -/* - ****************************************************************************** - * THIS FILE IS AUTOGENERATED. DO NOT EDIT. * - ****************************************************************************** - */ - -// Generated from: {sheet_link} -// Autogen date: {date} - -#ifndef SRC_SHARED_BOARDS_HOMEONE_EVENTS_H -#define SRC_SHARED_BOARDS_HOMEONE_EVENTS_H - -#include <cstdint> -#include <string> - -#include "events/Event.h" -#include "events/EventBroker.h" -#include "EventClasses.h" -#include "Topics.h" - -using std::string; -using std::map; - -namespace HomeoneBoard -{{ -/** - * Definition of all events in the Homeone Board software - * Refer to section 5.1.1 of the Software Design Document. - */ -enum Events : uint8_t -{{ -{enum_data} -}}; - -/** - * @brief Returns the name of the provided event - * - * @param event - * @return string - */ -string getEventString(uint8_t event); - -}} - -#endif /* SRC_SHARED_BOARDS_HOMEONE_EVENTS_H */ diff --git a/scripts/old/excel_eventgen/README.md b/scripts/old/excel_eventgen/README.md deleted file mode 100644 index f87e46c67ebcec406b02c58e10dbe91b00a0c8d3..0000000000000000000000000000000000000000 --- a/scripts/old/excel_eventgen/README.md +++ /dev/null @@ -1,14 +0,0 @@ -# Events Generator Script - -This script generates the Events.h and Topics.h heander file from a GoogleSheets document on Google Drive. - -To execute the script: - -``` -pip install --upgrade google-api-python-client -pip install oauth2client -python scripts/homeone/event_header_generator/event_generator.py -``` - -The first time a browser window should open asking for your credentials (use the Skyward ones). -If it doesn't and only gives you an error, try executing it by clicking on the icon. \ No newline at end of file diff --git a/scripts/old/excel_eventgen/credentials.json b/scripts/old/excel_eventgen/credentials.json deleted file mode 100644 index dae318afc5661116b82fe75f80f4316e538e670a..0000000000000000000000000000000000000000 --- a/scripts/old/excel_eventgen/credentials.json +++ /dev/null @@ -1 +0,0 @@ -{"installed":{"client_id":"1025168905991-tv31etsgm3lecodc5c798shqciekad40.apps.googleusercontent.com","project_id":"homeone-event-ge-1540834105298","auth_uri":"https://accounts.google.com/o/oauth2/auth","token_uri":"https://www.googleapis.com/oauth2/v3/token","auth_provider_x509_cert_url":"https://www.googleapis.com/oauth2/v1/certs","client_secret":"Yhaf67HuHR4DyXZKNXWu2lre","redirect_uris":["urn:ietf:wg:oauth:2.0:oob","http://localhost"]}} \ No newline at end of file diff --git a/scripts/old/excel_eventgen/event_generator.py b/scripts/old/excel_eventgen/event_generator.py deleted file mode 100755 index e895e6fc1bf6ee8615103c51250e5e85ae4a241a..0000000000000000000000000000000000000000 --- a/scripts/old/excel_eventgen/event_generator.py +++ /dev/null @@ -1,197 +0,0 @@ -#!/usr/bin/python3 - -# Copyright (c) 2018 Skyward Experimental Rocketry -# Authors: Luca Erbetta -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in -# all copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN -# THE SOFTWARE. -# - -from googleapiclient.discovery import build -from httplib2 import Http -from oauth2client import file, client, tools - -import re -import datetime -import sys -from os.path import join -import os - -OUTPUT_FOLDER = "generated" -SCOPES = 'https://www.googleapis.com/auth/spreadsheets.readonly' - -service = None - -SPREADSHEET_ID = '12TecOmDd7Uot-MvXkCbhDJRU48-XO6s5ChKDlr4AOvI' -EVENTS_RANGE_NAME = 'EventList!A2:A' -TOPICS_RANGE_NAME = 'Topics!B3:B' - - -def auth(): - try: - store = file.Storage('store.json') - creds = store.get() - if not creds or creds.invalid: - flow = client.flow_from_clientsecrets('credentials.json', SCOPES) - creds = tools.run_flow(flow, store) - - global service - service = build('sheets', 'v4', http=creds.authorize(Http())) - return True - except: - print("Authentication error:", sys.exc_info()[0]) - return False - - -def load_events(): - result = service.spreadsheets().values().get(spreadsheetId=SPREADSHEET_ID, - range=EVENTS_RANGE_NAME).execute() - lines = result.get('values', []) - - # Event names start with EV_ and contains only uppercase letters or underscores - re_event = re.compile(r'(?P<ev>^EV_([A-Z_]+)+)') - - # Only return lines with valid events, remove additional data - events = [] - for l in lines: - m = re_event.match(l[0]) - if m is not None: - events.append(m.group('ev')) - else: - print("Skipped line containing invalid event: {}".format(l)) - - return events - - -def load_topics(): - result = service.spreadsheets().values().get(spreadsheetId=SPREADSHEET_ID, - range=TOPICS_RANGE_NAME).execute() - lines = result.get('values', []) - re_topics = re.compile(r'(?P<topic>^TOPIC_([A-Z_]+)+)') - - # Only return lines with valid topics, remove additional data - topics = [] - for l in lines: - m = re_topics.match(l[0]) - if m is not None: - topics.append(m.group('topic')) - else: - print("Skipped line containing invalid topics: {}".format(l)) - - return topics - - -def has_duplicates(lst): - if len(lst) != len(set(lst)): - return True - return False - - - -print("Homeone on-board software event header generator v0.2") -print("Google sheets API auth in progress...") - -if auth(): - print("Auth successfull.") -else: - exit() - -#directory = os.path.dirname(OUTPUT_FOLDER) -if not os.path.exists(OUTPUT_FOLDER): - os.mkdir(OUTPUT_FOLDER) - -print("Reading from: https://docs.google.com/spreadsheets/d/12TecOmDd7Uot-MvXkCbhDJRU48-XO6s5ChKDlr4AOvI") - -events = load_events() -topics = load_topics() - -# Check duplicates -if has_duplicates(events): - print("Duplicate events found! Terminating.") - exit() - -if has_duplicates(topics): - print("Duplicate topics found! Terminating.") - exit() - -print("{} events loaded.".format(len(events))) -print("{} topics loaded.".format(len(topics))) - -enum_str = "" -event_map_str = "" - -date = datetime.datetime.now() -link = "https://docs.google.com/spreadsheets/d/{id}".format(id=SPREADSHEET_ID) - - -# Events.h generation - -print("Generating Events.h...") - -for e in events: - endl = ",\n" if e != events[-1] else "" - enum_str += " " + e + \ - (" = EV_FIRST_SIGNAL" if e == events[0] else "") + endl - event_map_str += " {{ {event}, {string} }}{endl}".format( - event=e, string='"' + e + '"', endl=endl) - -with open('Events.h.template', 'r') as template_file: - template = template_file.read() - -template = template.format(sheet_link=link, date=date, - enum_data=enum_str) - -with open(join(OUTPUT_FOLDER, 'Events.h'), 'w') as header_file: - header_file.write(template) - -print("Events.h successfully generated.") -# Topics.h generation - -print("Generating Topics.h...") -enum_str = "" -topic_map_str = "" - -for t in topics: - endl = ",\n" if t != topics[-1] else "" - enum_str += " " + t + endl - topic_map_str += " {{ {topics}, {string} }}{endl}".format( - topics=t, string='"' + t + '"', endl=endl) - -with open('Topics.h.template', 'r') as template_file: - template = template_file.read() - -template = template.format(sheet_link=link, date=date, - enum_data=enum_str) - -with open(join(OUTPUT_FOLDER, 'Topics.h'), 'w') as header_file: - header_file.write(template) - -with open('EventFunctions.cpp.template', 'r') as cpp_template_file: - cpp = cpp_template_file.read() - -cpp = cpp.format(sheet_link=link, date=date, - event_map_data=event_map_str, topic_map_data=topic_map_str) - -with open(join(OUTPUT_FOLDER, 'EventFunctions.cpp'), 'w') as cpp_file: - cpp_file.write(cpp) - -print("Topics.h successfully generated.") - -print() -print("All files successfully generated. Please move Events.h, Topics.h, EventFunction.cpp into the Homeone board folder.") -print(".... Done.") diff --git a/scripts/old/gen_fault_headers.py b/scripts/old/gen_fault_headers.py deleted file mode 100755 index 0a5badbdaac96f3de9d501d912fbe39c1f3f4ef2..0000000000000000000000000000000000000000 --- a/scripts/old/gen_fault_headers.py +++ /dev/null @@ -1,239 +0,0 @@ -#!/usr/bin/python - -# Copyright (c) 2017 Skyward Experimental Rocketry -# Authors: Alain Carlucci -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in -# all copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN -# THE SOFTWARE. - - -import csv,string,hashlib,datetime,sys - -if len(sys.argv) != 3: - print("Usage: %s <CSV File> <Output header file>" % (sys.argv[0])) - exit(-1) - -headerLine = None - -newLines = [] - -lineCtr = 0 -curCatId = 0 -categories={} -enums={} - -import hashlib - -def fileHash(filename): - h = hashlib.sha1() - with open(filename, 'rb', buffering=0) as f: - for b in iter(lambda : f.read(128*1024), b''): - h.update(b) - return h.hexdigest() - -def genEnum(name, s, inc): - a = ('''enum class %s -{ -''') % (name,); - cnt = 0 - for i in s: - if inc: - a += " " + i + " = " + str(cnt) + ",\n" - else: - a += " " + i + " = " + str(s[i]) + ",\n" - cnt += 1 - a += "};\n" - a += "const std::size_t %s_SIZE = %d;\n" %(name, cnt) - return a - -def genHeaderFile(fileName,csvFile): - print("[*] Generating header file (%s)" %(fileName,)) - content = ('''/* Copyright (c) 2017 Skyward Experimental Rocketry - * Authors: Alain Carlucci - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - */ - -/* - ****************************************************************************** - * THIS FILE IS AUTOGENERATED. DO NOT EDIT. * - ****************************************************************************** - */ - -// CSV File: %s -// SHA1 of CSV File: %s -// Autogen date: %s - -#include <cstdint> - -#ifndef SKYWARD_FAULT_CTRL_LIST_H -#define SKYWARD_FAULT_CTRL_LIST_H - -''') % (csvFile, fileHash(csvFile), datetime.datetime.now()) - content += genEnum("Fault", enums, True) - content += "\nnamespace FaultCounterData\n{\n\n" - content += genEnum("FaultCategory", categories, False) - content += ''' - -// Usage: categoryID = FaultCounter::FaultToCategory[faultID]; -const uint32_t FaultToCategory[] = -{ - ''' - colCnt = 0 - for i in enums: - content += "%d, " % (categories[enums[i]], ) - colCnt += 1 - if colCnt == 20: - content += "\n " - colCnt = 0 - content += ''' -}; /* CategoryMapping */ - -} /* FaultCounterData */ - -#endif /* SKYWARD_FAULT_CTRL_LIST_H */ - -''' - try: - with open(fileName, "w") as f: - f.write(content) - print("[+] Written %d lines in %s" % (len(content.split("\n")), fileName)) - except: - print("[!] Cannot open %s for writing.", fileName) - exit(-1) - - -def checkForGoodName(n): - if len(n) == 0: - return False - - if n[0] not in string.ascii_uppercase: - return False - - for x in n: - if x not in string.ascii_uppercase + string.digits + '_': - return False - - if n[-1] not in string.ascii_uppercase + string.digits: - return False - - return True - -def genEnumName(cat,name): - ctr = 2 - - genBName = "F_" + cat + "_" + name - genName = genBName - - while genName in enums: - genName = genBName + "_" + str(ctr) - ctr += 1 - - return genName - -# return False: csv file is ok -# return True: csv file must be updated -def handleLine(r): - global lineCtr,categories,newLines,enums,curCatId - - if len(r) != 4: - print("[!] Parsing error at line %d. I'm expecting 4 fields" % (lineCtr,)) - exit(-1) - - curCat = r[0].strip().upper() - curName = r[1].strip().upper() - curDesc = r[2].strip() - curEnum = r[3].strip().upper() - - if checkForGoodName(curCat) == False: - print("[!] Invalid category at line %d." % (lineCtr,)) - exit(-1) - - if checkForGoodName(curName) == False: - print("[!] Invalid name at line %d." % (lineCtr,)) - exit(-1) - - if len(curEnum) > 0 and (checkForGoodName(curEnum) == False or curEnum in enums): - print("[!] Invalid generated name at line %d." % (lineCtr,)) - exit(-1) - - retVal = False - if len(curEnum) == 0: - curEnum = genEnumName(curCat, curName) - retVal = True - - if curCat not in categories: - print("[+] Added category '%s'" % (curCat,)) - categories[curCat] = curCatId - curCatId += 1 - - print("[+] Added %s in category %s" %(curEnum,curCat)) - enums[curEnum] = curCat - - newLines.append([curCat, curName, curDesc, curEnum]) - return retVal - -mustUpdate = False -print("[*] Opening %s..." % (sys.argv[1],)) -try: - with open(sys.argv[1], "r") as csvfile: - r = csv.reader(csvfile, delimiter=',', quotechar='"') - for row in r: - lineCtr += 1 - if headerLine is None: - headerLine = row - continue - if handleLine(row): - mustUpdate = True -except Exception as e: - print("[!] Cannot open %s for reading: %s!" %(sys.argv[1],str(e))) - exit(-1) - -if not mustUpdate: - print("[+] No need to update the csv file.") -else: - print("[*] Updating %s..." % (sys.argv[1],)) - - try: - with open(sys.argv[1], "w") as csvfile: - r = csv.writer(csvfile, delimiter=',', quotechar='"', quoting=csv.QUOTE_ALL) - r.writerow(headerLine) - for row in newLines: - r.writerow(row) - print("[+] Successfully updated csv file") - except: - print("[!] Cannot open %s for writing!" %(sys.argv[1],)) - exit(-1) - -genHeaderFile(sys.argv[2], sys.argv[1]) diff --git a/scripts/openocd-flash.sh b/scripts/openocd/openocd-flash.sh similarity index 100% rename from scripts/openocd-flash.sh rename to scripts/openocd/openocd-flash.sh diff --git a/scripts/start_openocd.sh b/scripts/openocd/start_openocd.sh similarity index 100% rename from scripts/start_openocd.sh rename to scripts/openocd/start_openocd.sh diff --git a/scripts/scxml2plant/scxml2plant.sh b/scripts/scxml2plant/scxml2plant.sh new file mode 100755 index 0000000000000000000000000000000000000000..dbd1f04907a38ead88b5e27d8ae037cf95b88bac --- /dev/null +++ b/scripts/scxml2plant/scxml2plant.sh @@ -0,0 +1,32 @@ +#!/bin/bash + +# Input checks +if [ "$#" -ne 1 ]; then + echo "Usage: scxml2plant <FOLDER_TO_SEARCH>" + exit 1 +fi + +# Find this folder when calling the script from another folder +PATH_TO_XALAN=$(dirname $0) + +# Select all scxml files +for file in $(find $1 -name "*.scxml") +do + # generate plantuml + INPUT_XML=$file + OUTPUT_NAME=$(dirname $file)/$(basename -s ".scxml" $file).plantuml + echo "Input file: " $INPUT_XML " Output basename: " $OUTPUT_NAME + + java -cp $PATH_TO_XALAN/xalan/xalan.jar \ + -Dorg.apache.xerces.xni.parser.XMLParserConfiguration=org.apache.xerces.parsers.XIncludeParserConfiguration org.apache.xalan.xslt.Process \ + -IN $INPUT_XML -XSL $PATH_TO_XALAN/xslt/scxml2plantuml.xslt -OUT $OUTPUT_NAME + + # generate README + README_FILE=$(dirname $file)/README.md + + touch $README_FILE + echo "\`\`\`plantuml" > $README_FILE + cat $OUTPUT_NAME >> $README_FILE + echo "\`\`\`" >> $README_FILE + rm $OUTPUT_NAME +done diff --git a/scripts/scxml2plant/xalan/LICENSE.txt b/scripts/scxml2plant/xalan/LICENSE.txt new file mode 100644 index 0000000000000000000000000000000000000000..47ad566a4592992bb8c6cfe6bda017487dda8cf5 --- /dev/null +++ b/scripts/scxml2plant/xalan/LICENSE.txt @@ -0,0 +1,684 @@ +<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<< + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS +>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>> + +The license above applies to this Apache Xalan release of: + Xalan-Java 2 - XSLT Processor + Xalan-Java 2 - Serializer + +The license above also applies to the jar files +xalan.jar and xsltc.jar - Xalan-Java 2 - XSLT Processor from +Source: http://xalan.apache.org/ + +The license above also applies to the jar file +serializer.jar - Xalan-Java 2 - Serializer +Source: http://xalan.apache.org/ +Used by: Xalan-Java 2 and Xerces-Java 2 + +The license above also applies to the jar file +xercesImpl.jar - Xerces-Java 2 XML Parser. +Source: http://xerces.apache.org/ +Used by: Xalan-Java 2 + +The license above also applies to the jar file +xml-apis.jar - Xerces-Java 2 XML Parser. +Source: http://xerces.apache.org/ +Used by: Xalan-Java 2 and release copy of Xerces-Java 2 + + + + + + + + +The following license applies to the included files: + tools/ant.jar + tools/antRun + tools/antRun.bat +Source: http://ant.apache.org/ +Used By: Xalan's build process: java/build.xml and test/build.xml + +<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<< +/* + * ============================================================================ + * The Apache Software License, Version 1.1 + * ============================================================================ + * + * Copyright (C) 1999 The Apache Software Foundation. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modifica- + * tion, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The end-user documentation included with the redistribution, if any, must + * include the following acknowledgment: "This product includes software + * developed by the Apache Software Foundation (http://www.apache.org/)." + * Alternately, this acknowledgment may appear in the software itself, if + * and wherever such third-party acknowledgments normally appear. + * + * 4. The names "Ant" and "Apache Software Foundation" must not be used to + * endorse or promote products derived from this software without prior + * written permission. For written permission, please contact + * apache@apache.org. + * + * 5. Products derived from this software may not be called "Apache", nor may + * "Apache" appear in their name, without prior written permission of the + * Apache Software Foundation. + * + * THIS SOFTWARE IS PROVIDED ``AS IS'' AND ANY EXPRESSED OR IMPLIED WARRANTIES, + * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND + * FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * APACHE SOFTWARE FOUNDATION OR ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, + * INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLU- + * DING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF + * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + * This software consists of voluntary contributions made by many individuals + * on behalf of the Apache Software Foundation. For more information on the + * Apache Software Foundation, please see <http://www.apache.org/>. + * + */ +>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>> + + + + + + + + +The following license, Apache Software License, Version 1.1, +applies to the included BCEL.jar from Apache Jakarta +(Byte Code Engineering Library). +Source: http://jakarta.apache.org/bcel +Used By: XSLTC component of xml-xalan/java + +The following license, Apache Software License, Version 1.1, +also applies to the included regexp.jar, +jakarta-regexp-1.2.jar from Apache Jakarta. +Source: http://jakarta.apache.org/regexp +Used By: BCEL.jar which is used by XSLTC component of xml-xalan/java + +<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<< +/* + * + * Copyright (c) 2001 The Apache Software Foundation. All rights + * reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. The end-user documentation included with the redistribution, + * if any, must include the following acknowledgment: + * "This product includes software developed by the + * Apache Software Foundation (http://www.apache.org/)." + * Alternately, this acknowledgment may appear in the software itself, + * if and wherever such third-party acknowledgments normally appear. + * + * 4. The names "Apache" and "Apache Software Foundation" and + * "Apache BCEL" must not be used to endorse or promote products + * derived from this software without prior written permission. For + * written permission, please contact apache@apache.org. + * + * 5. Products derived from this software may not be called "Apache", + * "Apache BCEL", nor may "Apache" appear in their name, without + * prior written permission of the Apache Software Foundation. + * + * THIS SOFTWARE IS PROVIDED ``AS IS'' AND ANY EXPRESSED OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES + * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE APACHE SOFTWARE FOUNDATION OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF + * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT + * OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * ==================================================================== + * + * This software consists of voluntary contributions made by many + * individuals on behalf of the Apache Software Foundation. For more + * information on the Apache Software Foundation, please see + * <http://www.apache.org/>. + */ +>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>> + + + + + + + + +The following license applies to the DOM documentation +for the org.w3c.dom.* packages: + +<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<< +W3C® DOCUMENT LICENSE +http://www.w3.org/Consortium/Legal/2002/copyright-documents-20021231 +Public documents on the W3C site are provided by the copyright holders +under the following license. By using and/or copying this document, +or the W3C document from which this statement is linked, you (the licensee) +agree that you have read, understood, and will comply with the following +terms and conditions: + +Permission to copy, and distribute the contents of this document, or the +W3C document from which this statement is linked, in any medium for any +purpose and without fee or royalty is hereby granted, provided that you include +the following on ALL copies of the document, or portions thereof, that you use: + +1. A link or URL to the original W3C document. +2. The pre-existing copyright notice of the original author, or if it + doesn't exist, a notice (hypertext is preferred, but a textual representation + is permitted) of the form: "Copyright © [$date-of-document] World Wide Web + Consortium, (Massachusetts Institute of Technology, European Research + Consortium for Informatics and Mathematics, Keio University). All Rights + Reserved. http://www.w3.org/Consortium/Legal/2002/copyright-documents-20021231" +3. If it exists, the STATUS of the W3C document. + +When space permits, inclusion of the full text of this NOTICE should be provided. +We request that authorship attribution be provided in any software, documents, +or other items or products that you create pursuant to the implementation of the +contents of this document, or any portion thereof. + +No right to create modifications or derivatives of W3C documents is granted pursuant +to this license. However, if additional requirements (documented in the Copyright FAQ) +are satisfied, the right to create modifications or derivatives is sometimes granted +by the W3C to individuals complying with those requirements. + +THIS DOCUMENT IS PROVIDED "AS IS," AND COPYRIGHT HOLDERS MAKE NO REPRESENTATIONS +OR WARRANTIES, EXPRESS OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, WARRANTIES OF +MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, NON-INFRINGEMENT, OR TITLE; +THAT THE CONTENTS OF THE DOCUMENT ARE SUITABLE FOR ANY PURPOSE; NOR THAT THE +IMPLEMENTATION OF SUCH CONTENTS WILL NOT INFRINGE ANY THIRD PARTY PATENTS, +COPYRIGHTS, TRADEMARKS OR OTHER RIGHTS. + +COPYRIGHT HOLDERS WILL NOT BE LIABLE FOR ANY DIRECT, INDIRECT, SPECIAL OR +CONSEQUENTIAL DAMAGES ARISING OUT OF ANY USE OF THE DOCUMENT OR THE PERFORMANCE +OR IMPLEMENTATION OF THE CONTENTS THEREOF. + +The name and trademarks of copyright holders may NOT be used in advertising +or publicity pertaining to this document or its contents without specific, +written prior permission. Title to copyright in this document will at all +times remain with copyright holders. + + +---------------------------------------------------------------------------- + +This formulation of W3C's notice and license became active on December 31 2002. +This version removes the copyright ownership notice such that this license +can be used with materials other than those owned by the W3C, moves information +on style sheets, DTDs, and schemas to the Copyright FAQ, reflects that ERCIM +is now a host of the W3C, includes references to this specific dated version +of the license, and removes the ambiguous grant of "use". See the older +formulation for the policy prior to this date. Please see our Copyright FAQ for +common questions about using materials from our site, such as the translating +or annotating specifications. Other questions about this notice can be directed +to site-policy@w3.org. + + +Joseph Reagle <mailto:site-policy@w3.org +Last revised by Reagle $Date: 2005-07-19 12:33:09 -0400 (Tue, 19 Jul 2005) $ +>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>> + + + + + + + + + +The following license applies to the DOM software, +for the org.w3c.dom.* packages in jar file xml-apis.jar: + +<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<< +W3C® SOFTWARE NOTICE AND LICENSE +http://www.w3.org/Consortium/Legal/2002/copyright-software-20021231 +This work (and included software, documentation such as READMEs, +or other related items) is being provided by the copyright holders +under the following license. By obtaining, using and/or copying this +work, you (the licensee) agree that you have read, understood, and will +comply with the following terms and conditions. + +Permission to copy, modify, and distribute this software and its +documentation, with or without modification, for any purpose and +without fee or royalty is hereby granted, provided that you include +the following on ALL copies of the software and documentation or +portions thereof, including modifications: + +1. The full text of this NOTICE in a location viewable to users of the + redistributed or derivative work. +2. Any pre-existing intellectual property disclaimers, notices, + or terms and conditions. If none exist, the W3C Software Short Notice + should be included (hypertext is preferred, text is permitted) within + the body of any redistributed or derivative code. +3. Notice of any changes or modifications to the files, including the + date changes were made. (We recommend you provide URIs to the location + from which the code is derived.) + +THIS SOFTWARE AND DOCUMENTATION IS PROVIDED "AS IS," AND COPYRIGHT HOLDERS +MAKE NO REPRESENTATIONS OR WARRANTIES, EXPRESS OR IMPLIED, INCLUDING BUT +NOT LIMITED TO, WARRANTIES OF MERCHANTABILITY OR FITNESS FOR ANY PARTICULAR +PURPOSE OR THAT THE USE OF THE SOFTWARE OR DOCUMENTATION WILL NOT INFRINGE +ANY THIRD PARTY PATENTS, COPYRIGHTS, TRADEMARKS OR OTHER RIGHTS. + +COPYRIGHT HOLDERS WILL NOT BE LIABLE FOR ANY DIRECT, INDIRECT, SPECIAL OR +CONSEQUENTIAL DAMAGES ARISING OUT OF ANY USE OF THE SOFTWARE OR DOCUMENTATION. + +The name and trademarks of copyright holders may NOT be used in advertising +or publicity pertaining to the software without specific, written prior +permission. Title to copyright in this software and any associated documentation +will at all times remain with copyright holders. + + +____________________________________ + +This formulation of W3C's notice and license became active on December 31 2002. +This version removes the copyright ownership notice such that this license can +be used with materials other than those owned by the W3C, reflects that ERCIM +is now a host of the W3C, includes references to this specific dated version +of the license, and removes the ambiguous grant of "use". Otherwise, this +version is the same as the previous version and is written so as to preserve +the Free Software Foundation's assessment of GPL compatibility and OSI's +certification under the Open Source Definition. Please see our Copyright FAQ +for common questions about using materials from our site, including specific +terms and conditions for packages like libwww, Amaya, and Jigsaw. Other +questions about this notice can be directed to site-policy@w3.org. + + +Joseph Reagle <mailto:site-policy@w3.org +Last revised by Reagle $Date: 2005-07-19 12:33:09 -0400 (Tue, 19 Jul 2005) $ +>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>> + + + + + + + + +The following license applies to the SAX software, +for the org.xml.sax.* packages in jar file xml-apis.jar: + +<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<< +This module, both source code and documentation, is in the Public Domain, +and comes with NO WARRANTY. See http://www.saxproject.org for further information. +>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>> + + + + + + + + +The following license applies to the jar file +java_cup.jar - LALR Parser Generator for Java(TM). +Source: http://www.cs.princeton.edu/~appel/modern/java/CUP +Used By: XSLTC component of xml-xalan/java + +<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<< +CUP Parser Generator Copyright Notice, License, and Disclaimer + +Copyright 1996-1999 by Scott Hudson, Frank Flannery, C. Scott Ananian + +Permission to use, copy, modify, and distribute this software and its +documentation for any purpose and without fee is hereby granted, provided +that the above copyright notice appear in all copies and that both +the copyright notice and this permission notice and warranty disclaimer +appear in supporting documentation, and that the names of the authors +or their employers not be used in advertising or publicity pertaining +to distribution of the software without specific, written prior permission. + +The authors and their employers disclaim all warranties with regard to +this software, including all implied warranties of merchantability +and fitness. In no event shall the authors or their employers be liable +for any special, indirect or consequential damages or any damages +whatsoever resulting from loss of use, data or profits, whether in an action +of contract, negligence or other tortious action, arising out of or +in connection with the use or performance of this software. +>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>> + + + + + + + + +The following license applies to the jar file runtime.jar - Component +of JavaCup: LALR Parser Generator for Java(TM). +Source: http://www.cs.princeton.edu/~appel/modern/java/CUP +Used By: XSLTC component of xml-xalan/java + +<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<< +CUP Parser Generator Copyright Notice, License, and Disclaimer +(runtime.jar component) + +Copyright 1996-1999 by Scott Hudson, Frank Flannery, C. Scott Ananian + +Permission to use, copy, modify, and distribute this software and its +documentation for any purpose and without fee is hereby granted, provided +that the above copyright notice appear in all copies and that both +the copyright notice and this permission notice and warranty disclaimer +appear in supporting documentation, and that the names of the authors +or their employers not be used in advertising or publicity pertaining +to distribution of the software without specific, written prior permission. + +The authors and their employers disclaim all warranties with regard to +this software, including all implied warranties of merchantability +and fitness. In no event shall the authors or their employers be liable +for any special, indirect or consequential damages or any damages +whatsoever resulting from loss of use, data or profits, whether in an action +of contract, negligence or other tortious action, arising out of or +in connection with the use or performance of this software. +>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>> + + + + + + + + +The following license applies to the JLEX jar file +JLex.jar - A Lexical Analyzer Generator for Java(TM). +Source: http://www.cs.princeton.edu/~appel/modern/java/JLex +Used By: XSLTC component of xml-xalan/java + +<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<< +JLEX COPYRIGHT NOTICE, LICENSE AND DISCLAIMER. + +Copyright 1996-2000 by Elliot Joel Berk and C. Scott Ananian + +Permission to use, copy, modify, and distribute this software and its +documentation for any purpose and without fee is hereby granted, +provided that the above copyright notice appear in all copies and +that both the copyright notice and this permission notice and +warranty disclaimer appear in supporting documentation, and that the +name of the authors or their employers not be used in advertising or +publicity pertaining to distribution of the software without specific, +written prior permission. + +The authors and their employers disclaim all warranties with regard +to this software, including all implied warranties of merchantability and +fitness. In no event shall the authors or their employers be liable for any +special, indirect or consequential damages or any damages whatsoever resulting +from loss of use, data or profits, whether in an action of contract, +negligence or other tortious action, arising out of or in connection +with the use or performance of this software. + +Java is a trademark of Sun Microsystems, Inc. References to the Java +programming language in relation to JLex are not meant to imply that +Sun endorses this product. +>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>> + + + + + + + + +The following license applies to the jar file +stylebook-1.0-b3_xalan-2.jar - Tool for generating Xalan documentation. +Integrated with Xalan-Java 2 and Xerces 2. +Source: http://svn.apache.org/viewvc/xml/stylebook/ +Used by: Xalan-Java 2, Xalan-C++ + +<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<< +/* + * The Apache Software License, Version 1.1 + * + * + * Copyright (c) 1999 The Apache Software Foundation. All rights + * reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * 3. The end-user documentation included with the redistribution, + * if any, must include the following acknowledgment: + * "This product includes software developed by the + * Apache Software Foundation (http://www.apache.org/)." + * Alternately, this acknowledgment may appear in the software itself, + * if and wherever such third-party acknowledgments normally appear. + * + * 4. The names "Xalan", "Xerces", and "Apache Software Foundation" must + * not be used to endorse or promote products derived from this + * software without prior written permission. For written + * permission, please contact apache@apache.org. + * + * 5. Products derived from this software may not be called "Apache", + * nor may "Apache" appear in their name, without prior written + * permission of the Apache Software Foundation. + * + * THIS SOFTWARE IS PROVIDED ``AS IS'' AND ANY EXPRESSED OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES + * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE APACHE SOFTWARE FOUNDATION OR + * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF + * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT + * OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF + * SUCH DAMAGE. + * ==================================================================== + * + * This software consists of voluntary contributions made by many + * individuals on behalf of the Apache Software Foundation and was + * originally based on software copyright (c) 1999, International + * Business Machines, Inc., http://www.apache.org. For more + * information on the Apache Software Foundation, please see + * <http://www.apache.org/>. + */ +>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>> diff --git a/scripts/scxml2plant/xalan/NOTICE.txt b/scripts/scxml2plant/xalan/NOTICE.txt new file mode 100644 index 0000000000000000000000000000000000000000..132f8bccd53579fb004f2b5d095588d3ff9e832a --- /dev/null +++ b/scripts/scxml2plant/xalan/NOTICE.txt @@ -0,0 +1,80 @@ + ========================================================================= + == NOTICE file corresponding to section 4(d) of the Apache License, == + == Version 2.0, in this case for the Apache Xalan Java distribution. == + ========================================================================= + + Apache Xalan (Xalan XSLT processor) + Copyright 1999-2014 The Apache Software Foundation + + Apache Xalan (Xalan serializer) + Copyright 1999-2012 The Apache Software Foundation + + This product includes software developed at + The Apache Software Foundation (http://www.apache.org/). + + ========================================================================= + Portions of this software was originally based on the following: + - software copyright (c) 1999-2002, Lotus Development Corporation., + http://www.lotus.com. + - software copyright (c) 2001-2002, Sun Microsystems., + http://www.sun.com. + - software copyright (c) 2003, IBM Corporation., + http://www.ibm.com. + + ========================================================================= + The binary distribution package (ie. jars, samples and documentation) of + this product includes software developed by the following: + + - The Apache Software Foundation + - Xerces Java - see LICENSE.txt + - JAXP 1.3 APIs - see LICENSE.txt + - Bytecode Engineering Library - see LICENSE.txt + - Regular Expression - see LICENSE.txt + + - Scott Hudson, Frank Flannery, C. Scott Ananian + - CUP Parser Generator runtime (javacup\runtime) - see LICENSE.txt + + ========================================================================= + The source distribution package (ie. all source and tools required to build + Xalan Java) of this product includes software developed by the following: + + - The Apache Software Foundation + - Xerces Java - see LICENSE.txt + - JAXP 1.3 APIs - see LICENSE.txt + - Bytecode Engineering Library - see LICENSE.txt + - Regular Expression - see LICENSE.txt + - Ant - see LICENSE.txt + - Stylebook doc tool - see LICENSE.txt + + - Elliot Joel Berk and C. Scott Ananian + - Lexical Analyzer Generator (JLex) - see LICENSE.txt + + ========================================================================= + Apache Xerces Java + Copyright 1999-2006 The Apache Software Foundation + + This product includes software developed at + The Apache Software Foundation (http://www.apache.org/). + + Portions of Apache Xerces Java in xercesImpl.jar and xml-apis.jar + were originally based on the following: + - software copyright (c) 1999, IBM Corporation., http://www.ibm.com. + - software copyright (c) 1999, Sun Microsystems., http://www.sun.com. + - voluntary contributions made by Paul Eng on behalf of the + Apache Software Foundation that were originally developed at iClick, Inc., + software copyright (c) 1999. + + ========================================================================= + Apache xml-commons xml-apis (redistribution of xml-apis.jar) + + Apache XML Commons + Copyright 2001-2003,2006 The Apache Software Foundation. + + This product includes software developed at + The Apache Software Foundation (http://www.apache.org/). + + Portions of this software were originally based on the following: + - software copyright (c) 1999, IBM Corporation., http://www.ibm.com. + - software copyright (c) 1999, Sun Microsystems., http://www.sun.com. + - software copyright (c) 2000 World Wide Web Consortium, http://www.w3.org + diff --git a/scripts/scxml2plant/xalan/readme.html b/scripts/scxml2plant/xalan/readme.html new file mode 100644 index 0000000000000000000000000000000000000000..538f4286b0308b84b3c4dcfbeb6937ab2d3d56a4 --- /dev/null +++ b/scripts/scxml2plant/xalan/readme.html @@ -0,0 +1,39 @@ +<!-- + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. + * The ASF licenses this file to You under the Apache License, Version 2.0 + * (the "License"); you may not use this file except in compliance with + * the License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. +--> + +<html> +<head> +<title> +</title> +</head> +<body> +<meta content="0; URL=docs/whatsnew.html" http-equiv="Refresh"> + Redirecting to <a href="docs/whatsnew.html">What's New in Xalan_Java 2</a> +</body> +</html> + + + + + + + + + + + + diff --git a/scripts/scxml2plant/xalan/serializer.jar b/scripts/scxml2plant/xalan/serializer.jar new file mode 100644 index 0000000000000000000000000000000000000000..175126880ff58fab0922f3e0cd25ecff765989ba Binary files /dev/null and b/scripts/scxml2plant/xalan/serializer.jar differ diff --git a/scripts/scxml2plant/xalan/xalan.jar b/scripts/scxml2plant/xalan/xalan.jar new file mode 100644 index 0000000000000000000000000000000000000000..5c6c6f947071ef42c8d984f13ace5884e2bc7f03 Binary files /dev/null and b/scripts/scxml2plant/xalan/xalan.jar differ diff --git a/scripts/scxml2plant/xalan/xercesImpl.jar b/scripts/scxml2plant/xalan/xercesImpl.jar new file mode 100644 index 0000000000000000000000000000000000000000..0aaa990f3ecadf60d28b5395dc87bbe49da0cdd7 Binary files /dev/null and b/scripts/scxml2plant/xalan/xercesImpl.jar differ diff --git a/scripts/scxml2plant/xalan/xml-apis.jar b/scripts/scxml2plant/xalan/xml-apis.jar new file mode 100644 index 0000000000000000000000000000000000000000..46733464fc746776c331ecc51061f3a05e662fd1 Binary files /dev/null and b/scripts/scxml2plant/xalan/xml-apis.jar differ diff --git a/scripts/scxml2plant/xalan/xsltc.jar b/scripts/scxml2plant/xalan/xsltc.jar new file mode 100644 index 0000000000000000000000000000000000000000..e11dbeca0aa04a138ea1a5fb29ed331ed02191f6 Binary files /dev/null and b/scripts/scxml2plant/xalan/xsltc.jar differ diff --git a/scripts/scxml2plant/xslt/scxml2plantuml.xslt b/scripts/scxml2plant/xslt/scxml2plantuml.xslt new file mode 100644 index 0000000000000000000000000000000000000000..8468b2c3f684ab52e06678ff41d747407b5751a3 --- /dev/null +++ b/scripts/scxml2plant/xslt/scxml2plantuml.xslt @@ -0,0 +1,124 @@ +<?xml version="1.0" encoding="utf-8"?> +<xsl:stylesheet version="1.0" + xmlns:xsl="http://www.w3.org/1999/XSL/Transform" + xmlns:sc="http://www.w3.org/2005/07/scxml"> + + <xsl:output method="text" encoding="utf-8"/> + <xsl:strip-space elements="*" /> + <xsl:template match="text()|@*"/> + <xsl:template match="text()|@*" mode="target"/> + <xsl:template match="text()|@*" mode="id"/> + + <xsl:template match="/sc:scxml"> + <xsl:text>@startuml
</xsl:text> + <xsl:apply-templates select="@initial"/> + <xsl:apply-templates select="*"/> + <xsl:text>@enduml
</xsl:text> + </xsl:template> + + <xsl:template match="@initial"> + <xsl:text>[*] --> </xsl:text> + <xsl:call-template name="gettargetname"> + <xsl:with-param name="id" select="."/> + </xsl:call-template> + <xsl:text>
</xsl:text> + </xsl:template> + + <xsl:template match="sc:initial"> + <xsl:apply-templates select="*"/> + </xsl:template> + + <xsl:template match="sc:final[@id]"> + <xsl:value-of select="concat(@id, ' : <<final>>
')"/> + </xsl:template> + <xsl:template match="sc:final"> + <xsl:text>unnamed : <<final>>
</xsl:text> + </xsl:template> + + <xsl:template match="sc:state"> + <xsl:text>state </xsl:text> + <xsl:apply-templates select="." mode="id"/> + <xsl:text> {
</xsl:text> + + <xsl:apply-templates select="@initial"/> + <xsl:apply-templates select="*"/> + + <xsl:text>}
</xsl:text> + </xsl:template> + + <xsl:template match="sc:history"> + <xsl:text>state </xsl:text> + <xsl:apply-templates select="." mode="id"/> + <xsl:text> {
</xsl:text> + + <xsl:apply-templates select="*"/> + + <xsl:apply-templates select="." mode="id"/> + <xsl:value-of select="concat(' : <<', @type, ' history>>
')"/> + + <xsl:text>}
</xsl:text> + </xsl:template> + + <xsl:template match="sc:parallel"> + <xsl:text>state </xsl:text> + <xsl:apply-templates select="." mode="id"/> + <xsl:text> {
</xsl:text> + + <xsl:for-each select="sc:state | sc:parallel | sc:history"> + <xsl:apply-templates select="."/> + <xsl:if test="position() != last()"> + <xsl:text>||
</xsl:text> + </xsl:if> + </xsl:for-each> + + <xsl:apply-templates select="sc:transition"/> + + <xsl:text>}
</xsl:text> + </xsl:template> + + + <!--get id of the state - special case for initial state--> + <xsl:template match="sc:state[@id] | sc:history[@id] | sc:parallel[@id] | sc:final[@id]" mode="id"> + <xsl:value-of select="@id"/> + </xsl:template> + <xsl:template match="sc:state | sc:history | sc:parallel" mode="id"> + <xsl:text>unnamed</xsl:text> + </xsl:template> + <xsl:template match="sc:initial" mode="id"> + <xsl:text>[*]</xsl:text> + </xsl:template> + + <xsl:template name="gettargetname"> + <xsl:param name="id"/> + <xsl:apply-templates select="//*[@id = $id][1]" mode="id"/> + </xsl:template> + + <!--target can be specified explicitely as some other state--> + <xsl:template match="sc:transition[@target]" mode="target"> + <xsl:call-template name="gettargetname"> + <xsl:with-param name="id" select="@target"/> + </xsl:call-template> + </xsl:template> + <!--or self-transiton when @target not specified--> + <xsl:template match="sc:transition" mode="target"> + <xsl:apply-templates select=".." mode="id"/> + </xsl:template> + + <!--if 'cond' attribute exists it shall be sourrounded with brackets--> + <xsl:template match="sc:transition/@cond"> + <xsl:value-of select="concat('[', ., ']')"/> + </xsl:template> + + <xsl:template match="sc:transition"> + <xsl:apply-templates select=".." mode="id"/> + <xsl:text> --> </xsl:text> + <xsl:apply-templates select="." mode="target"/> + <xsl:if test="@event or @cond"> + <xsl:text> : </xsl:text> + </xsl:if> + <xsl:value-of select="@event"/> + <xsl:apply-templates select="@cond"/> + <xsl:text>
</xsl:text> + </xsl:template> + +</xsl:stylesheet> diff --git a/scripts/scxml2plant/xslt/scxml2plantuml_finaldot.xslt b/scripts/scxml2plant/xslt/scxml2plantuml_finaldot.xslt new file mode 100644 index 0000000000000000000000000000000000000000..f9050a05ddb1f253be2cea26a355830028cbe939 --- /dev/null +++ b/scripts/scxml2plant/xslt/scxml2plantuml_finaldot.xslt @@ -0,0 +1,117 @@ +<?xml version="1.0" encoding="utf-8"?> +<xsl:stylesheet version="1.0" + xmlns:xsl="http://www.w3.org/1999/XSL/Transform" + xmlns:sc="http://www.w3.org/2005/07/scxml"> + + <xsl:output method="text" encoding="utf-8"/> + <xsl:strip-space elements="*" /> + <xsl:template match="text()|@*"/> + <xsl:template match="text()|@*" mode="target"/> + <xsl:template match="text()|@*" mode="id"/> + + <xsl:template match="/sc:scxml"> + <xsl:text>@startuml
</xsl:text> + <xsl:apply-templates select="@initial"/> + <xsl:apply-templates select="*"/> + <xsl:text>@enduml
</xsl:text> + </xsl:template> + + <xsl:template match="@initial"> + <xsl:text>[*] --> </xsl:text> + <xsl:call-template name="gettargetname"> + <xsl:with-param name="id" select="."/> + </xsl:call-template> + <xsl:text>
</xsl:text> + </xsl:template> + + <xsl:template match="sc:initial"> + <xsl:apply-templates select="*"/> + </xsl:template> + + <xsl:template match="sc:state"> + <xsl:text>state </xsl:text> + <xsl:apply-templates select="." mode="id"/> + <xsl:text> {
</xsl:text> + + <xsl:apply-templates select="@initial"/> + <xsl:apply-templates select="*"/> + + <xsl:text>}
</xsl:text> + </xsl:template> + + <xsl:template match="sc:history"> + <xsl:text>state </xsl:text> + <xsl:apply-templates select="." mode="id"/> + <xsl:text> {
</xsl:text> + + <xsl:apply-templates select="*"/> + + <xsl:apply-templates select="." mode="id"/> + <xsl:value-of select="concat(' : <<', @type, ' history>>
')"/> + + <xsl:text>}
</xsl:text> + </xsl:template> + + <xsl:template match="sc:parallel"> + <xsl:text>state </xsl:text> + <xsl:apply-templates select="." mode="id"/> + <xsl:text> {
</xsl:text> + + <xsl:for-each select="sc:state | sc:parallel | sc:history"> + <xsl:apply-templates select="."/> + <xsl:if test="position() != last()"> + <xsl:text>||
</xsl:text> + </xsl:if> + </xsl:for-each> + + <xsl:apply-templates select="sc:transition"/> + + <xsl:text>}
</xsl:text> + </xsl:template> + + + <!--get id of the state - special case for initial state--> + <xsl:template match="sc:state[@id] | sc:history[@id] | sc:parallel[@id]" mode="id"> + <xsl:value-of select="@id"/> + </xsl:template> + <xsl:template match="sc:state | sc:history | sc:parallel" mode="id"> + <xsl:text>unnamed</xsl:text> + </xsl:template> + <xsl:template match="sc:initial | sc:final" mode="id"> + <xsl:text>[*]</xsl:text> + </xsl:template> + + <xsl:template name="gettargetname"> + <xsl:param name="id"/> + <xsl:apply-templates select="//*[@id = $id][1]" mode="id"/> + </xsl:template> + + <!--target can be specified explicitely as some other state--> + <xsl:template match="sc:transition[@target]" mode="target"> + <xsl:call-template name="gettargetname"> + <xsl:with-param name="id" select="@target"/> + </xsl:call-template> + </xsl:template> + <!--or self-transiton when @target not specified--> + <xsl:template match="sc:transition" mode="target"> + <xsl:apply-templates select=".." mode="id"/> + </xsl:template> + + <!--if 'cond' attribute exists it shall be sourrounded with brackets--> + <xsl:template match="sc:transition/@cond"> + <xsl:value-of select="concat('[', ., ']')"/> + </xsl:template> + + <xsl:template match="sc:transition"> + <xsl:apply-templates select=".." mode="id"/> + <xsl:text> --> </xsl:text> + <xsl:apply-templates select="." mode="target"/> + <xsl:if test="@event or @cond"> + <xsl:text> : </xsl:text> + </xsl:if> + <xsl:value-of select="@event"/> + <xsl:apply-templates select="@cond"/> + <xsl:text>
</xsl:text> + </xsl:template> + +</xsl:stylesheet> diff --git a/src/shared/drivers/Xbee/Xbee.h b/src/shared/drivers/Xbee/Xbee.h index ea5625585ead196ab292591194e8f5e2942fcf47..cea5d667c63934b656b2da8f9647a8c34bb1c593 100644 --- a/src/shared/drivers/Xbee/Xbee.h +++ b/src/shared/drivers/Xbee/Xbee.h @@ -117,7 +117,7 @@ class Xbee : public Transceiver, public ActiveObject public: Xbee(SPIBusInterface& bus, GpioPin cs, GpioPin attn, GpioPin rst, unsigned int send_timeout = 1000) - : send_timeout(send_timeout), spi_xbee(bus, cs), attn(attn), rst(rst) + : send_timeout(send_timeout), spi_xbee(bus, cs, {}), attn(attn), rst(rst) { spi_xbee.config.clock_div = SPIClockDivider::DIV128; diff --git a/src/shared/drivers/spi/MockSPIBus.h b/src/shared/drivers/spi/MockSPIBus.h index 5bbcb07737e5ea0b15cd99d06ecf0c4b528a2f40..d3436ffe53216251065910730c580914af6e49f8 100644 --- a/src/shared/drivers/spi/MockSPIBus.h +++ b/src/shared/drivers/spi/MockSPIBus.h @@ -26,7 +26,7 @@ #include <cstdint> #include <vector> -#include "SPIInterface.h" +#include "SPIBusInterface.h" using std::vector; diff --git a/src/shared/drivers/spi/SPIBus.h b/src/shared/drivers/spi/SPIBus.h index eb02b313e4aa7fb938287342ecc0d12f2e39085b..e31c4232974fd91442c5181a45023e5bcfea18d0 100644 --- a/src/shared/drivers/spi/SPIBus.h +++ b/src/shared/drivers/spi/SPIBus.h @@ -21,7 +21,7 @@ * THE SOFTWARE. */ -#include "SPIInterface.h" +#include "SPIBusInterface.h" #pragma once @@ -48,17 +48,11 @@ public: SPIBus& operator=(SPIBus&&) = delete; /** - * @brief Wether to apply slave-specific bus configuration before each - * transaction (BusTemplate compatibility mode). - * Only set to false to use SPIDriver alongside BusTemplate.h. - * Default value is true. - * - * @param value True: The slave configuration is applied to the SPI - * peripheral before each transaction. False: No configuration is ever - * applied to the SPI peripheral. The SPI peripheral retains the - * configuration set by BusTemplate.h + * @brief Disable bus configuration: calls to configure() will have no + * effect after calling this & the SPI peripheral will need to be configured + * manually. */ - void enableSlaveConfiguration(bool value) { config_enabled = value; } + void disableBusConfiguration() { config_enabled = false; } /** * @brief See SPIBusInterface::write() @@ -105,7 +99,7 @@ public: */ void configure(SPIBusConfig config) override; -private: +protected: /** * Writes a single byte on the SPI bus. * @@ -130,7 +124,7 @@ private: SPI_TypeDef* spi; - SPIBusConfig config; + SPIBusConfig config{}; bool config_enabled = true; bool first_config_applied = false; }; @@ -141,7 +135,7 @@ inline void SPIBus::write(uint8_t data) { write(&data); } inline void SPIBus::write(uint8_t* data, size_t size) { - for (size_t i = 0; i < size; i++) + for (size_t i = 0; i < size; ++i) { write(data + i); } @@ -157,7 +151,7 @@ inline uint8_t SPIBus::read() inline void SPIBus::read(uint8_t* data, size_t size) { - for (size_t i = 0; i < size; i++) + for (size_t i = 0; i < size; ++i) { read(data + i); } @@ -171,7 +165,7 @@ inline uint8_t SPIBus::transfer(uint8_t data) inline void SPIBus::transfer(uint8_t* data, size_t size) { - for (size_t i = 0; i < size; i++) + for (size_t i = 0; i < size; ++i) { transfer(data + i); } @@ -232,7 +226,7 @@ inline void SPIBus::read(uint8_t* byte) // Wait until the peripheral is ready to transmit while ((spi->SR & SPI_SR_TXE) == 0) ; - // Write the byte in the transmit buffer + // Write 0 in the transmit buffer spi->DR = 0; // Wait until byte is transmitted diff --git a/src/shared/drivers/spi/SPIInterface.h b/src/shared/drivers/spi/SPIBusInterface.h similarity index 98% rename from src/shared/drivers/spi/SPIInterface.h rename to src/shared/drivers/spi/SPIBusInterface.h index 7a3eaa1fd3497e99dc517492833fe82d69badd81..9af7e336a23e77f59faf3d23144f216a65e3d3ea 100644 --- a/src/shared/drivers/spi/SPIInterface.h +++ b/src/shared/drivers/spi/SPIBusInterface.h @@ -31,6 +31,8 @@ using miosix::delayUs; using miosix::GpioPin; +class SPITransaction; + /** * @brief SPI Clock divider. * SPI clock frequency will be equal to the SPI peripheral bus clock speed (see @@ -116,6 +118,7 @@ struct SPIBusConfig */ class SPIBusInterface { + friend class SPITransaction; public: SPIBusInterface() {} @@ -198,6 +201,9 @@ public: * @return */ virtual void configure(SPIBusConfig config) = 0; + +private: + bool locked = false; // For use by SPITransaction }; /** @@ -211,8 +217,6 @@ struct SPISlave ///> with the slave. GpioPin cs; ///> Chip select pin - SPISlave(SPIBusInterface& bus, GpioPin cs) : bus(bus), cs(cs) {} - SPISlave(SPIBusInterface& bus, GpioPin cs, SPIBusConfig config) : bus(bus), config(config), cs(cs) { diff --git a/src/shared/drivers/spi/SPIDriver.h b/src/shared/drivers/spi/SPIDriver.h index c90ba4743742cfef611f55a0217c44fcd81d46ed..171d35b8263da201a6d00deb1b79a285e24204f6 100644 --- a/src/shared/drivers/spi/SPIDriver.h +++ b/src/shared/drivers/spi/SPIDriver.h @@ -23,6 +23,6 @@ #pragma once -#include "SPIInterface.h" +#include "SPIBusInterface.h" #include "SPITransaction.h" #include "SPIBus.h" \ No newline at end of file diff --git a/src/shared/drivers/spi/SPITransaction.cpp b/src/shared/drivers/spi/SPITransaction.cpp index a6f026c6b821325aa8e4e836cbd8fbdb924aa4b3..de43334f0cb5770f0fdc6537748929f491e8f27f 100644 --- a/src/shared/drivers/spi/SPITransaction.cpp +++ b/src/shared/drivers/spi/SPITransaction.cpp @@ -23,37 +23,49 @@ #include "SPITransaction.h" +#include <cassert> + +SPITransaction::SPITransaction(SPISlave slave) + : SPITransaction(slave.bus, slave.cs, slave.config) +{ +} + SPITransaction::SPITransaction(SPIBusInterface& bus, GpioPin cs, SPIBusConfig config) : bus(bus), cs(cs) { + // Only one SPITransaction may be active at any given time. + // Do not store an instance of SPITransaction for a long time! Create one, + // use it, and destroy it as soon as you are done operating on the bus! + // (just like mutexes) +#ifdef DEBUG + assert(bus.locked == false); +#endif + bus.locked = true; bus.configure(config); } -SPITransaction::SPITransaction(SPISlave slave) - : SPITransaction(slave.bus, slave.cs, slave.config) -{ -} +SPITransaction::~SPITransaction() { bus.locked = false; } void SPITransaction::write(uint8_t cmd) { bus.select(cs); - bus.write(&cmd, 1); + bus.write(cmd); bus.deselect(cs); } void SPITransaction::write(uint8_t reg, uint8_t val) { bus.select(cs); - bus.write(®, 1); - bus.write(&val, 1); + bus.write(reg); + bus.write(val); bus.deselect(cs); } void SPITransaction::write(uint8_t reg, uint8_t* data, size_t size) { bus.select(cs); - bus.write(®, 1); + bus.write(reg); bus.write(data, size); bus.deselect(cs); } @@ -75,11 +87,13 @@ void SPITransaction::transfer(uint8_t* data, size_t size) uint8_t SPITransaction::read(uint8_t reg, bool set_read_bit) { if (set_read_bit) + { reg = reg | 0x80; + } bus.select(cs); - bus.write(®, 1); - bus.read(®, 1); + bus.write(reg); + reg = bus.read(); bus.deselect(cs); return reg; } @@ -88,10 +102,12 @@ void SPITransaction::read(uint8_t reg, uint8_t* data, size_t size, bool set_read_bit) { if (set_read_bit) + { reg = reg | 0x80; + } bus.select(cs); - bus.write(®, 1); + bus.write(reg); bus.read(data, size); bus.deselect(cs); } diff --git a/src/shared/drivers/spi/SPITransaction.h b/src/shared/drivers/spi/SPITransaction.h index 2aed6c404cdbae94736c72ed2e86c9ff94fed219..b75c20d4ab86f2fdc8e57f8f08e6ba6a7e6ee038 100644 --- a/src/shared/drivers/spi/SPITransaction.h +++ b/src/shared/drivers/spi/SPITransaction.h @@ -1,19 +1,19 @@ /** - * - * + * + * * Copyright (c) 2020 Skyward Experimental Rocketry * Authors: Luca Erbetta (luca.erbetta@skywarder.eu) - * + * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal * in the Software without restriction, including without limitation the rights * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell * copies of the Software, and to permit persons to whom the Software is * furnished to do so, subject to the following conditions: - * + * * The above copyright notice and this permission notice shall be included in * all copies or substantial portions of the Software. - * + * * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE @@ -25,7 +25,7 @@ #pragma once -#include "SPIInterface.h" +#include "SPIBusInterface.h" /** * @brief Provides high-level access to the SPI Bus for a single transaction. @@ -41,14 +41,15 @@ * { * // Transaction begin: * SPITransaction spi(bus, cs, config); // Configures the bus with the - * // provided parameters + * // provided parameters. * * spi.write(REG_EX, 0x56); // writes data to REG_EX * uint8_t reg2 = spi.read(REG_EX_2); // reads from REG_EX_2 * * // ...As many read/writes as you wish... * - * // transaction end. SPITransaction object is destructed + * // transaction end. SPITransaction object is destructed and the bus is + * // freed for use by someone else * } */ class SPITransaction @@ -72,6 +73,8 @@ public: */ SPITransaction(SPIBusInterface& bus, GpioPin cs, SPIBusConfig config); + ~SPITransaction(); + // Delete copy/move contructors/operators SPITransaction(const SPITransaction&) = delete; SPITransaction& operator=(const SPITransaction&) = delete; diff --git a/src/shared/sensors/LIS3DSH/LIS3DSH.h b/src/shared/sensors/LIS3DSH/LIS3DSH.h new file mode 100644 index 0000000000000000000000000000000000000000..78d5094e8c6a89de8023e165675dff96114227e1 --- /dev/null +++ b/src/shared/sensors/LIS3DSH/LIS3DSH.h @@ -0,0 +1,458 @@ +/* Copyright (c) 2020 Skyward Experimental Rocketry + * Authors: Luca Conterio + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#pragma once + +#include "sensors/Sensor.h" +#include "drivers/spi/SPIDriver.h" + +/** + * Driver for stm32f407vg discovery on-board 3-axis + * accelerometer + temperature sensor. + * + * The sensor is connected to SPI1 using the + * following GPIOs: PA5 : clock + * PA6 : miso + * PA7 : mosi + * PE3 : chip select +*/ +class LIS3DSH: public AccelSensor, public TemperatureSensor +{ + public: + + /** + * @brief Constructor. + * + * @param bus the spi bus. + * @param chip_select the chip_select for the sensor. + * @param _odr output data rate for the accelerometer. + * Default value is 100 Hz. + * @param _bdu BDU value, continuous or non-continuous update mode. + * Default value is to update after data has been read (BDU=1). + * @param _full_scale full scale range (from +/-2g up to +/-16g). + * Default value is +/-2g. + */ + LIS3DSH(SPIBusInterface& bus, + GpioPin chip_select, + uint8_t _odr=ODR_100_HZ, + uint8_t _bdu=UPDATE_AFTER_READ_MODE, + uint8_t _full_scale=FULL_SCALE_2G): + spi_slave(bus, chip_select, {}), odr(_odr), bdu(_bdu), full_scale(_full_scale) + { + spi_slave.config.clock_div = SPIClockDivider::DIV64; // used to set the spi baud rate (maximum is 10 Mhz) + } + + /** + * @brief Constructor. + * + * @param bus the spi bus. + * @param chip_select the chip_select for the sensor. + * @param config the spi bus configurations. + * @param _odr output data rate for the accelerometer. + * Default value is 100 Hz. + * @param _bdu BDU value, continuous or non-continuous update mode. + * Default value is to update after data has been read (BDU=1). + * @param _full_scale full scale range (from +/-2g up to +/-16g). + * Default value is +/-2g. + */ + LIS3DSH(SPIBusInterface& bus, + GpioPin chip_select, + SPIBusConfig config, + uint8_t _odr=ODR_100_HZ, + uint8_t _bdu=UPDATE_AFTER_READ_MODE, + uint8_t _full_scale=FULL_SCALE_2G): + spi_slave(bus, chip_select, config), odr(_odr), bdu(_bdu), full_scale(_full_scale) {} + + /** + * @brief Initialize the sensor. + * + * @return boolean value indicating whether the operation succeded or not + */ + bool init() override { + // check if the sensor is already initialized + if (initialized) { + TRACE("[LIS3DSH] init() : already initialized \n"); + return false; + } + + // check if the sensor is working properly + if (!checkWhoAmI()) { // whoami default value + return false; // sensor correctly initialized + } + + SPITransaction spi(spi_slave); + + // set the full scale value in CTRL_REG5 + uint8_t ctrl_reg5_value = (full_scale << 3); + spi.write(CTRL_REG5, ctrl_reg5_value); + + // select the correct sensitivity + // for the specified full scale range + sensitivity = select_sensitivity(); + + // set the output data rate and the BDU in CTRL_REG4 + // the three least significant bits are enable bits for X, Y and Z axis + uint8_t ctrl_reg4_value = (odr << 4) | (bdu << 3) | (7 << 0); // 7 = 111 -> enable the 3 axis + spi.write(CTRL_REG4, ctrl_reg4_value); + + TRACE("[LIS3DSH] init() : ok \n"); + + initialized = true; + + return true; + } + + /** + * @brief Read new data from the accelerometer. + * Acceleretions are returned in mg. + * + * @return boolean value indicating whether the operation succeded or not + */ + bool onSimpleUpdate() override { + // check if the sensor is initialized + if (!initialized) { + TRACE("[LIS3DSH] onSimpleUpdate() : not initialized, unable to sample data \n"); + return false; + } + return readAccelData(); + } + + /** + * @brief Read temperature data. + * The temperature returned by the sensor is an 8-bits integer. + * + * @return boolean value indicating whether the operation succeded or not + */ + bool updateTemperature() { + // check if the sensor is initialized + if (!initialized) { + TRACE("[LIS3DSH] updateTemperature() : not initialized, unable to sample data \n"); + return false; + } + + SPITransaction spi(spi_slave); + + // NOTE: the temperature is given as a 8-bits integer (in 2-complement) + // while the TemperatureSensor interface returns a float value + // through the method tempDataPtr() + mLastTemp = spi.read(OUT_T) + TEMPERATURE_REF; // add the 'zero' of the temperature sensor + + return true; + } + + /** + * @brief Check if the sensor is working. + * + * @return boolean indicating whether the sensor is correctly working or not + */ + bool selfTest() override { + // check if the sensor is initialized + if (!initialized) { + TRACE("[LIS3DSH] selfTest() : not initialized, unable to self-test \n"); + return false; + } + + SPITransaction spi(spi_slave); + + const uint8_t num_samples = 5; // number of samples to be used + // vectors for storing samples, both + // in self-test and no-self-test modes + float X_ST[] = {0, 0, 0, 0, 0}; + float Y_ST[] = {0, 0, 0, 0, 0}; + float Z_ST[] = {0, 0, 0, 0, 0}; + float X_NO_ST[] = {0, 0, 0, 0, 0}; + float Y_NO_ST[] = {0, 0, 0, 0, 0}; + float Z_NO_ST[] = {0, 0, 0, 0, 0}; + // vectors containing avg values for each axis + float AVG_ST[] = {0, 0, 0}; // one element per axis + float AVG_NO_ST[] = {0, 0, 0}; // one element per axis + + // set full scale to default value +/-2g + // enable the self-test mode with positive sign + uint8_t ctrl_reg5_value = (FULL_SCALE_2G << 3) | (1 << 1); + spi.write(CTRL_REG5, ctrl_reg5_value); + // read samples in self-test positive sign mode + for (int i = 0; i < num_samples; i++) { + readAccelData(); + X_ST[i] = mLastAccel.getX(); + Y_ST[i] = mLastAccel.getY(); + Z_ST[i] = mLastAccel.getZ(); + miosix::Thread::sleep(10); + } + // reset the self-test bits + ctrl_reg5_value &= ~(3 << 1); + // normal mode with full scale range +/-2g + ctrl_reg5_value |= (FULL_SCALE_2G << 3); + spi.write(CTRL_REG5, ctrl_reg5_value); + // read samples in normal mode + for (int i = 0; i < num_samples; i++) { + readAccelData(); + X_NO_ST[i] = mLastAccel.getX(); + Y_NO_ST[i] = mLastAccel.getY(); + Z_NO_ST[i] = mLastAccel.getZ(); + miosix::Thread::sleep(10); + } + // compute averages vectors: + // they contain one element for each axis + // (position 0 for x, 1 for y and 2 for z) + // AVG_ST : for self-test samples + // AVG_NO_ST : for normal mode samples + for (int i = 0; i < num_samples; i++) { + AVG_ST[0] += X_ST[i]; + AVG_ST[1] += Y_ST[i]; + AVG_ST[2] += Z_ST[i]; + AVG_NO_ST[0] += X_NO_ST[i]; + AVG_NO_ST[1] += Y_NO_ST[i]; + AVG_NO_ST[2] += Z_NO_ST[i]; + } + for (int i = 0; i < 3; i++) { + AVG_ST[i] /= num_samples; + AVG_NO_ST[i] /= num_samples; + } + + // Reset registers values with the ones + // specified in the constructor: + // set the full scale value in CTRL_REG5 + ctrl_reg5_value = (full_scale << 3); // normal mode + spi.write(CTRL_REG5, ctrl_reg5_value); + + // check that the averages differences + // do not exceed maximum tolerance + if ((AVG_NO_ST[0] - AVG_ST[0] > SELF_TEST_TOLERANCE_X_Y) || + (AVG_NO_ST[1] - AVG_ST[1] > SELF_TEST_TOLERANCE_X_Y) || + (AVG_NO_ST[2] - AVG_ST[2] > SELF_TEST_TOLERANCE_Z)) { + TRACE("[LIS3DSH] selfTest() : failed \n"); + return false; + } + TRACE("[LIS3DSH] selfTest() : ok \n"); + return true; + } + + /** + * @brief Output data rate allowed values (4 bits). + */ + enum ODR { + ODR_POWER_DOWN = 0, // 0000 + ODR_3_125_HZ = 1, // 0001, 3.125 Hz + ODR_6_25_HZ = 2, // 0010, 6.25 Hz + ODR_12_5_HZ = 3, // 0011, 12.5 Hz + ODR_25_HZ = 4, // 0100 + ODR_50_HZ = 5, // 0101 + ODR_100_HZ = 6, // 0110, default value + ODR_400_HZ = 7, // 0111 + ODR_800_HZ = 8, // 1000 + ODR_1600_HZ = 9 // 1001 + }; + + /** + * @brief Full scale range allowed values (3 bits). + */ + enum FULL_SCALE { + FULL_SCALE_2G = 0, // 000, +/- 2g + FULL_SCALE_4G = 1, // 001, +/- 4g + FULL_SCALE_6G = 2, // 010, +/- 6g + FULL_SCALE_8G = 3, // 011, +/- 8g + FULL_SCALE_16G = 4, // 100 +/- 16g + }; + + /** + * @brief Block data update allowed modes (1 bit). + */ + enum BDU { + CONTINUOUS_UPDATE_MODE = 0, // continuous update of accelerometer data + UPDATE_AFTER_READ_MODE = 1 // values updated only when MSB and LSB are read (recommended) + }; + + private: + + /** + * @brief Read data from the accelerometer. + * + * @return whether the operation succeded or not + */ + bool readAccelData() { + SPITransaction spi(spi_slave); + + // read the sensor's status register + uint8_t status = spi.read(STATUS); + + if (status & 0x08) { // bit 3 of status set to 1 (new data available) + if (status & 0x80) { // bit 7 of status set to 1 (some data overwritten) + + // read acceleration on X + int8_t acc_L = spi.read(OUT_X_L); + int8_t acc_H = spi.read(OUT_X_H); + int16_t acceleration = combine(acc_H, acc_L) * sensitivity; + mLastAccel.setX(acceleration); + + // read acceleration on Y + acc_L = spi.read(OUT_Y_L); + acc_H = spi.read(OUT_Y_H); + acceleration = combine(acc_H, acc_L) * sensitivity; + mLastAccel.setY(acceleration); + + // read acceleration on Z + acc_L = spi.read(OUT_Z_L); + acc_H = spi.read(OUT_Z_H); + acceleration = combine(acc_H, acc_L) * sensitivity; + mLastAccel.setZ(acceleration); + + return true; + } + } + + return false; + } + + /** + * @brief Check that the WHO_AM_I register + * contains the correct value. + * + * @return boolean value indicating whether the value read + * from the WHO_AM_I register is correct or not + */ + bool checkWhoAmI() { + SPITransaction spi(spi_slave); + + // check the WHO_AM_I_REG register + uint8_t who_am_i_value = spi.read(WHO_AM_I_REG); + if (who_am_i_value == WHO_AM_I_DEFAULT_VALUE) { // whoami default value + TRACE("[LIS3DSH] WHO_AM_I : ok \n"); + return true; + } + else { + TRACE("[LIS3DSH] WHO_AM_I : wrong value, %d instead of %d \n", + who_am_i_value, WHO_AM_I_DEFAULT_VALUE); + last_error = ERR_NOT_ME; + } + + return false; + } + + /** + * @brief Combine low and high bits in a single number. + * + * @param msb the most significatn bits + * @param lsb the least significant bits + * @return MSB and LSB combined in one value + */ + int16_t combine(uint8_t msb, uint8_t lsb) { + return (msb << 8) | lsb; + } + + /** + * @brief Given the requested full scale range, select the correct sensitivity value. + * + * @return the sensitivity value corresponding to the requested full scale range + */ + float select_sensitivity() { + float s; + switch (full_scale) { + case FULL_SCALE_2G: + s = sensitivity_values._2G; + break; + case FULL_SCALE_4G: + s = sensitivity_values._4G; + break; + case FULL_SCALE_6G: + s = sensitivity_values._6G; + break; + case FULL_SCALE_8G: + s = sensitivity_values._8G; + break; + case FULL_SCALE_16G: + s = sensitivity_values._16G; + break; + default: + TRACE("[LIS3DSH] Invalid full scale range given, using +/-2g \n"); + this->full_scale = FULL_SCALE_2G; + s = sensitivity_values._2G; + break; + } + return s; + } + + /** + * @brief Registers' addresses definition. + */ + enum REG { + + // whoami register + WHO_AM_I_REG = 0x0F, + + // control registers for the accelerometer + CTRL_REG4 = 0x20, // control register to set accelerometer's ODR and BDU + CTRL_REG1 = 0x21, // state Machine 1 interrupt configuration register + CTRL_REG2 = 0x22, // state Machine 2 interrupt configuration register + CTRL_REG3 = 0x23, + CTRL_REG5 = 0x24, // control register to set the accelerometer full scale range, + // anti-aliansing filter and self-test enable + CTRL_REG6 = 0x25, + + // status register + STATUS = 0x27, + + // accelerometer output registers + // for x, y and z axis + // (low and high bits in separate registers) + OUT_X_L = 0x28, + OUT_X_H = 0x29, + OUT_Y_L = 0x2A, + OUT_Y_H = 0x2B, + OUT_Z_L = 0x2C, + OUT_Z_H = 0x2D, + + // temperature output register + OUT_T = 0x0C, + }; + + /** + * @brief Definition of each sensitivity value, + * corresponding to full scale range allowed values. + */ + struct SENSITIVITY { + const float _2G = 0.06; // +/- 2g + const float _4G = 0.12; // +/- 4g + const float _6G = 0.18; // +/- 6g + const float _8G = 0.24; // +/- 8g + const float _16G = 0.73; // +/- 16g + }; + SENSITIVITY sensitivity_values; + + SPISlave spi_slave; + + bool initialized = false; // whether the sensor has been initialized or not + + uint8_t odr; // output data rate, default 100 Hz + uint8_t bdu; // continuous mode or not, default is 0 (continuous update) + uint8_t full_scale; // full scale range value (default +/-2g) + + float sensitivity = sensitivity_values._2G; // default sensitivity value + + uint8_t WHO_AM_I_DEFAULT_VALUE = 63; // 00111111 + + uint8_t TEMPERATURE_REF = 25; // temperature sensor 'zero'/reference value + // (value 0x00 from the sensor corresponds to 25 degrees celsius) + + uint16_t SELF_TEST_TOLERANCE_X_Y = 140; // 140 mg + uint16_t SELF_TEST_TOLERANCE_Z = 590; // 590 mg +}; diff --git a/scripts/old/excel_eventgen/Topics.h.template b/src/shared/sensors/LIS3DSH/LIS3DSHData.h similarity index 54% rename from scripts/old/excel_eventgen/Topics.h.template rename to src/shared/sensors/LIS3DSH/LIS3DSHData.h index 43e72f7302673cf61bbb3a6605681feb08cf7236..b9d834d5ea7a8ddb8fe45ad5ff4d313022060901 100644 --- a/scripts/old/excel_eventgen/Topics.h.template +++ b/src/shared/sensors/LIS3DSH/LIS3DSHData.h @@ -1,5 +1,5 @@ -/* Copyright (c) 2018 Skyward Experimental Rocketry - * Authors: Luca Erbetta +/* Copyright (c) 2020 Skyward Experimental Rocketry + * Authors: Luca Conterio * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal @@ -20,42 +20,25 @@ * THE SOFTWARE. */ -/* - ****************************************************************************** - * THIS FILE IS AUTOGENERATED. DO NOT EDIT. * - ****************************************************************************** - */ - -// Generated from: {sheet_link} -// Autogen date: {date} - -#ifndef SRC_SHARED_BOARDS_HOMEONE_TOPICS_H -#define SRC_SHARED_BOARDS_HOMEONE_TOPICS_H - -#include <stdint.h> -#include <string> +#pragma once -using std::map; -using std::string; +#include <ostream> +#include "math/Vec3.h" -namespace HomeoneBoard -{{ -/** - * Definition of various event topics to use in the EventBroker - */ -enum Topics : uint8_t -{{ -{enum_data} -}}; - -/** - * @brief Returns the name of the provided event - * - * @param event - * @return string - */ -string getTopicString(uint8_t topic); +struct LIS3DSHData +{ + long long timestamp; + Vec3 accel; + int8_t temperature; -}} // namespace HomeoneBoard + static std::string header() + { + return "timestamp,acc_x,acc_y,acc_z,temperature\n"; + } -#endif /* SRC_SHARED_BOARDS_HOMEONE_TOPICS_H_ */ + void print(std::ostream& os) const + { + os << timestamp << "," << accel.getX() << "," << accel.getY() << "," + << accel.getZ() << temperature << "\n"; + } +}; diff --git a/src/shared/sensors/LSM9DS1/LSM9DS1_AxelGyro.h b/src/shared/sensors/LSM9DS1/LSM9DS1_AxelGyro.h index d0b1d3416f989db4b4d5b8fb905ae9b1ea0031de..6d9f6b947412774a1cef8bfeebb7623421b2e6c1 100644 --- a/src/shared/sensors/LSM9DS1/LSM9DS1_AxelGyro.h +++ b/src/shared/sensors/LSM9DS1/LSM9DS1_AxelGyro.h @@ -32,6 +32,14 @@ using miosix::GpioPin; using std::array; +// data Structs +struct lsm9ds1XLGSample +{ + uint64_t timestamp; + Vec3 axelData; + Vec3 gyroData; +}; + class LSM9DS1_XLG : public GyroSensor, public AccelSensor, public TemperatureSensor @@ -82,7 +90,7 @@ public: GyroFSR gyroRange = GyroFSR::FS_245, ODR odr = ODR::ODR_15, bool fifo_enabled = false, unsigned int fifo_watermark = 24) : fifo_enabled(fifo_enabled), fifo_watermark(fifo_watermark), - spislave(bus, cs), axelFSR(axelRange), gyroFSR(gyroRange), odr(odr) + spislave(bus, cs, {}), axelFSR(axelRange), gyroFSR(gyroRange), odr(odr) { // SPI config spislave.config.clock_div = SPIClockDivider::DIV64; @@ -177,35 +185,27 @@ public: } // common setup - spi.write(regMapXLG::CTRL_REG8, - CTRL_REG8_VAL); // addr auto-increment while reading/writing + spi.write(regMapXLG::CTRL_REG8, CTRL_REG8_VAL); // addr auto-increment while reading/writing // FIFO setup: FIFO enabled in continous mode, decimation OFF, // temperature on FIFO ON. if (fifo_enabled) { - spi.write(regMapXLG::FIFO_CTRL, - (FIFO_CTRL_VAL | - fifo_watermark)); // FIFO continous mode + fifo - // watermark threshold setup - spi.write(regMapXLG::INT1_CTRL, - INT1_CTRL_VAL); // interrupt on FIFO treshold - spi.write( - regMapXLG::CTRL_REG9, - (CTRL_REG9_VAL | 0x02)); // DRDY_mask_bit OFF, I2C OFF, FIFO ON + + spi.write(regMapXLG::FIFO_CTRL,(FIFO_CTRL_VAL | fifo_watermark)); // FIFO continous mode + fifo watermark threshold setup + spi.write(regMapXLG::INT1_CTRL,INT1_CTRL_VAL); // interrupt on FIFO treshold + spi.write(regMapXLG::CTRL_REG9,(CTRL_REG9_VAL | 0x02)); // DRDY_mask_bit OFF, I2C OFF, FIFO ON } else { - spi.write(regMapXLG::CTRL_REG9, - CTRL_REG9_VAL); // DRDY_mask_bit OFF, I2C OFF, FIFO OFF + spi.write(regMapXLG::CTRL_REG9,CTRL_REG9_VAL); // DRDY_mask_bit OFF, I2C OFF, FIFO OFF } // Axel Setup: ODR, FSR defined by constructor, auto anti-aliasing BW // (max), LPF2/HPF bypassed and disabled, axel output enabled by default // @ startup uint8_t CTRL_REG6_XL_VAL = (int)odr << 5 | (int)axelFSR << 3; - spi.write(regMapXLG::CTRL_REG6_XL, - CTRL_REG6_XL_VAL); // ODR, FSR, auto BW (max) function of ODR + spi.write(regMapXLG::CTRL_REG6_XL, CTRL_REG6_XL_VAL); // ODR, FSR, auto BW (max) function of ODR // Gyro Setup : ODR, FSR defined by constructor, LPF2/HPF bypassed and // disabled, gyro output enabled by default @ startup @@ -215,43 +215,21 @@ public: // sign and orientation Setup <--- BOARD DEPENDENT // Check all the registers have been written correctly - if (spi.read(regMapXLG::CTRL_REG8) != CTRL_REG8_VAL) - { - return false; - } + if (spi.read(regMapXLG::CTRL_REG8) != CTRL_REG8_VAL) { return false; } if (fifo_enabled) - { - if (spi.read(regMapXLG::FIFO_CTRL) != - (FIFO_CTRL_VAL | fifo_watermark)) - { - return false; - } - if (spi.read(regMapXLG::INT1_CTRL) != INT1_CTRL_VAL) - { - return false; - } - if (spi.read(regMapXLG::CTRL_REG9) != (CTRL_REG9_VAL | 0x02)) - { - return false; - } + { + if (spi.read(regMapXLG::FIFO_CTRL) != (FIFO_CTRL_VAL | fifo_watermark)) { return false; } + if (spi.read(regMapXLG::INT1_CTRL) != INT1_CTRL_VAL) { return false; } + if (spi.read(regMapXLG::CTRL_REG9) != (CTRL_REG9_VAL | 0x02)) { return false; } } else { - if (spi.read(regMapXLG::CTRL_REG9) != CTRL_REG9_VAL) - { - return false; - } - } - if (spi.read(regMapXLG::CTRL_REG6_XL) != CTRL_REG6_XL_VAL) - { - return false; - } - if (spi.read(regMapXLG::CTRL_REG1_G) != CTRL_REG1_G_VAL) - { - return false; + if (spi.read(regMapXLG::CTRL_REG9) != CTRL_REG9_VAL) { return false; } } - - discardSamples(); + if (spi.read(regMapXLG::CTRL_REG6_XL) != CTRL_REG6_XL_VAL) { return false; } + if (spi.read(regMapXLG::CTRL_REG1_G) != CTRL_REG1_G_VAL) { return false; } + + discardSamples(spi); //LUCA SCS MERDA (x2) <3 return true; } @@ -289,9 +267,9 @@ public: y_gy * gyroSensitivity / 1000, z_gy * gyroSensitivity / 1000); - mLastTemp = - tempZero + (temp / tempSensistivity); // 25°C + TEMP*S devo - // castare a float "temp"? + mLastTemp = tempZero + + (temp / tempSensistivity); // 25°C + TEMP*S devo + // castare a float "temp"? } else { // if FIFO enabled: do not store temperature, it can be read using @@ -301,10 +279,12 @@ public: { SPITransaction spi(spislave); - spi.read(OUT_X_L_G, buf, - fifo_watermark * 12); // format: - // gxl,gxh,gyl,gyh,gzl,gzh,axl,axh,ayl,ayh,azl,azh - // for each sample + spi.read( + OUT_X_L_G, buf, + fifo_watermark * + 12); // format: + // gxl,gxh,gyl,gyh,gzl,gzh,axl,axh,ayl,ayh,azl,azh + // for each sample } // convert & store for (int i = 0; i < fifo_watermark; i++) @@ -317,12 +297,12 @@ public: int16_t y_xl = buf[i * 12 + 8] | buf[i * 12 + 9] << 8; int16_t z_xl = buf[i * 12 + 10] | buf[i * 12 + 11] << 8; - gyro_fifo[i] = Vec3(x_gy * gyroSensitivity / 1000, - y_gy * gyroSensitivity / 1000, - z_gy * gyroSensitivity / 1000); - axel_fifo[i] = Vec3(x_xl * axelSensitivity / 1000, - y_xl * axelSensitivity / 1000, - z_xl * axelSensitivity / 1000); + fifo[i].gyroData = Vec3(x_gy * gyroSensitivity / 1000, + y_gy * gyroSensitivity / 1000, + z_gy * gyroSensitivity / 1000); + fifo[i].axelData = Vec3(x_xl * axelSensitivity / 1000, + y_xl * axelSensitivity / 1000, + z_xl * axelSensitivity / 1000); } } return true; @@ -350,16 +330,15 @@ public: spi.write(FIFO_CTRL, 0); // Bypass Mode miosix::Thread::sleep(20); // Wait spi.write(FIFO_CTRL, FIFO_CTRL_VAL | fifo_watermark); // re-enable FIFO - discardSamples(); + discardSamples(spi); } - const array<Vec3, 32>& getGyroFIFO() const { return gyro_fifo; } - const array<Vec3, 32>& getAxelFIFO() const { return axel_fifo; } + const array<lsm9ds1XLGSample, 32>& getLsm9ds1FIFO() const { return fifo; } private: bool fifo_enabled; uint8_t fifo_watermark; - array<Vec3, 32> gyro_fifo, axel_fifo; + array<lsm9ds1XLGSample, 32> fifo; SPISlave spislave; @@ -374,7 +353,7 @@ private: float tempSensistivity = 16.0f; static const uint8_t samplesToDiscard = 8; // max possible val - void discardSamples() + void discardSamples(SPITransaction& spi) { //@ startup, some samples have to be discarded (datasheet) @@ -387,7 +366,6 @@ private: { // if FIFO is enabled, read first <samplesToDiscard> samples and // discard them - SPITransaction spi(spislave); for (int i = 0; i < samplesToDiscard; i++) { spi.read(regMapXLG::OUT_X_L_XL, 6); diff --git a/src/shared/sensors/LSM9DS1/LSM9DSI_Magneto.h b/src/shared/sensors/LSM9DS1/LSM9DSI_Magneto.h index 658899900bd8d65693e054661ee0495fd9849f31..be2d6361683e76134c410e6d04c7078ca4cbfb85 100644 --- a/src/shared/sensors/LSM9DS1/LSM9DSI_Magneto.h +++ b/src/shared/sensors/LSM9DS1/LSM9DSI_Magneto.h @@ -71,7 +71,7 @@ class LSM9DS1_M : public CompassSensor GpioPin cs, MagFSR magRange = MagFSR::FS_8, ODR odr = ODR::ODR_0_625 - ): spislave(bus, cs), magFSR(magRange), odr(odr){ + ): spislave(bus, cs, {}), magFSR(magRange), odr(odr){ //SPI config spislave.config.clock_div=SPIClockDivider::DIV64; } diff --git a/src/shared/sensors/SensorManager.cpp b/src/shared/sensors/SensorManager.cpp new file mode 100755 index 0000000000000000000000000000000000000000..3bfcd024fa71da12c024fd20e2cd4549f731a3f8 --- /dev/null +++ b/src/shared/sensors/SensorManager.cpp @@ -0,0 +1,120 @@ +/* Copyright (c) 2020 Skyward Experimental Rocketry + * Authors: Luca Conterio + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include "SensorManager.h" + +SensorManager::SensorManager() { + +} + +SensorManager::~SensorManager() { + +} + +bool SensorManager::start() { + initScheduler(); + return scheduler.start(); +} + +void SensorManager::stop() { + scheduler.stop(); +} + +bool SensorManager::addSensor(Sensor* sensor, + uint32_t freq, + function_t sensor_callback, + SamplerType sampler_type) { + + // avoid adding sensors that fail to be initalized + if (!initSensor(sensor)) { + TRACE("[SM] Failed to initialize sensor \n"); + return false; + } + + TRACE("[SM] Adding sensor with frequency %u Hz \n", freq); + + // check if a sampler with the same frequency and the same type exists + for(auto s : samplers) { + if (freq == s.sampler->getFrequency() && + sampler_type == s.sampler->getType()) { + s.sampler->addSensor(sensor, sensor_callback); + return true; + } + } + + SensorSampler* new_sampler; + + if (sampler_type == SIMPLE_SAMPLER) // assign the correct type and frequency to the sampler + new_sampler = new SimpleSensorSampler(freq, current_id); + else + new_sampler = new DMASensorSampler(freq, current_id); + + current_id++; + + new_sampler->addSensor(sensor, sensor_callback); // add the sensor to the sampler + + /* + * std::bind syntax: + * std::bind(&MyClass::someFunction, &myclass_instance, [someFunction args]) + */ + // function to be periodically called by the scheduler (to sample the sensors) + function_t new_sampler_update_function = std::bind(&SensorSampler::sampleAndCallback, new_sampler); + + samplers.push_back({ + new_sampler, + new_sampler_update_function + }); + + return true; +} + +void SensorManager::addCallback(uint32_t freq, function_t callback, uint8_t id) { + scheduler.add( + callback, + 1000 / freq, + id, + miosix::getTick() + 10 + ); +} + +bool SensorManager::initSensor(Sensor* sensor) { + return sensor->init() && sensor->selfTest(); +} + +void SensorManager::initScheduler() { + uint64_t start_time = miosix::getTick() + 10; + uint32_t period = 0; + // add all the samplers to the scheduler + for(auto& s : samplers) { + period = 1000 / s.sampler->getFrequency(); // in milliseconds + // use the frequency as the ID of the task in the scheduler + scheduler.add(s.sampler_update_function, period, s.sampler->getId(), start_time); + } +} + +vector<SensorManager::Sampler_t>& SensorManager::getSamplers() { + return samplers; +} + +TaskScheduler& SensorManager::getScheduler() { + return scheduler; +} diff --git a/src/shared/sensors/SensorManager.h b/src/shared/sensors/SensorManager.h new file mode 100755 index 0000000000000000000000000000000000000000..2467cc83ffb37e8a413852a50e1b97b69900210c --- /dev/null +++ b/src/shared/sensors/SensorManager.h @@ -0,0 +1,127 @@ +/* Copyright (c) 2020 Skyward Experimental Rocketry + * Authors: Luca Conterio + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#pragma once + +#include <scheduler/TaskScheduler.h> +#include <sensors/SensorSampler.h> + +using std::vector; + +/** + * The SensorManager class manages all the sensors connected to the Board. + * + * Sensors are grouped by "type" (Simple or DMA) and "sample frequency" and + * grouped in various SensorSampler objects. These objects are then added to the + * scheduler that manages the timings for the sampling. + * After a SensorSampler has finished sampling its sensors, it will call a + * callback, where these samples can be processed and dispatched. + */ +class SensorManager +{ +public: + + typedef std::function<void()> function_t; + + /** + * @brief Structure used to keep track of already existing + * SimplerSensorSampler, their frequency and the function + * to be passed to the scheduler. + */ + struct Sampler_t { + SensorSampler* sampler; // the sensor sampler + function_t sampler_update_function; // function periodically called by the scheduler + }; + + SensorManager(); + + ~SensorManager(); + + /** + * @brief Start the sensor manager. + */ + bool start(); + + /** + * @brief Stop the sensor manager. + */ + void stop(); + + /** + * @brief Add a sensor to be sampled with a SensorSampler + * and the corresponding callback to be called at the given frequency. + * + * @param sensor the sensor to be added + * @param freq the frequency at which the sensor must be sampled + * @param callback the function to be called after the sensor has been sampled + * @param sampler_type the type of the sampler, SIMPLE_SAMPLER or DMA_SAMPLER + * @return boolen value indicating whether the operation complete successfully or not + */ + bool addSensor(Sensor* sensor, uint32_t freq, + function_t callback, + SamplerType sampler_type=SIMPLE_SAMPLER); + + /** + * @brief Add a callback to be called at the given frequency. + * + * @param freq the frequency at which the function must be called + * @param callback the function to be called periodically + * @param id the identifier for the task in the scheduler + */ + void addCallback(uint32_t freq, function_t callback, uint8_t id); + + /** + * @return refernece to the samplers vector + */ + vector<Sampler_t>& getSamplers(); + + /** + * @return reference to the sensors sampling task scheduler + */ + TaskScheduler& getScheduler(); + + //SensorManagerStatus getStatus() { return status; } + +private: + /** + * @brief Initialize a sensor and run the self-test. + * + * @param sensor the sensor to be initialized + */ + bool initSensor(Sensor* sensor); + + /** + * @brief Add all the SensorSamplers to the scheduler and begins sampling. + */ + void initScheduler(); + + + TaskScheduler scheduler; + + // vectors containing samplers + vector<Sampler_t> samplers; + + //SensorManagerStatus status; + //SensorStatus sensor_status; + + uint32_t current_id = 0; // incrementally assign IDs to scheduler tasks +}; diff --git a/src/shared/sensors/SensorSampler.cpp b/src/shared/sensors/SensorSampler.cpp new file mode 100644 index 0000000000000000000000000000000000000000..1f8b853e812e1ddafb06d08467017a8e3a8fa2ca --- /dev/null +++ b/src/shared/sensors/SensorSampler.cpp @@ -0,0 +1,92 @@ +/* Copyright (c) 2017-2020 Skyward Experimental Rocketry + * Author: Alain Carlucci, Luca Conterio + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include "SensorSampler.h" + +using namespace std; + +SensorSampler::SensorSampler(SamplerType type, uint32_t freq, uint32_t id) : + type(type), freq(freq), id(id) {} + +void SensorSampler::sampleAndCallback() { + for (auto it = sensors_map.begin(); it != sensors_map.end(); it++) { + sampleSensor(it->first); + it->second(); // callback + } +} + +SamplerType SensorSampler::getType() { + return type; +} + +uint32_t SensorSampler::getId() { + return id; +} + +uint32_t SensorSampler::getFrequency() { + return freq; +} + +uint32_t SensorSampler::getNumSensors() { + return sensors_map.size(); +} + +// simple sampler + +SimpleSensorSampler::SimpleSensorSampler(uint32_t freq, uint32_t id) : + SensorSampler(SIMPLE_SAMPLER, freq, id) {} + +SimpleSensorSampler::~SimpleSensorSampler() {} + +void SimpleSensorSampler::addSensor(Sensor* sensor, function_t sensor_callback) { + sensors_map[sensor] = sensor_callback; +} + +void SimpleSensorSampler::sampleSensor(Sensor* s) { + s->onSimpleUpdate(); +} + +// DMA sampler +DMASensorSampler::DMASensorSampler(uint32_t freq, uint32_t id) : + SensorSampler(DMA_SAMPLER, freq, id) {} + + +DMASensorSampler::~DMASensorSampler() {} + +void DMASensorSampler::addSensor(Sensor* sensor, function_t sensor_callback) { + vector<SPIRequest> requests = sensor->buildDMARequest(); + + sensors_map[sensor] = sensor_callback; + requests_map.insert(pair<Sensor*, vector<SPIRequest>>(sensor, requests)); // can't use standard operator= +} + +void DMASensorSampler::sampleSensor(Sensor* s) { + auto& driver = SPIDriver::instance(); + + vector<SPIRequest> requests = requests_map[s]; + + if (driver.transaction(requests)) { + for (auto r : requests) { + s->onDMAUpdate(r); + } + } +} \ No newline at end of file diff --git a/src/shared/sensors/SensorSampler.h b/src/shared/sensors/SensorSampler.h new file mode 100644 index 0000000000000000000000000000000000000000..1e43f276ce98edb6fa80bc8a62d79dbf01ed70a6 --- /dev/null +++ b/src/shared/sensors/SensorSampler.h @@ -0,0 +1,140 @@ +/* Copyright (c) 2017-2020 Skyward Experimental Rocketry + * Author: Alain Carlucci, Luca Conterio + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ +#ifndef SENSOR_SAMPLING_H +#define SENSOR_SAMPLING_H + +#include <Common.h> +#include "Sensor.h" + +using namespace std; + +/** + * Enum to distinguish the sensor sampler type, + * if it a simple one or if it uses DMA. + */ +enum SamplerType { + SIMPLE_SAMPLER = 0, + DMA_SAMPLER = 1 +}; + + +/** + * Virtual sensor sampler class. + */ +class SensorSampler +{ + public: + + typedef function<void()> function_t; + + /** + * @brief Constructor. + * + * @param type sampler type, SIMPLER_SAMPLER or DMA_SAMPLER + * @param freq frequency at which the sampler performs sensors update + */ + SensorSampler(SamplerType type, uint32_t freq, uint32_t id); + + /** + * @brief Add a sensor to the sensors vector. + * + * @param sensor the sensor to be added + */ + virtual void addSensor(Sensor* sensor, function_t callback) = 0; + + /** + * @brief For each sensor, sample it and call the corresponding callback. + */ + void sampleAndCallback(); + + /** + * @return the sampler's type + */ + SamplerType getType(); + + /** + * @return the sampler's ID + */ + uint32_t getId(); + + /** + * @return the sampler's activation frequency + */ + uint32_t getFrequency(); + + /** + * @return the number of sensors assigned to this sampler + */ + uint32_t getNumSensors(); + + private: + /** + * @brief Perform the update of all the sensors in the sampler. + */ + virtual void sampleSensor(Sensor* s) = 0; + + SamplerType type; // the sampler's type + uint32_t freq; // frequency at which the sampler performs sensors update + uint32_t id; // id used for scheduler task + + protected: + map<Sensor*, function_t> sensors_map; // for each sensor a callback + +}; + + +/** + * @brief Sampler for simple sensors, those that are simply + * sampled by calling the onSimpleUpdate() method. + */ +class SimpleSensorSampler : public SensorSampler + { + public: + SimpleSensorSampler(uint32_t freq, uint32_t id); + + ~SimpleSensorSampler(); + + void addSensor(Sensor* sensor, function_t sensor_callback) override; + + void sampleSensor(Sensor* s) override; +}; + + +/** + * @brief Sampler for sensors that DMA for updates. + */ +class DMASensorSampler : public SensorSampler +{ + public: + DMASensorSampler(uint32_t freq, uint32_t id); + + ~DMASensorSampler(); + + void addSensor(Sensor* sensor, function_t sensor_callback) override; + + void sampleSensor(Sensor* s) override; + + private: + map<Sensor*, vector<SPIRequest>> requests_map; // SPI requests needed to perform DMA updates +}; + +#endif /* ifndef SENSOR_SAMPLING_H */ \ No newline at end of file diff --git a/src/shared/sensors/SensorSampling.h b/src/shared/sensors/SensorSampling.h deleted file mode 100644 index 06bb4b9eae810c7158b9d81da9d4dfbe0eb84398..0000000000000000000000000000000000000000 --- a/src/shared/sensors/SensorSampling.h +++ /dev/null @@ -1,99 +0,0 @@ -/* Copyright (c) 2017 Skyward Experimental Rocketry - * Author: Alain Carlucci - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - */ -#ifndef SENSOR_SAMPLING_H -#define SENSOR_SAMPLING_H - -#include <Common.h> -#include <diagnostic/Log.h> -#include <drivers/spi/SensorSpi.h> - -#include "Sensor.h" - -class DMASensorSampler -{ -public: - DMASensorSampler() {} - ~DMASensorSampler() {} - - void AddSensor(Sensor* sensor) - { - std::vector<SPIRequest> requests = sensor->buildDMARequest(); - for (size_t i = 0; i < requests.size(); i++) - { - mRequests.push_back(requests[i]); - mSensors.push_back(sensor); - } - } - - void Update() - { - TRACE("Update\n"); - auto& driver = SPIDriver::instance(); - bool ret = driver.transaction(mRequests); - - if (ret) - for (size_t i = 0; i < mSensors.size(); i++) - mSensors[i]->onDMAUpdate(mRequests[i]); - - TRACE("Update end\n"); - - } - - void UpdateAndCallback(std::function<void()> onSampleUpdateCallback) - { - Update(); - TRACE("Update callback\n"); - - onSampleUpdateCallback(); - } - -private: - std::vector<Sensor*> mSensors; - std::vector<SPIRequest> mRequests; -}; - -class SimpleSensorSampler -{ -public: - SimpleSensorSampler() {} - ~SimpleSensorSampler() {} - - void AddSensor(Sensor* sensor) { mSensors.push_back(sensor); } - - void Update() - { - for (Sensor* s : mSensors) - s->onSimpleUpdate(); - } - - void UpdateAndCallback(std::function<void()> onSampleUpdateCallback) - { - Update(); - - onSampleUpdateCallback(); - } - -private: - std::vector<Sensor*> mSensors; -}; - -#endif /* ifndef SENSOR_SAMPLING_H */ diff --git a/scripts/old/excel_eventgen/EventFunctions.cpp.template b/src/shared/utils/testutils/TestSensor.h old mode 100644 new mode 100755 similarity index 54% rename from scripts/old/excel_eventgen/EventFunctions.cpp.template rename to src/shared/utils/testutils/TestSensor.h index 18f7690704c127e2bd5eb516097a08868e505565..f424accf60e3f60abde217736ce1598a686f89de --- a/scripts/old/excel_eventgen/EventFunctions.cpp.template +++ b/src/shared/utils/testutils/TestSensor.h @@ -1,4 +1,4 @@ -/* Copyright (c) 2018 Skyward Experimental Rocketry +/* Copyright (c) 2015-2018 Skyward Experimental Rocketry * Authors: Luca Erbetta * * Permission is hereby granted, free of charge, to any person obtaining a copy @@ -19,41 +19,44 @@ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN * THE SOFTWARE. */ - -/* - ****************************************************************************** - * THIS FILE IS AUTOGENERATED. DO NOT EDIT. * - ****************************************************************************** - */ - -// Generated from: {sheet_link} -// Autogen date: {date} - - -#include "Events.h" -#include "Topics.h" - -#include <map> - -namespace HomeoneBoard -{{ - -string getEventString(uint8_t event) -{{ - static const map<uint8_t, string> event_string_map {{ -{event_map_data} - }}; - auto it = event_string_map.find(event); - return it == event_string_map.end() ? "EV_UNKNOWN" : it->second; -}} - -string getTopicString(uint8_t topic) -{{ - static const map<uint8_t, string> topic_string_map{{ -{topic_map_data} - }}; - auto it = topic_string_map.find(topic); - return it == topic_string_map.end() ? "TOPIC_UNKNOWN" : it->second; -}} - -}} \ No newline at end of file +#ifndef SRC_SHARED_BOARDS_HOMEONE_SENSORMANAGER_TESTSENSOR_H +#define SRC_SHARED_BOARDS_HOMEONE_SENSORMANAGER_TESTSENSOR_H + +#include <cmath> +#include "Common.h" +#include "sensors/Sensor.h" + +using miosix::getTick; +using miosix::TICK_FREQ; + +class TestSensor : public virtual Sensor +{ +public: + TestSensor() : mLastSample(0) {} + ~TestSensor() {} + + bool init() override + { + return true; + } + + bool onSimpleUpdate() override + { + // printf("onSimpleUpdate\n"); + mLastSample = 10 * sin(PI * static_cast<float>(getTick()) / + static_cast<float>(TICK_FREQ)); + return true; + } + + bool selfTest() override + { + return true; + } + + float* testDataPtr() { return &mLastSample; } + +private: + float mLastSample; +}; + +#endif /* SRC_SHARED_BOARDS_HOMEONE_SENSORMANAGER_TESTSENSOR_H */ diff --git a/src/tests/catch/spidriver/FakeSPIBus.h b/src/tests/catch/spidriver/FakeSPIBus.h index 94087b088fa4957db9d30b9520a4f3edc7374dde..d1213bfd6e6f9441e453cb84eb68e631572ca863 100644 --- a/src/tests/catch/spidriver/FakeSPIBus.h +++ b/src/tests/catch/spidriver/FakeSPIBus.h @@ -22,7 +22,7 @@ */ #include "FakeSpiTypedef.h" -#include "drivers/spi/SPIInterface.h" +#include "drivers/spi/SPIBusInterface.h" #pragma once @@ -49,18 +49,7 @@ public: FakeSPIBus(FakeSPIBus&&) = delete; FakeSPIBus& operator=(FakeSPIBus&&) = delete; - /** - * @brief Wether to apply slave-specific bus configuration before each - * transaction (BusTemplate compatibility mode). - * Only set to false to use SPIDriver alongside BusTemplate.h. - * Default value is true. - * - * @param value True: The slave configuration is applied to the SPI - * peripheral before each transaction. False: No configuration is ever - * applied to the SPI peripheral. The SPI peripheral retains the - * configuration set by BusTemplate.h - */ - void enableSlaveConfiguration(bool value) { config_enabled = value; } + void disableBusConfiguration() { config_enabled = false; } /** * @brief See SPIBusInterface::write() diff --git a/src/tests/catch/spidriver/test-spidriver.cpp b/src/tests/catch/spidriver/test-spidriver.cpp index 8b2f47f7edea4fedcaeab4c58f4cd9874d97a343..e0facfd1b7da9cce148af88ea0ebe7075d605c3f 100644 --- a/src/tests/catch/spidriver/test-spidriver.cpp +++ b/src/tests/catch/spidriver/test-spidriver.cpp @@ -60,84 +60,82 @@ TEST_CASE("SPIBus - Bus Configuration") SECTION("Mode") { - config.mode = SPIMode::MODE0; - uint32_t expected_CR1 = 0x0344; + config.mode = SPIMode::MODE0; + uint32_t expected_CR1 = 0x0344; bus.configure(config); REQUIRE(spi.CR1 == expected_CR1); - config.mode = SPIMode::MODE1; - expected_CR1 = 0x0345; + config.mode = SPIMode::MODE1; + expected_CR1 = 0x0345; bus.configure(config); REQUIRE(spi.CR1 == expected_CR1); - config.mode = SPIMode::MODE2; - expected_CR1 = 0x0346; + config.mode = SPIMode::MODE2; + expected_CR1 = 0x0346; bus.configure(config); REQUIRE(spi.CR1 == expected_CR1); - config.mode = SPIMode::MODE3; - expected_CR1 = 0x0347; + config.mode = SPIMode::MODE3; + expected_CR1 = 0x0347; bus.configure(config); REQUIRE(spi.CR1 == expected_CR1); - } SECTION("Clock Divider") { - config.clock_div = SPIClockDivider::DIV2; - uint32_t expected_CR1 = 0x0344; + config.clock_div = SPIClockDivider::DIV2; + uint32_t expected_CR1 = 0x0344; bus.configure(config); REQUIRE(spi.CR1 == expected_CR1); config.clock_div = SPIClockDivider::DIV4; - expected_CR1 = 0x034C; + expected_CR1 = 0x034C; bus.configure(config); REQUIRE(spi.CR1 == expected_CR1); config.clock_div = SPIClockDivider::DIV8; - expected_CR1 = 0x0354; + expected_CR1 = 0x0354; bus.configure(config); REQUIRE(spi.CR1 == expected_CR1); config.clock_div = SPIClockDivider::DIV16; - expected_CR1 = 0x035C; + expected_CR1 = 0x035C; bus.configure(config); REQUIRE(spi.CR1 == expected_CR1); config.clock_div = SPIClockDivider::DIV32; - expected_CR1 = 0x0364; + expected_CR1 = 0x0364; bus.configure(config); REQUIRE(spi.CR1 == expected_CR1); - + config.clock_div = SPIClockDivider::DIV64; - expected_CR1 = 0x036C; + expected_CR1 = 0x036C; bus.configure(config); REQUIRE(spi.CR1 == expected_CR1); config.clock_div = SPIClockDivider::DIV128; - expected_CR1 = 0x0374; + expected_CR1 = 0x0374; bus.configure(config); REQUIRE(spi.CR1 == expected_CR1); config.clock_div = SPIClockDivider::DIV256; - expected_CR1 = 0x037C; + expected_CR1 = 0x037C; bus.configure(config); REQUIRE(spi.CR1 == expected_CR1); } SECTION("Bit order") { - config.bit_order = SPIBitOrder::MSB_FIRST; - uint32_t expected_CR1 = 0x0344; + config.bit_order = SPIBitOrder::MSB_FIRST; + uint32_t expected_CR1 = 0x0344; bus.configure(config); REQUIRE(spi.CR1 == expected_CR1); config.bit_order = SPIBitOrder::LSB_FIRST; - expected_CR1 = 0x03C4; + expected_CR1 = 0x03C4; bus.configure(config); REQUIRE(spi.CR1 == expected_CR1); } - } SECTION("Disable configuration") @@ -148,7 +146,7 @@ TEST_CASE("SPIBus - Bus Configuration") config.mode = SPIMode::MODE3; config.bit_order = SPIBitOrder::LSB_FIRST; - bus.enableSlaveConfiguration(false); + bus.disableBusConfiguration(); bus.configure(config); REQUIRE(spi.CR1 == 0); } @@ -224,7 +222,7 @@ TEST_CASE("SPIBus - Multi byte operations") { FakeSpiTypedef spi; - spi.DR.in_buf = {1, 2, 3, 4, 5, 6, 7, 8, 9}; + spi.DR.in_buf = {100, 101, 102, 103, 104, 105, 106, 107, 108}; spi.CR1_expected = 0x03DF; FakeSPIBus bus{&spi}; @@ -239,28 +237,38 @@ TEST_CASE("SPIBus - Multi byte operations") bus.select(spi.cs); // 2 identical buffers - uint8_t buf[] = {4, 3, 2, 1}; - uint8_t bufc[] = {4, 3, 2, 1}; + uint8_t buf[] = {5, 4, 3, 2, 1}; + uint8_t bufc[] = {5, 4, 3, 2, 1}; SECTION("Write") { bus.write(buf, 0); REQUIRE(spi.DR.out_buf.size() == 0); + bus.write(buf, 1); + REQUIRE(spi.DR.out_buf.size() == 1); + REQUIRE(spi.DR.out_buf.back() == bufc[0]); + bus.write(buf, 4); - REQUIRE(spi.DR.out_buf.size() == 4); - REQUIRE(bufcmp(bufc, spi.DR.out_buf.data(), 4)); + REQUIRE(spi.DR.out_buf.size() == 5); + REQUIRE(bufcmp(bufc, spi.DR.out_buf.data() + 1, 4)); } SECTION("Read") { bus.read(buf, 0); // Nothing read - REQUIRE(bufcmp(bufc, buf, 4)); + REQUIRE(bufcmp(bufc, buf, 5)); - bus.read(buf, 4); + bus.read(buf, 1); + REQUIRE(bufcmp(buf, spi.DR.in_buf.data(), 1)); + // No overflows + REQUIRE(bufcmp(bufc + 1, buf + 1, 4)); - REQUIRE(bufcmp(buf, spi.DR.in_buf.data(), 4)); + bus.read(buf, 4); + REQUIRE(bufcmp(buf, spi.DR.in_buf.data() + 1, 4)); + // No overflows + REQUIRE(bufcmp(bufc + 4, buf + 4, 1)); } SECTION("Transfer") @@ -271,11 +279,19 @@ TEST_CASE("SPIBus - Multi byte operations") // Nothing written REQUIRE(spi.DR.out_buf.size() == 0); - bus.transfer(buf, 4); - REQUIRE(spi.DR.out_buf.size() == 4); + bus.transfer(buf, 1); + REQUIRE(spi.DR.out_buf.size() == 1); + REQUIRE(bufcmp(bufc, spi.DR.out_buf.data(), 1)); + REQUIRE(bufcmp(buf, spi.DR.in_buf.data(), 1)); + // No overflows + REQUIRE(bufcmp(bufc + 1, buf + 1, 4)); - REQUIRE(bufcmp(bufc, spi.DR.out_buf.data(), 4)); - REQUIRE(bufcmp(buf, spi.DR.in_buf.data(), 4)); + bus.transfer(buf + 1, 3); + REQUIRE(spi.DR.out_buf.size() == 4); + REQUIRE(bufcmp(bufc + 1, spi.DR.out_buf.data() + 1, 3)); + REQUIRE(bufcmp(buf + 1, spi.DR.in_buf.data() + 1, 3)); + // No overflows + REQUIRE(bufcmp(bufc + 4, buf + 4, 1)); } } @@ -284,8 +300,8 @@ TEST_CASE("SPITransaction - writes") MockSPIBus bus{}; SPIBusConfig config1{}; - config1.mode = SPIMode::MODE1; - config1.clock_div = SPIClockDivider::DIV32; + config1.mode = SPIMode::MODE1; + config1.clock_div = SPIClockDivider::DIV32; bus.expected_config = config1; @@ -376,12 +392,12 @@ TEST_CASE("SPITransaction - reads") { MockSPIBus bus; - bus.in_buf = {1, 2, 3, 4, 5, 6, 7, 8, 9, 10}; + bus.in_buf = {100, 101, 102, 103, 104, 105, 106, 107, 108, 109}; SPIBusConfig config1; - config1.mode = SPIMode::MODE1; - config1.clock_div = SPIClockDivider::DIV32; + config1.mode = SPIMode::MODE1; + config1.clock_div = SPIClockDivider::DIV32; bus.expected_config = config1; @@ -395,19 +411,19 @@ TEST_CASE("SPITransaction - reads") SECTION("1 byte reg read") { - REQUIRE(spi.read(0x05) == 1); + REQUIRE(spi.read(0x05) == bus.in_buf[0]); REQUIRE_FALSE(bus.isSelected()); REQUIRE(bus.out_buf.size() == 1); REQUIRE(bus.out_buf.back() == 0x85); - REQUIRE(spi.read(0x05, true) == 2); + REQUIRE(spi.read(0x05, true) == bus.in_buf[1]); REQUIRE_FALSE(bus.isSelected()); REQUIRE(bus.out_buf.size() == 2); REQUIRE(bus.out_buf.back() == 0x85); - REQUIRE(spi.read(0x05, false) == 3); + REQUIRE(spi.read(0x05, false) == bus.in_buf[2]); REQUIRE_FALSE(bus.isSelected()); REQUIRE(bus.out_buf.size() == 3); @@ -416,48 +432,54 @@ TEST_CASE("SPITransaction - reads") SECTION("multi byte reg read") { - uint8_t read[4] = {0, 0, 0, 0}; - uint8_t zero[4] = {0, 0, 0, 0}; + const int buf_size = 7; + uint8_t buf[] = {1, 2, 3, 4, 5, 6, 7}; + uint8_t cmp[] = {1, 2, 3, 4, 5, 6, 7}; - spi.read(0x05, read, 0); + spi.read(0x05, buf, 0); REQUIRE_FALSE(bus.isSelected()); REQUIRE(bus.out_buf.size() == 1); REQUIRE(bus.out_buf.back() == 0x85); - REQUIRE(bufcmp(read, zero, 4)); + REQUIRE(bufcmp(buf, cmp, buf_size)); - spi.read(0x05, read, 3); + spi.read(0x05, buf, 3); REQUIRE_FALSE(bus.isSelected()); REQUIRE(bus.out_buf.size() == 2); REQUIRE(bus.out_buf.back() == 0x85); - REQUIRE(bufcmp(read, bus.in_buf.data(), 3)); + REQUIRE(bufcmp(buf, bus.in_buf.data(), 3)); + REQUIRE(bufcmp(buf + 3, cmp + 3, buf_size - 3)); - spi.read(0x05, read, 3, true); + spi.read(0x05, buf, 3, true); REQUIRE_FALSE(bus.isSelected()); REQUIRE(bus.out_buf.size() == 3); REQUIRE(bus.out_buf.back() == 0x85); - REQUIRE(bufcmp(read, bus.in_buf.data() + 3, 3)); + REQUIRE(bufcmp(buf, bus.in_buf.data() + 3, 3)); + REQUIRE(bufcmp(buf + 3, cmp + 3, buf_size - 3)); - spi.read(0x05, read, 4, false); + spi.read(0x05, buf, 4, false); REQUIRE_FALSE(bus.isSelected()); REQUIRE(bus.out_buf.size() == 4); REQUIRE(bus.out_buf.back() == 0x05); - REQUIRE(bufcmp(read, bus.in_buf.data() + 6, 4)); + REQUIRE(bufcmp(buf, bus.in_buf.data() + 6, 4)); + REQUIRE(bufcmp(buf + 4, cmp + 4, buf_size - 4)); } SECTION("multi byte raw read") { - uint8_t read[4] = {0, 0, 0, 0}; - uint8_t zero[4] = {0, 0, 0, 0}; + const int buf_size = 7; + uint8_t buf[] = {1, 2, 3, 4, 5, 6, 7}; + uint8_t cmp[] = {1, 2, 3, 4, 5, 6, 7}; - spi.read(read, 0); + spi.read(buf, 0); REQUIRE_FALSE(bus.isSelected()); REQUIRE(bus.out_buf.size() == 0); - REQUIRE(bufcmp(read, zero, 4)); + REQUIRE(bufcmp(buf, cmp, buf_size)); - spi.read(read, 3); + spi.read(buf, 3); REQUIRE_FALSE(bus.isSelected()); REQUIRE(bus.out_buf.size() == 0); - REQUIRE(bufcmp(read, bus.in_buf.data(), 3)); + REQUIRE(bufcmp(buf, bus.in_buf.data(), 3)); + REQUIRE(bufcmp(buf + 3, cmp + 3, buf_size - 3)); } } } @@ -470,8 +492,8 @@ TEST_CASE("SPITransaction - transfer") SPIBusConfig config1; - config1.mode = SPIMode::MODE1; - config1.clock_div = SPIClockDivider::DIV32; + config1.mode = SPIMode::MODE1; + config1.clock_div = SPIClockDivider::DIV32; bus.expected_config = config1; @@ -480,18 +502,20 @@ TEST_CASE("SPITransaction - transfer") SPISlave slave(bus, GpioPin(GPIOA_BASE, 1), config1); SPITransaction spi(slave); - uint8_t buf[4] = {4, 3, 2, 1}; - uint8_t cmp[4] = {4, 3, 2, 1}; + const int buf_size = 7; + uint8_t buf[] = {1, 2, 3, 4, 5, 6, 7}; + uint8_t cmp[] = {1, 2, 3, 4, 5, 6, 7}; spi.transfer(buf, 0); REQUIRE_FALSE(bus.isSelected()); REQUIRE(bus.out_buf.size() == 0); - REQUIRE(bufcmp(buf, cmp, 4)); + REQUIRE(bufcmp(buf, cmp, buf_size)); spi.transfer(buf, 4); REQUIRE_FALSE(bus.isSelected()); REQUIRE(bus.out_buf.size() == 4); REQUIRE(bufcmp(buf, bus.in_buf.data(), 4)); REQUIRE(bufcmp(cmp, bus.out_buf.data(), 4)); + REQUIRE(bufcmp(buf + 4, cmp + 4, buf_size - 4)); } } \ No newline at end of file diff --git a/src/tests/catch/test-sensormanager.cpp b/src/tests/catch/test-sensormanager.cpp new file mode 100755 index 0000000000000000000000000000000000000000..fb4466f907a546cc20ed13f176234c81b1dfd4e1 --- /dev/null +++ b/src/tests/catch/test-sensormanager.cpp @@ -0,0 +1,60 @@ +/* Copyright (c) 2018-2020 Skyward Experimental Rocketry + * Authors: Luca Conterio + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#ifdef STANDALONE_CATCH1_TEST +#include "catch-tests-entry.cpp" +#endif + +#include "utils/testutils/catch.hpp" + +#include "utils/testutils/TestSensor.h" +#include "sensors/SensorManager.h" + +TestSensor* sensor1 = new TestSensor(); +TestSensor* sensor2 = new TestSensor(); +TestSensor* sensor3 = new TestSensor(); + + +TEST_CASE("check that sensors are correctly added to the samplers") { + + SensorManager sensor_manager; + + sensor_manager.addSensor(sensor1, 1, std::bind([&]() {})); // 1 Hz + sensor_manager.addSensor(sensor2, 1, std::bind([&]() {})); // 1 Hz + sensor_manager.addSensor(sensor3, 2, std::bind([&]() {})); // 2 Hz + + // check that 2 samplers exist (1 hz and 2 hz) + REQUIRE(sensor_manager.getSamplers().size() == 2); + + // check that sampler at 1 Hz has 2 sensors, sampler at 2 Hz has 1 sensor + for(auto s : sensor_manager.getSamplers()) { + if (s.sampler->getFrequency() == 1) { + REQUIRE(s.sampler->getNumSensors() == 2); + } + else if (s.sampler->getFrequency() == 2) { + REQUIRE(s.sampler->getNumSensors() == 1); + } + else { + FAIL("Can't exist a sampler with frequency different from 1 or 2 Hz"); // no sampler with a different frequency exist + } + } +} \ No newline at end of file diff --git a/src/tests/drivers/calibrate-mpu9250.cpp b/src/tests/drivers/calibrate-mpu9250.cpp index 54467bace1bc84ba09b93fb321a99e2be543eaea..69076a5c921e2fe28064fd008076ff5f14e52ce4 100644 --- a/src/tests/drivers/calibrate-mpu9250.cpp +++ b/src/tests/drivers/calibrate-mpu9250.cpp @@ -26,29 +26,28 @@ #include <sensors/MPU9250/MPU9250.h> #include <drivers/spi/SensorSpi.h> -#include <sensors/SensorSampling.h> +#include <sensors/SensorSampler.h> using namespace miosix; using namespace miosix::interfaces; typedef BusSPI<1,spi1::mosi,spi1::miso,spi1::sck> busSPI1; typedef ProtocolSPI<busSPI1,sensors::mpu9250::cs> spiMPU9250_a; -typedef MPU9250<spiMPU9250_a> mpu_t; int main() { float bias[3]; - SimpleSensorSampler sampler; + SimpleSensorSampler sampler(250, 1); spiMPU9250_a::init(); - mpu_t* mpu = new mpu_t(1, 1); + MPU9250<spiMPU9250_a>* mpu = new MPU9250<spiMPU9250_a>(1, 1); Thread::sleep(100); if(mpu->init()){ printf("MPU9250 Init succeeded\n" ); - sampler.AddSensor(mpu); + sampler.addSensor(mpu, std::bind([&]() {})); } else { printf("MPU9250 Init failed\n"); @@ -81,7 +80,7 @@ int main() while(true) { - sampler.Update(); + sampler.sampleAndCallback(); const Vec3* last_data = mpu->accelDataPtr(); printf("%f %f %f\n", last_data->getX(), last_data->getY(), diff --git a/src/tests/drivers/test-imu-adis.cpp b/src/tests/drivers/test-imu-adis.cpp index 52889cacb147e4563210b5c3d70aaa5ca3ea970b..8d570150e8ea25609a8c5d0bb22e59b7e6b91317 100644 --- a/src/tests/drivers/test-imu-adis.cpp +++ b/src/tests/drivers/test-imu-adis.cpp @@ -24,7 +24,7 @@ #include <drivers/BusTemplate.h> #include <interfaces-impl/hwmapping.h> #include <sensors/ADIS16405/ADIS16405.h> -#include <sensors/SensorSampling.h> +#include <sensors/SensorSampler.h> #include <math/Stats.h> #include <diagnostic/CpuMeter.h> #include <drivers/spi/SensorSpi.h> @@ -38,31 +38,27 @@ typedef Gpio<GPIOD_BASE, 5> rstPin; // PD5 for the HomeoneBoard // SPI1 binding to the sensor typedef BusSPI<1,spi1::mosi,spi1::miso,spi1::sck> busSPI1; //Create SPI1 typedef ProtocolSPI<busSPI1,miosix::sensors::adis16405::cs> spiADIS16405; //La lego al Chip Select 1 per la IMU 1 -typedef ADIS16405<spiADIS16405,rstPin> adis_t; //Passo il bus creato al sensore int main() { spiADIS16405::init(); Thread::sleep(1000); - adis_t adis(adis_t::GYRO_FS_300); + ADIS16405<spiADIS16405,rstPin>* adis = new ADIS16405<spiADIS16405,rstPin>(adis->GYRO_FS_300); - if(adis.init()) + if(adis->init()) printf("[ADIS16405] Init succeeded\n" ); else printf("[ADIS16405] Init failed\n"); - if(adis.selfTest()) + if(adis->selfTest()) printf("[ADIS16405] Self test succeeded\n" ); else printf("[ADIS16405] Self test failed\n"); - SimpleSensorSampler sampler; - sampler.AddSensor(&adis); - - // DMASensorSampler sampler; - // sampler.AddSensor(&adis); + SimpleSensorSampler sampler(250, 1); + sampler.addSensor(adis, std::bind([&]() {})); StatsResult statResult; Stats stats; @@ -70,7 +66,7 @@ int main() int counter = 0; while(true) { - sampler.Update(); + sampler.sampleAndCallback(); stats.add(averageCpuUtilization()); @@ -79,7 +75,7 @@ int main() printf("CPU usage: %f\n", statResult.mean); counter = 0; - const Vec3* last_data = adis.accelDataPtr(); + const Vec3* last_data = adis->accelDataPtr(); printf("%f %f %f\n", last_data->getX(), last_data->getY(), last_data->getZ()); } diff --git a/src/tests/drivers/test-lis3dsh.cpp b/src/tests/drivers/test-lis3dsh.cpp new file mode 100644 index 0000000000000000000000000000000000000000..79fc511fa17bd7a64f22be5a9b48def0fce47180 --- /dev/null +++ b/src/tests/drivers/test-lis3dsh.cpp @@ -0,0 +1,111 @@ +/* Copyright (c) 2020 Skyward Experimental Rocketry + * Authors: Luca Conterio + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include <miosix.h> +#include <drivers/spi/SPIDriver.h> +#include "sensors/LIS3DSH/LIS3DSH.h" +#include "sensors/LIS3DSH/LIS3DSHData.h" + +using namespace std; +using namespace miosix; + +SPIBus bus(SPI1); +GpioPin cs(GPIOE_BASE, 3); + +int main() { + + { + FastInterruptDisableLock dLock; + + RCC->APB2ENR |= RCC_APB2ENR_SPI1EN; // SPI1 ENABLE + + cs.mode(Mode::OUTPUT); + } + cs.high(); + + LIS3DSH sensor( + bus, + cs, + sensor.ODR_100_HZ, + sensor.UPDATE_AFTER_READ_MODE, + sensor.FULL_SCALE_4G + ); + + Vec3 acc; + int8_t temp; + + // sensor not initialized, should return false + if (sensor.onSimpleUpdate() || sensor.updateTemperature()) { + printf("\nTest failed: sensor not initialized \n"); + return -1; + } + + bool initialized = false; + // initialize imu + if (!sensor.init()) { + if (sensor.getLastError() == sensor.ERR_NOT_ME) { + printf("Test failed: invalid WHO_AM_I value, init failed \n"); + } + else { + printf("Test failed: init failed \n"); + } + return -1; + } + initialized = true; + + // check if the sensor is properly working + if (!sensor.selfTest()) { + printf("\nTest failed: self-test failed \n"); + return -1; + } + + // if sensor already inizialized, init() should return false + if (initialized) { + if (sensor.init()) { + printf("\nTest failed: sensor is already initialized \n"); + return -1; + } + } + + Thread::sleep(500); + + // sample some data from the sensor + for(int i = 0; i < 5; i++) { + sensor.updateTemperature(); + // sensor intitialized, should return true (false if no new data exist) + if (!sensor.onSimpleUpdate()) { + printf("\nWarning: no new data to be read \n"); + } + + acc = *(sensor.accelDataPtr()); + temp = (int8_t) *(sensor.tempDataPtr()); + + printf("\nAccel: x: %.2f | y: %.2f | z: %.2f \n", acc.getX(), acc.getY(), acc.getZ()); + printf("Temp: %d C \n", temp); + + Thread::sleep(200); + } + + printf("\nTest ok \n"); + + return 0; +} \ No newline at end of file diff --git a/src/tests/drivers/test-lsm.cpp b/src/tests/drivers/test-lsm.cpp index 641d490a1510c60bd3ae1fa42ac2a88aeaf4476a..83c3d8e66757d0e3fb817c309d2004e301c78abe 100644 --- a/src/tests/drivers/test-lsm.cpp +++ b/src/tests/drivers/test-lsm.cpp @@ -26,7 +26,7 @@ #include <sensors/LSM6DS3H/LSM6DS3H.h> #include <drivers/spi/SensorSpi.h> -#include <sensors/SensorSampling.h> +#include <sensors/SensorSampler.h> #include <math/Stats.h> #include <diagnostic/CpuMeter.h> @@ -36,19 +36,18 @@ using namespace miosix::interfaces; /* SPI1 binding to the sensor */ typedef BusSPI<1,spi1::mosi,spi1::miso,spi1::sck> busSPI1; typedef ProtocolSPI<busSPI1,sensors::lsm6ds3h::cs> spiLSM6DS3H0_a; -typedef LSM6DS3H<spiLSM6DS3H0_a> lsm6ds3h_t; int main() { - SimpleSensorSampler sampler; + SimpleSensorSampler sampler(250, 1); spiLSM6DS3H0_a::init(); - lsm6ds3h_t* lsm6ds3h = new lsm6ds3h_t(3,3); + LSM6DS3H<spiLSM6DS3H0_a>* lsm6ds3h = new LSM6DS3H<spiLSM6DS3H0_a>(3,3); if(lsm6ds3h->init()) { printf("[LSM6DS3H] Init succeeded\n" ); - sampler.AddSensor(lsm6ds3h); + sampler.addSensor(lsm6ds3h, std::bind([&]() {})); } else { @@ -64,7 +63,7 @@ int main() while(true) { - sampler.Update(); + sampler.sampleAndCallback(); // const Vec3* last_data = lsm6ds3h->gyroDataPtr(); // printf("%f %f %f\n", last_data->getX(), last_data->getY(), diff --git a/src/tests/drivers/test-lsm9ds1-fifo.cpp b/src/tests/drivers/test-lsm9ds1-fifo.cpp index 174a78af6d9454a132a3c8c544633aba8245d377..48c1e4e71d78ed63663912a6e0642db3c635e985 100644 --- a/src/tests/drivers/test-lsm9ds1-fifo.cpp +++ b/src/tests/drivers/test-lsm9ds1-fifo.cpp @@ -23,24 +23,19 @@ */ #include <array> -#include <iostream> #include "drivers/HardwareTimer.h" #include "drivers/spi/SPIDriver.h" #include "sensors/LSM9DS1/LSM9DS1_AxelGyro.h" +#include "logger/Logger.h" using namespace miosix; using namespace std; -typedef Gpio<GPIOA_BASE, 5> GpioSck; // questi sono i pin SPI per - // f407_discovery +typedef Gpio<GPIOA_BASE, 5> GpioSck; //SPI1 f407 typedef Gpio<GPIOA_BASE, 6> GpioMiso; typedef Gpio<GPIOA_BASE, 7> GpioMosi; -typedef Gpio<GPIOA_BASE, 1> GpioINT1; - -static const bool FIFO_ENABLED = true; -static const uint8_t FIFO_WATERMARK = 20; -static const uint8_t FIFO_SAMPLES = 5; +typedef Gpio<GPIOC_BASE, 13> GpioINT1; //INT1 A/G // SPI SPIBus bus(SPI1); @@ -48,10 +43,16 @@ GpioPin cs_XLG(GPIOE_BASE, 7); // LED just for init GpioPin LED1(GPIOD_BASE, 15); +GpioPin LED2(GPIOD_BASE, 13); // SPI read flag volatile bool flagSPIReadRequest = false; +//IMU obj data +static const bool FIFO_ENABLED = true; +static const uint8_t FIFO_WATERMARK = 20; +static const uint8_t FIFO_SAMPLES = 5; + // High Resolution hardware timer using TIM5 HardwareTimer<uint32_t> hrclock( TIM5, TimerUtils::getPrescalerInputFrequency(TimerUtils::InputClock::APB1)); @@ -60,21 +61,18 @@ HardwareTimer<uint32_t> hrclock( volatile uint32_t last_tick; volatile uint32_t delta; -// Arrays for samples -array<Vec3, 32> axelData[FIFO_SAMPLES], gyroData[FIFO_SAMPLES]; - // LSM9DS1 obj LSM9DS1_XLG* lsm9ds1 = nullptr; // Interrupt handlers -void __attribute__((naked)) EXTI1_IRQHandler() +void __attribute__((naked)) EXTI13_IRQHandler() { saveContext(); - asm volatile("bl _Z20EXTI1_IRQHandlerImplv"); + asm volatile("bl _Z20EXTI13_IRQHandlerImplv"); restoreContext(); } -void __attribute__((used)) EXTI1_IRQHandlerImpl() +void __attribute__((used)) EXTI13_IRQHandlerImpl() { // Computing delta beetween interrupts uint32_t tick = hrclock.tick(); @@ -94,39 +92,47 @@ void __attribute__((used)) EXTI1_IRQHandlerImpl() void gpioConfig(); void timer5Config(); void EXTI1Config(); +void fakeLogger(lsm9ds1XLGSample sample); +void printLogger(); int main() { uint8_t fifo_counter = 0; - uint32_t dt[FIFO_SAMPLES]; + uint32_t dt; + uint64_t timestamp = 0; gpioConfig(); - - Thread::sleep(1000); - LED1.low(); - + Thread::sleep(5000); + return 0; timer5Config(); EXTI1Config(); lsm9ds1 = new LSM9DS1_XLG( bus, cs_XLG, LSM9DS1_XLG::AxelFSR::FS_8, LSM9DS1_XLG::GyroFSR::FS_245, - LSM9DS1_XLG::ODR::ODR_952, FIFO_ENABLED, FIFO_WATERMARK); - - while (!lsm9ds1->init()) - ; + LSM9DS1_XLG::ODR::ODR_238, FIFO_ENABLED, FIFO_WATERMARK); - lsm9ds1->clearFIFO(); + while (!lsm9ds1->init()); + LED2.high(); //init OK + + lsm9ds1->clearFIFO(); //just to be sure to intercept the first interrupt + //start sampling for (;;) { + //printf("%d\n", GpioINT1::value()); if (flagSPIReadRequest && fifo_counter < FIFO_SAMPLES) { flagSPIReadRequest = false; - dt[fifo_counter] = hrclock.toMicroSeconds(delta); + dt = hrclock.toMicroSeconds(delta)/FIFO_WATERMARK; //delta of each sample lsm9ds1->onSimpleUpdate(); - axelData[fifo_counter] = lsm9ds1->getAxelFIFO(); - gyroData[fifo_counter] = lsm9ds1->getGyroFIFO(); + for(int i=0 ; i < FIFO_WATERMARK; i++) + { + lsm9ds1XLGSample sample = lsm9ds1->getLsm9ds1FIFO()[i]; + timestamp += dt; + sample.timestamp = timestamp; + fakeLogger(sample); + } LED1.low(); fifo_counter++; } @@ -137,22 +143,11 @@ int main() } } - // print data - uint32_t timestamp = 0; - - for (uint8_t i = 0; i < FIFO_SAMPLES; i++) - { - std::cout << "FIFO " << (int)i + 1 << std::endl; - for (uint8_t j = 0; j < FIFO_WATERMARK; j++) - { - timestamp += dt[i] / FIFO_WATERMARK; - printf("%d>>%ld>>%.3f,%.3f,%.3f,%.3f,%.3f,%.3f\n", j,timestamp, - axelData[i][j].getX(), axelData[i][j].getY(), - axelData[i][j].getZ(), gyroData[i][j].getX(), - gyroData[i][j].getY(), gyroData[i][j].getZ()); - } - } + printLogger(); + LED1.low(); + LED2.low(); + while(1); return 0; } @@ -185,6 +180,8 @@ void gpioConfig() // Select LED built in GPIO mode LED1.mode(Mode::OUTPUT); + LED2.mode(Mode::OUTPUT); + } cs_XLG.high(); @@ -210,18 +207,51 @@ void EXTI1Config() // PC13 } // Configure mask bit of 1st interrupt line - EXTI->IMR |= EXTI_IMR_MR1; + EXTI->IMR |= EXTI_IMR_MR13; // Configure trigger selection bit (rising edge) - EXTI->RTSR |= EXTI_RTSR_TR1; + EXTI->RTSR |= EXTI_RTSR_TR13; // Clear pending interrupt register before enable - EXTI->PR |= EXTI_PR_PR1; + EXTI->PR |= EXTI_PR_PR13; - // Select PB1 as interrupt source in line 1 - SYSCFG->EXTICR[0] &= 0xFFFFFF0F; + // Select PC13 as interrupt source in line 13 (EXTICR4) + SYSCFG->EXTICR[3] &= 0xFFFFFF0F; + SYSCFG->EXTICR[3] |= 0xFFFFFF2F; // Enable the interrupt in the interrupt controller - NVIC_EnableIRQ(EXTI1_IRQn); - NVIC_SetPriority(EXTI1_IRQn, 14); + NVIC_EnableIRQ(IRQn_Type::EXTI15_10_IRQn); + NVIC_SetPriority(IRQn_Type::EXTI15_10_IRQn, 47); +} + +uint16_t counter = 0; +float ax[FIFO_WATERMARK*FIFO_SAMPLES], + ay[FIFO_WATERMARK*FIFO_SAMPLES], + az[FIFO_WATERMARK*FIFO_SAMPLES], + gx[FIFO_WATERMARK*FIFO_SAMPLES], + gy[FIFO_WATERMARK*FIFO_SAMPLES], + gz[FIFO_WATERMARK*FIFO_SAMPLES]; + +uint64_t t[FIFO_WATERMARK*FIFO_SAMPLES]; + +void fakeLogger(lsm9ds1XLGSample sample) +{ + ax[counter] = sample.axelData.getX(); + ay[counter] = sample.axelData.getY(); + az[counter] = sample.axelData.getZ(); + gx[counter] = sample.gyroData.getX(); + gy[counter] = sample.gyroData.getY(); + gz[counter] = sample.gyroData.getZ(); + t[counter] = sample.timestamp; + counter++; +} + +void printLogger() +{ + for(int i = 0; i < counter; i++) + { + printf("%lld>>%.3f,%.3f,%.3f,%.3f,%.3f,%.3f\n", t[i],ax[i],ay[i],az[i], + gx[i],gy[i],gz[i]); + + } } \ No newline at end of file diff --git a/src/tests/drivers/test-lsm9ds1.cpp b/src/tests/drivers/test-lsm9ds1.cpp index f595cd209d6d03566c12c9ed30932a02b701d485..1299f8d4ef531496dbd7f8844ad26e52ff5a4b79 100644 --- a/src/tests/drivers/test-lsm9ds1.cpp +++ b/src/tests/drivers/test-lsm9ds1.cpp @@ -37,9 +37,9 @@ static const bool FIFO_ENABLED = false; //SPI SPIBus bus(SPI1); -SPIBusConfig cfg; +//SPIBusConfig cfg; GpioPin cs_XLG(GPIOE_BASE, 7); -GpioPin cs_M(GPIOE_BASE, 8); +GpioPin cs_M(GPIOE_BASE, 9); //LEDs GpioPin LED1(GPIOD_BASE, 15); @@ -52,9 +52,6 @@ int main(){ Vec3 adata, gdata, mdata; float tdata; - - cfg.clock_div=SPIClockDivider::DIV64; - { FastInterruptDisableLock dLock; @@ -97,7 +94,7 @@ int main(){ LSM9DS1_XLG lsm9ds1X( bus, cs_XLG, - cfg, + //cfg, LSM9DS1_XLG::AxelFSR::FS_8, LSM9DS1_XLG::GyroFSR::FS_245, LSM9DS1_XLG::ODR::ODR_952 diff --git a/src/tests/drivers/test-mpu9250.cpp b/src/tests/drivers/test-mpu9250.cpp index f53889a6de00d03789cb215c2f6487b0878cf9c2..268b59522315e8e3ed0649252bab468ae42759b6 100644 --- a/src/tests/drivers/test-mpu9250.cpp +++ b/src/tests/drivers/test-mpu9250.cpp @@ -26,27 +26,26 @@ #include <sensors/MPU9250/MPU9250.h> #include <drivers/spi/SensorSpi.h> -#include <sensors/SensorSampling.h> +#include <sensors/SensorSampler.h> using namespace miosix; using namespace miosix::interfaces; typedef BusSPI<1,spi1::mosi,spi1::miso,spi1::sck> busSPI1; typedef ProtocolSPI<busSPI1,sensors::mpu9250::cs> spiMPU9250_a; -typedef MPU9250<spiMPU9250_a> mpu_t; int main() { - SimpleSensorSampler sampler; + SimpleSensorSampler sampler(250, 1); spiMPU9250_a::init(); - mpu_t* mpu = new mpu_t(1, 1); + MPU9250<spiMPU9250_a>* mpu = new MPU9250<spiMPU9250_a>(1, 1); Thread::sleep(100); if(mpu->init()){ printf("MPU9250 Init succeeded\n" ); - sampler.AddSensor(mpu); + sampler.addSensor(mpu, std::bind([&]() {})); } else { printf("MPU9250 Init failed\n"); @@ -61,7 +60,7 @@ int main() while(true) { - sampler.Update(); + sampler.sampleAndCallback(); mpu->updateMagneto(); const Vec3* last_data = mpu->compassDataPtr(); diff --git a/src/tests/drivers/test-ms5803.cpp b/src/tests/drivers/test-ms5803.cpp index 1a339433d914d7b5005246c6bf62f038f9b8a18e..bb25d974f5325d3adf83fec5d6fdb1b280700e16 100644 --- a/src/tests/drivers/test-ms5803.cpp +++ b/src/tests/drivers/test-ms5803.cpp @@ -24,7 +24,7 @@ #include <drivers/spi/SPIDriver.h> #include <drivers/spi/SensorSpi.h> #include <interfaces-impl/hwmapping.h> -#include <sensors/SensorSampling.h> +#include <sensors/SensorSampler.h> #include "sensors/MS580301BA07/MS580301BA07.h" @@ -44,7 +44,7 @@ int main() // SCK, MISO, MOSI already initialized in the bsp } - SimpleSensorSampler sampler; + SimpleSensorSampler sampler(50, 1); MS580301BA07* ms58 = new MS580301BA07(bus, chip_select); @@ -53,7 +53,7 @@ int main() if (ms58->init()) { printf("MS58 Init succeeded\n"); - sampler.AddSensor(ms58); + sampler.addSensor(ms58, std::bind([&]() {})); } else { @@ -70,7 +70,7 @@ int main() printf("raw_p,p,raw_t,t\n"); while (true) { - sampler.Update(); + sampler.sampleAndCallback(); const float* last_pressure = ms58->pressureDataPtr(); const float* last_temp = ms58->tempDataPtr();