diff --git a/Documents/EPOS4 50 15 Compact/CAN_wiring.png b/Documents/EPOS4 50 15 Compact/CAN_wiring.png new file mode 100644 index 0000000..829973e Binary files /dev/null and b/Documents/EPOS4 50 15 Compact/CAN_wiring.png differ diff --git a/Documents/EPOS4 50 15 Compact/CiA 301 - CANopen.pdf b/Documents/EPOS4 50 15 Compact/CiA 301 - CANopen.pdf new file mode 100644 index 0000000..d23d3c4 Binary files /dev/null and b/Documents/EPOS4 50 15 Compact/CiA 301 - CANopen.pdf differ diff --git a/Documents/EPOS4 50 15 Compact/EPOS - command library.pdf b/Documents/EPOS4 50 15 Compact/EPOS - command library.pdf new file mode 100644 index 0000000..614c2bb Binary files /dev/null and b/Documents/EPOS4 50 15 Compact/EPOS - command library.pdf differ diff --git a/Documents/EPOS4 50 15 Compact/EPOS - communication guid.pdf b/Documents/EPOS4 50 15 Compact/EPOS - communication guid.pdf new file mode 100644 index 0000000..66caedb Binary files /dev/null and b/Documents/EPOS4 50 15 Compact/EPOS - communication guid.pdf differ diff --git a/Documents/EPOS4 50 15 Compact/EPOS4 - application notes collection.pdf b/Documents/EPOS4 50 15 Compact/EPOS4 - application notes collection.pdf new file mode 100644 index 0000000..a852ce1 Binary files /dev/null and b/Documents/EPOS4 50 15 Compact/EPOS4 - application notes collection.pdf differ diff --git a/Documents/EPOS4 50 15 Compact/EPOS4 - firmware specification.pdf b/Documents/EPOS4 50 15 Compact/EPOS4 - firmware specification.pdf new file mode 100644 index 0000000..7abf228 Binary files /dev/null and b/Documents/EPOS4 50 15 Compact/EPOS4 - firmware specification.pdf differ diff --git a/Documents/EPOS4 50 15 Compact/EPOS4 - hardware reference.pdf b/Documents/EPOS4 50 15 Compact/EPOS4 - hardware reference.pdf new file mode 100644 index 0000000..6390767 Binary files /dev/null and b/Documents/EPOS4 50 15 Compact/EPOS4 - hardware reference.pdf differ diff --git a/Documents/STM32F4/dm00031020-stm32f405-415-stm32f407-417-stm32f427-437-and-stm32f429-439-advanced-arm-based-32-bit-mcus-stmicroelectronics.pdf b/Documents/STM32F4/dm00031020-stm32f405-415-stm32f407-417-stm32f427-437-and-stm32f429-439-advanced-arm-based-32-bit-mcus-stmicroelectronics.pdf new file mode 100644 index 0000000..8ed39b1 Binary files /dev/null and b/Documents/STM32F4/dm00031020-stm32f405-415-stm32f407-417-stm32f427-437-and-stm32f429-439-advanced-arm-based-32-bit-mcus-stmicroelectronics.pdf differ diff --git a/Documents/STM32F4/dm00037051.pdf b/Documents/STM32F4/dm00037051.pdf new file mode 100644 index 0000000..0aca177 Binary files /dev/null and b/Documents/STM32F4/dm00037051.pdf differ diff --git a/Documents/STM32F4/dm00039084-discovery-kit-with-stm32f407vg-mcu-stmicroelectronics.pdf b/Documents/STM32F4/dm00039084-discovery-kit-with-stm32f407vg-mcu-stmicroelectronics.pdf new file mode 100644 index 0000000..b4e6c17 Binary files /dev/null and b/Documents/STM32F4/dm00039084-discovery-kit-with-stm32f407vg-mcu-stmicroelectronics.pdf differ diff --git a/Documents/Seeed Arduino/shield Can pinout.png b/Documents/Seeed Arduino/shield Can pinout.png new file mode 100644 index 0000000..c9476a2 Binary files /dev/null and b/Documents/Seeed Arduino/shield Can pinout.png differ diff --git a/Examples/epos_basic/CMakeLists.txt b/Examples/epos_basic/CMakeLists.txt new file mode 100644 index 0000000..ca24a06 --- /dev/null +++ b/Examples/epos_basic/CMakeLists.txt @@ -0,0 +1,11 @@ +# Find Zephyr. This also loads Zephyr's build system. +cmake_minimum_required(VERSION 3.13.1) +find_package(Zephyr) +project(epos_controller_mainTest) + +target_sources(app PRIVATE + src/main.cpp + ../../Library/epos4/epos4.cpp +) + +include_directories(../../Library/epos4) diff --git a/zephyr/epos_controller/Kconfig b/Examples/epos_basic/Kconfig similarity index 100% rename from zephyr/epos_controller/Kconfig rename to Examples/epos_basic/Kconfig diff --git a/Examples/epos_basic/ReadmeNiko.txt b/Examples/epos_basic/ReadmeNiko.txt new file mode 100644 index 0000000..88554fb --- /dev/null +++ b/Examples/epos_basic/ReadmeNiko.txt @@ -0,0 +1,10 @@ +Dieses Projekt soll zum Testen der Can-Kommunikation und das Verfahrens des Motors mittels PPM OHNE simulink model verwendet werden. + +Interessant -> Funktioniert tx_callback(int ?,..-) + +Motor bewegt sich im PPM modus + +west build -b stm32f4_disco .\zephyr\Medit\epos_matlab +west flash + +python3 .\Downloads\pythonploter2.py \ No newline at end of file diff --git a/Examples/epos_basic/prj.conf b/Examples/epos_basic/prj.conf new file mode 100644 index 0000000..dfb53c3 --- /dev/null +++ b/Examples/epos_basic/prj.conf @@ -0,0 +1,17 @@ +CONFIG_CAN=y +CONFIG_CAN_INIT_PRIORITY=80 +CONFIG_CAN_MAX_FILTER=10 + +CONFIG_LOG=y +# CONFIG_CAN_LOG_LEVEL_DBG=y +CONFIG_DEBUG_OPTIMIZATIONS=y + +CONFIG_CPLUSPLUS=y +CONFIG_NEWLIB_LIBC_FLOAT_PRINTF=y +CONFIG_CBPRINTF_FP_SUPPORT=y +CONFIG_NEWLIB_LIBC=y + +CONFIG_PM=y +CONFIG_DMA=y +CONFIG_DMA_STM32=y +CONFIG_UART_ASYNC_API=y \ No newline at end of file diff --git a/Examples/epos_basic/src/.vscode/c_cpp_properties.json b/Examples/epos_basic/src/.vscode/c_cpp_properties.json new file mode 100644 index 0000000..166e479 --- /dev/null +++ b/Examples/epos_basic/src/.vscode/c_cpp_properties.json @@ -0,0 +1,21 @@ +{ + "configurations": [ + { + "name": "Win32", + "includePath": [ + "${workspaceFolder}/**", + "${workspaceFolder}/epos4" + ], + "defines": [ + "_DEBUG", + "UNICODE", + "_UNICODE" + ], + "cStandard": "c17", + "cppStandard": "c++17", + "intelliSenseMode": "windows-msvc-x64", + "compilerArgs": [] + } + ], + "version": 4 +} \ No newline at end of file diff --git a/Examples/epos_basic/src/main.cpp b/Examples/epos_basic/src/main.cpp new file mode 100644 index 0000000..0177359 --- /dev/null +++ b/Examples/epos_basic/src/main.cpp @@ -0,0 +1,351 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#ifdef CONFIG_UART_ASYNC_API +#include +#include +#endif + +#include "epos4.h" + +#define RX_THREAD_STACK_SIZE 512 +#define RX_THREAD_PRIORITY 2 +#define STATE_POLL_THREAD_STACK_SIZE 512 +#define STATE_POLL_THREAD_PRIORITY 2 +#define LED_MSG_ID 0x10 +#define COUNTER_MSG_ID 0x12345 +#define SET_LED 1 +#define RESET_LED 0 +#define SLEEP_TIME K_MSEC(250) + +K_THREAD_STACK_DEFINE(rx_thread_stack, RX_THREAD_STACK_SIZE); + +#define CAN_DEVICE_LABEL DT_PROP(DT_ALIAS(can_dev), label) +const struct device* can_dev; + +// uart config +#define UART_DEVICE_NODE DT_ALIAS(usart2) +const struct device *uart_dev = DEVICE_DT_GET(UART_DEVICE_NODE); + +epos4* epos4_1_pointer = NULL; + +struct k_thread rx_thread_data; +struct k_thread poll_state_thread_data; +struct k_work state_change_work; +enum can_state current_state; +struct can_bus_err_cnt current_err_cnt; + +CAN_MSGQ_DEFINE(my_can_msgq1, 100); +CAN_MSGQ_DEFINE(my_can_msgq2, 100); + +struct zcan_frame rx_frame; +struct k_timer sync_timer; +struct k_timer print_timer; +struct k_mutex blocker_can; + +extern void sync_function(struct k_timer *timer_id); + +uint32_t glob_counter = 0; +int glob_counter_int = 0; + +uint8_t uart_data[100]; +volatile float final_pos = 100.0; + +/** + * @brief Predefined trajectory to run down. + * + * @details At any point in time, the value of the trajectory can be returned. + */ +float get_trejectory(int glob_counter, int mode) +{ + float final_pos = 0.0; + if( mode == 0 ){ + + // Two jumps. Start at 0 degrees. Then drive to 50 degrees and then back to 30 degrees. + if( glob_counter >= 0 && glob_counter < 3000 ){ + final_pos = 0.0; + }else if ( glob_counter >= 3000 && glob_counter < 10000 ){ + final_pos = 50.0; + }else if ( glob_counter >= 10000 ){ + final_pos = 30.0; + } else { + final_pos = 0.0; + } + + }else if( mode == 1 ){ + + // Preset trejectory with ramps + if( glob_counter >= 0 && glob_counter < 5000 ){ + final_pos = 0.0; + }else if ( glob_counter >= 5000 && glob_counter < 10000 ){ + final_pos = (50.0/5000.0)*(glob_counter - 5000.0) + 0.0; + }else if ( glob_counter >= 10000 && glob_counter < 15000 ){ + final_pos = (50.0/5000.0)*(glob_counter - 10000.0) + 50.0; + }else if ( glob_counter >= 15000 && glob_counter < 20000 ){ + final_pos = (-40.0/5000.0)*(glob_counter - 15000.0) + 100.0; + }else if ( glob_counter >= 20000 && glob_counter < 25000 ){ + final_pos = (-30.0/5000.0)*(glob_counter - 20000.0) + 60.0; + }else if ( glob_counter >= 25000 && glob_counter < 30000 ){ + final_pos = (20.0/5000.0)*(glob_counter - 25000.0) + 30.0; + }else if ( glob_counter >= 30000 ){ + final_pos = 50.0; + }else{ + final_pos = 0.0; + } + + }else{ + + final_pos = 0.0; + + } + return final_pos; +} + +/** + * @brief UART data format + * + * @details So that measurement data can be sent to the computer via uart, the measurement data is put into this stupid format. + * This way the measured values can be distinguished from other uart data. + */ +void save_data_for_uart(uint8_t *uart_data, uint8_t *time_pointer, uint8_t *pos_pointer, int8_t *pointer_tor, int8_t *final_pos_pointer, int buffer_part) +{ + uart_data[(buffer_part)] = 'D'; + uart_data[(buffer_part)+1] = '='; + uart_data[(buffer_part)+2] = 'x'; + uart_data[(buffer_part)+3] = time_pointer[0]; + uart_data[(buffer_part)+4] = time_pointer[1]; + uart_data[(buffer_part)+5] = time_pointer[2]; + uart_data[(buffer_part)+6] = time_pointer[3]; + uart_data[(buffer_part)+7] = 'x'; + uart_data[(buffer_part)+8] = '='; + uart_data[(buffer_part)+9] = pos_pointer[0]; + uart_data[(buffer_part)+10] = pos_pointer[1]; + uart_data[(buffer_part)+11] = pos_pointer[2]; + uart_data[(buffer_part)+12] = pos_pointer[3]; + uart_data[(buffer_part)+13] = 'x'; + uart_data[(buffer_part)+14] = '='; + uart_data[(buffer_part)+15] = final_pos_pointer[0]; + uart_data[(buffer_part)+16] = final_pos_pointer[1]; + uart_data[(buffer_part)+17] = final_pos_pointer[2]; + uart_data[(buffer_part)+18] = final_pos_pointer[3]; + uart_data[(buffer_part)+19] = 'x'; + uart_data[(buffer_part)+20] = '='; + uart_data[(buffer_part)+21] = pointer_tor[0]; + uart_data[(buffer_part)+22] = pointer_tor[1]; + uart_data[(buffer_part)+23] = '\r'; + uart_data[(buffer_part)+24] = '\n'; +} + +void tx_irq_callback_main(const struct device *CAN_INTERFACE, int error_flags, void *arg) +{ + k_mutex_unlock(epos4_1_pointer->_blocker_can); +} + +void sync_function(struct k_timer *timer_id) +{ + // ---------------------------------------------------------------------- + // Einlesen der Aktuellen Position und Geschwindigkeit des Aktuators. + // Position ist in Encode increments und Geschwindigkeit in rpm. + int32_t tmp_pos = epos4_1_pointer->position; + int32_t tmp_vel = epos4_1_pointer->velocity; + + // ---------------------------------------------------------------------- + // Send synconization signal (once a millisecond) to the EPOS. + // This expects it once per time interval (1ms). + // Then it sends previously agreed data (SPO Object. position and speed). + epos4_1_pointer->sync(); + + // ---------------------------------------------------------------------- + // Conversion of position and speed in radian and rad/s + // 1 rad == 0.00000756309 inc. + // 104 deg == 120000 inc. + float ac_pos = (((float)(tmp_pos)) * 0.00001512618 + 1.5707963267); + float ac_vel = (((float)(tmp_vel)) * 0.00065797516 ); + + // ---------------------------------------------------------------------- + // Defining the next position + final_pos = get_trejectory(glob_counter, 0); + + + // ---------------------------------------------------------------------- + // Here you can calc the qoutput torque you want the epos to provide. + float output_torque = 0.0; + + // Save the torque calculated by the controller to send it to the EPOS4. + float target_tor = output_torque * 1000.0; + int8_t *tar_tor_array = (int8_t*)(&target_tor); + + // ---------------------------------------------------------------------- + // conversion from signed int to unsigned int. + // This allows the data to be sent directly as a byte via UART. + uint32_t int_pos = (uint32_t)(tmp_pos); + uint32_t int_tor = (uint32_t)(tmp_vel); + + // ---------------------------------------------------------------------- + // Change all variables to the correct data types for further processing. + // Send via CAN to the current controller (EPOS4) and send via UART to the computer for graphical output. + int16_t int16_tor = (int16_t)(target_tor); + int32_t int32_final_pos = (int32_t)(final_pos); + + uint8_t *time_pointer = (uint8_t *)(&glob_counter); + uint8_t *pos_pointer = (uint8_t *)(&int_pos); + uint8_t *tor_pointer = (uint8_t *)(&int_tor); + int8_t *pointer_tor = (int8_t *)(&int16_tor); + int8_t *final_pos_pointer = (int8_t *)(&int32_final_pos); + + // ---------------------------------------------------------------------- + // Sending the data via UART. + // First the data is written into a buffer. We use a DMA to send the data via UART. + // With this we can save the UART send oberhead at every send call and send directly larger amounts of data. + // We send at every fourth pass (every 4 ms) the measurement data of the last 4 passes. + int buffer_part_mod = glob_counter%4; + + // save the data on the predefined buffer + save_data_for_uart(uart_data, time_pointer, pos_pointer, pointer_tor, final_pos_pointer, buffer_part_mod*25); + + // When the buffer is full or every 4ms the buffer is passed to the DMA. + // This then sends it asynchronously to the uart port. + if( buffer_part_mod == 3 ){ + uart_tx(uart_dev, uart_data, 100, 0); + } + + // Create a CAN frame. + // This is sent to the EPOS4 and contains the next position to be approached. + struct zcan_frame frame = { + .id = 0x401, + .rtr = CAN_DATAFRAME, + .id_type = CAN_STANDARD_IDENTIFIER, + .dlc = 2, + .data = {pointer_tor[0],pointer_tor[1]} + }; + + // Wait until the last can send function has returned to avoid a deadlock. Known bug from the CAN library of zephyr + k_mutex_lock(epos4_1_pointer->_blocker_can, K_FOREVER); + + // ---------------------------------------------------------------------- + // Send the CAN frame + int can_send_return = can_send(epos4_1_pointer->_can_interface, &frame, K_FOREVER, tx_irq_callback_main, NULL); + + // increase of the cycle counter + glob_counter += 1; + glob_counter_int += 1; + + // ---------------------------------------------------------------------- + // General possibility to perform a time measurement. + // The number of cycles must be multiplied with the clock rate of the controller to calculate the execution time. + // uint32_t start_time = k_cycle_get_32(); + // uint32_t end_time = k_cycle_get_32(); + // uint32_t diff_time = end_time - start_time; +} + +void serial_cb(const struct device *dev, struct uart_event *evt, void *user_data) +{ + +} + +void rx_callback_function(const struct device *dev, struct zcan_frame *frame, void *user_data) +{ + epos4_1_pointer->reciveCANdataSPO((char*)(frame->data)); +} + +void main(void) +{ + // -------------------------------------- + // Complete init of the CAN controller and the UART device. + + // init uart dev + if ( !device_is_ready(uart_dev) ) { + printk("uart devices not ready\n"); + return; + } + uart_callback_set(uart_dev, serial_cb, NULL); + + // init the Epos instance and the CAN interface for it. + epos4 epos4_1(0x581,0x601, can_dev, &my_can_msgq1, &my_can_msgq2, &rx_frame, &blocker_can); + epos4_1_pointer = &epos4_1; + epos4_1_pointer->_can_interface = device_get_binding("CAN_1"); + epos4_1_pointer->measure_mode = 0; + + if (!device_is_ready(epos4_1_pointer->_can_interface)) { + printk("CAN: Device %s not ready.\n", epos4_1_pointer->_can_interface->name); + return; + }else{ + printk("CAN device %s is ready...\n", epos4_1_pointer->_can_interface->name); + } + can_set_mode(epos4_1_pointer->_can_interface, CAN_MODE_NORMAL); + + // Due to a known bug in the Zephyr CAN interface, we need a mutex to protect the CAN send function. This is initialized here. + k_mutex_init(epos4_1_pointer->_blocker_can); + + // Setting up the filters for receiving CAN msgs. + const struct zcan_filter my_filter = { + .id = 0x581, + .rtr = CAN_DATAFRAME, + .id_type = CAN_STANDARD_IDENTIFIER, + .id_mask = CAN_STD_ID_MASK, + .rtr_mask = 1 + }; + int filter_id; + + filter_id = can_add_rx_filter_msgq(epos4_1_pointer->_can_interface, &my_can_msgq1, &my_filter); + if (filter_id < 0) { + printk("Unable to attach isr [%d]", filter_id); + return; + } + + const struct zcan_filter spo_recieve = { + .id = 0x181, + .rtr = CAN_DATAFRAME, + .id_type = CAN_STANDARD_IDENTIFIER, + .id_mask = CAN_STD_ID_MASK, + .rtr_mask = 1 + }; + int spo_recieve_filter_id; + + spo_recieve_filter_id = can_add_rx_filter(epos4_1_pointer->_can_interface, rx_callback_function, NULL, &spo_recieve); + // spo_recieve_filter_id = can_add_rx_filter_msgq(epos4_1_pointer->_can_interface, &my_can_msgq2, &spo_recieve); + if (spo_recieve_filter_id < 0) { + printk("Unable to attach isr [%d]", spo_recieve_filter_id); + return; + } + // Program init finished + // ------------------------------------------- + + k_sleep(K_MSEC(500)); + + // ------------------------------------------- + // Init the Epos4 Controller + + printk(" ------------------------------- \n"); + printk("Start init ... \n"); + epos4_1_pointer->init(); + printk("\ndone!\nStart init CST-Mode ... \n"); + epos4_1_pointer->initCST(); + printk("\ndone!\n"); + + k_msgq_cleanup(&my_can_msgq1); + k_msgq_cleanup(&my_can_msgq2); + + // Epos4 init finished + // ------------------------------------------- + + k_sleep(K_MSEC(1000)); + + // Initialize and start the interrupt routines to call the sync function regularly. + // There happens the main routine of the program + k_timer_init( &sync_timer, sync_function, 0); + k_timer_start( &sync_timer, K_MSEC(0), K_MSEC(1) ); + + while(1) + { + // ... + } +} diff --git a/zephyr/epos_controller_model/stm32f4_disco.overlay b/Examples/epos_basic/stm32f4_disco.overlay similarity index 77% rename from zephyr/epos_controller_model/stm32f4_disco.overlay rename to Examples/epos_basic/stm32f4_disco.overlay index bc7dd94..e36ff83 100644 --- a/zephyr/epos_controller_model/stm32f4_disco.overlay +++ b/Examples/epos_basic/stm32f4_disco.overlay @@ -34,14 +34,33 @@ // #address-cells = <1>; // #size-cells = <0>; + &can2 { status = "disabled"; }; +&dma1 { + status = "okay"; + dma-requests = <8>; +}; + +&usart2 { + status = "okay"; + current-speed = < 0xe1000 >; + dmas = <&dma1 5 4 0x440 0x3>, + <&dma1 6 4 0x440 0x3>; + dma-names = "rx", "tx"; +}; + / { chosen { zephyr,can-primary = &can1; + zephyr,shell-uart = &usart2; + }; + aliases { + usart2 = &usart2; }; -}; \ No newline at end of file +}; + diff --git a/Examples/epos_matlab/CMakeLists.txt b/Examples/epos_matlab/CMakeLists.txt new file mode 100644 index 0000000..05b7974 --- /dev/null +++ b/Examples/epos_matlab/CMakeLists.txt @@ -0,0 +1,25 @@ +# Find Zephyr. This also loads Zephyr's build system. +cmake_minimum_required(VERSION 3.13.1) +find_package(Zephyr) +project(epos_controller_mainTest) + +target_sources(app PRIVATE + src/main.cpp + ../../Library/epos4/epos4.cpp + src/simulinkcode/controller/Control_System.c + src/simulinkcode/controller/referenced_model_includes/PositionControl.c + src/simulinkcode/controller/referenced_model_includes/VelocityControl.c + src/simulinkcode/Matlab/R2018b/rtw/c/src/rt_logging.c + src/simulinkcode/Matlab/_sharedutils/rt_nonfinite.c + src/simulinkcode/Matlab/_sharedutils/rtGetInf.c + src/simulinkcode/Matlab/_sharedutils/rtGetNaN.c +) + +include_directories(../../Library/epos4) + +target_include_directories(app PUBLIC src/simulinkcode/controller main.cpp) +target_include_directories(app PUBLIC src/simulinkcode/controller/referenced_model_includes main.cpp) +target_include_directories(app PUBLIC src/simulinkcode/Matlab/R2018b/extern/include main.cpp) +target_include_directories(app PUBLIC src/simulinkcode/Matlab/R2018b/simulink/include main.cpp) +target_include_directories(app PUBLIC src/simulinkcode/Matlab/R2018b/rtw/c/src main.cpp) +target_include_directories(app PUBLIC src/simulinkcode/Matlab/_sharedutils main.cpp) \ No newline at end of file diff --git a/zephyr/epos_controller_mcp2515/Kconfig b/Examples/epos_matlab/Kconfig similarity index 100% rename from zephyr/epos_controller_mcp2515/Kconfig rename to Examples/epos_matlab/Kconfig diff --git a/Examples/epos_matlab/ReadmeNiko.txt b/Examples/epos_matlab/ReadmeNiko.txt new file mode 100644 index 0000000..88554fb --- /dev/null +++ b/Examples/epos_matlab/ReadmeNiko.txt @@ -0,0 +1,10 @@ +Dieses Projekt soll zum Testen der Can-Kommunikation und das Verfahrens des Motors mittels PPM OHNE simulink model verwendet werden. + +Interessant -> Funktioniert tx_callback(int ?,..-) + +Motor bewegt sich im PPM modus + +west build -b stm32f4_disco .\zephyr\Medit\epos_matlab +west flash + +python3 .\Downloads\pythonploter2.py \ No newline at end of file diff --git a/Examples/epos_matlab/prj.conf b/Examples/epos_matlab/prj.conf new file mode 100644 index 0000000..dfb53c3 --- /dev/null +++ b/Examples/epos_matlab/prj.conf @@ -0,0 +1,17 @@ +CONFIG_CAN=y +CONFIG_CAN_INIT_PRIORITY=80 +CONFIG_CAN_MAX_FILTER=10 + +CONFIG_LOG=y +# CONFIG_CAN_LOG_LEVEL_DBG=y +CONFIG_DEBUG_OPTIMIZATIONS=y + +CONFIG_CPLUSPLUS=y +CONFIG_NEWLIB_LIBC_FLOAT_PRINTF=y +CONFIG_CBPRINTF_FP_SUPPORT=y +CONFIG_NEWLIB_LIBC=y + +CONFIG_PM=y +CONFIG_DMA=y +CONFIG_DMA_STM32=y +CONFIG_UART_ASYNC_API=y \ No newline at end of file diff --git a/Examples/epos_matlab/src/.vscode/c_cpp_properties.json b/Examples/epos_matlab/src/.vscode/c_cpp_properties.json new file mode 100644 index 0000000..166e479 --- /dev/null +++ b/Examples/epos_matlab/src/.vscode/c_cpp_properties.json @@ -0,0 +1,21 @@ +{ + "configurations": [ + { + "name": "Win32", + "includePath": [ + "${workspaceFolder}/**", + "${workspaceFolder}/epos4" + ], + "defines": [ + "_DEBUG", + "UNICODE", + "_UNICODE" + ], + "cStandard": "c17", + "cppStandard": "c++17", + "intelliSenseMode": "windows-msvc-x64", + "compilerArgs": [] + } + ], + "version": 4 +} \ No newline at end of file diff --git a/Examples/epos_matlab/src/main.cpp b/Examples/epos_matlab/src/main.cpp new file mode 100644 index 0000000..9717e91 --- /dev/null +++ b/Examples/epos_matlab/src/main.cpp @@ -0,0 +1,381 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#ifdef CONFIG_UART_ASYNC_API +#include +#include +#endif + +#ifdef __cplusplus +extern "C" +{ +#endif +#include "Control_System.h" +#ifdef __cplusplus +} +#endif + +#include "epos4.h" + +#define RX_THREAD_STACK_SIZE 512 +#define RX_THREAD_PRIORITY 2 +#define STATE_POLL_THREAD_STACK_SIZE 512 +#define STATE_POLL_THREAD_PRIORITY 2 +#define LED_MSG_ID 0x10 +#define COUNTER_MSG_ID 0x12345 +#define SET_LED 1 +#define RESET_LED 0 +#define SLEEP_TIME K_MSEC(250) + +K_THREAD_STACK_DEFINE(rx_thread_stack, RX_THREAD_STACK_SIZE); + + +#define CAN_DEVICE_LABEL DT_PROP(DT_ALIAS(can_dev), label) +const struct device* can_dev; + +// uart config +#define UART_DEVICE_NODE DT_ALIAS(usart2) +const struct device *uart_dev = DEVICE_DT_GET(UART_DEVICE_NODE); + +epos4* epos4_1_pointer = NULL; + +struct k_thread rx_thread_data; +struct k_thread poll_state_thread_data; +struct k_work state_change_work; +enum can_state current_state; +struct can_bus_err_cnt current_err_cnt; + +CAN_MSGQ_DEFINE(my_can_msgq1, 100); +CAN_MSGQ_DEFINE(my_can_msgq2, 100); + +struct zcan_frame rx_frame; +struct k_timer sync_timer; +struct k_timer print_timer; +struct k_mutex blocker_can; + +extern void sync_function(struct k_timer *timer_id); + +uint32_t glob_counter = 0; +int glob_counter_int = 0; + +uint8_t uart_data[100]; +volatile float final_pos = 100.0; + +/** + * @brief Predefined trajectory to run down. + * + * @details At any point in time, the value of the trajectory can be returned. + */ +float get_trejectory(int glob_counter, int mode) +{ + float final_pos = 0.0; + if( mode == 0 ){ + + // Two jumps. Start at 0 degrees. Then drive to 50 degrees and then back to 30 degrees. + if( glob_counter >= 0 && glob_counter < 3000 ){ + final_pos = 0.0; + }else if ( glob_counter >= 3000 && glob_counter < 10000 ){ + final_pos = 50.0; + }else if ( glob_counter >= 10000 ){ + final_pos = 30.0; + } else { + final_pos = 0.0; + } + + }else if( mode == 1 ){ + + // Preset trejectory with ramps + if( glob_counter >= 0 && glob_counter < 5000 ){ + final_pos = 0.0; + }else if ( glob_counter >= 5000 && glob_counter < 10000 ){ + final_pos = (50.0/5000.0)*(glob_counter - 5000.0) + 0.0; + }else if ( glob_counter >= 10000 && glob_counter < 15000 ){ + final_pos = (50.0/5000.0)*(glob_counter - 10000.0) + 50.0; + }else if ( glob_counter >= 15000 && glob_counter < 20000 ){ + final_pos = (-40.0/5000.0)*(glob_counter - 15000.0) + 100.0; + }else if ( glob_counter >= 20000 && glob_counter < 25000 ){ + final_pos = (-30.0/5000.0)*(glob_counter - 20000.0) + 60.0; + }else if ( glob_counter >= 25000 && glob_counter < 30000 ){ + final_pos = (20.0/5000.0)*(glob_counter - 25000.0) + 30.0; + }else if ( glob_counter >= 30000 ){ + final_pos = 50.0; + }else{ + final_pos = 0.0; + } + + }else{ + + final_pos = 0.0; + + } + return final_pos; +} + +/** + * @brief UART data format + * + * @details So that measurement data can be sent to the computer via uart, the measurement data is put into this stupid format. + * This way the measured values can be distinguished from other uart data. + */ +void save_data_for_uart(uint8_t *uart_data, uint8_t *time_pointer, uint8_t *pos_pointer, int8_t *pointer_tor, int8_t *final_pos_pointer, int buffer_part) +{ + uart_data[(buffer_part)] = 'D'; + uart_data[(buffer_part)+1] = '='; + uart_data[(buffer_part)+2] = 'x'; + uart_data[(buffer_part)+3] = time_pointer[0]; + uart_data[(buffer_part)+4] = time_pointer[1]; + uart_data[(buffer_part)+5] = time_pointer[2]; + uart_data[(buffer_part)+6] = time_pointer[3]; + uart_data[(buffer_part)+7] = 'x'; + uart_data[(buffer_part)+8] = '='; + uart_data[(buffer_part)+9] = pos_pointer[0]; + uart_data[(buffer_part)+10] = pos_pointer[1]; + uart_data[(buffer_part)+11] = pos_pointer[2]; + uart_data[(buffer_part)+12] = pos_pointer[3]; + uart_data[(buffer_part)+13] = 'x'; + uart_data[(buffer_part)+14] = '='; + uart_data[(buffer_part)+15] = final_pos_pointer[0]; + uart_data[(buffer_part)+16] = final_pos_pointer[1]; + uart_data[(buffer_part)+17] = final_pos_pointer[2]; + uart_data[(buffer_part)+18] = final_pos_pointer[3]; + uart_data[(buffer_part)+19] = 'x'; + uart_data[(buffer_part)+20] = '='; + uart_data[(buffer_part)+21] = pointer_tor[0]; + uart_data[(buffer_part)+22] = pointer_tor[1]; + uart_data[(buffer_part)+23] = '\r'; + uart_data[(buffer_part)+24] = '\n'; +} + +void tx_irq_callback_main(const struct device *CAN_INTERFACE, int error_flags, void *arg) +{ + k_mutex_unlock(epos4_1_pointer->_blocker_can); +} + +void sync_function(struct k_timer *timer_id) +{ + // ---------------------------------------------------------------------- + // Einlesen der Aktuellen Position und Geschwindigkeit des Aktuators. + // Position ist in Encode increments und Geschwindigkeit in rpm. + int32_t tmp_pos = epos4_1_pointer->position; + int32_t tmp_vel = epos4_1_pointer->velocity; + + // ---------------------------------------------------------------------- + // Send synconization signal (once a millisecond) to the EPOS. + // This expects it once per time interval (1ms). + // Then it sends previously agreed data (SPO Object. position and speed). + epos4_1_pointer->sync(); + + // ---------------------------------------------------------------------- + // Conversion of position and speed in radian and rad/s + // 1 rad == 0.00000756309 inc. + // 104 deg == 120000 inc. + float ac_pos = (((float)(tmp_pos)) * 0.00001512618 + 1.5707963267); + float ac_vel = (((float)(tmp_vel)) * 0.00065797516 ); + + // ---------------------------------------------------------------------- + // Defining the next position + final_pos = get_trejectory(glob_counter, 0); + + // ---------------------------------------------------------------------- + // Here we use a code generated Simulink model (position controller) to calculate the new Controlling variable. + // If no Simulink model is used, the new value must be calculated in another way. + + // Store the measured values (position and velocity) and the default position on the Simulink object of the mathematical model. + Control_System_U.vel_meas_rads = ac_vel; + Control_System_U.pos_meas_rad = ac_pos; + Control_System_U.User_Posdeg = final_pos; + + // Some constants + Control_System_U.Unlock_Motor = 1; + Control_System_U.User_ControlMode = 1; + Control_System_U.torque_meas_Nm = 0.0; + + // ---------------------------------------------------------------------- + // Perform a simulation step in the Simulink model (controller). + // This calculates the new motor current/torque. + // the new value is stored in >Control_System_Y.Output_Torque< + Control_System_step(); + + // ---------------------------------------------------------------------- + // Save the torque calculated by the controller to send it to the EPOS4. + float target_tor = Control_System_Y.Output_Torque * 1000.0; + int8_t *tar_tor_array = (int8_t*)(&target_tor); + + // ---------------------------------------------------------------------- + // conversion from signed int to unsigned int. + // This allows the data to be sent directly as a byte via UART. + uint32_t int_pos = (uint32_t)(tmp_pos); + uint32_t int_tor = (uint32_t)(tmp_vel); + + // ---------------------------------------------------------------------- + // Change all variables to the correct data types for further processing. + // Send via CAN to the current controller (EPOS4) and send via UART to the computer for graphical output. + int16_t int16_tor = (int16_t)(target_tor); + int32_t int32_final_pos = (int32_t)(final_pos); + + uint8_t *time_pointer = (uint8_t *)(&glob_counter); + uint8_t *pos_pointer = (uint8_t *)(&int_pos); + uint8_t *tor_pointer = (uint8_t *)(&int_tor); + int8_t *pointer_tor = (int8_t *)(&int16_tor); + int8_t *final_pos_pointer = (int8_t *)(&int32_final_pos); + + // ---------------------------------------------------------------------- + // Sending the data via UART. + // First the data is written into a buffer. We use a DMA to send the data via UART. + // With this we can save the UART send oberhead at every send call and send directly larger amounts of data. + // We send at every fourth pass (every 4 ms) the measurement data of the last 4 passes. + int buffer_part_mod = glob_counter%4; + + // save the data on the predefined buffer + save_data_for_uart(uart_data, time_pointer, pos_pointer, pointer_tor, final_pos_pointer, buffer_part_mod*25); + + // When the buffer is full or every 4ms the buffer is passed to the DMA. + // This then sends it asynchronously to the uart port. + if( buffer_part_mod == 3 ){ + uart_tx(uart_dev, uart_data, 100, 0); + } + + // Create a CAN frame. + // This is sent to the EPOS4 and contains the next position to be approached. + struct zcan_frame frame = { + .id = 0x401, + .rtr = CAN_DATAFRAME, + .id_type = CAN_STANDARD_IDENTIFIER, + .dlc = 2, + .data = {pointer_tor[0],pointer_tor[1]} + }; + + // Wait until the last can send function has returned to avoid a deadlock. Known bug from the CAN library of zephyr + k_mutex_lock(epos4_1_pointer->_blocker_can, K_FOREVER); + + // ---------------------------------------------------------------------- + // Send the CAN frame + int can_send_return = can_send(epos4_1_pointer->_can_interface, &frame, K_FOREVER, tx_irq_callback_main, NULL); + + // increase of the cycle counter + glob_counter += 1; + glob_counter_int += 1; + + // ---------------------------------------------------------------------- + // General possibility to perform a time measurement. + // The number of cycles must be multiplied with the clock rate of the controller to calculate the execution time. + // uint32_t start_time = k_cycle_get_32(); + // uint32_t end_time = k_cycle_get_32(); + // uint32_t diff_time = end_time - start_time; +} + +void serial_cb(const struct device *dev, struct uart_event *evt, void *user_data) +{ + +} + +void rx_callback_function(const struct device *dev, struct zcan_frame *frame, void *user_data) +{ + epos4_1_pointer->reciveCANdataSPO((char*)(frame->data)); +} + +void main(void) +{ + // -------------------------------------- + // Complete init of the CAN controller and the UART device. + + // init uart dev + if ( !device_is_ready(uart_dev) ) { + printk("uart devices not ready\n"); + return; + } + uart_callback_set(uart_dev, serial_cb, NULL); + + // init the Epos instance and the CAN interface for it. + epos4 epos4_1(0x581,0x601, can_dev, &my_can_msgq1, &my_can_msgq2, &rx_frame, &blocker_can); + epos4_1_pointer = &epos4_1; + epos4_1_pointer->_can_interface = device_get_binding("CAN_1"); + epos4_1_pointer->measure_mode = 0; + + if (!device_is_ready(epos4_1_pointer->_can_interface)) { + printk("CAN: Device %s not ready.\n", epos4_1_pointer->_can_interface->name); + return; + }else{ + printk("CAN device %s is ready...\n", epos4_1_pointer->_can_interface->name); + } + can_set_mode(epos4_1_pointer->_can_interface, CAN_MODE_NORMAL); + + // Due to a known bug in the Zephyr CAN interface, we need a mutex to protect the CAN send function. This is initialized here. + k_mutex_init(epos4_1_pointer->_blocker_can); + + // Setting up the filters for receiving CAN msgs. + const struct zcan_filter my_filter = { + .id = 0x581, + .rtr = CAN_DATAFRAME, + .id_type = CAN_STANDARD_IDENTIFIER, + .id_mask = CAN_STD_ID_MASK, + .rtr_mask = 1 + }; + int filter_id; + + filter_id = can_add_rx_filter_msgq(epos4_1_pointer->_can_interface, &my_can_msgq1, &my_filter); + if (filter_id < 0) { + printk("Unable to attach isr [%d]", filter_id); + return; + } + + const struct zcan_filter spo_recieve = { + .id = 0x181, + .rtr = CAN_DATAFRAME, + .id_type = CAN_STANDARD_IDENTIFIER, + .id_mask = CAN_STD_ID_MASK, + .rtr_mask = 1 + }; + int spo_recieve_filter_id; + + spo_recieve_filter_id = can_add_rx_filter(epos4_1_pointer->_can_interface, rx_callback_function, NULL, &spo_recieve); + // spo_recieve_filter_id = can_add_rx_filter_msgq(epos4_1_pointer->_can_interface, &my_can_msgq2, &spo_recieve); + if (spo_recieve_filter_id < 0) { + printk("Unable to attach isr [%d]", spo_recieve_filter_id); + return; + } + // Program init finished + // ------------------------------------------- + + k_sleep(K_MSEC(500)); + + // ------------------------------------------- + // Init the Epos4 Controller + + printk(" ------------------------------- \n"); + printk("Start init ... \n"); + epos4_1_pointer->init(); + printk("\ndone!\nStart init CST-Mode ... \n"); + epos4_1_pointer->initCST(); + printk("\ndone!\n"); + + k_msgq_cleanup(&my_can_msgq1); + k_msgq_cleanup(&my_can_msgq2); + + // Epos4 init finished + // ------------------------------------------- + + k_sleep(K_MSEC(1000)); + + + // Init Matlab code model + Control_System_initialize(); + + // Initialize and start the interrupt routines to call the sync function regularly. + // There happens the main routine of the program + k_timer_init( &sync_timer, sync_function, 0); + k_timer_start( &sync_timer, K_MSEC(0), K_MSEC(1) ); + + while(1) + { + // ... + } +} diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/extern/include/tmwtypes.h b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/extern/include/tmwtypes.h new file mode 100644 index 0000000..fb478e1 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/extern/include/tmwtypes.h @@ -0,0 +1,831 @@ +/* + * Copyright 1984-2018 The MathWorks, Inc. + */ + +#if defined(_MSC_VER) +# pragma once +#endif +#if defined(__GNUC__) && (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ > 3)) +# pragma once +#endif + +#ifndef tmwtypes_h +#define tmwtypes_h + +#ifndef __TMWTYPES__ +#define __TMWTYPES__ +/* + * File : tmwtypes.h + * Abstract: + * Data types for use with MATLAB/SIMULINK and the Real-Time Workshop. + * + * When compiling stand-alone model code, data types can be overridden + * via compiler switches. + * + * Define NO_FLOATS to eliminate reference to real_T, etc. + */ + +#include + +#ifdef __APPLE_CC__ +#include +#endif + +#define LOGICAL_IS_A_TYPE +#define SPARSE_GENERALIZATION + +#ifdef NO_FLOATS +# define double double_not_allowed +# define float float_not_allowed +#endif /*NO_FLOATS*/ + +#ifndef NO_FLOATS + +#ifndef __MWERKS__ +# ifdef __STDC__ +# include +# else +# define FLT_MANT_DIG 24 +# define DBL_MANT_DIG 53 +# endif +#endif + +#endif /*NO_FLOATS*/ + +/* + * The following data types cannot be overridden when building MEX files. + */ +#ifdef MATLAB_MEX_FILE +# undef CHARACTER_T +# undef INTEGER_T +# undef BOOLEAN_T +# undef REAL_T +# undef TIME_T +#endif + +/* + * The uchar_T, ushort_T and ulong_T types are needed for compilers which do + * not allow defines to be specified, at the command line, with spaces in them. + */ + +typedef unsigned char uchar_T; +typedef unsigned short ushort_T; +typedef unsigned long ulong_T; + +#if (defined(_MSC_VER) && _MSC_VER >= 1500) \ + || defined(__x86_64__) || defined(__LP64__) \ + || defined(__LCC64__) + +typedef unsigned long long ulonglong_T; +#endif + + + +/*=======================================================================* + * Fixed width word size data types: * + * int8_T, int16_T, int32_T - signed 8, 16, or 32 bit integers * + * uint8_T, uint16_T, uint32_T - unsigned 8, 16, or 32 bit integers * + * real32_T, real64_T - 32 and 64 bit floating point numbers * + *=======================================================================*/ + +/* When used with Real Time Workshop generated code, this + * header file can be used with a variety of compilers. + * + * The compiler could be for an 8 bit embedded processor that + * only had 8 bits per integer and 16 bits per long. + * In that example, a 32 bit integer size is not even available. + * This header file should be robust to that. + * + * For the case of an 8 bit processor, the preprocessor + * may be limited to 16 bit math like its target. That limitation + * would mean that 32 bit comparisons can't be done accurately. + * To increase robustness to this, comparisons are done against + * smaller values first. An inaccurate 32 bit comparison isn't + * attempted if the 16 bit comparison has already succeeded. + * + * Limitations on preprocessor math can also be stricter than + * for the target. There are known cases where a compiler + * targeting processors with 64 bit longs can't do accurate + * preprocessor comparisons on more than 32 bits. + */ + +/* Determine the number of bits for int, long, short, and char. + * If one fails to be determined, set the number of bits to -1 + */ + +#ifndef TMW_BITS_PER_INT +# if INT_MAX == 0x7FL +# define TMW_BITS_PER_INT 8 +# elif INT_MAX == 0x7FFFL +# define TMW_BITS_PER_INT 16 +# elif INT_MAX == 0x7FFFFFFFL +# define TMW_BITS_PER_INT 32 +# else +# define TMW_BITS_PER_INT -1 +# endif +#endif + +#ifndef TMW_BITS_PER_LONG +# if LONG_MAX == 0x7FL +# define TMW_BITS_PER_LONG 8 +# elif LONG_MAX == 0x7FFFL +# define TMW_BITS_PER_LONG 16 +# elif LONG_MAX == 0x7FFFFFFFL +# define TMW_BITS_PER_LONG 32 +# else +# define TMW_BITS_PER_LONG -1 +# endif +#endif + +#ifndef TMW_BITS_PER_SHRT +# if SHRT_MAX == 0x7FL +# define TMW_BITS_PER_SHRT 8 +# elif SHRT_MAX == 0x7FFFL +# define TMW_BITS_PER_SHRT 16 +# elif SHRT_MAX == 0x7FFFFFFFL +# define TMW_BITS_PER_SHRT 32 +# else +# define TMW_BITS_PER_SHRT -1 +# endif +#endif + +#ifndef TMW_BITS_PER_SCHAR +# if SCHAR_MAX == 0x7FL +# define TMW_BITS_PER_SCHAR 8 +# elif SCHAR_MAX == 0x7FFFL +# define TMW_BITS_PER_SCHAR 16 +# elif SCHAR_MAX == 0x7FFFFFFFL +# define TMW_BITS_PER_SCHAR 32 +# else +# define TMW_BITS_PER_SCHAR -1 +# endif +#endif + +#ifndef TMW_CHAR_SIGNED +# if SCHAR_MAX == CHAR_MAX +# define TMW_CHAR_SIGNED 1 +# else +# define TMW_CHAR_SIGNED 0 +# endif +#endif + +/* It is common for one or more of the integer types + * to be the same size. For example, on many embedded + * processors, both shorts and ints are 16 bits. On + * processors used for workstations, it is quite common + * for both int and long to be 32 bits. + * When there is more than one choice for typdef'ing + * a portable type like int16_T or uint32_T, in + * concept, it should not matter which choice is made. + * However, some style guides and some code checking + * tools do identify and complain about seemingly + * irrelevant differences. For example, a code + * checking tool may complain about an implicit + * conversion from int to short even though both + * are 16 bits. To reduce these types of + * complaints, it is best to make int the + * preferred choice when more than one is available. + */ + +#ifndef INT8_T +# if TMW_BITS_PER_INT == 8 +# define INT8_T int +# elif TMW_BITS_PER_LONG == 8 +# define INT8_T long +# elif TMW_BITS_PER_SCHAR == 8 +# define INT8_T signed char +# elif TMW_BITS_PER_SHRT == 8 +# define INT8_T short +# endif +#endif +#ifdef INT8_T + typedef INT8_T int8_T; +#endif + +#ifndef UINT8_T +# if TMW_BITS_PER_INT == 8 +# define UINT8_T unsigned int +# elif TMW_BITS_PER_LONG == 8 +# define UINT8_T unsigned long +# elif TMW_BITS_PER_SCHAR == 8 +# define UINT8_T unsigned char +# elif TMW_BITS_PER_SHRT == 8 +# define UINT8_T unsigned short +# endif +#endif +#ifdef UINT8_T + typedef UINT8_T uint8_T; +#endif + + +#ifndef INT16_T +# if TMW_BITS_PER_INT == 16 +# define INT16_T int +# elif TMW_BITS_PER_LONG == 16 +# define INT16_T long +# elif TMW_BITS_PER_SCHAR == 16 +# define INT16_T signed char +# elif TMW_BITS_PER_SHRT == 16 +# define INT16_T short +# endif +#endif +#ifdef INT16_T + typedef INT16_T int16_T; +#endif + + +#ifndef UINT16_T +# if TMW_BITS_PER_INT == 16 +# define UINT16_T unsigned int +# elif TMW_BITS_PER_LONG == 16 +# define UINT16_T unsigned long +# elif TMW_BITS_PER_SCHAR == 16 +# define UINT16_T unsigned char +# elif TMW_BITS_PER_SHRT == 16 +# define UINT16_T unsigned short +# endif +#endif +#ifdef UINT16_T + typedef UINT16_T uint16_T; +#endif + + +#ifndef INT32_T +# if TMW_BITS_PER_INT == 32 +# define INT32_T int +# elif TMW_BITS_PER_LONG == 32 +# define INT32_T long +# elif TMW_BITS_PER_SCHAR == 32 +# define INT32_T signed char +# elif TMW_BITS_PER_SHRT == 32 +# define INT32_T short +# endif +#endif +#ifdef INT32_T + typedef INT32_T int32_T; +#endif + + +#ifndef UINT32_T +# if TMW_BITS_PER_INT == 32 +# define UINT32_T unsigned int +# elif TMW_BITS_PER_LONG == 32 +# define UINT32_T unsigned long +# elif TMW_BITS_PER_SCHAR == 32 +# define UINT32_T unsigned char +# elif TMW_BITS_PER_SHRT == 32 +# define UINT32_T unsigned short +# endif +#endif +#ifdef UINT32_T + typedef UINT32_T uint32_T; +#endif + +/* The following is used to emulate smaller integer types when only + * larger types are available. For example, compilers for TI C3x/C4x DSPs + * define char and short to be 32 bits, so 8 and 16 bits are not directly + * available. This target is commonly used with RTW rapid prototyping. + * Other DSPs define char to be 16 bits, so 8 bits is not directly + * available. + */ +#ifndef INT8_T +# ifdef INT16_T +# define INT8_T INT16_T + typedef INT8_T int8_T; +# else +# ifdef INT32_T +# define INT8_T INT32_T + typedef INT8_T int8_T; +# endif +# endif +#endif + +#ifndef UINT8_T +# ifdef UINT16_T +# define UINT8_T UINT16_T + typedef UINT8_T uint8_T; +# else +# ifdef UINT32_T +# define UINT8_T UINT32_T + typedef UINT8_T uint8_T; +# endif +# endif +#endif + +#ifndef INT16_T +# ifdef INT32_T +# define INT16_T INT32_T + typedef INT16_T int16_T; +# endif +#endif + +#ifndef UINT16_T +# ifdef UINT32_T +# define UINT16_T UINT32_T + typedef UINT16_T uint16_T; +# endif +#endif + + +#ifndef NO_FLOATS + +#ifndef REAL32_T +# ifndef __MWERKS__ +# if FLT_MANT_DIG >= 23 +# define REAL32_T float +# endif +# else +# define REAL32_T float +# endif +#endif +#ifdef REAL32_T + typedef REAL32_T real32_T; +#endif + + +#ifndef REAL64_T +# ifndef __MWERKS__ +# if DBL_MANT_DIG >= 52 +# define REAL64_T double +# endif +# else +# define REAL64_T double +# endif +#endif +#ifdef REAL64_T + typedef REAL64_T real64_T; +#endif + +#endif /* NO_FLOATS*/ + +/*=======================================================================* + * Fixed width word size data types: * + * int64_T - signed 64 bit integers * + * uint64_T - unsigned 64 bit integers * + *=======================================================================*/ + + + +#ifndef INT64_T +# if defined(__APPLE__) +# define INT64_T long long +# define FMT64 "ll" +# if defined(__LP64__) && !defined(INT_TYPE_64_IS_LONG) +# define INT_TYPE_64_IS_LONG +# endif +# elif (defined(__x86_64__) || defined(__LP64__))&& !defined(__MINGW64__) +# define INT64_T long +# define FMT64 "l" +# if !defined(INT_TYPE_64_IS_LONG) +# define INT_TYPE_64_IS_LONG +# endif +# elif defined(_MSC_VER) || (defined(__BORLANDC__) && __BORLANDC__ >= 0x530) \ + || (defined(__WATCOMC__) && __WATCOMC__ >= 1100) +# define INT64_T __int64 +# define FMT64 "I64" +# elif defined(__GNUC__) || defined(TMW_ENABLE_INT64) \ + || defined(__LCC64__) +# define INT64_T long long +# define FMT64 "ll" +# endif +#endif + + + +#if defined(INT64_T) +# if defined(__GNUC__) && \ + ((__GNUC__ > 2) || ((__GNUC__ == 2) && (__GNUC_MINOR__ >=9))) + __extension__ +# endif + typedef INT64_T int64_T; +#endif + + + +#ifndef UINT64_T +# if defined(__APPLE__) +# define UINT64_T unsigned long long +# define FMT64 "ll" +# if defined(__LP64__) && !defined(INT_TYPE_64_IS_LONG) +# define INT_TYPE_64_IS_LONG +# endif +# elif (defined(__x86_64__) || defined(__LP64__))&& !defined(__MINGW64__) +# define UINT64_T unsigned long +# define FMT64 "l" +# if !defined(INT_TYPE_64_IS_LONG) +# define INT_TYPE_64_IS_LONG +# endif +# elif defined(_MSC_VER) || (defined(__BORLANDC__) && __BORLANDC__ >= 0x530) \ + || (defined(__WATCOMC__) && __WATCOMC__ >= 1100) +# define UINT64_T unsigned __int64 +# define FMT64 "I64" +# elif defined(__GNUC__) || defined(TMW_ENABLE_INT64) \ + || defined(__LCC64__) +# define UINT64_T unsigned long long +# define FMT64 "ll" +# endif +#endif + +#if defined(_WIN64) || (defined(__APPLE__) && defined(__LP64__)) \ + || defined(__x86_64__) \ + || defined(__LP64__) +# define INT_TYPE_64_IS_SUPPORTED +#endif + +#if defined(UINT64_T) +# if defined(__GNUC__) && \ + ((__GNUC__ > 2) || ((__GNUC__ == 2) && (__GNUC_MINOR__ >=9))) + __extension__ +# endif + typedef UINT64_T uint64_T; +#endif + +/*===========================================================================* + * Format string modifiers for using size_t variables in printf statements. * + *===========================================================================*/ + +#ifndef FMT_SIZE_T +# if (defined( __GNUC__ ) || defined(_STDC_C99))&& !defined(__MINGW64__) +# define FMT_SIZE_T "z" +# elif defined (__WATCOMC__) +# define FMT_SIZE_T "l" +# elif defined (_WIN32 ) +# define FMT_SIZE_T "I" +# else +# define FMT_SIZE_T "l" +# endif +#endif + +#ifndef FMT_PTRDIFF_T +# if defined(__APPLE__) +# define FMT_PTRDIFF_T "l" +# elif defined( __GNUC__ ) || defined(_STDC_C99) +# define FMT_PTRDIFF_T "t" +# elif defined (__WATCOMC__) +# define FMT_PTRDIFF_T "l" +# elif defined (_WIN32 ) +# define FMT_PTRDIFF_T "I" +# else +# define FMT_PTRDIFF_T "l" +# endif +#endif + +/*===========================================================================* + * General or logical data types where the word size is not guaranteed. * + * real_T - possible settings include real32_T or real64_T * + * time_T - possible settings include real32_T or real64_T * + * boolean_T * + * char_T * + * int_T * + * uint_T * + * byte_T * + *===========================================================================*/ + +#ifndef NO_FLOATS + +#ifndef REAL_T +# ifdef REAL64_T +# define REAL_T real64_T +# else +# ifdef REAL32_T +# define REAL_T real32_T +# endif +# endif +#endif +#ifdef REAL_T + typedef REAL_T real_T; +#endif + +#ifndef TIME_T +# ifdef REAL_T +# define TIME_T real_T +# endif +#endif +#ifdef TIME_T + typedef TIME_T time_T; +#endif + +#endif /* NO_FLOATS */ + +#ifndef BOOLEAN_T +# if defined(UINT8_T) +# define BOOLEAN_T UINT8_T +# else +# define BOOLEAN_T unsigned int +# endif +#endif +typedef BOOLEAN_T boolean_T; + + +#ifndef CHARACTER_T +# define CHARACTER_T char +#endif +typedef CHARACTER_T char_T; + + +#ifndef INTEGER_T +# define INTEGER_T int +#endif +typedef INTEGER_T int_T; + + +#ifndef UINTEGER_T +# define UINTEGER_T unsigned +#endif +typedef UINTEGER_T uint_T; + + +#ifndef BYTE_T +# define BYTE_T unsigned char +#endif +typedef BYTE_T byte_T; + + +/*===========================================================================* + * Define Complex Structures * + *===========================================================================*/ +#ifndef NO_FLOATS + +#ifndef CREAL32_T +# ifdef REAL32_T + typedef struct { + real32_T re, im; + } creal32_T; +# define CREAL32_T creal32_T +# endif +#endif + +#ifndef CREAL64_T +# ifdef REAL64_T + typedef struct { + real64_T re, im; + } creal64_T; +# define CREAL64_T creal64_T +# endif +#endif + +#ifndef CREAL_T +# ifdef REAL_T + typedef struct { + real_T re, im; + } creal_T; +# define CREAL_T creal_T +# endif +#endif + +#endif /* NO_FLOATS */ + +#ifndef CINT8_T +# ifdef INT8_T + typedef struct { + int8_T re, im; + } cint8_T; +# define CINT8_T cint8_T +# endif +#endif + +#ifndef CUINT8_T +# ifdef UINT8_T + typedef struct { + uint8_T re, im; + } cuint8_T; +# define CUINT8_T cuint8_T +# endif +#endif + +#ifndef CINT16_T +# ifdef INT16_T + typedef struct { + int16_T re, im; + } cint16_T; +# define CINT16_T cint16_T +# endif +#endif + +#ifndef CUINT16_T +# ifdef UINT16_T + typedef struct { + uint16_T re, im; + } cuint16_T; +# define CUINT16_T cuint16_T +# endif +#endif + +#ifndef CINT32_T +# ifdef INT32_T + typedef struct { + int32_T re, im; + } cint32_T; +# define CINT32_T cint32_T +# endif +#endif + +#ifndef CUINT32_T +# ifdef UINT32_T + typedef struct { + uint32_T re, im; + } cuint32_T; +# define CUINT32_T cuint32_T +# endif +#endif + +#ifndef CINT64_T +# ifdef INT64_T + typedef struct { + int64_T re, im; + } cint64_T; +# define CINT64_T cint64_T +# endif +#endif + +#ifndef CUINT64_T +# ifdef UINT64_T + typedef struct { + uint64_T re, im; + } cuint64_T; +# define CUINT64_T cuint64_T +# endif +#endif + +/*=======================================================================* + * Min and Max: * + * int8_T, int16_T, int32_T - signed 8, 16, or 32 bit integers * + * uint8_T, uint16_T, uint32_T - unsigned 8, 16, or 32 bit integers * + *=======================================================================*/ + +#define MAX_int8_T ((int8_T)(127)) /* 127 */ +#define MIN_int8_T ((int8_T)(-128)) /* -128 */ +#define MAX_uint8_T ((uint8_T)(255)) /* 255 */ +#define MIN_uint8_T ((uint8_T)(0)) + +#define MAX_int16_T ((int16_T)(32767)) /* 32767 */ +#define MIN_int16_T ((int16_T)(-32768)) /* -32768 */ +#define MAX_uint16_T ((uint16_T)(65535)) /* 65535 */ +#define MIN_uint16_T ((uint16_T)(0)) + +#define MAX_int32_T ((int32_T)(2147483647)) /* 2147483647 */ +#define MIN_int32_T ((int32_T)(-2147483647-1)) /* -2147483648 */ +#define MAX_uint32_T ((uint32_T)(0xFFFFFFFFU)) /* 4294967295 */ +#define MIN_uint32_T ((uint32_T)(0)) + +#if defined(_MSC_VER) || (defined(__BORLANDC__) && __BORLANDC__ >= 0x530) \ + || (defined(__WATCOMC__) && __WATCOMC__ >= 1100) \ + || defined(__LCC64__) +# ifdef INT64_T +# define MAX_int64_T ((int64_T)(9223372036854775807LL)) +# define MIN_int64_T ((int64_T)(-9223372036854775807LL-1LL)) +# endif +# ifdef UINT64_T +# define MAX_uint64_T ((uint64_T)(0xFFFFFFFFFFFFFFFFULL)) +# define MIN_uint64_T ((uint64_T)(0)) +# endif +#else +# ifdef INT64_T +# ifdef INT_TYPE_64_IS_LONG +# define MAX_int64_T ((int64_T)(9223372036854775807L)) +# define MIN_int64_T ((int64_T)(-9223372036854775807L-1L)) +# else +# define MAX_int64_T ((int64_T)(9223372036854775807LL)) +# define MIN_int64_T ((int64_T)(-9223372036854775807LL-1LL)) +# endif +# endif +# ifdef UINT64_T +# ifdef INT_TYPE_64_IS_LONG +# define MAX_uint64_T ((uint64_T)(0xFFFFFFFFFFFFFFFFUL)) +# define MIN_uint64_T ((uint64_T)(0)) +# else +# define MAX_uint64_T ((uint64_T)(0xFFFFFFFFFFFFFFFFULL)) +# define MIN_uint64_T ((uint64_T)(0)) +# endif +# endif +#endif + +#ifdef _MSC_VER +/* Conversion from unsigned __int64 to double is not implemented in windows + * and results in a compile error, thus the value must first be cast to + * signed __int64, and then to double. + * + * If the 64 bit int value is greater than 2^63-1, which is the signed int64 max, + * the macro below provides a workaround for casting a uint64 value to a double + * in windows. + */ +# define uint64_to_double(u) ( ((u) > _I64_MAX) ? \ + (double)(__int64)((u) - _I64_MAX - 1) + (double)_I64_MAX + 1: \ + (double)(__int64)(u) ) + +/* The following inline function should only be used in the macro double_to_uint64, + * as it only handles the specfic range of double between 2^63 and 2^64-1 */ +__forceinline +uint64_T double_to_uint64_helper(double d) { + union double_to_uint64_union_type { + double dd; + uint64_T i64; + } di; + di.dd = d; + return (((di.i64 & 0x000fffffffffffff) | 0x0010000000000000) << 11); +} + +/* The largest double value that can be cast to uint64 in windows is the + * signed int64 max, which is 2^63-1. The macro below provides + * a workaround for casting large double values to uint64 in windows. + */ +/* The magic number 18446744073709551616.0 is 2^64 */ +/* The magic number 9223372036854775808.0 is 2^63 */ +# define double_to_uint64(d) ( ((d) >= 18446744073709551616.0) ? \ + 0xffffffffffffffffULL : \ + ((d) >= 0.0) ? \ + ((d) >= 9223372036854775808.0) ? \ + double_to_uint64_helper(d) : \ + (unsigned __int64)(d) : \ + 0ULL ) +#else +# define uint64_to_double(u) ((double)(u)) +# if defined(__BORLANDC__) || defined(__WATCOMC__) || defined(__TICCSC__) +/* double_to_uint64 defined only for MSVC and UNIX */ +# else +# define double_to_uint64(d) ( ((d) >= 18446744073709551616.0) ? \ + (unsigned long long) 0xffffffffffffffffULL : \ + ((d) >= 0) ? (unsigned long long)(d) : (unsigned long long) 0 ) +# endif +#endif + +#if !defined(__cplusplus) && !defined(__bool_true_false_are_defined) + +#ifndef _bool_T +#define _bool_T + +typedef boolean_T bool; + +#ifndef false +#define false (0) +#endif +#ifndef true +#define true (1) +#endif + +#endif /* _bool_T */ + +#endif /* !__cplusplus */ + +/* + * This software assumes that the code is being compiled on a target using a + * 2's complement representation for signed integer values. + */ +#if ((SCHAR_MIN + 1) != -SCHAR_MAX) +#error "This code must be compiled using a 2's complement representation for signed integer values" +#endif + +/* + * Maximum length of a MATLAB identifier (function/variable/model) + * including the null-termination character. + */ +#define TMW_NAME_LENGTH_MAX 64 + +/* + * Maximum values for indices and dimensions + */ +#include + +#ifdef MX_COMPAT_32 +typedef int mwSize; +typedef int mwIndex; +typedef int mwSignedIndex; +#else +typedef size_t mwSize; /* unsigned pointer-width integer */ +typedef size_t mwIndex; /* unsigned pointer-width integer */ +typedef ptrdiff_t mwSignedIndex; /* a signed pointer-width integer */ +#endif + +typedef int SLIndex; +typedef int SLSize; + +#if (defined(_LP64) || defined(_WIN64)) && !defined(MX_COMPAT_32) +/* Currently 2^48 based on hardware limitations */ +# define MWSIZE_MAX 281474976710655UL +# define MWINDEX_MAX 281474976710655UL +# define MWSINDEX_MAX 281474976710655L +# define MWSINDEX_MIN -281474976710655L +#else +# define MWSIZE_MAX 2147483647UL +# define MWINDEX_MAX 2147483647UL +# define MWSINDEX_MAX 2147483647L +# define MWSINDEX_MIN -2147483647L +#endif +#define MWSIZE_MIN 0UL +#define MWINDEX_MIN 0UL + +/** UTF-16 character type */ + +#if (defined(__cplusplus) && (__cplusplus >= 201103L)) || (defined(_HAS_CHAR16_T_LANGUAGE_SUPPORT) && _HAS_CHAR16_T_LANGUAGE_SUPPORT) +typedef char16_t CHAR16_T; +#define U16_STRING_LITERAL_PREFIX u +#elif defined(_MSC_VER) +typedef wchar_t CHAR16_T; +#define U16_STRING_LITERAL_PREFIX L +#else +typedef UINT16_T CHAR16_T; +#endif + +#endif /* __TMWTYPES__ */ + +#endif /* tmwtypes_h */ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/rtw/c/src/common/rt_main.c b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/rtw/c/src/common/rt_main.c new file mode 100644 index 0000000..21084f6 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/rtw/c/src/common/rt_main.c @@ -0,0 +1,455 @@ +/* + * Copyright 2012-2018 The MathWorks, Inc. + * + * File: rt_main.c + * + * Abstract: + * + * A real-time main that runs generated Simulink Coder code under most + * operating systems. Based on the definition of MULTITASKING, a single-task + * or multitask step function is employed. + * + * This file is a useful starting point for creating a custom main when + * targeting a custom floating point processor or integer micro-controller. + * + * Alternatively for ERT targets, you can generate a sample ert_main.c file + * with the generated code by selecting the "Generate an example main program" + * option. In this case, ert_main.c is precisely customized to the + * model requirements. + * + * Required Defines: + * + * MODEL - Model name + * NUMST - Number of sample times + * + */ + +/*==================* + * Required defines * + *==================*/ + +#ifndef MODEL +# error Must specify a model name. Define MODEL=name. +#else +/* create generic macros that work with any model */ +# define EXPAND_CONCAT(name1,name2) name1 ## name2 +# define CONCAT(name1,name2) EXPAND_CONCAT(name1,name2) +# define MODEL_INITIALIZE CONCAT(MODEL,_initialize) +# define MODEL_STEP CONCAT(MODEL,_step) +# define MODEL_TERMINATE CONCAT(MODEL,_terminate) +# define RT_MDL CONCAT(MODEL,_M) +#endif + +#ifndef NUMST +# error Must specify the number of sample times. Define NUMST=number. +#endif + +#if CLASSIC_INTERFACE == 1 +# error "Classic call interface is not supported by rt_main.c." +#endif + +#if ONESTEPFCN==0 +#error Separate output and update functions are not supported by rt_main.c. \ +You must update rt_main.c to suit your application needs, or select \ +the 'Single output/update function' option. +#endif + +#if TERMFCN==0 +#error The terminate function is required by rt_main.c. \ +You must update rt_main.c to suit your application needs, or select \ +the 'Terminate function required' option. +#endif + +#if MULTI_INSTANCE_CODE==1 +#error The static version of rt_main.c does not support reusable \ +code generation. Either deselect ERT option 'Generate reusable code', \ +select option 'Generate an example main program', or modify rt_main.c for \ +your application needs. +#endif + +#define QUOTE1(name) #name +#define QUOTE(name) QUOTE1(name) /* need to expand name */ + +#ifndef SAVEFILE +# define MATFILE2(file) #file ".mat" +# define MATFILE1(file) MATFILE2(file) +# define MATFILE MATFILE1(MODEL) +#else +# define MATFILE QUOTE(SAVEFILE) +#endif + +/*==========* + * Includes * + *==========*/ + +#include "rtwtypes.h" +#if !defined(INTEGER_CODE) || INTEGER_CODE == 0 +# include /* optional for printf */ +#else +#ifdef __cplusplus +extern "C" { +#endif + extern int printf(const char *, ...); + extern int fflush(void *); +#ifdef __cplusplus +} +#endif +#endif +#include /* optional for strcmp */ +#include "rtmodel.h" /* optional for automated builds */ + +#include "rt_logging.h" +#ifdef UseMMIDataLogging +#include "rt_logging_mmi.h" +#endif + +#include "ext_work.h" + +#ifdef MODEL_STEP_FCN_CONTROL_USED +#error The static version of rt_main.c does not support model step function prototype control. +#endif + +/*========================* + * Setup for multitasking * + *========================*/ + +/* + * Let MT be synonym for MULTITASKING (to shorten command line for DOS) + */ +#if defined(MT) +# if MT == 0 +# undef MT +# else +# define MULTITASKING 1 +# endif +#endif + +#if defined(TID01EQ) && TID01EQ == 1 +#define FIRST_TID 1 +#else +#define FIRST_TID 0 +#endif + +/*====================* + * External functions * + *====================*/ + +extern void MODEL_INITIALIZE(void); +extern void MODEL_TERMINATE(void); + +#if !defined(MULTITASKING) + extern void MODEL_STEP(void); /* single-rate step function */ +#else + extern void MODEL_STEP(int_T tid); /* multirate step function */ +#endif + + +/*==================================* + * Global data local to this module * + *==================================*/ +#ifndef MULTITASKING +static boolean_T OverrunFlags[1]; /* ISR overrun flags */ +static boolean_T eventFlags[1]; /* necessary for overlapping preemption */ +#else +static boolean_T OverrunFlags[NUMST]; +static boolean_T eventFlags[NUMST]; +#endif + +/*===================* + * Visible functions * + *===================*/ + +#if !defined(MULTITASKING) /* single task */ + +/* Function: rtOneStep ======================================================== + * + * Abstract: + * Perform one step of the model. This function is modeled such that + * it could be called from an interrupt service routine (ISR) with minor + * modifications. + */ +static void rt_OneStep(void) +{ + /* Disable interrupts here */ + + /*********************************************** + * Check and see if base step time is too fast * + ***********************************************/ + if (OverrunFlags[0]++) { + rtmSetErrorStatus(RT_MDL, "Overrun"); + } + + /************************************************* + * Check and see if an error status has been set * + * by an overrun or by the generated code. * + *************************************************/ + if (rtmGetErrorStatus(RT_MDL) != NULL) { + return; + } + + /* Save FPU context here (if necessary) */ + /* Reenable interrupts here */ + /* Set model inputs here */ + + /************** + * Step model * + **************/ + MODEL_STEP(); + + /* Get model outputs here */ + + /************************** + * Decrement overrun flag * + **************************/ + OverrunFlags[0]--; + + rtExtModeCheckEndTrigger(); + + /* Disable interrupts here */ + /* Restore FPU context here (if necessary) */ + /* Reenable interrupts here */ + +} /* end rtOneStep */ + +#else /* multitask */ + +/* Function: rtOneStep ======================================================== + * + * Abstract: + * Perform one step of the model. This function is modeled such that + * it could be called from an interrupt service routine (ISR) with minor + * modifications. + * + * Note that error checking is only necessary when this routine is + * attached to an interrupt. + * + * Also, you may wish to unroll any or all of for and while loops to + * improve the real-time performance of this function. + */ +static void rt_OneStep(void) +{ + int_T i; + + /* Disable interrupts here */ + + /*********************************************** + * Check and see if base step time is too fast * + ***********************************************/ + if (OverrunFlags[0]++) { + rtmSetErrorStatus(RT_MDL, "Overrun"); + } + + /************************************************* + * Check and see if an error status has been set * + * by an overrun or by the generated code. * + *************************************************/ + if (rtmGetErrorStatus(RT_MDL) != NULL) { + return; + } + + /* Save FPU context here (if necessary) */ + /* Reenable interrupts here */ + + /************************************************* + * Update EventFlags and check subrate overrun * + *************************************************/ + for (i = FIRST_TID+1; i < NUMST; i++) { + if (rtmStepTask(RT_MDL,i) && eventFlags[i]++) { + OverrunFlags[0]--; + OverrunFlags[i]++; + /* Sampling too fast */ + rtmSetErrorStatus(RT_MDL, "Overrun"); + return; + } + if (++rtmTaskCounter(RT_MDL,i) == rtmCounterLimit(RT_MDL,i)) + rtmTaskCounter(RT_MDL, i) = 0; + } + + /* Set model inputs associated with base rate here */ + + /******************************************* + * Step the model for the base sample time * + *******************************************/ + MODEL_STEP(0); + + /* Get model outputs associated with base rate here */ + + /************************************************************************ + * Model step complete for base sample time, now it is okay to * + * re-interrupt this ISR. * + ************************************************************************/ + OverrunFlags[0]--; + + /********************************************************* + * Step the model for any other sample times (subrates) * + *********************************************************/ + for (i = FIRST_TID+1; i < NUMST; i++) { + /************************************************************* + * If task "i" is running, don't run any lower priority task * + *************************************************************/ + if (OverrunFlags[i]) return; + + if (eventFlags[i]) { + OverrunFlags[i]++; + + /* Set model inputs associated with subrate here */ + + /****************************************** + * Step the model for sample time "i" * + ******************************************/ + MODEL_STEP(i); + + /* Get model outputs associated with subrate here */ + + /********************************************** + * Indicate task complete for sample time "i" * + **********************************************/ + OverrunFlags[i]--; + eventFlags[i]--; + } + } + + rtExtModeCheckEndTrigger(); + /* Disable interrupts here */ + /* Restore FPU context here (if necessary) */ + /* Enable interrupts here */ + +} /* end rtOneStep */ + +#endif /* MULTITASKING */ + +/* Function: rt_InitModel ==================================================== + * + * Abstract: + * Initialized the model and the overrun flags + * + */ +static void rt_InitModel(void) +{ +#if defined(MULTITASKING) + int i; + for(i=0; i < NUMST; i++) { + OverrunFlags[i] = 0; + eventFlags[i] = 0; + } +#else + OverrunFlags[0] = 0; + eventFlags[0] = 0; +#endif + + /************************ + * Initialize the model * + ************************/ + MODEL_INITIALIZE(); +} + +/* Function: rt_TermModel ==================================================== + * + * Abstract: + * Terminates the model and prints the error status + * + */ +static int_T rt_TermModel(void) +{ + MODEL_TERMINATE(); + + { + const char_T *errStatus = (const char_T *) (rtmGetErrorStatus(RT_MDL)); + int_T i = 0; + + if (errStatus != NULL && strcmp(errStatus, "Simulation finished")) { + (void)printf("%s\n", errStatus); +#if defined(MULTITASKING) + for (i = 0; i < NUMST; i++) { + if (OverrunFlags[i]) { + (void)printf("ISR overrun - sampling rate too" + "fast for sample time index %d.\n", i); + } + } +#else + if (OverrunFlags[i]) { + (void)printf("ISR overrun - base sampling rate too fast.\n"); + } +#endif + return(1); + } + } + + return(0); +} + +/* Function: main ============================================================= + * + * Abstract: + * Execute model on a generic target such as a workstation. + */ +int_T main(int_T argc, const char *argv[]) +{ + int_T ret; + + /* External mode */ + rtParseArgsForExtMode(argc, argv); + + /******************************************* + * warn if the model will run indefinitely * + *******************************************/ +#if MAT_FILE==0 && EXT_MODE==0 + printf("warning: the simulation will run with no stop time; " + "to change this behavior select the 'MAT-file logging' option\n"); + fflush(NULL); +#endif + + /************************ + * Initialize the model * + ************************/ + rt_InitModel(); + + /* External mode */ + rtSetTFinalForExtMode(&rtmGetTFinal(RT_MDL)); + rtExtModeCheckInit(NUMST); + rtExtModeWaitForStartPkt(rtmGetRTWExtModeInfo(RT_MDL), + NUMST, + (boolean_T *)&rtmGetStopRequested(RT_MDL)); + + (void)printf("\n** starting the model **\n"); + + /*********************************************************************** + * Execute (step) the model. You may also attach rtOneStep to an ISR, * + * in which case you replace the call to rtOneStep with a call to a * + * background task. Note that the generated code sets error status * + * to "Simulation finished" when MatFileLogging is specified in TLC. * + ***********************************************************************/ + while (rtmGetErrorStatus(RT_MDL) == NULL && + !rtmGetStopRequested(RT_MDL)) { + + rtExtModePauseIfNeeded(rtmGetRTWExtModeInfo(RT_MDL), + NUMST, + (boolean_T *)&rtmGetStopRequested(RT_MDL)); + + if (rtmGetStopRequested(RT_MDL)) break; + + /* external mode */ + rtExtModeOneStep(rtmGetRTWExtModeInfo(RT_MDL), + NUMST, + (boolean_T *)&rtmGetStopRequested(RT_MDL)); + + rt_OneStep(); + } + + /******************************* + * Cleanup and exit (optional) * + *******************************/ + +#ifdef UseMMIDataLogging + rt_CleanUpForStateLogWithMMI(rtmGetRTWLogInfo(RT_MDL)); +#endif + rt_StopDataLogging(MATFILE,rtmGetRTWLogInfo(RT_MDL)); + + ret = rt_TermModel(); + + rtExtModeShutdown(NUMST); + + return ret; +} + +/* [EOF] rt_main.c */ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/rtw/c/src/ext_mode/common/ext_work.h b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/rtw/c/src/ext_mode/common/ext_work.h new file mode 100644 index 0000000..e7f1322 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/rtw/c/src/ext_mode/common/ext_work.h @@ -0,0 +1,127 @@ +/* + * Copyright 1994-2012 The MathWorks, Inc. + * + * File: ext_work.h + * + * Abstract: + * + */ + +#ifndef __EXT_WORK_OBJECT__ +#define __EXT_WORK_OBJECT__ + +#ifdef __cplusplus +extern "C" { +#endif + +#ifdef EXT_MODE +#include "ext_types.h" + +#if defined(VXWORKS) + /*VxWorks headers*/ + #include + #include + #include + #include + #include + #include + + extern void rtExtModeTornadoStartup(RTWExtModeInfo *ei, + int_T numSampTimes, + boolean_T *stopReqPtr, + int_T priority, + int32_T stack_size, + SEM_ID startStopSem); + + extern void rtExtModeTornadoCleanup(int_T numSampTimes); + + extern void rtExtModeTornadoSetPortInExtUD(const int_T port); + +#elif defined(C6000_EXT_MODE) + /* C6000 headers*/ + #include + #include + #include + + extern void rtExtModeC6000Startup( RTWExtModeInfo *ei, + int_T numSampTimes, + boolean_T *stopReqPtr); + + extern void rtExtModeC6000Cleanup(int_T numSampTimes); +#else + extern void rtExtModePauseIfNeeded(RTWExtModeInfo *ei, + int_T numSampTimes, + boolean_T *stopReqPtr); + + extern void rtExtModeWaitForStartPkt(RTWExtModeInfo *ei, + int_T numSampTimes, + boolean_T *stopReqPtr); + void rtExtModeInitUD(void); +#endif /* #if defined(VXWORKS) */ + +extern void rtExtModeOneStep(RTWExtModeInfo *ei, + int_T numSampTimes, + boolean_T *stopReqPtr); + +extern void rtExtModeCheckEndTrigger(void); + +extern void rtExtModeUploadCheckTrigger(int_T numSampTimes); + +extern void rtExtModeUpload(int_T tid, + real_T taskTime); + +extern void rtExtModeCheckInit(int_T numSampTimes); + +extern void rtExtModeShutdown(int_T numSampTimes); + +extern void rtExtModeParseArgs(int_T argc, + const char_T *argv[], + real_T *rtmFinal); + +extern void rtERTExtModeSetTFinal(real_T *rtmTFinal); +extern void rtSetTFinalForExtMode(real_T *rtmTFinal); + +extern void rtParseArgsForExtMode(int_T argc, + const char_T *argv[]); + +extern void rtERTExtModeStartMsg(void); + +#else /* #ifdef EXTMODE */ + +#if defined(VXWORKS) + #define rtExtModeTornadoStartup(ei, \ + numSampTimes, \ + stopReqPtr, \ + priority, \ + stack_size, \ + startStopSem) /* do nothing */ + #define rtExtModeTornadoCleanup(numSampTimes); /* do nothing */ + #define rtExtModeTornadoSetPortInExtUD(port); /* do nothing */ +#elif defined(C6000_EXT_MODE) + #define rtExtModePauseIfNeeded(ei,st,sr) /* do nothing */ + #define rtExtModeWaitForStartPkt(ei,st,sr) /* do nothing */ +#else + #define rtExtModePauseIfNeeded(ei,st,sr) /* do nothing */ + #define rtExtModeWaitForStartPkt(ei,st,sr) /* do nothing */ +#endif /* #ifdef VXWORKS */ + +#define rtExtModeOneStep(ei,st,sr) /* do nothing */ +#define rtExtModeCheckEndTrigger() /* do nothing */ +#define rtExtModeUploadCheckTrigger(numSampTimes) /* do nothing */ +#define rtExtModeUpload(t,ttime) /* do nothing */ +#define rtExtModeCheckInit(numSampTimes) /* do nothing */ +#define rtExtModeShutdown(numSampTimes) /* do nothing */ +#define rtExtModeParseArgs(argc, argv, tf); /* do nothing */ +#define rtERTExtModeSetTFinal(tf); /* do nothing */ +#define rtSetTFinalForExtMode(tf); /* do nothing */ +#define rtParseArgsForExtMode(argc, argv); (void)(argc); \ + (void)(argv); +#define rtERTExtModeStartMsg(); /* do nothing */ + +#endif /* #ifdef EXTMODE */ + +#ifdef __cplusplus +} +#endif + +#endif /* __EXT_WORK_OBJECT__ */ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/rtw/c/src/rt_logging.c b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/rtw/c/src/rt_logging.c new file mode 100644 index 0000000..97c7df1 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/rtw/c/src/rt_logging.c @@ -0,0 +1,4292 @@ +/* + * + * Copyright 1994-2018 The MathWorks, Inc. + * + * File: rt_logging.c + * + * Abstract: + * Real-Time Workshop data logging routines using circular buffers of + * fixed size. The buffers are allocated at start, filled in at each + * major time step and finally written to a MAT-file at the end of the + * simulation. + * + * This file handles redefining the following standard MathWorks types + * (see tmwtypes.h): + * [u]int8_T to be int32_T (logged as Matlab [u]int32) + * [u]int16_T to be int32_T (logged as Matlab [u]int32) + * real_T to be real32_T (logged as Matlab single) + * + */ + +#include +#include +#include +#include +#include + + +#if !defined(MAT_FILE) || (defined(MAT_FILE) && MAT_FILE == 1) + +#include /* size_t */ +#include "rt_logging.h" +#include "rt_mxclassid.h" +#include "rtw_matlogging.h" + +#ifndef TMW_NAME_LENGTH_MAX +#define TMW_NAME_LENGTH_MAX 64 +#endif +#define mxMAXNAM TMW_NAME_LENGTH_MAX /* maximum name length */ +#define matUNKNOWN 0 +#define matINT8 1 +#define matUINT8 2 +#define matINT16 3 +#define matUINT16 4 +#define matINT32 5 +#define matUINT32 6 +#define matFLOAT 7 +#define matDOUBLE 9 +#define matINT64 12 +#define matUINT64 13 +#define matMATRIX 14 + +#define matLOGICAL_BIT 0x200 +#define matCOMPLEX_BIT 0x800 + +#define matKEY 0x4D49 +#define matVERSION 0x0100 +#define matVERSION_INFO_OFFSET 124L + +#define matINT64_ALIGN(e) ( ( ((unsigned)(e))+7 ) & (~7) ) +#define matTAG_SIZE (sizeof(int32_T) << 1) + +#ifndef DEFAULT_BUFFER_SIZE +#define DEFAULT_BUFFER_SIZE 1024 /* used if maxRows=0 and Tfinal=0.0 */ +#endif + +#define FREE(m) if (m != NULL) free(m) + +/* Logical definitions */ +#if (!defined(__cplusplus)) +# ifndef false +# define false (0U) +# endif +# ifndef true +# define true (1U) +# endif +#endif + +/*==========* + * typedefs * + *==========*/ + +typedef struct LogInfo_Tag { + LogVar *t; /* Time log variable */ + void *x; /* State log variable */ + int_T ny; /* Length of "y" log variables */ + void **y; /* Output log vars */ + void *xFinal; /* Final state log variable */ + + LogVar *logVarsList; /* Linked list of all LogVars */ + StructLogVar *structLogVarsList; /* Linked list of all StructLogVars */ + + boolean_T haveLogVars; /* Are logging one or more vars? */ +} LogInfo; + +typedef struct MatItem_tag { + int32_T type; + uint32_T nbytes; + const void *data; +} MatItem; + +typedef enum { + DATA_ITEM, + MATRIX_ITEM, + STRUCT_LOG_VAR_ITEM, + SIGNALS_STRUCT_ITEM +} ItemDataKind; + +/*===========* + * Constants * + *===========*/ + +static const char_T rtMemAllocError[] = "Memory allocation error"; + +#define ZEROS32 "\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" + +#if mxMAXNAM==32 + +#define ZERO_PAD + +#elif mxMAXNAM==64 + +#define ZERO_PAD ZEROS32 + +#elif mxMAXNAM==128 + +#define ZERO_PAD ZEROS32 ZEROS32 ZEROS32 + +#else + +#error "Cannot Handle mxMAXNAM other than 32,64, and 128" + +#endif +/* field names: for variable-size signal logging */ +static const char_T rtStructLogVarFieldNames[] = + "time\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "signals\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "blockName\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD; +static const char_T rtLocalLoggingSignalsStructFieldNames[] = + "values\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "valueDimensions\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "dimensions\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "label\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "title\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "plotStyle\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD; +static const char_T rtGlobalLoggingSignalsStructFieldNames[] = + "values\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "valueDimensions\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "dimensions\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "label\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "blockName\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "stateName\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "inReferencedModel\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD; +#define TIME_FIELD_NAME (rtStructLogVarFieldNames[0*mxMAXNAM]) +#define SIGNALS_FIELD_NAME (rtStructLogVarFieldNames[1*mxMAXNAM]) +#define BLOCKNAME_FIELD_NAME (rtStructLogVarFieldNames[2*mxMAXNAM]) + +#define VALUES_FIELD_NAME (rtLocalLoggingSignalsStructFieldNames[0*mxMAXNAM]) +#define VALUEDIMENSIONS_FIELD_NAME (rtLocalLoggingSignalsStructFieldNames[1*mxMAXNAM]) +#define DIMENSION_FIELD_NAME (rtLocalLoggingSignalsStructFieldNames[2*mxMAXNAM]) +#define LABEL_FIELD_NAME (rtLocalLoggingSignalsStructFieldNames[3*mxMAXNAM]) +#define TITLE_FIELD_NAME (rtLocalLoggingSignalsStructFieldNames[4*mxMAXNAM]) +#define PLOTSTYLE_FIELD_NAME (rtLocalLoggingSignalsStructFieldNames[5*mxMAXNAM]) + +#define STATENAME_FIELD_NAME (rtGlobalLoggingSignalsStructFieldNames[5*mxMAXNAM]) +#define CROSS_MDL_REF_FIELD_NAME (rtGlobalLoggingSignalsStructFieldNames[6*mxMAXNAM]) + +/* field names: for fixed-size signal logging */ +static const char_T rtLocalLoggingSignalsStructFieldNames_noValDims[] = + "values\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "dimensions\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "label\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "title\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "plotStyle\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD; +static const char_T rtGlobalLoggingSignalsStructFieldNames_noValDims[] = + "values\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "dimensions\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "label\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "blockName\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "stateName\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD + "inReferencedModel\0\0\0\0\0\0\0\0\0\0\0\0\0\0\0" ZERO_PAD; + +extern real_T rtInf; /* declared by rt_nonfinite.c */ +extern real_T rtNaN; +extern real32_T rtNaNF; + +/*================* + * Local routines * + *================*/ + +/* Function: rt_GetSizeofDataType ============================================== + * Abstract: + * Get the element size in bytes given the data type id. + */ +static size_t rt_GetSizeofDataType(BuiltInDTypeId dTypeID) +{ + size_t elSz = 0; /* unknown */ + + switch (dTypeID) { + case SS_DOUBLE: + elSz = sizeof(real_T); + break; + case SS_SINGLE: + elSz = sizeof(real32_T); + break; + case SS_INT8: + elSz = sizeof(int8_T); + break; + case SS_UINT8: + elSz = sizeof(uint8_T); + break; + case SS_INT16: + elSz = sizeof(int16_T); + break; + case SS_UINT16: + elSz = sizeof(uint16_T); + break; + case SS_INT32: + elSz = sizeof(int32_T); + break; + case SS_UINT32: + elSz = sizeof(uint32_T); + break; + case SS_BOOLEAN: + elSz = sizeof(boolean_T); + break; + } + return(elSz); + +} /* end rt_GetSizeofDataType */ + + +/* Function: rt_GetSizeofComplexType =========================================== + * Abstract: + * Get the element size in bytes given the data type id. + */ +static size_t rt_GetSizeofComplexType(BuiltInDTypeId dTypeID) +{ + size_t elSz = 2*rt_GetSizeofDataType(dTypeID); + + switch (dTypeID) { + case SS_DOUBLE: + #ifdef CREAL_T + elSz = sizeof(creal_T); + #endif + break; + case SS_SINGLE: + #ifdef CREAL_T + elSz = sizeof(creal32_T); + #endif + break; + case SS_INT8: + #ifdef CINT8_T + elSz = sizeof(cint8_T); + #endif + break; + case SS_UINT8: + #ifdef CUINT8_T + elSz = sizeof(cuint8_T); + #endif + break; + case SS_INT16: + #ifdef CINT16_T + elSz = sizeof(cint16_T); + #endif + break; + case SS_UINT16: + #ifdef CUINT16_T + elSz = sizeof(cuint16_T); + #endif + break; + case SS_INT32: + #ifdef CINT32_T + elSz = sizeof(cint32_T); + #endif + break; + case SS_UINT32: + #ifdef CUINT32_T + elSz = sizeof(cuint32_T); + #endif + break; + case SS_BOOLEAN: + elSz = sizeof(boolean_T); + break; + } + + return(elSz); + +} /* end rt_GetSizeofComplexType */ + + +/* Function: rt_GetDataTypeConvertInfo ========================================= + * Abstract: + * Directly copy if pointer to structure is non-NULL, otherwise set to + * default. + */ +static RTWLogDataTypeConvert rt_GetDataTypeConvertInfo( + const RTWLogDataTypeConvert *pDataTypeConvertInfo, + BuiltInDTypeId dTypeID + ) +{ + RTWLogDataTypeConvert dataTypeConvertInfoCopy; + + if (pDataTypeConvertInfo == NULL) { + dataTypeConvertInfoCopy.conversionNeeded = 0; + dataTypeConvertInfoCopy.dataTypeIdLoggingTo = dTypeID; + dataTypeConvertInfoCopy.dataTypeIdOriginal = (DTypeId)dTypeID; + dataTypeConvertInfoCopy.bitsPerChunk = 0; + dataTypeConvertInfoCopy.numOfChunk = 0; + dataTypeConvertInfoCopy.isSigned = 0; + dataTypeConvertInfoCopy.fracSlope = 1.0; + dataTypeConvertInfoCopy.fixedExp = 0; + dataTypeConvertInfoCopy.bias = 0.0; + } else { + dataTypeConvertInfoCopy = *pDataTypeConvertInfo; + } + + return dataTypeConvertInfoCopy; + +} /* end rt_GetDataTypeConvertInfo */ + + +/* Function: rt_GetDblValueFromOverSizedData =================================== + * Abstract: + */ +static double rt_GetDblValueFromOverSizedData( + const void *pVoid, + int bitsPerChunk, + int numOfChunk, + unsigned int isSigned, + double fracSlope, + int fixedExp, + double bias) +{ + double retValue = 0; + + double *dblValue = (double *) calloc(numOfChunk, sizeof(double)); + + int i; + double isSignedNeg; + + if(isSigned) { + const chunk_T *pData = (const chunk_T *) (pVoid); + for (i = 0; i 0; i--) { + isSignedNeg = dblValue[i - 1] < 0 ? (double)isSigned : 0; + retValue = retValue + isSignedNeg; + + retValue = ldexp(retValue, bitsPerChunk)+ dblValue[i-1]; + } + retValue = ldexp( fracSlope * retValue, fixedExp ) + bias; + + FREE(dblValue); + return (retValue); + +} /* end rt_GetDblValueFromOverSizedData */ + + +/* Function: rt_GetNonBoolMxIdFromDTypeId ====================================== + * Abstract: + * Get the mx???_CLASS given the simulink builtin data type id. + */ +static mxClassID rt_GetNonBoolMxIdFromDTypeId(BuiltInDTypeId dTypeID) +{ + mxClassID mxID; + + switch (dTypeID) { + case SS_DOUBLE: + mxID = (sizeof(real_T)==4? mxSINGLE_CLASS: mxDOUBLE_CLASS); + break; + case SS_SINGLE: + mxID = mxSINGLE_CLASS; + break; + case SS_INT8: + switch (sizeof(int8_T)) { + case 4: /* polyspace DEFECT:DEAD_CODE [Not a defect:Unset] + "Needed for when PWS maps int8_T into 32-bits" */ + mxID = mxINT32_CLASS; + break; + case 2: /* polyspace DEFECT:DEAD_CODE [Not a defect:Unset] + "Needed for when PWS maps int8_T into 16-bits" */ + mxID = mxINT16_CLASS; + break; + case 1: + mxID = mxINT8_CLASS; + break; + default: /* polyspace DEFECT:DEAD_CODE [Not a defect:Unset] + "Needed to handle an unknown data type ID" */ + mxID = mxUNKNOWN_CLASS; + break; + } + break; + case SS_UINT8: + switch (sizeof(uint8_T)) { + case 4: /* polyspace DEFECT:DEAD_CODE [Not a defect:Unset] + "Needed for when PWS maps uint8_T into 32-bits" */ + mxID = mxUINT32_CLASS; + break; + case 2: /* polyspace DEFECT:DEAD_CODE [Not a defect:Unset] + "Needed for when PWS maps uint8_T into 16-bits" */ + mxID = mxUINT16_CLASS; + break; + case 1: + mxID = mxUINT8_CLASS; + break; + default: /* polyspace DEFECT:DEAD_CODE [Not a defect:Unset] + "Needed to handle an unknown data type ID" */ + mxID = mxUNKNOWN_CLASS; + break; + } + break; + case SS_INT16: + mxID = (sizeof(int16_T)==4? mxINT32_CLASS: mxINT16_CLASS); + break; + case SS_UINT16: + mxID = (sizeof(uint16_T)==4? mxUINT32_CLASS: mxUINT16_CLASS); + break; + case SS_INT32: + mxID = mxINT32_CLASS; + break; + case SS_UINT32: + mxID = mxUINT32_CLASS; + break; + /*case SS_BOOLEAN: + mxID = (sizeof(boolean_T)==4? mxUINT32_CLASS: mxLOGICAL_CLASS); + break;*/ + default: + mxID = mxUNKNOWN_CLASS; + break; + } + + return(mxID); + +} /* end rt_GetNonBoolMxIdFromDTypeId */ + + + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Function: rt_GetMxIdFromDTypeIdForRSim ====================================== + * Abstract: + * Get the mx???_CLASS given the simulink builtin data type id. + */ +mxClassID rt_GetMxIdFromDTypeIdForRSim(BuiltInDTypeId dTypeID) +{ + mxClassID mxID; + + if (dTypeID == SS_BOOLEAN) { + switch (sizeof(boolean_T)) { + case 4: /* polyspace DEFECT:DEAD_CODE [Not a defect:Unset] + "Needed for when PWS maps boolean_T into 32-bits" */ + mxID = mxUINT32_CLASS; + break; + case 2: /* polyspace DEFECT:DEAD_CODE [Not a defect:Unset] + "Needed for when PWS maps boolean_T into 16-bits" */ + mxID = mxUINT16_CLASS; + break; + default: + mxID = mxLOGICAL_CLASS; + break; + } + } else { + mxID = rt_GetNonBoolMxIdFromDTypeId(dTypeID); + } + + return(mxID); + +} /* end rt_GetMxIdFromDTypeIdForRSim */ + + +#ifdef __cplusplus +} +#endif + + + + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Function: rt_GetMxIdFromDTypeId ============================================= + * Abstract: + * Get the mx???_CLASS given the simulink builtin data type id. + */ +mxClassID rt_GetMxIdFromDTypeId(BuiltInDTypeId dTypeID) +{ + mxClassID mxID; + + if (dTypeID == SS_BOOLEAN) { + switch (sizeof(boolean_T)) { + case 4: /* polyspace DEFECT:DEAD_CODE [Not a defect:Unset] + "Needed for when PWS maps boolean_T into 32-bits" */ + mxID = mxUINT32_CLASS; + break; + case 2: /* polyspace DEFECT:DEAD_CODE [Not a defect:Unset] + "Needed for when PWS maps boolean_T into 16-bits" */ + mxID = mxUINT16_CLASS; + break; + default: + mxID = mxUINT8_CLASS; + break; + } + } else { + mxID = rt_GetNonBoolMxIdFromDTypeId(dTypeID); + } + return(mxID); + +} /* end rt_GetMxIdFromDTypeId */ + + +#ifdef __cplusplus +} +#endif + + + +/* Function: rt_GetMatIdFromMxId =============================================== + * Abstract: + * Get the MatId given the mxClassID. + */ +static int_T rt_GetMatIdFromMxId(mxClassID mxID) +{ + int_T matID; + + switch (mxID) { + case mxCELL_CLASS: + case mxSTRUCT_CLASS: + case mxOBJECT_CLASS: + matID = -1; + break; + case mxCHAR_CLASS: + matID = matUINT16; + break; + case mxDOUBLE_CLASS: + matID = matDOUBLE; + break; + case mxSINGLE_CLASS: + matID = matFLOAT; + break; + case mxINT8_CLASS: + matID = matINT8; + break; + case mxUINT8_CLASS: + matID = matUINT8; + break; + case mxINT16_CLASS: + matID = matINT16; + break; + case mxUINT16_CLASS: + matID = matUINT16; + break; + case mxINT32_CLASS: + matID = matINT32; + break; + case mxUINT32_CLASS: + matID = matUINT32; + break; + case mxINT64_CLASS: + matID = matINT64; + break; + case mxUINT64_CLASS: + matID = matUINT64; + break; + default: + matID = matUNKNOWN; + break; + } + return(matID); + +} /* end rt_GetMatIdFromMxId */ + + +/* Forward declaration */ +static int_T rt_WriteItemToMatFile(FILE *fp, + MatItem *pItem, + ItemDataKind dataKind); + + +/* Function: rt_ProcessMatItem ================================================= + * Abstract: + * This routine along with rt_WriteItemToMatFile() write out a specified + * mat-item the .mat file. Note that if the input argument + * cmd == 0, then this function just calculates the size of the item. + * cmd <> 0, this function writes the mat-item to the file. + * Return values is + * -1 : coding/logic error + * 0 : upon success + * > 0 : upon write failure (1) + */ +static int_T rt_ProcessMatItem(FILE *fp, + MatItem *pItem, + ItemDataKind itemKind, + int_T cmd) +{ + mxClassID mxID = mxUNKNOWN_CLASS; + uint32_T arrayFlags[2] = {0, 0}; + int32_T *dims = NULL; + int32_T _dims[3] = {0, 0, 0}; + int32_T nDims = 2; + int32_T nBytesInItem = 0; + const char_T *itemName; + MatItem item; + int_T retStat = 0; + + switch (itemKind) { + case DATA_ITEM: { + (void)fprintf(stderr,"Unexpected itemKind = DATA_ITEM in " + "rt_ProcessMatItem @A\n"); + retStat = -1; + goto EXIT_POINT; + } + case MATRIX_ITEM: { + const MatrixData *var = (const MatrixData *) pItem->data; + + mxID = var->mxID; + arrayFlags[0] = mxID; + arrayFlags[0] |= var->logical; + arrayFlags[0] |= var->complex; + if (var->nDims < 2) { + dims = _dims; + dims[0] = var->nRows; + dims[1] = var->nCols; + nDims = 2; + } else { + int32_T k; + dims = (int32_T*)malloc(sizeof(int32_T)*(var->nDims+1)); + for (k = 0; k < var->nDims; k++) { + dims[k] = var->dims[k]; + } + dims[var->nDims] = var->nRows; + nDims = var->nDims + 1; + } + itemName = var->name; + break; + } + case STRUCT_LOG_VAR_ITEM: { + const StructLogVar *var = (const StructLogVar *) pItem->data; + + mxID = mxSTRUCT_CLASS; + arrayFlags[0] = mxID; + dims = _dims; + dims[0] = 1; + dims[1] = 1; + itemName = var->name; + break; + } + case SIGNALS_STRUCT_ITEM: { + const SignalsStruct *var = (const SignalsStruct *) pItem->data; + + mxID = mxSTRUCT_CLASS; + arrayFlags[0] = mxID; + dims = _dims; + dims[0] = 1; + dims[1] = var->numSignals; + itemName = &SIGNALS_FIELD_NAME; + break; + } + default: + (void)fprintf(stderr,"Unexpected itemKind=%d in rt_ProcessMatItem @B\n", + itemKind); + retStat = -1; + goto EXIT_POINT; + } + + /* array flags */ + item.nbytes = 2*sizeof(uint32_T); + if (cmd) { + item.type = matUINT32; + item.data = arrayFlags; + if (rt_WriteItemToMatFile(fp,&item, DATA_ITEM)) { + retStat = 1; + goto EXIT_POINT; + } + } else { + /*LINTED E_CAST_INT_TO_SMALL_INT*/ + nBytesInItem += matINT64_ALIGN(matTAG_SIZE + item.nbytes); + } + /* dimensions */ + /*LINTED E_ASSIGN_INT_TO_SMALL_INT*/ + item.nbytes = nDims*sizeof(int32_T); + if (cmd) { + item.type = matINT32; + item.data = dims; + if (rt_WriteItemToMatFile(fp,&item, DATA_ITEM)) { + retStat = 1; + goto EXIT_POINT; + } + } else { + /*LINTED E_CAST_INT_TO_SMALL_INT*/ + nBytesInItem += matINT64_ALIGN(matTAG_SIZE + item.nbytes); + } + /* name */ + item.nbytes = (int32_T)strlen(itemName); + if (cmd) { + item.type = matINT8; + item.data = (const char_T*) itemName; + if (rt_WriteItemToMatFile(fp,&item, DATA_ITEM)) { + retStat = 1; + goto EXIT_POINT; + } + } else { + nBytesInItem += (item.nbytes <= 4) ? /*LINTED E_CAST_INT_TO_SMALL_INT*/ + matTAG_SIZE : matINT64_ALIGN(matTAG_SIZE + item.nbytes); + } + + if (itemKind == MATRIX_ITEM) { + const MatrixData *var = (const MatrixData*) pItem->data; + int_T matID = rt_GetMatIdFromMxId(mxID); + size_t elSize = var->elSize; + + /* data */ + item.nbytes = (int32_T)(var->nRows * var->nCols * elSize); + if (cmd) { + item.type = matID; + item.data = var->re; + if (rt_WriteItemToMatFile(fp, &item, DATA_ITEM)) { + retStat = 1; + goto EXIT_POINT; + } + } else { + nBytesInItem += (item.nbytes <= 4) ? /*LINTED*/ + matTAG_SIZE : matINT64_ALIGN(matTAG_SIZE + item.nbytes); + } + /* imaginary part */ + if (var->complex) { + item.nbytes = (int32_T)(var->nRows * var->nCols * elSize); + if (cmd) { + item.type = matID; + item.data = var->im; + if (rt_WriteItemToMatFile(fp, &item, DATA_ITEM)) { + retStat = 1; + goto EXIT_POINT; + } + } else { + nBytesInItem += (item.nbytes <= 4) ? /*LINTED*/ + matTAG_SIZE : matINT64_ALIGN(matTAG_SIZE + item.nbytes); + } + } + } else { /* some type of structure item */ + const char_T *fieldNames; + int_T sizeofFieldNames; + + /* field names */ + switch (itemKind) { + case STRUCT_LOG_VAR_ITEM: { + const StructLogVar *var = (const StructLogVar *) pItem->data; + fieldNames = rtStructLogVarFieldNames; + sizeofFieldNames = var->numActiveFields * mxMAXNAM; + break; + } + case SIGNALS_STRUCT_ITEM: { + const SignalsStruct *var = (const SignalsStruct *) pItem->data; + fieldNames = var->fieldNames; + sizeofFieldNames = var->numActiveFields * mxMAXNAM; + break; + } + default: /* polyspace DEFECT:DEAD_CODE [Not a defect:Unset] + "Needed to handle an unknown itemKind" */ + (void)fprintf(stderr, "Unexpected itemKind=%d in " + "rt_ProcessMatItem @C\n", itemKind); + retStat = -1; + goto EXIT_POINT; + } + + /* write field names */ + if (cmd) { + int32_T tmpInt = mxMAXNAM; + + item.nbytes = sizeof(int32_T); + item.type = matINT32; + item.data = &tmpInt; + if (rt_WriteItemToMatFile(fp,&item, DATA_ITEM)) { + retStat = 1; + goto EXIT_POINT; + } + + item.nbytes = sizeofFieldNames; + item.type = matINT8; + item.data = (const char_T*) fieldNames; + if (rt_WriteItemToMatFile(fp,&item, DATA_ITEM)) { + retStat = 1; + goto EXIT_POINT; + } + } else { + /*LINTED E_CAST_INT_TO_SMALL_INT*/ + nBytesInItem += matINT64_ALIGN( matTAG_SIZE + matTAG_SIZE + + sizeofFieldNames ); + } + + /* process each field of the structure */ + switch (itemKind) { + case STRUCT_LOG_VAR_ITEM: { + const StructLogVar *var = pItem->data; + + /* time */ + { + const void *data = var->time; + + if (var->logTime) { /* time is a LogVar, get the MatrixData */ + data = &(((const LogVar*) (var->time))->data); + } + + item.type = matMATRIX; + item.data = data; + if (cmd) { + if (rt_WriteItemToMatFile(fp,&item,MATRIX_ITEM)){ + retStat = 1; + goto EXIT_POINT; + } + } else { + if (rt_ProcessMatItem(fp, &item, MATRIX_ITEM,0)){ + retStat = 1; + goto EXIT_POINT; + } + nBytesInItem += item.nbytes + matTAG_SIZE; + } + } + + /* signals */ + item.type = matMATRIX; + item.data = &(var->signals); + if (cmd) { + if (rt_WriteItemToMatFile(fp,&item,SIGNALS_STRUCT_ITEM)) { + retStat = 1; + goto EXIT_POINT; + } + } else { + if (rt_ProcessMatItem(fp, &item, SIGNALS_STRUCT_ITEM,0)) { + retStat = 1; + goto EXIT_POINT; + } + nBytesInItem += item.nbytes + matTAG_SIZE; + } + + /* block name */ + if (var->blockName != NULL) { + item.type = matMATRIX; + item.data = var->blockName; + if (cmd) { + if (rt_WriteItemToMatFile(fp, &item, MATRIX_ITEM)) { + retStat = 1; + goto EXIT_POINT; + } + } else { + if (rt_ProcessMatItem(fp, &item, MATRIX_ITEM, 0)) { + retStat = 1; + goto EXIT_POINT; + } + nBytesInItem += item.nbytes + matTAG_SIZE; + } + } + break; + } + case SIGNALS_STRUCT_ITEM: { + const SignalsStruct *var = pItem->data; + const LogVar *values = var->values; + const MatrixData *dimensions = var->dimensions; + const MatrixData *labels = var->labels; + const MatrixData *plotStyles = var->plotStyles; + const MatrixData *titles = var->titles; + const MatrixData *blockNames = var->blockNames; + const MatrixData *stateNames = var->stateNames; + const MatrixData *crossMdlRef = var->crossMdlRef; + const boolean_T logValueDimensions = var->logValueDimensions; + int_T i; + + for (i = 0; i < var->numSignals; i++) { + /* values */ + item.type = matMATRIX; + item.data = &(values->data); + if (cmd) { + if (rt_WriteItemToMatFile(fp, &item,MATRIX_ITEM)) { + retStat = 1; + goto EXIT_POINT; + } + } else { + if (rt_ProcessMatItem(fp, &item, MATRIX_ITEM, 0)) { + retStat = 1; + goto EXIT_POINT; + } + nBytesInItem += item.nbytes + matTAG_SIZE; + } + + if(logValueDimensions) + { + /* valueDimensions */ + /* Since the functions rt_WriteItemToMatFile and + rt_ProcessMatItem deal with MatrixData, + convert valDims to tempData, and fill up the + necessary fields. + */ + MatrixData tempData; + (void)memcpy(tempData.name, &VALUEDIMENSIONS_FIELD_NAME, mxMAXNAM); + tempData.nRows = values->valDims->nRows; + tempData.nCols = values->valDims->nCols; + tempData.nDims = 1; + tempData._dims[0] = values->valDims->nCols; + tempData.re = values->valDims->dimsData; + tempData.im = NULL; + tempData.dTypeID = SS_DOUBLE; + tempData.elSize = sizeof(real_T); + tempData.mxID = mxDOUBLE_CLASS; + tempData.logical = 0; + tempData.complex = 0; + tempData.frameData = 0; + tempData.frameSize = 1; + + item.type = matMATRIX; + item.data = &tempData; /*values->valDims;*/ + + if (cmd) { + if (rt_WriteItemToMatFile(fp, &item,MATRIX_ITEM)) { + retStat = 1; + goto EXIT_POINT; + } + } else { + if (rt_ProcessMatItem(fp, &item, MATRIX_ITEM, 0)) { + retStat = 1; + goto EXIT_POINT; + } + nBytesInItem += item.nbytes + matTAG_SIZE; + } + } + values = values->next; + + /* dimensions */ + if (dimensions != NULL) { + item.type = matMATRIX; + item.data = &(dimensions[i]); + if (cmd) { + if (rt_WriteItemToMatFile(fp,&item, MATRIX_ITEM)) { + retStat = 1; + goto EXIT_POINT; + } + } else { + if (rt_ProcessMatItem(fp, &item, MATRIX_ITEM, 0)) { + retStat = 1; + goto EXIT_POINT; + } + nBytesInItem += item.nbytes + matTAG_SIZE; + } + } + + /* label */ + item.type = matMATRIX; + item.data = &(labels[i]); + if (cmd) { + if (rt_WriteItemToMatFile(fp, &item,MATRIX_ITEM)) { + retStat = 1; + goto EXIT_POINT; + } + } else { + if (rt_ProcessMatItem(fp, &item, MATRIX_ITEM, 0)) { + retStat = 1; + goto EXIT_POINT; + } + nBytesInItem += item.nbytes + matTAG_SIZE; + } + /* title */ + if (titles != NULL) { + item.type = matMATRIX; + item.data = &(titles[i]); + if (cmd) { + if (rt_WriteItemToMatFile(fp, &item, MATRIX_ITEM)) { + retStat = 1; + goto EXIT_POINT; + } + } else { + if (rt_ProcessMatItem(fp, &item, MATRIX_ITEM, 0)) { + retStat = 1; + goto EXIT_POINT; + } + nBytesInItem += item.nbytes + matTAG_SIZE; + } + } + /* plot style */ + if (plotStyles != NULL) { + item.type = matMATRIX; + item.data = &(plotStyles[i]); + if (cmd) { + if (rt_WriteItemToMatFile(fp,&item, MATRIX_ITEM)) { + retStat = 1; + goto EXIT_POINT; + } + } else { + if (rt_ProcessMatItem(fp, &item, MATRIX_ITEM, 0)) { + retStat = 1; + goto EXIT_POINT; + } + nBytesInItem += item.nbytes + matTAG_SIZE; + } + } + /* block name */ + if (blockNames != NULL) { + item.type = matMATRIX; + item.data = &(blockNames[i]); + if (cmd) { + if (rt_WriteItemToMatFile(fp, &item, MATRIX_ITEM)) { + retStat = 1; + goto EXIT_POINT; + } + } else { + if (rt_ProcessMatItem(fp, &item, MATRIX_ITEM, 0)) { + retStat = 1; + goto EXIT_POINT; + } + nBytesInItem += item.nbytes + matTAG_SIZE; + } + } + /* state name */ + if (stateNames != NULL) { + item.type = matMATRIX; + item.data = &(stateNames[i]); + if (cmd) { + if (rt_WriteItemToMatFile(fp, &item, MATRIX_ITEM)) { + retStat = 1; + goto EXIT_POINT; + } + } else { + if (rt_ProcessMatItem(fp, &item, MATRIX_ITEM, 0)) { + retStat = 1; + goto EXIT_POINT; + } + nBytesInItem += item.nbytes + matTAG_SIZE; + } + } + /* crossMdlRef */ + if (crossMdlRef != NULL) { + item.type = matMATRIX; + item.data = &(crossMdlRef[i]); + if (cmd) { + if (rt_WriteItemToMatFile(fp, &item, MATRIX_ITEM)) { + retStat = 1; + goto EXIT_POINT; + } + } else { + if (rt_ProcessMatItem(fp, &item, MATRIX_ITEM, 0)) { + retStat = 1; + goto EXIT_POINT; + } + nBytesInItem += item.nbytes + matTAG_SIZE; + } + } + } /* for i=1:numSignals */ + break; + } + default: /* polyspace DEFECT:DEAD_CODE [Not a defect:Unset] + "Needed to handle an unknown itemKind" */ + (void)fprintf(stderr, "Unexpected itemKind=%d in " + "rt_ProcessMatItem @D\n", itemKind); + retStat = -1; + goto EXIT_POINT; + } + } /* end struct item */ + + if (!cmd) { + pItem->nbytes = nBytesInItem; + } + + EXIT_POINT: + if (dims != _dims) { + FREE(dims); + } + return(retStat); + +} /* end rt_ProcessMatItem */ + + +/* Function: rt_WriteItemToMatFile ============================================= + * Abstract: + * Entry function for writing out a mat item to the mat file. + * + * Return values is + * == 0 : upon success + * <> 0 : upon failure + */ +static int_T rt_WriteItemToMatFile(FILE *fp, + MatItem *pItem, + ItemDataKind itemKind) +{ + /* Determine the item size */ + if (pItem->type == matMATRIX) { + if (rt_ProcessMatItem(fp, pItem, itemKind, 0)) return(1); + } + + /* Write the item tag and data */ + if (pItem->nbytes > 4) { + int32_T nAlignBytes; + + if (fwrite(pItem, 1, matTAG_SIZE, fp) != matTAG_SIZE) return(1); + + if (pItem->type == matMATRIX) { + if (rt_ProcessMatItem(fp, pItem, itemKind, 1)) return(1); + } else { + if ( fwrite(pItem->data, 1, pItem->nbytes, fp) != + ((size_t) pItem->nbytes) ) { + return(1); + } + } + + /* Add offset for 8-byte alignment */ + nAlignBytes = matINT64_ALIGN(pItem->nbytes) - pItem->nbytes; + if (nAlignBytes > 0) { + int pad[2] = {0, 0}; + if ( fwrite(pad,1,nAlignBytes,fp) != ((size_t) nAlignBytes) ) { + return(1); + } + } + } else { + MatItem item = {0, 0, NULL}; + item.type = ((uint32_T)(pItem->type))|(((uint32_T)(pItem->nbytes))<<16); + (void)memcpy(&item.nbytes, pItem->data, pItem->nbytes); + if (fwrite(&item, 1, matTAG_SIZE, fp) != matTAG_SIZE) return(1); + } + + return(0); + +} /* end rt_WriteItemToMatFile */ + + +/* Function: rt_WriteMat5FileHeader ============================================ + * Abstract: + * Function to write the mat file header. + * Return values is + * == 0 : upon success + * <> 0 : upon failure + */ +static int_T rt_WriteMat5FileHeader(FILE *fp) +{ + int_T nbytes; + int_T nspaces; + int_T i, n; + unsigned short ver[2]; + char_T spaces[16]; + const char_T *matversion = "MATLAB 5.0 MAT-file"; + + (void)memset(spaces, ' ', sizeof(spaces)); + + n = (int_T)strlen(matversion); + nbytes = (int_T)fwrite(matversion, 1, n, fp); + /*LINTED E_ASSIGN_INT_TO_SMALL_INT*/ + nspaces = matVERSION_INFO_OFFSET - nbytes; + /*LINTED E_ASSIGN_INT_TO_SMALL_INT*/ + n = nspaces % sizeof(spaces); + nbytes += (int_T)fwrite(spaces, 1, n, fp); + /*LINTED E_ASSIGN_INT_TO_SMALL_INT*/ + n = nspaces / sizeof(spaces); + for (i = 0; i < n; ++i) { + nbytes += (int_T)fwrite(spaces, 1, sizeof(spaces), fp); + } + if (nbytes == matVERSION_INFO_OFFSET) { + ver[0] = matVERSION; + ver[1] = matKEY; + nbytes += (int_T)fwrite(ver, 1, sizeof(ver), fp); + } + return(nbytes != matVERSION_INFO_OFFSET + sizeof(ver)); + +} /* end rt_WriteMat5FileHeader */ + + +/* Function: rt_FixupLogVar ==================================================== + * Abstract: + * Make the logged variable suitable for MATLAB. + */ +static const char_T *rt_FixupLogVar(LogVar *var,int verbose) +{ + int_T nCols = var->data.nCols; + int_T maxRows = var->data.nRows; + int_T nDims = var->data.nDims; + size_t elSize = var->data.elSize; + int_T nRows = (var->wrapped ? maxRows : var->rowIdx); + + var->nDataPoints = var->rowIdx + var->wrapped * maxRows; + + if (var->wrapped > 1 || (var->wrapped == 1 && var->rowIdx != 0)) { + /* + * Warn the user the circular buffer has wrapped, implying that + * some data has been lost. + */ + if( verbose) { + (void)fprintf(stdout, + "*** Log variable %s has wrapped %d times\n" + " using a circular buffer of size %d\n", + var->data.name, var->wrapped, var->data.nRows); + } + if (var->usingDefaultBufSize) { + /* + * If wrapping occurred using the default buffer size, + * let the user know what size buffer to use in the + * future to avoid wrapping. If the default buffer + * size was not used, the user has no control to specify + * the correct value. Wrapping may occur when not using + * the default buffer if we allocated too small a buffer + * size for this logvar. One common case is a toWorkspace + * block inside of an iterative subsystem - we can not take + * the number of iterations into account (they may be + * variable) when allocating the buffer. In this case, + * just warn the buffer wrapped and don't tell user they + * can override the buffer size. + */ + if( verbose ) { + (void)fprintf(stdout, + "*** To avoid wrapping, explicitly specify a\n" + " buffer size of %d in your Simulink model\n" + " by adding OPTS=\"-DDEFAULT_BUFFER_SIZE=%d\"\n" + " as an argument to the ConfigSet MakeCommand\n" + " parameter\n", + var->nDataPoints, var->nDataPoints); + } + } + } + + if (nDims < 2 && nCols > 1) { /* Transpose? */ + /* Don't need to transpose valueDimensions */ + int_T nEl = nRows*nCols; + char *src = var->data.re; + char *pmT; + int_T k; + + /********************************** + * If memory cannot be allocated, * + * write to a temporary buffer * + **********************************/ + if ((pmT = malloc(nEl*elSize)) == NULL) { + FILE *fptr; + char fName[mxMAXNAM+13]; + + (void)sprintf(fName, "%s%s", var->data.name, "_rtw_tmw.tmw"); + if ((fptr=fopen(fName,"w+b")) == NULL) { + (void)fprintf(stderr,"*** Error opening %s",fName); + return("unable to open data file\n"); + } + + /**************************** + * Write the data to a file * + ****************************/ + for (k=0; kdata.complex) { + char *pmiT = var->data.re; + src = var->data.im; + for (k=0; kdata.re = var->data.im; + var->data.im = pmiT; + } + + /******************************* + * Read the data from the file * + *******************************/ + (void)rewind(fptr); + (void)fread(var->data.re, elSize, nEl, fptr); + (void)fclose(fptr); + (void)remove(fName); + } else { + for (k=0; kdata.complex) { + char *pmiT = var->data.re; + src = var->data.im; + for (k=0; kdata.re = var->data.im; + var->data.im = pmiT; + } + FREE(var->data.re); + var->data.re = pmT; + } + } /* Transpose? */ + + if (var->wrapped > 0 && var->rowIdx != 0 ) { /* Rotate? */ + char_T *buffer = var->data.re; + int_T done = 0; /* done: 0 (1) rotate real (imag) part. */ + + do { + char_T *col = buffer; + int_T rowOffset = (int_T)((nDims == 1) ? (elSize) : (elSize * nCols)); + int_T colOffset = (int_T)((nDims == 1)? (nRows*elSize) : elSize); + int_T zeroIdx = var->rowIdx; + int_T j; + + for (j = 0 ; j < nCols; ++j, col += colOffset) { + int_T swapCount; + int_T srcIdx; + int_T dstIdx; + int_T tmpIdx; + MatReal tmp; + + for (tmpIdx=0, swapCount=0; swapCount < nRows; tmpIdx++) { + (void)memcpy(&tmp, col + tmpIdx*rowOffset, elSize); + + dstIdx=tmpIdx; + srcIdx = ((dstIdx + zeroIdx) % nRows); + while (srcIdx != tmpIdx) { + (void)memcpy(col + dstIdx*rowOffset, + col + srcIdx*rowOffset, + elSize); + ++swapCount; + dstIdx = srcIdx; + srcIdx = ((dstIdx + zeroIdx) % nRows); + + } + (void)memcpy(col + dstIdx*rowOffset, &tmp, elSize); + ++swapCount; + } + } + done ++; + /* need to rotate the imaginary part */ + } while ((done == 1) && ((buffer = var->data.im) != NULL)); + + var->rowIdx = 0; + } /* Rotate? */ + + /* + * We might have allocated more number of rows than the number of data + * points that have been logged, in which case set nRows to nDataPoints + * so that only these values get saved. + */ + if (var->nDataPoints < var->data.nRows) { + var->data.nRows = var->nDataPoints; + if(var->valDims != NULL){ + size_t elSizeValDims = sizeof(real_T); + int_T k; + real_T *dimsData = var->valDims->dimsData + nRows; + /* + Keep nRows of values and that of valueDimensions consistent + for variable-size signals. + */ + var->valDims->nRows = var->data.nRows; + /* + Also need to move data when shrinking the array size, + because valueDimensions data is stored in array format. + e.g. maxRows = 4; nRows = 2; nDims = 3; + Before fixing up the logVar, the locations of data are as below: + (x, y, z -- useful data / o -- junk) + a[0] = x a[4] = y a[8] = z + a[1] = x a[5] = y a[9] = z + a[2] = o a[6] = o a[10]= o + a[3] = o a[7] = o a[11]= o + After fixing up the logVar, we want the data to be stored as: + a[0] = x a[4] = z a[8] = o + a[1] = x a[5] = z a[9] = o + a[2] = y a[6] = o a[10]= o + a[3] = y a[7] = o a[11]= o + */ + for(k = 1; k < nDims; k++){ + (void) memmove(dimsData, + var->valDims->dimsData + k*maxRows, + elSizeValDims * nRows); + dimsData += nRows; + } + } + } + return(NULL); + +} /* end rt_FixupLogVar */ + + +/* Function: rt_LoadModifiedLogVarName ========================================= + * Abstract: + * The name of the logged variable is obtained from the input argument + * varName and the nameModifier which is obtained from the simstruct. If + * the nameModifier begins with an '_', then nameModifier is post-pended to + * varName to obtain the name of the logged variable. If the first + * character does not begin with an '_', then the nameModifier is + * pre-pended to varName. + * + * Examples: + * a) varName = "tout" & nameModifier = "_rt" => logVarName = "tout_rt" + * b) varName = "tout" & nameModifier = "rt_" => logVarName = "rt_tout" + * c) varName = "tout" & nameModifier = "none" => logVarName = "tout" + */ +static void rt_LoadModifiedLogVarName(const RTWLogInfo *li, /* in */ + const char *varName, /* in */ + char *logVarName) /* out */ +{ + int_T nameLen; + const char_T *nameModifier = rtliGetLogVarNameModifier(li); + + if (nameModifier != NULL && strcmp(nameModifier,"none")==0) { + nameModifier = NULL; + } + + logVarName[mxMAXNAM-1] = '\0'; + if (nameModifier == NULL) { + (void)strncpy(logVarName, varName, mxMAXNAM-1); + } else if (nameModifier[0] == '_') { + (void)strncpy(logVarName, varName, mxMAXNAM-1); + nameLen = (int_T)strlen(logVarName); + (void)strncat(logVarName, nameModifier, mxMAXNAM-1-nameLen); + } else { + (void)strncpy(logVarName, nameModifier, mxMAXNAM-1); + nameLen = (int_T)strlen(logVarName); + (void)strncat(logVarName, varName, mxMAXNAM-1-nameLen); + } + +} /* end rt_LoadModifiedLogVarName */ + + +/* Function: rt_GetActualDTypeID =============================================== + * Abstract: + * Given a built-in data type id, return the actual data type id. + * The only time these are different is when real_T has been mapped + * to a single. + */ +#if defined(_MSC_VER) + #pragma warning(push) + #pragma warning(disable: 4127) +#endif +static BuiltInDTypeId rt_GetActualDTypeID(BuiltInDTypeId dTypeID) +{ + /*LINTED E_FALSE_LOGICAL_EXPR*/ + if (dTypeID == SS_DOUBLE && sizeof(real_T) != 8) { /* polyspace DEFECT:DEAD_CODE + [Not a defect:Unset] + "Needed for when reat_T has been + mapped to a single" */ + return(SS_SINGLE); + } else { + return(dTypeID); + } + +} /* end rt_GetActualDTypeID */ +#if defined(_MSC_VER) + #pragma warning(pop) +#endif + + +/* Function: rt_DestroyLogVar ================================================== + * Abstract: + * Destroy the log var linked list. + */ +static void rt_DestroyLogVar(LogVar *head) +{ + while(head) { + LogVar *var = head; + head = var->next; + FREE(var->data.re); + FREE(var->data.im); + if (var->data.dims != var->data._dims) { + FREE(var->data.dims); + } + /* free valDims if necessary */ + if(var->valDims != NULL) { + FREE(var->valDims->dimsData); + FREE(var->valDims); + } + /* free coords, strides and currStrides if necessary */ + FREE(var->coords); + FREE(var->strides); + FREE(var->currStrides); + + FREE(var); + } + +} /* end rt_DestroyLogVar */ + + +/* Function: rt_DestroyStructLogVar ============================================ + * Abstract: + * Destroy the struct log var linked list. + */ +static void rt_DestroyStructLogVar(StructLogVar *head) +{ + while(head) { + StructLogVar *var = head; + + head = var->next; + + if (var->logTime) { /* time is LogVar */ + rt_DestroyLogVar(var->time); + } else { /* time is MatrixData */ + FREE(var->time); + } + rt_DestroyLogVar(var->signals.values); + FREE(var->signals.labels); + FREE(var->signals.plotStyles); + FREE(var->signals.dimensions); + FREE(var->signals.titles); + FREE(var->signals.blockNames); + FREE(var->signals.stateNames); + FREE(var->signals.crossMdlRef); + FREE(var->blockName); + FREE(var); + } + +} /* end rt_DestroyStructLogVar */ + + +/* Function: rt_InitSignalsStruct ============================================== + * Abstract: + * Initialize the signals structure in the struct log variable. + * + * Returns: + * == NULL => success. + * ~= NULL => failure, the return value is a pointer to the error + * message, which is also set in the simstruct. + */ +static const char_T *rt_InitSignalsStruct(RTWLogInfo *li, + const real_T startTime, + const real_T finalTime, + const real_T inStepSize, + const char_T **errStatus, + StructLogVar *var, + int_T maxRows, + int_T decimation, + real_T sampleTime, + const RTWLogSignalInfo *sigInfo) +{ + int_T i, sigIdx; + SignalsStruct *sig = &(var->signals); + int_T nSignals = sigInfo->numSignals; + const int_T *numCols = sigInfo->numCols; + const int_T *numDims = sigInfo->numDims; + const int_T *dims = sigInfo->dims; + const BuiltInDTypeId *dTypes = sigInfo->dataTypes; + const int_T *cSgnls = sigInfo->complexSignals; + const int_T *fData = sigInfo->frameData; + const char_T **labels = sigInfo->labels.cptr; + const int_T *plotStyles = sigInfo->plotStyles; + const char_T *titles = sigInfo->titles; + const int_T *titleLen = sigInfo->titleLengths; + const char_T **blockNames = sigInfo->blockNames.cptr; + const char_T **stateNames = sigInfo->stateNames.cptr; + const boolean_T *crossMdlRef = sigInfo->crossMdlRef; + + void **currSigDims = sigInfo->currSigDims; + int_T *currSigDimsSize = sigInfo->currSigDimsSize; + LogVar *prevValues = NULL; + int_T dimsOffset = 0; + boolean_T *isVarDims = sigInfo->isVarDims; + /* if any signal is variable-size, the field 'valueDimensions' is needed */ + boolean_T logValueDimensions = false; + const RTWLogDataTypeConvert *pDTConvInfo = sigInfo->dataTypeConvert; + + /* reset error status */ + *errStatus = NULL; + + sig->numActiveFields = 1; + sig->numSignals = nSignals; + + sig->isVarDims = isVarDims; + /* check whether we need valueDimensions field*/ + for (i=0; ivalues == NULL) { + sig->values = values; + } else { + if (prevValues == NULL) goto ERROR_EXIT; + prevValues->next = values; + } + prevValues = values; + dimsOffset += nd; + } + + if(logValueDimensions){ + ++sig->numActiveFields; + sig->logValueDimensions = true; + } + else{ + sig->logValueDimensions = false; + } + + /* Dimensions */ + { + real_T *data; + size_t nbytes; + int_T dataLen = 0; + BuiltInDTypeId dTypeId = rt_GetActualDTypeID(SS_DOUBLE); + size_t dataOffset = nSignals*sizeof(MatrixData); + uint_T overhang = (uint_T)(dataOffset % sizeof(real_T)); + + if (overhang) { /* polyspace DEFECT:DEAD_CODE [Not a defect:Unset] + "Needed for possible padding determination. */ + dataOffset += (sizeof(real_T) - overhang); + } + for (i=0; i< nSignals; i++) { + int_T nd = (numDims) ? numDims[i] : 1; + dataLen += nd; + } + nbytes = dataOffset + dataLen*sizeof(real_T); + + if ( (sig->dimensions = calloc(nbytes, 1)) == NULL ) goto ERROR_EXIT; + + data = (real_T*) (((char_T*) (sig->dimensions)) + dataOffset); + + for (i = 0; i < dataLen; i++) { + data[i] = dims[i]; /* cannot memcpy double <- int */ + } + + for (i = 0; i < nSignals; i++) { + MatrixData *mtxData = &(sig->dimensions[i]); + int_T nd = (numDims) ? numDims[i] : 1; + + (void)memcpy(mtxData->name, &DIMENSION_FIELD_NAME, mxMAXNAM); + + mtxData->nRows = 1; + mtxData->nCols = nd; + + mtxData->nDims = 1; /* assume */ + mtxData->dims = mtxData->_dims; + mtxData->dims[0] = mtxData->nCols; + + mtxData->re = data; + mtxData->im = NULL; + mtxData->dTypeID = dTypeId; + mtxData->mxID = rt_GetMxIdFromDTypeId(dTypeId); + mtxData->elSize = rt_GetSizeofDataType(dTypeId); + mtxData->logical = 0U; + mtxData->complex = 0U; + + data += nd; + } + ++sig->numActiveFields; + } + + /* labels */ + if (labels != NULL) { + unsigned short *data; + size_t nbytes; + int_T dataLen = 0; + size_t dataOffset = nSignals * sizeof(MatrixData); + uint_T overhang = (uint_T)(dataOffset % sizeof(short)); + int_T dataIdx = 0; + + for (i=0;ilabels = calloc(nbytes, 1)) == NULL ) goto ERROR_EXIT; + + data = (unsigned short*) (((char_T*) (sig->labels)) + dataOffset); + for(sigIdx=0;sigIdxlabels[i]); + int_T labelLen = (int_T)strlen(labels[i]); + + (void)memcpy(mtxData->name, &LABEL_FIELD_NAME, mxMAXNAM); + mtxData->nRows = (labelLen) ? 1 : 0; + mtxData->nCols = labelLen; + + mtxData->re = data; + mtxData->im = NULL; + + mtxData->nDims = 1; /* assume */ + mtxData->dims = mtxData->_dims; + mtxData->dims[0] = mtxData->nCols; + + mtxData->dTypeID = SS_INT16; + mtxData->mxID = mxCHAR_CLASS; + mtxData->elSize = sizeof(short); + mtxData->logical = 0U; + mtxData->complex = 0U; + + data += labelLen; + } + ++sig->numActiveFields; + } + + /* plot styles */ + if (plotStyles != NULL) { + real_T *data; + size_t nbytes; + int_T dataLen = 0; + BuiltInDTypeId dTypeId = rt_GetActualDTypeID(SS_DOUBLE); + /*LINTED E_ASSIGN_INT_TO_SMALL_INT*/ + size_t dataOffset = nSignals*sizeof(MatrixData); + /*LINTED E_ASSIGN_INT_TO_SMALL_INT*/ + uint_T overhang = (uint_T)(dataOffset % sizeof(real_T)); + + if (overhang) { /* polyspace DEFECT:DEAD_CODE [Not a defect:Unset] + "Needed for possible padding determination. */ + dataOffset += (sizeof(real_T) - overhang); + } + for (i=0; i< nSignals; i++) { + dataLen += numCols[i]; + } + /*LINTED E_ASSIGN_INT_TO_SMALL_INT*/ + nbytes = dataOffset + dataLen*sizeof(real_T); + + if ( (sig->plotStyles = calloc(nbytes, 1)) == NULL ) goto ERROR_EXIT; + + /*LINTED E_BAD_PTR_CAST_ALIGN*/ + data = (real_T*) (((char_T*) (sig->plotStyles)) + dataOffset); + + for (i = 0; i < dataLen; i++) { + data[i] = plotStyles[i]; + } + + dimsOffset = 0; + for (i = 0; i < nSignals; i++) { + MatrixData *mtxData = &(sig->plotStyles[i]); + + (void)memcpy(mtxData->name, &PLOTSTYLE_FIELD_NAME, mxMAXNAM); + + mtxData->nRows = (numCols[i]) ? 1 : 0; + mtxData->nCols = numCols[i]; + + mtxData->nDims = numDims[i]; + + if(mtxData->nDims > 2) { + if ((mtxData->dims = calloc(mtxData->nDims, sizeof(int_T))) == NULL) goto ERROR_EXIT; + } else { + mtxData->dims = mtxData->_dims; + } + + mtxData->dims[0] = *(dims + dimsOffset); + if(mtxData->nDims >= 2) { + int32_T j; + for (j=1; jnDims; j++) { + mtxData->dims[j] = *(dims + dimsOffset + j); + } + } + + mtxData->re = data; + mtxData->im = NULL; + mtxData->dTypeID = dTypeId; + mtxData->mxID = rt_GetMxIdFromDTypeId(dTypeId); + mtxData->elSize = rt_GetSizeofDataType(dTypeId); + mtxData->logical = 0U; + mtxData->complex = 0U; + + data += numCols[i]; + dimsOffset += numDims[i]; + } + ++sig->numActiveFields; + } + + /* titles */ + if (titles != NULL) { + unsigned short *data; + size_t nbytes; + int_T dataLen = (int_T)strlen(titles); + /*LINTED E_ASSIGN_INT_TO_SMALL_INT*/ + size_t dataOffset = nSignals * sizeof(MatrixData); + /*LINTED E_ASSIGN_INT_TO_SMALL_INT*/ + uint_T overhang = (uint_T)(dataOffset % sizeof(short)); + + if (overhang) { /* polyspace DEFECT:DEAD_CODE [Not a defect:Unset] + "Needed for possible padding determination. */ + dataOffset += (sizeof(short) - overhang); + } + /*LINTED E_ASSIGN_INT_TO_SMALL_INT*/ + nbytes = dataOffset + dataLen*sizeof(short); + + if ( (sig->titles = calloc(nbytes, 1)) == NULL ) goto ERROR_EXIT; + + /*LINTED E_BAD_PTR_CAST_ALIGN*/ + data = (unsigned short*) (((char_T*) (sig->titles)) + dataOffset); + for (i = 0; i < dataLen; i++) { + data[i] = titles[i]; + } + + for (i = 0; i < nSignals; i++) { + MatrixData *mtxData = &(sig->titles[i]); + + (void)memcpy(mtxData->name, &TITLE_FIELD_NAME, mxMAXNAM); + if (titleLen) { + mtxData->nRows = (titleLen[i]) ? 1 : 0; + mtxData->nCols = titleLen[i]; + } else { + mtxData->nRows = (dataLen) ? 1 : 0; + mtxData->nCols = dataLen; + } + + mtxData->nDims = 1; /* assume */ + mtxData->dims = mtxData->_dims; + mtxData->dims[0] = mtxData->nCols; + + mtxData->re = data; + mtxData->im = NULL; + mtxData->dTypeID = SS_INT16; + mtxData->mxID = mxCHAR_CLASS; + mtxData->elSize = sizeof(short); + mtxData->logical = 0U; + mtxData->complex = 0U; + + data += ((titleLen) ? titleLen[i] : dataLen); + } + ++sig->numActiveFields; + } + + /* block names */ + if (blockNames != NULL) { + unsigned short *data; + size_t nbytes; + int_T dataLen = 0; + size_t dataOffset = nSignals * sizeof(MatrixData); + uint_T overhang = (uint_T)(dataOffset % sizeof(short)); + int_T dataIdx = 0; + + for (i=0;iblockNames = calloc(nbytes, 1)) == NULL ) goto ERROR_EXIT; + + data = (unsigned short*) (((char_T*) (sig->blockNames)) + dataOffset); + + for(sigIdx=0;sigIdxblockNames[i]); + int_T blockNameLen = (int_T)strlen(blockNames[i]); + + (void)memcpy(mtxData->name, &BLOCKNAME_FIELD_NAME, mxMAXNAM); + mtxData->nRows = (blockNameLen) ? 1 : 0; + mtxData->nCols = blockNameLen; + + mtxData->nDims = 1; /* assume */ + mtxData->dims = mtxData->_dims; + mtxData->dims[0] = mtxData->nCols; + + mtxData->re = data; + mtxData->im = NULL; + mtxData->dTypeID = SS_INT16; + mtxData->mxID = mxCHAR_CLASS; + mtxData->elSize = sizeof(short); + mtxData->logical = 0U; + mtxData->complex = 0U; + + data += blockNameLen; + } + ++sig->numActiveFields; + if(logValueDimensions){ + sig->fieldNames = rtGlobalLoggingSignalsStructFieldNames; + } + else{ + sig->fieldNames = rtGlobalLoggingSignalsStructFieldNames_noValDims; + } + + } else { + if(logValueDimensions){ + sig->fieldNames = rtLocalLoggingSignalsStructFieldNames; + } + else{ + sig->fieldNames = rtLocalLoggingSignalsStructFieldNames_noValDims; + } + + } + + /* state names */ + if (stateNames != NULL) { + unsigned short *data; + size_t nbytes; + int_T dataLen = 0; + size_t dataOffset = nSignals * sizeof(MatrixData); + uint_T overhang = (uint_T)(dataOffset % sizeof(short)); + int_T dataIdx = 0; + + for (i=0;istateNames = calloc(nbytes, 1)) == NULL ) goto ERROR_EXIT; + + data = (unsigned short*) (((char_T*) (sig->stateNames)) + dataOffset); + + for(sigIdx=0;sigIdxstateNames[i]); + int_T stateNameLen = (int_T)strlen(stateNames[i]); + + (void)memcpy(mtxData->name, &STATENAME_FIELD_NAME, mxMAXNAM); + mtxData->nRows = (stateNameLen) ? 1 : 0; + mtxData->nCols = stateNameLen; + + mtxData->nDims = 1; /* assume */ + mtxData->dims = mtxData->_dims; + mtxData->dims[0] = mtxData->nCols; + + mtxData->re = data; + mtxData->im = NULL; + mtxData->dTypeID = SS_INT16; + mtxData->mxID = mxCHAR_CLASS; + mtxData->elSize = sizeof(short); + mtxData->logical = 0U; + mtxData->complex = 0U; + + data += stateNameLen; + } + ++sig->numActiveFields; + + if(logValueDimensions){ + sig->fieldNames = rtGlobalLoggingSignalsStructFieldNames; + } + else{ + sig->fieldNames = rtGlobalLoggingSignalsStructFieldNames_noValDims; + } + + } + + /* CrossMdlRef */ + if (crossMdlRef != NULL) { + real_T *data; + size_t nbytes; + size_t dataOffset = nSignals * sizeof(MatrixData); + uint_T overhang = (uint_T)(dataOffset % sizeof(real_T)); + + if (overhang) { /* polyspace DEFECT:DEAD_CODE [Not a defect:Unset] + "Needed for possible padding determination. */ + dataOffset += (sizeof(real_T) - overhang); + } + + nbytes = dataOffset + nSignals*sizeof(real_T); + + if ( (sig->crossMdlRef = calloc(nbytes, 1)) == NULL ) goto ERROR_EXIT; + + data = (real_T*) (((char_T*) (sig->crossMdlRef)) + dataOffset); + + for(sigIdx=0;sigIdxcrossMdlRef[i]); + + (void)memcpy(mtxData->name, &CROSS_MDL_REF_FIELD_NAME, mxMAXNAM); + mtxData->nRows = 1; + mtxData->nCols = 1; + mtxData->nDims = 1; /* => matlab scalar */ + + mtxData->re = &data[i]; + mtxData->im = NULL; + mtxData->dTypeID = SS_DOUBLE; + mtxData->mxID = rt_GetMxIdFromDTypeId(SS_DOUBLE); + mtxData->elSize = sizeof(real_T); + mtxData->logical = matLOGICAL_BIT; + mtxData->complex = 0U; + mtxData->frameData = 0; + mtxData->frameSize = 1; + } + ++sig->numActiveFields; + } + + return(NULL); /* NORMAL_EXIT */ + + ERROR_EXIT: + + (void)fprintf(stderr, "*** Error creating signals structure " + "in the struct log variable %s\n", var->name); + if (*errStatus == NULL) { + *errStatus = rtMemAllocError; + } + rt_DestroyLogVar(sig->values); + FREE(sig->labels); + FREE(sig->plotStyles); + FREE(sig->dimensions); + FREE(sig->titles); + FREE(sig->blockNames); + FREE(sig->stateNames); + FREE(sig->crossMdlRef); + + return(*errStatus); + +} /* end rt_InitSignalsStruct */ + + +/* Function: local_CreateStructLogVar ========================================== + * Abstract: + * Create a logging variable in the structure format. + * + * Returns: + * ~= NULL => success, returns the log variable created. + * == NULL => failure, error message set in the simstruct. + */ +static StructLogVar *local_CreateStructLogVar( + RTWLogInfo *li, + const real_T startTime, + const real_T finalTime, + const real_T inStepSize, + const char_T **errStatus, + const char_T *varName, + boolean_T logTime, + int_T maxRows, + int_T decimation, + real_T sampleTime, + const RTWLogSignalInfo *sigInfo, + const char_T *blockName) +{ + StructLogVar *var; + LogInfo *logInfo = rtliGetLogInfo(li); + + /* reset error status */ + *errStatus = NULL; + + if ( (var = calloc(1, sizeof(StructLogVar))) == NULL ) goto ERROR_EXIT; + + var->numActiveFields = 2; + + /* Setup the structure name using varName and nameModifier */ + rt_LoadModifiedLogVarName(li,varName,var->name); + + /* time field */ + if (logTime) { + /* need to create a LogVar to log time */ + int_T dims = 1; + var->time = rt_CreateLogVarWithConvert(li, startTime, finalTime, + inStepSize, errStatus, + &TIME_FIELD_NAME, SS_DOUBLE, + NULL, + 0, 0, 0, 1, + 1, &dims, NO_LOGVALDIMS, + NULL, NULL, maxRows, + decimation, sampleTime, 0); + if (var->time == NULL) goto ERROR_EXIT; + } else { + /* create a dummy MatrixData to write out time as an empty matrix */ + BuiltInDTypeId dt = rt_GetActualDTypeID(SS_DOUBLE); + size_t nbytes = sizeof(MatrixData); + MatrixData *time; + + if ( (var->time = calloc(nbytes, 1)) == NULL ) goto ERROR_EXIT; + time = var->time; + + (void)memcpy(time->name, &TIME_FIELD_NAME, mxMAXNAM); + time->nRows = 0; + time->nCols = 0; + time->nDims = 0; + time->re = NULL; + time->im = NULL; + time->dTypeID = dt; + time->mxID = rt_GetMxIdFromDTypeId(dt); + time->elSize = rt_GetSizeofDataType(dt); + time->logical = 0U; + time->complex = 0U; + } + var->logTime = logTime; + + /* signals field */ + if (sigInfo) { + if (rt_InitSignalsStruct(li,startTime,finalTime,inStepSize,errStatus, + var,maxRows,decimation,sampleTime,sigInfo)) { + goto ERROR_EXIT; + } + } + + /* blockName Field */ + if (blockName != NULL) { + int_T dataLen = (int_T)strlen(blockName); + size_t nbytes; + size_t dataOffset = sizeof(MatrixData); + /*LINTED E_ASSIGN_INT_TO_SMALL_INT*/ + uint_T overhang = (uint_T)(dataOffset % sizeof(short)); + + if (overhang) { /* polyspace DEFECT:DEAD_CODE [Not a defect:Unset] + "Needed for possible padding determination. */ + dataOffset += (sizeof(short) - overhang); + } + /*LINTED E_ASSIGN_INT_TO_SMALL_INT*/ + nbytes = dataOffset + dataLen*sizeof(short); + + if ( (var->blockName = calloc(nbytes, 1)) == NULL ) goto ERROR_EXIT; + + (void)memcpy(var->blockName->name, &BLOCKNAME_FIELD_NAME, mxMAXNAM); + var->blockName->nRows = (dataLen) ? 1 : 0; + var->blockName->nCols = dataLen; + + var->blockName->nDims = 1; + var->blockName->dims = var->blockName->_dims; + var->blockName->dims[0] = dataLen; + { + /*LINTED E_BAD_PTR_CAST_ALIGN*/ + unsigned short *data = (unsigned short*)(((char_T*) (var->blockName))+dataOffset); + int_T i; + + for (i=0; iblockName->re = data; + } + var->blockName->im = NULL; + var->blockName->dTypeID = SS_INT16; + var->blockName->mxID = mxCHAR_CLASS; + var->blockName->elSize = sizeof(short); + var->blockName->logical = 0U; + var->blockName->complex = 0U; + + ++var->numActiveFields; + } + + /* Add this struct log var to the linked list in log info */ + { + StructLogVar *list = logInfo->structLogVarsList; + + if (list != NULL) { + while (list->next != NULL) { + list = list->next; + } + list->next = var; + } else { + logInfo->structLogVarsList = var; + } + } + + return(var); /* NORMAL_EXIT */ + + ERROR_EXIT: + (void)fprintf(stderr, "*** Error creating log variable %s\n", varName); + if (*errStatus == NULL) { + *errStatus = rtMemAllocError; + } + rt_DestroyStructLogVar(var); + return(NULL); + +} /* end local_CreateStructLogVar */ + + +/* Function: rt_StartDataLoggingForOutput ====================================== + * Abstract: + */ +static const char_T *rt_StartDataLoggingForOutput(RTWLogInfo *li, + const real_T startTime, + const real_T finalTime, + const real_T stepSize, + const char_T **errStatus) +{ + const char_T *varName; + real_T sampleTime = stepSize; + int_T maxRows = rtliGetLogMaxRows(li); + int_T decimation = rtliGetLogDecimation(li); + int_T logFormat = rtliGetLogFormat(li); + boolean_T logTime = (logFormat==2) ? 1 : 0; + + LogInfo * logInfo; + logInfo = rtliGetLogInfo(li); + + /* reset error status */ + *errStatus = NULL; + + /* outputs */ + varName = rtliGetLogY(li); + if (varName[0] != '\0') { + int_T i; + int_T ny; + int_T yIdx; + char_T name[mxMAXNAM]; + const char_T *cp = strchr(varName,','); + LogSignalPtrsType ySigPtrs = rtliGetLogYSignalPtrs(li); + const RTWLogSignalInfo *yInfo = rtliGetLogYSignalInfo(li); + + /* count the number of variables (matrices or structures) to create */ + for (ny=1; cp != NULL; ny++) { + cp = strchr(cp+1,','); + } + logInfo->ny = ny; + + if (logFormat==0) { + if ( (logInfo->y = calloc(ny,sizeof(LogVar*))) == NULL ) { + *errStatus = rtMemAllocError; + goto ERROR_EXIT; + } + } else { + if ( (logInfo->y = calloc(ny,sizeof(StructLogVar*))) == NULL ) { + *errStatus = rtMemAllocError; + goto ERROR_EXIT; + } + } + + for (i = yIdx = 0, cp = varName; i < ny; i++) { + int_T len; + const char_T *cp1 = strchr(cp+1,','); + + if (cp1 != NULL) { + /*LINTED E_ASSIGN_INT_TO_SMALL_INT*/ + len = (int_T)(cp1 - cp); + if (len >= mxMAXNAM) len = mxMAXNAM - 1; + } else { + len = mxMAXNAM - 1; + } + (void)strncpy(name, cp, len); + name[len] = '\0'; + + if (ny > 1 && ySigPtrs[i] == NULL) { + goto NEXT_NAME; + } + + if (logFormat == 0) { + int numCols; + int nDims; + const int *dims; + BuiltInDTypeId dataType; + int isComplex; + + if (ny == 1) { + int_T op; + + numCols = yInfo[0].numCols[0]; + for (op = 1; op < yInfo[0].numSignals; op++) { + numCols += yInfo[0].numCols[op]; + } + /* + * If we have only one "matrix" outport, + * we can still log it as a matrix + */ + if (yInfo[0].numSignals == 1) { + nDims = yInfo[0].numDims ? yInfo[0].numDims[0] : 1; + dims = yInfo[0].dims; + } else { + nDims = 1; + dims = &numCols; + } + + dataType = yInfo[0].dataTypes[0]; + isComplex = yInfo[0].complexSignals[0]; + } else { + numCols = yInfo[yIdx].numCols[0]; + nDims = yInfo[yIdx].numDims ? yInfo[yIdx].numDims[0] : 1; + dims = yInfo[yIdx].dims; + dataType = yInfo[yIdx].dataTypes[0]; + isComplex = yInfo[yIdx].complexSignals[0]; + } + + logInfo->y[yIdx] = rt_CreateLogVarWithConvert( + li, startTime, finalTime, + stepSize, errStatus, + name, + dataType, + yInfo[yIdx].dataTypeConvert, + 0,isComplex, + 0,numCols,nDims,dims, + NO_LOGVALDIMS, NULL, NULL, + maxRows,decimation, + sampleTime,1); + if (logInfo->y[yIdx] == NULL) goto ERROR_EXIT; + } else { + logInfo->y[yIdx] = local_CreateStructLogVar(li, startTime, + finalTime, stepSize, + errStatus, name, + logTime, maxRows, + decimation, sampleTime, + &yInfo[yIdx], NULL); + if (logInfo->y[yIdx] == NULL) goto ERROR_EXIT; + } + ++yIdx; + NEXT_NAME: + cp = cp1; + if (cp != NULL && *cp == ',') cp++; + } + } + + return(NULL); /* NORMAL_EXIT */ + + ERROR_EXIT: + (void)fprintf(stderr, "*** Errors occurred when starting data logging.\n"); + if (*errStatus == NULL) { + *errStatus = rtMemAllocError; + } + if (logInfo) { /* polyspace DEFECT:USELESS_IF [No action planned:Unset] + "Defense coding." */ + rt_DestroyLogVar(logInfo->logVarsList); + logInfo->logVarsList = NULL; + rt_DestroyStructLogVar(logInfo->structLogVarsList); + logInfo->structLogVarsList = NULL; + FREE(logInfo->y); + logInfo->y = NULL; + } + return(*errStatus); + +} /* end rt_StartDataLoggingForOutput */ + + +/* Function: rt_ReallocLogVar ================================================== + * Abstract: + * Allocate more memory for the data buffers in the log variable. + * Exit if unable to allocate more memory. + */ +static void rt_ReallocLogVar(LogVar *var, boolean_T isVarDims) +{ + void *tmp; + int_T nCols = var->data.nCols; + int_T nRows; + size_t elSize = var->data.elSize; + + if (isVarDims) + { + nRows = var->data.nRows + DEFAULT_BUFFER_SIZE; + } + else + { + nRows = var->data.nRows == 0 ? 1 : 2*var->data.nRows; + } + + tmp = realloc(var->data.re, nRows*nCols*elSize); + if (tmp == NULL) { + (void)fprintf(stderr, + "*** Memory allocation error.\n"); + (void)fprintf(stderr, "" + " varName = %s%s\n" + " nRows = %d\n" + " nCols = %d\n" + " elementSize = %lu\n" + " Current Size = %.16g\n" + " Failed resize = %.16g\n\n", + var->data.name, + var->data.complex ? " (real part)" : "", + var->data.nRows, + var->data.nCols, + (unsigned long) var->data.elSize, + (double)nRows*nCols*elSize, + (double)(nRows+DEFAULT_BUFFER_SIZE)*nCols*elSize); + exit(1); + } + var->data.re = tmp; + + if (var->data.complex) { + tmp = realloc(var->data.im, nRows*nCols*elSize); + if (tmp == NULL) { + (void)fprintf(stderr, + "*** Memory allocation error.\n"); + (void)fprintf(stderr, "" + " varName = %s (complex part)\n" + " nRows = %d\n" + " nCols = %d\n" + " elementSize = %lu\n" + " Current Size = %.16g\n" + " Failed resize = %.16g\n\n", + var->data.name, + var->data.nRows, + var->data.nCols, + (unsigned long) var->data.elSize, + (double)nRows*nCols*elSize, + (double)(nRows+DEFAULT_BUFFER_SIZE)*nCols*elSize); + exit(1); + } + var->data.im = tmp; + } + var->data.nRows = nRows; + + /* Also reallocate memory for "valueDimensions" + when logging the variable-size signal + */ + if(isVarDims){ + int_T k; + + nCols = var->valDims->nCols; + nRows = var->valDims->nRows + DEFAULT_BUFFER_SIZE; + elSize = sizeof(real_T); + tmp = realloc(var->valDims->dimsData, nRows*nCols*elSize); + if (tmp == NULL) { + (void)fprintf(stderr, + "*** Memory allocation error.\n"); + (void)fprintf(stderr, "" + " varName = %s\n" + " nRows = %d\n" + " nCols = %d\n" + " elementSize = %lu\n" + " Current Size = %.16g\n" + " Failed resize = %.16g\n\n", + var->valDims->name, + var->valDims->nRows, + var->valDims->nCols, + (unsigned long) elSize, + (double)nRows*nCols*elSize, + (double)(nRows+DEFAULT_BUFFER_SIZE)*nCols*elSize); + exit(1); + } + + /* + * valueDimensions data is stored in array format and must be + * adjusted after reallocation (see also rt_FixupLogVar()) + * + * Example: maxRows = 4; nRows = 4; nDims = 3; + * Before realloc of the logVar, the locations of data are as below: + * (x, y, z -- useful data / o -- junk, don't care) + * a[0] = x a[4] = y a[8] = z + * a[1] = x a[5] = y a[9] = z + * a[2] = x a[6] = y a[10]= z + * a[3] = x a[7] = y a[11]= z + * + * After realloc of the logVar (suppose 2 extra rows are added), + * the locations of data are as below: + * a[0] = x a[6] = y a[12]= o + * a[1] = x a[7] = y a[13]= o + * a[2] = x a[8] = z a[14]= o + * a[3] = x a[9] = z a[15]= o + * a[4] = y a[10]= z a[16]= o + * a[5] = y a[11]= z a[17]= o + * + * The data must be adjusted as below: + * a[0] = x a[6] = y a[12]= z + * a[1] = x a[7] = y a[13]= z + * a[2] = x a[8] = y a[14]= z + * a[3] = x a[9] = y a[15]= z + * a[4] = o a[10]= o a[16]= o + * a[5] = o a[11]= o a[17]= o + */ + for(k = var->data.nDims-1; k > 0; k--){ + (void) memcpy((real_T*)tmp + k*nRows, + (real_T*)tmp + k*var->valDims->nRows, + elSize * var->valDims->nRows); + } + + var->valDims->dimsData = tmp; + var->valDims->nRows = nRows; + } + +} /* end rt_ReallocLogVar */ + +const char_T *rt_UpdateLogVarWithDiscontiguousData(LogVar *var, + int8_T** data, + const int_T *segmentLengths, + int_T nSegments, + RTWPreprocessingFcnPtr *preprocessingPtrs); + +/* Function: rt_UpdateLogVarWithDiscontiguousData ============================== + * Abstract: + * Log one row of the LogVar with data that is not contiguous. + */ +const char_T *rt_UpdateLogVarWithDiscontiguousData(LogVar *var, + int8_T** data, + const int_T *segmentLengths, + int_T nSegments, + RTWPreprocessingFcnPtr *preprocessingPtrs) +{ + size_t elSize = 0; + size_t offset = 0; + int segIdx = 0; + + if (++var->numHits % var->decimation) return(NULL); + var->numHits = 0; + + /* + * Reallocate or wrap the LogVar + */ + if (var->rowIdx == var->data.nRows) { + if (var->okayToRealloc == 1) { + rt_ReallocLogVar(var, false); + } else { + /* Circular buffer */ + var->rowIdx = 0; + ++(var->wrapped); /* increment the wrap around counter */ + } + } + + /* This function is only used to log states, there's no var-dims issue. */ + elSize = var->data.elSize; + offset = (size_t)(elSize * var->rowIdx * var->data.nCols); + + if (var->data.complex) { + char_T *dstRe = (char_T*)(var->data.re) + offset; + char_T *dstIm = (char_T*)(var->data.im) + offset; + + for (segIdx = 0; segIdx < nSegments; segIdx++) { + int_T nEl = segmentLengths[segIdx]; + char_T *src = (char_T *)data[segIdx]; + int_T el; + + /* preprocess data in-place before logging */ + RTWPreprocessingFcnPtr preprocessingPtr = preprocessingPtrs[segIdx]; + if (preprocessingPtr != NULL) { + src = malloc(elSize * nEl * 2); + preprocessingPtr(src, (void *)data[segIdx]); + } + + if (src == NULL) { + const char_T *errorMessage = "Could not allocate memory for logging."; + fprintf(stderr,"%s.\n", errorMessage); + return(errorMessage); + } + else { + for (el = 0; el < nEl; el++) { + (void)memcpy(dstRe, src, elSize); + dstRe += elSize; src += elSize; + (void)memcpy(dstIm, src, elSize); + dstIm += elSize; src += elSize; + } + } + + /* free temporarily declared data */ + if (preprocessingPtr != NULL) { + free( src ); + } + } + } else { + char_T *dst = (char_T*)(var->data.re) + offset; + + for (segIdx = 0; segIdx < nSegments; segIdx++) { + size_t segSize = elSize*segmentLengths[segIdx]; + char_T *src = (void *) data[segIdx]; + + /* preprocess data in-place before logging */ + RTWPreprocessingFcnPtr preprocessingPtr = preprocessingPtrs[segIdx]; + if (preprocessingPtr != NULL) { + src = malloc(segSize); + preprocessingPtr(src, data[segIdx]); + } + if (src == NULL) { + const char_T *errorMessage = "Could not allocate memory for logging."; + fprintf(stderr,"%s.\n", errorMessage); + return(errorMessage); } + else { + (void)memcpy(dst, src, segSize); + dst += segSize; + } + + /* free temporarily declared data */ + if (preprocessingPtr != NULL) { + free( src ); + } + } + } + + ++var->rowIdx; + return(NULL); + +} /* end rt_UpdateLogVarWithDiscontiguousData */ + + +/*==================* + * Visible routines * + *==================*/ + + + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Function: rt_CreateLogVarWithConvert ======================================== + * Abstract: + * Create a logging variable. + * + * Returns: + * ~= NULL => success, returns the log variable created. + * == NULL => failure, error message set in the simstruct. + */ +LogVar *rt_CreateLogVarWithConvert( + RTWLogInfo *li, + const real_T startTime, + const real_T finalTime, + const real_T inStepSize, + const char_T **errStatus, + const char_T *varName, + BuiltInDTypeId inpDataTypeID, + const RTWLogDataTypeConvert *pDataTypeConvertInfo, + int_T logical, + int_T complex, + int_T frameData, + int_T nCols, + int_T nDims, + const int_T *dims, + LogValDimsStat logValDimsStat, + void **currSigDims, + int_T *currSigDimsSize, + int_T maxRows, + int_T decimation, + real_T sampleTime, + int_T appendToLogVarsList) +{ + int_T usingDefaultBufSize = 0; +#ifdef NO_LOGGING_REALLOC + int_T okayToRealloc = 0; +#else + int_T okayToRealloc = 1; +#endif + LogVar *var = NULL; + /*inpDataTypeID is the rt_LoggedOutputDataTypeId*/ + BuiltInDTypeId dTypeID = (BuiltInDTypeId)inpDataTypeID; + size_t elementSize = rt_GetSizeofDataType(dTypeID); + int_T frameSize; + int_T nRows; + int_T nColumns; + + /*===================================================================* + * Determine the frame size if the data is frame based * + *===================================================================*/ + frameSize = frameData ? dims[0] : 1; + + /*===================================================================* + * Calculate maximum number of rows needed in the buffer * + *===================================================================*/ + + if (finalTime > startTime && finalTime != rtInf) { + real_T nPoints; /* Tfinal is finite ===> nRows can be */ + real_T stepSize; /* computed since the StepSize is fixed */ + + if (sampleTime == -2.0) { /* The signal being logged is constant, * + * Hence, only one data point is logged. */ + stepSize = finalTime; + } else if (sampleTime == -1.0 || sampleTime == 0.0) { + /* Signal being logged is either inside a * + * triggered sub-system or it is continuous. */ + stepSize = inStepSize; + } else { /* Discrete signal */ + stepSize = sampleTime; + } + + if (stepSize == 0.0) { + /* small initial value, so as to exercise the realloc code */ + nRows = maxRows+1; + okayToRealloc = 1; + } else { + nPoints = 1.0 + floor((finalTime-startTime)/stepSize); + + /* + * Add one more data point if needed. + */ + if ( stepSize*(nPoints-1.0) < (finalTime-startTime) ) { + nPoints += 1.0; + } + + /* + * Actual number of points to log = nPoints * size of + * each frame if data is frame-based + */ + nPoints = frameData ? (nPoints * frameSize) : nPoints; + + nPoints /= decimation; + if (nPoints != floor(nPoints)) { + nPoints += 1.0; + } + nRows = (nPoints <= INT_MAX) ? ((int_T) nPoints) : INT_MAX; + } + /* + * If maxRows is specified, and if this number is less + * than the number we computed (nRows) then use maxRows. + */ + if ((maxRows > 0) && (maxRows < nRows)) { + nRows = maxRows; + okayToRealloc = 0; + } + } else if (finalTime == startTime) { + /* + * Number of rows to log is equal to 1 if not frame-based and + * equal to frame size if frame-based + */ + nRows = frameData ? frameSize : 1; + + /* + * If maxRows is specified, and if this number is less + * than the number we computed (nRows) then use maxRows. + */ + if ((maxRows > 0) && (maxRows < nRows)) { + nRows = maxRows; + okayToRealloc = 0; + } + } else if (maxRows > 0) { /* maxRows is specified => nRows=maxRows */ + nRows = maxRows; + okayToRealloc = 0; + } else { + + if (inStepSize == 0) { + /* small initial value, so as to exercise the realloc code */ + nRows = maxRows+1; + okayToRealloc = 1; + } else { /* Use a default value for nRows */ + usingDefaultBufSize = 1; + nRows = DEFAULT_BUFFER_SIZE; + okayToRealloc = 0; /* No realloc with infinite stop time */ + (void)fprintf(stdout, "*** Using a default buffer of size %d for " + "logging variable %s\n", nRows, varName); + } + } + + /* + * Figure out the number of columns that the log variable should have. + * If the data is not frame based, then number of columns should equal + * nCols that is provided as input to the function. If the data is + * frame-based, then the number of columns should be equal to the + * number of channels = nCols/frameSize = dims[1]; + */ + nColumns = frameData ? dims[1] : nCols; + + /* + * Error out if the size of the circular buffer is absurdly large, this + * error message is more informative than the one we get when we try to + * malloc this many number of bytes in one fell swoop. + */ + { + double tmpDbl = ((double)elementSize)*((double)nRows)* + ((double)nColumns); + + if (tmpDbl >= UINT_MAX) { + (void)fprintf(stderr, + "\n*** Memory required to log variable '%s' is too" + "\n big. Use the 'Limit rows to last:' and (or)" + "\n 'Decimation:' options to reduce the required" + "\n memory size.\n", varName); + (void)fprintf(stderr, "*** Details:\n" + " varName = %s\n" + " nRows = %d\n" + " nCols = %d\n" + " elementSize = %lu\n" + " Bytes Required = %.16g\n\n", + varName, nRows, nColumns, (unsigned long) + elementSize, tmpDbl); + goto ERROR_EXIT; + } + } + + /* Allocate memory for the log variable */ + if ( (var = calloc(1, sizeof(LogVar))) == NULL ) { + (void)fprintf(stderr, "*** Error allocating memory for logging %s\n", + varName); + goto ERROR_EXIT; + } + + /* Allocate memory for the circular buffer (real part) */ + if ( (var->data.re = malloc(nRows*nColumns*elementSize)) == NULL ) { + (void)fprintf(stderr, + "*** Error allocating memory for the circular buffer\n"); + (void)fprintf(stderr, "*** Details:\n" + " varName = %s\n" + " nRows = %d\n" + " nCols = %d\n" + " elementSize = %lu\n" + " Bytes Requested = %.16g\n\n", + varName, nRows, nColumns, (unsigned long) elementSize, + ((double)elementSize)*((double)nRows)*((double)nColumns)); + goto ERROR_EXIT; + } + + /* Allocate memory for the circular buffer for the imaginary part */ + if (complex) { + if ( (var->data.im = malloc(nRows*nColumns*elementSize)) == NULL ) { + (void)fprintf(stderr, + "*** Error allocating memory for the circular buffer " + "for logging the imaginary part of %s\n", varName); + (void)fprintf(stderr, "*** Details:\n" + " varName = %s\n" + " nRows = %d\n" + " nCols = %d\n" + " elementSize = %lu\n" + " Bytes Requested = %.16g\n\n", + varName, nRows, nColumns, (unsigned long) elementSize, + ((double)elementSize)*((double)nRows)* + ((double)nColumns)); + goto ERROR_EXIT; + } + } + /* + * Initialize the fields in LogVar structure. + */ + if (appendToLogVarsList) { + rt_LoadModifiedLogVarName(li,varName,var->data.name); + } else { + var->data.name[mxMAXNAM-1] = '\0'; + (void)strncpy(var->data.name,varName,mxMAXNAM-1); + } + var->data.nCols = nColumns; + var->data.nRows = nRows; + + var->data.nDims = frameData ? 1 : nDims; + if (var->data.nDims > 2) { + var->data.dims = (int_T*)malloc(sizeof(int_T)*var->data.nDims); + } else { + var->data.dims = var->data._dims; + } + if (frameData) { + var->data.dims[0] = nColumns; + } else { + /*LINTED E_CAST_INT_TO_SMALL_INT*/ + (void)memcpy(var->data.dims, dims, (size_t)(nDims*sizeof(int_T))); + } + + var->data.dTypeID = dTypeID; + var->data.elSize = elementSize; + + var->data.dataTypeConvertInfo = rt_GetDataTypeConvertInfo( + pDataTypeConvertInfo, dTypeID); + + var->data.mxID = rt_GetMxIdFromDTypeId(dTypeID); + /* over-ride logical bit if data type is boolean */ + logical = dTypeID == SS_BOOLEAN ? 1 : 0; + var->data.logical = (logical) ? matLOGICAL_BIT : 0x0; + var->data.complex = (complex) ? matCOMPLEX_BIT : 0x0; + var->data.frameData = frameData; + var->data.frameSize = (frameData) ? frameSize : 1; + + /* fill up valDims field */ + if(logValDimsStat == NO_LOGVALDIMS){ + /* All signals are fixed-size, no need to log valueDimensions field */ + var->valDims = NULL; + /* Set these pointers to NULLs in this case */ + var->coords = NULL; + var->strides = NULL; + var->currStrides = NULL; + } + else{ + if ( (var->valDims = calloc(1, sizeof(ValDimsData))) == NULL ) { + goto ERROR_EXIT; + } + + (void)memcpy(var->valDims->name, &VALUEDIMENSIONS_FIELD_NAME, mxMAXNAM); + + if (logValDimsStat == LOGVALDIMS_EMPTYMX) { + /* At least one signal is variable-size, + but the current signal is fixed-size. + Therefore, create a dummy MatrixData to write out valueDimensions + as an empty matrix. + */ + var->valDims->nRows = 0; + var->valDims->nCols = 0; + var->valDims->currSigDims = NULL; + var->valDims->currSigDimsSize = NULL; + var->valDims->dimsData = NULL; + /* Set these pointers to NULLs in this case */ + var->coords = NULL; + var->strides = NULL; + var->currStrides = NULL; + } else { /* The current signal is a variable-size signal. */ + /* The "valueDimensions" must be double, so re-assign element size */ + elementSize = sizeof(real_T); + + /* When signals are frame-based, 'valueDimensions' has 1 column */ + if(frameData){ + /* When signal is frame-based, the first dimension is always fixed, + so we only need to record the second dimension. + e.g. Two frame-based signals [10x4] and [10x3], + 'valueDimensions' and 'currSigDims' + only record 4 or 3. + */ + nColumns = 1; + var->valDims->currSigDims = (void**) (currSigDims + 1); + var->valDims->currSigDimsSize = (int_T*) (currSigDimsSize + 1); + } else { /* non-frame based */ + nColumns = nDims; + var->valDims->currSigDims = (void**) currSigDims; + var->valDims->currSigDimsSize = (int_T*) currSigDimsSize; + } + + /* Allocate memory for the circular buffer */ + if ( (var->valDims->dimsData = malloc(nRows*nColumns*elementSize)) == NULL ) { + (void)fprintf(stderr, + "*** Error allocating memory for the circular buffer\n"); + (void)fprintf(stderr, "*** Details:\n" + " varName = %s\n" + " nRows = %d\n" + " nCols = %d\n" + " elementSize = %lu\n" + " Bytes Requested = %.16g\n\n", + var->valDims->name, nRows, nColumns, (unsigned long) elementSize, + ((double)elementSize)*((double)nRows)*((double)nColumns)); + goto ERROR_EXIT; + } + var->valDims->nRows = nRows; + var->valDims->nCols = nColumns; + + /* Allocate memory for these dynamic arrays */ + { + size_t nbytes = var->data.nDims*sizeof(int_T); + if( ((var->coords = calloc(nbytes, 1)) == NULL) + ||((var->strides = calloc(nbytes, 1)) == NULL) + ||((var->currStrides = calloc(nbytes, 1)) == NULL) ) + goto ERROR_EXIT; + } + } + } + + var->rowIdx = 0; + var->wrapped = 0; + var->nDataPoints = 0; + var->usingDefaultBufSize = usingDefaultBufSize; + var->okayToRealloc = okayToRealloc; + var->decimation = decimation; + var->numHits = -1; /* so first point gets logged */ + + /* Add this log var to list in log info, if necessary */ + if (appendToLogVarsList) { + LogInfo *logInfo = (LogInfo*) rtliGetLogInfo(li); + LogVar *varList = logInfo->logVarsList; + + if (varList != NULL) { + while (varList->next != NULL) { + varList = varList->next; + } + varList->next = var; + } else { + logInfo->logVarsList = var; + } + } + + return(var); /* NORMAL_EXIT */ + + ERROR_EXIT: + + *errStatus = rtMemAllocError; + rt_DestroyLogVar(var); + return(NULL); + +} /* end rt_CreateLogVarWithConvert */ + + +#ifdef __cplusplus +} +#endif + + + + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Function: rt_CreateLogVar =================================================== + * Abstract: + * Create a logging variable. + * + * Returns: + * ~= NULL => success, returns the log variable created. + * == NULL => failure, error message set in the simstruct. + */ +LogVar *rt_CreateLogVar(RTWLogInfo *li, + const real_T startTime, + const real_T finalTime, + const real_T inStepSize, + const char_T **errStatus, + const char_T *varName, + BuiltInDTypeId inpDataTypeID, + int_T logical, + int_T complex, + int_T frameData, + int_T nCols, + int_T nDims, + const int_T *dims, + LogValDimsStat logValDimsStat, + void **currSigDims, + int_T *currSigDimsSize, + int_T maxRows, + int_T decimation, + real_T sampleTime, + int_T appendToLogVarsList) +{ + const RTWLogDataTypeConvert *pDataTypeConvertInfo = NULL; + + return rt_CreateLogVarWithConvert(li, + startTime, + finalTime, + inStepSize, + errStatus, + varName, + inpDataTypeID, + pDataTypeConvertInfo, + logical, + complex, + frameData, + nCols, + nDims, + dims, + logValDimsStat, + currSigDims, + currSigDimsSize, + maxRows, + decimation, + sampleTime, + appendToLogVarsList); + +} /* end rt_CreateLogVar */ + + +#ifdef __cplusplus +} +#endif + + + + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Function: rt_CreateStructLogVar ============================================= + * Abstract: + * Create a logging variable in the structure format. + * + * Returns: + * ~= NULL => success, returns the log variable created. + * == NULL => failure, error message set in the simstruct. + */ +StructLogVar *rt_CreateStructLogVar(RTWLogInfo *li, + const real_T startTime, + const real_T finalTime, + const real_T inStepSize, + const char_T **errStatus, + const char_T *varName, + boolean_T logTime, + int_T maxRows, + int_T decimation, + real_T sampleTime, + const RTWLogSignalInfo *sigInfo, + const char_T *blockName) +{ + + return( local_CreateStructLogVar(li, + startTime, + finalTime, + inStepSize, + errStatus, + varName, + logTime, + maxRows, + decimation, + sampleTime, + sigInfo, + blockName)); + +} /* end rt_CreateStructLogVar */ + + +#ifdef __cplusplus +} +#endif + + + + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Function: rt_StartDataLoggingWithStartTime ================================== + * Abstract: + * Initialize data logging info based upon the following settings cached + * in the RTWLogging data structure of the SimStruct. + * + * Return value is: + * == NULL => success + * != NULL => failure (the return value is a pointer that points to the + * error message, which is also set in the simstruct) + */ +const char_T *rt_StartDataLoggingWithStartTime(RTWLogInfo *li, + const real_T startTime, + const real_T finalTime, + const real_T stepSize, + const char_T **errStatus) +{ + const char_T *varName; + LogInfo *logInfo; + real_T sampleTime = stepSize; + int_T maxRows = rtliGetLogMaxRows(li); + int_T decimation = rtliGetLogDecimation(li); + int_T logFormat = rtliGetLogFormat(li); + boolean_T logTime = (logFormat==2) ? 1 : 0; + + /* reset error status */ + *errStatus = NULL; + + if ((logInfo=calloc(1,sizeof(LogInfo))) == NULL) { + *errStatus = rtMemAllocError; + goto ERROR_EXIT; + } + rtliSetLogInfo(li, (void*)logInfo); + + /* time */ + varName = rtliGetLogT(li); + if (varName[0] != '\0') { + int_T dims = 1; + logInfo->t = rt_CreateLogVarWithConvert(li, startTime, finalTime, + stepSize, errStatus, + varName,SS_DOUBLE, + NULL, + 0,0,0,1,1, + &dims, NO_LOGVALDIMS, NULL, NULL, + maxRows,decimation, + sampleTime,1); + if (logInfo->t == NULL) goto ERROR_EXIT; + } + + /* states */ + if ( rtliGetLogX(li)[0] != '\0' || rtliGetLogXFinal(li)[0] != '\0' ) { + const RTWLogSignalInfo *xInfo = rtliGetLogXSignalInfo(li); + + if (logFormat == 0) { /* Matrix Format */ + int numCols; + int nDims; + const int *dims; + BuiltInDTypeId dataType; + int isComplex; + int_T sIdx; + + const RTWLogDataTypeConvert *pDTConvInfo; + + numCols = xInfo[0].numCols ? xInfo[0].numCols[0] : 0; + for (sIdx = 1; sIdx < xInfo[0].numSignals; sIdx++) { + numCols += xInfo[0].numCols[sIdx]; + } + /* If we have only one "matrix" state, we can log as a matrix */ + if (xInfo[0].numSignals == 1) { + nDims = xInfo[0].numDims ? xInfo[0].numDims[0] : 1; + dims = xInfo[0].dims; + } else { + nDims = 1; + dims = &numCols; + } + dataType = xInfo[0].dataTypes ? xInfo[0].dataTypes[0] : 0; + isComplex = xInfo[0].complexSignals ? xInfo[0].complexSignals[0] : 0; + + pDTConvInfo = xInfo[0].dataTypeConvert; + + if (rtliGetLogX(li)[0] != '\0') { + logInfo->x = rt_CreateLogVarWithConvert(li, startTime, finalTime, + stepSize, errStatus, + rtliGetLogX(li),dataType, + pDTConvInfo, + 0, + isComplex,0,numCols,nDims,dims, + NO_LOGVALDIMS, NULL, NULL, + maxRows,decimation,sampleTime,1); + if (logInfo->x == NULL) goto ERROR_EXIT; + } + if (rtliGetLogXFinal(li)[0] != '\0') { + logInfo->xFinal = rt_CreateLogVarWithConvert(li, startTime, finalTime, + stepSize, errStatus, + rtliGetLogXFinal(li),dataType, + pDTConvInfo, + 0,isComplex,0,numCols,nDims, + dims, NO_LOGVALDIMS, NULL, + NULL, 1,decimation, + sampleTime,1); + if (logInfo->xFinal == NULL) goto ERROR_EXIT; + } + } else { /* Structure Format */ + if (rtliGetLogX(li)[0] != '\0') { + logInfo->x = local_CreateStructLogVar(li, startTime, finalTime, + stepSize, errStatus, + rtliGetLogX(li), logTime, + maxRows, decimation, + sampleTime, xInfo, NULL); + if (logInfo->x == NULL) goto ERROR_EXIT; + } + if (rtliGetLogXFinal(li)[0] != '\0') { + logInfo->xFinal = local_CreateStructLogVar(li, startTime, finalTime, + stepSize, errStatus, + rtliGetLogXFinal(li), + logTime,1,decimation, + sampleTime,xInfo,NULL); + if (logInfo->xFinal == NULL) goto ERROR_EXIT; + } + } + } + + /* outputs */ + *errStatus = rt_StartDataLoggingForOutput(li,startTime,finalTime, + stepSize,errStatus); + if (*errStatus != NULL) goto ERROR_EXIT; + + return(NULL); /* NORMAL_EXIT */ + + ERROR_EXIT: + (void)fprintf(stderr, "*** Errors occurred when starting data logging.\n"); + if (*errStatus == NULL) { + *errStatus = rtMemAllocError; + } + if (logInfo) { + rt_DestroyLogVar(logInfo->logVarsList); + logInfo->logVarsList = NULL; + rt_DestroyStructLogVar(logInfo->structLogVarsList); + logInfo->structLogVarsList = NULL; + FREE(logInfo); + rtliSetLogInfo(li,NULL); + } + return(*errStatus); + +} /* end rt_StartDataLoggingWithStartTime */ + + +#ifdef __cplusplus +} +#endif + + + + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Function: rt_StartDataLogging =============================================== + * Abstract: + */ +const char_T *rt_StartDataLogging(RTWLogInfo *li, + const real_T finalTime, + const real_T stepSize, + const char_T **errStatus) +{ + return rt_StartDataLoggingWithStartTime(li, + 0.0, + finalTime, + stepSize, + errStatus); +} + + +#ifdef __cplusplus +} +#endif + + + + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Function: rt_UpdateLogVar =================================================== + * Abstract: + * Called to log data for a log variable. + */ +void rt_UpdateLogVar(LogVar *var, const void *data, boolean_T isVarDims) +{ + size_t elSize = var->data.elSize; + const char_T *cData = data; + const int_T frameData = var->data.frameData; + const int_T frameSize = frameData ? (var->data.frameSize) : 1; + const int_T logWidth = var->data.nCols; + BuiltInDTypeId dTypeID = var->data.dTypeID; + + size_t offset = 0; + char_T *currRealRow = NULL; + char_T *currImagRow = NULL; + int_T pointSize = (int_T)((var->data.complex) ? rt_GetSizeofComplexType(dTypeID) : elSize); + + int i, j, k; + + /* The following variables will be used for + logging variable-size signals */ + const int_T nDims = var->data.nDims; + const int_T *dims = var->data.dims; + const void * const *currDimsPtr = NULL; + const int_T *currDimsSizePtr = NULL; + + /* The following variables will be used for + logging "valueDimensions" field */ + size_t offset_valDims = 0; + char_T *currValDimsRow = NULL; + size_t elSize_valDims = sizeof(real_T); + real_T currentSigDims = 0; + int_T nRows_valDims = 0; + int_T logWidth_valDims = 0; + + for (i = 0; i < frameSize; i++) { + if (++var->numHits % var->decimation) continue; + var->numHits = 0; + + if (var->rowIdx == var->data.nRows) { + if (var->okayToRealloc == 1) { + rt_ReallocLogVar(var, isVarDims); + } else { + /* Circular buffer */ + var->rowIdx = 0; + ++(var->wrapped); /* increment the wrap around counter */ + } + } + + if(isVarDims){ + currDimsPtr = (const void * const *) var->valDims->currSigDims; + currDimsSizePtr = (const int_T*) var->valDims->currSigDimsSize; + logWidth_valDims = frameData ? 1 : var->valDims->nCols; + nRows_valDims = var->valDims->nRows; + + var->strides[0] = 1; + var->currStrides[0] = 1; + + for (k = 1; k < nDims; k++){ + int32_T currDimsVal=0; + switch (currDimsSizePtr[k-1]) { + case 1: + currDimsVal = (**(((const uint8_T * const *) currDimsPtr)+(k-1))); + break; + case 2: + currDimsVal = (**(((const uint16_T * const *) currDimsPtr)+(k-1))); + break; + case 4: + currDimsVal = (**(((const uint32_T * const *) currDimsPtr)+(k-1))); + break; + } + var->strides[k] = var->strides[k-1] * dims[k-1]; + var->currStrides[k] = var->currStrides[k-1] * currDimsVal; + } + } + + offset = (size_t)(elSize * var->rowIdx * logWidth); + currRealRow = ((char_T*) (var->data.re)) + offset; + currImagRow = (var->data.complex) ? + ((char_T*) (var->data.im)) + offset : NULL; + + /* update logging data */ + for (j = 0; j < logWidth; j++) { + + boolean_T inRange = true; + int idx = j; + + /* Check whether the currently logged value is in range or not. + For fixed-size signal logging, always inRange = true; idx = j; + For variable-size signal logging, use strides, coordinates + and current strides to decide whether the currently logged + data is in range or not and its location in the logging + matrix. + */ + if(isVarDims){ + int rem = j; + idx = 0; + for(k = nDims-1; k>=0; k--){ + int32_T currDimsVal=0; + switch (currDimsSizePtr[k]) { + case 1: + currDimsVal = (**(((const uint8_T * const *) currDimsPtr)+k)); + break; + case 2: + currDimsVal = (**(((const uint16_T * const *) currDimsPtr)+k)); + break; + case 4: + currDimsVal = (**(((const uint32_T * const *) currDimsPtr)+k)); + break; + } + var->coords[k] = rem / var->strides[k]; + if( var->coords[k] >= currDimsVal ){ + inRange = false; + break; + } + rem = rem - var->coords[k] * var->strides[k]; + } + if(inRange){ + idx = var->coords[0]; + for (k = 1; k < nDims; k++){ + idx += var->coords[k] * var->currStrides[k]; + } + } + } + + if (!var->data.dataTypeConvertInfo.conversionNeeded) { + /* NO conversion needed + */ + if (inRange) { + /* If in range, fill in data */ + const char *cDataPoint = cData + (i+frameSize*idx) * pointSize; + + (void) memcpy(currRealRow, cDataPoint, elSize); + currRealRow += elSize; + if (var->data.complex) { + (void) memcpy(currImagRow, cDataPoint + pointSize/2, elSize); + currImagRow += elSize; + } + } else { + /* If out of range, fill in NaN or 0: + 1) For bool, int32, uint32, int16, uint16, etc, + memset to zeros; + 2) For fixed-point data type, NaN conversion is not + allowed, memset to zeros. + */ + if (dTypeID == SS_DOUBLE) { + (void) memcpy(currRealRow, &rtNaN, elSize); + } else if (dTypeID == SS_SINGLE){ + (void) memcpy(currRealRow, &rtNaNF, elSize); + } else { + (void) memset(currRealRow, 0, elSize); + } + + currRealRow += elSize; + if (var->data.complex) { + /* For imaginary part, fill in 0 */ + (void) memset(currImagRow, 0, elSize); + currImagRow += elSize; + } + } + } + else + { + /* YES conversion needed + */ + DTypeId dataTypeIdOriginal = + var->data.dataTypeConvertInfo.dataTypeIdOriginal; + int_T DpSize = (int_T)((var->data.complex) ? + rt_GetSizeofComplexType(dataTypeIdOriginal) : + rt_GetSizeofDataType(dataTypeIdOriginal)); + + DTypeId dataTypeIdLoggingTo = + var->data.dataTypeConvertInfo.dataTypeIdLoggingTo; + + int bitsPerChunk = var->data.dataTypeConvertInfo.bitsPerChunk; + int numOfChunk = var->data.dataTypeConvertInfo.numOfChunk; + unsigned int isSigned = var->data.dataTypeConvertInfo.isSigned; + + double fracSlope = var->data.dataTypeConvertInfo.fracSlope; + int fixedExp = var->data.dataTypeConvertInfo.fixedExp; + double bias = var->data.dataTypeConvertInfo.bias; + + double curRealValue = -0.12345678987654; + double curImagValue = -0.12345678987654; + + int_T adjIndexIfComplex = (var->data.complex) ? 2 : 1; + + if(inRange){ + if(numOfChunk > 1) + { + /* For multiword */ + const char *pInData = (const char *)(cData); + int dtSize = bitsPerChunk*numOfChunk/8; + pInData += ((i+frameSize*idx) * adjIndexIfComplex) * dtSize; + + curRealValue = rt_GetDblValueFromOverSizedData(pInData, bitsPerChunk, numOfChunk, + isSigned, fracSlope, fixedExp, bias); + if (var->data.complex) { + curImagValue = rt_GetDblValueFromOverSizedData((pInData+dtSize), bitsPerChunk, numOfChunk, + isSigned, fracSlope, fixedExp, bias); + } + } + else + { + /* if in range, fill in data that is converted first */ + switch ( dataTypeIdOriginal ) + { + case SS_DOUBLE: + { + const real_T *pInData = (const real_T *)(cData + (i+frameSize*idx)* DpSize); + + curRealValue = ldexp( fracSlope * (double)(*pInData), fixedExp ) + bias; + if (var->data.complex) { + pInData = (const real_T *)(cData + (i+frameSize*idx)* DpSize + DpSize/2); + curImagValue = ldexp( fracSlope * (double)(*pInData), fixedExp ) + bias; + } + } + break; + case SS_SINGLE: + { + const real32_T *pInData = (const real32_T *)(cData + (i+frameSize*idx)* DpSize); + + curRealValue = ldexp( fracSlope * (double)(*pInData), fixedExp ) + bias; + if (var->data.complex) { + pInData = (const real32_T *)(cData + (i+frameSize*idx)* DpSize + DpSize/2); + curImagValue = ldexp( fracSlope * (double)(*pInData), fixedExp ) + bias; + } + } + break; + case SS_INT8: + { + const int8_T *pInData = (const int8_T *)(cData + (i+frameSize*idx)* DpSize); + + curRealValue = ldexp( fracSlope * (double)(*pInData), fixedExp ) + bias; + if (var->data.complex) { + pInData = (const int8_T *)(cData + (i+frameSize*idx)* DpSize + DpSize/2); + curImagValue = ldexp( fracSlope * (double)(*pInData), fixedExp ) + bias; + } + } + break; + case SS_UINT8: + { + const uint8_T *pInData = (const uint8_T *)(cData + (i+frameSize*idx)* DpSize); + + curRealValue = ldexp( fracSlope * (double)(*pInData), fixedExp ) + bias; + if (var->data.complex) { + pInData = (const uint8_T *)(cData + (i+frameSize*idx)* DpSize + DpSize/2); + curImagValue = ldexp( fracSlope * (double)(*pInData), fixedExp ) + bias; + } + } + break; + case SS_INT16: + { + const int16_T *pInData = (const int16_T *)(cData + (i+frameSize*idx)* DpSize); + + curRealValue = ldexp( fracSlope * (double)(*pInData), fixedExp ) + bias; + if (var->data.complex) { + pInData = (const int16_T *)(cData + (i+frameSize*idx)* DpSize + DpSize/2); + curImagValue = ldexp( fracSlope * (double)(*pInData), fixedExp ) + bias; + } + } + break; + case SS_UINT16: + { + const uint16_T *pInData = (const uint16_T *)(cData + (i+frameSize*idx)* DpSize); + + curRealValue = ldexp( fracSlope * (double)(*pInData), fixedExp ) + bias; + if (var->data.complex) { + pInData = (const uint16_T *)(cData + (i+frameSize*idx)* DpSize + DpSize/2); + curImagValue = ldexp( fracSlope * (double)(*pInData), fixedExp ) + bias; + } + } + break; + case SS_INT32: + { + const int32_T *pInData = (const int32_T *)(cData + (i+frameSize*idx)* DpSize); + + curRealValue = ldexp( fracSlope * (double)(*pInData), fixedExp ) + bias; + if (var->data.complex) { + pInData = (const int32_T *)(cData + (i+frameSize*idx)* DpSize + DpSize/2); + curImagValue = ldexp( fracSlope * (double)(*pInData), fixedExp ) + bias; + } + } + break; + case SS_UINT32: + { + const uint32_T *pInData = (const uint32_T *)(cData + (i+frameSize*idx)* DpSize); + + curRealValue = ldexp( fracSlope * (double)(*pInData), fixedExp ) + bias; + if (var->data.complex) { + pInData = (const uint32_T *)(cData + (i+frameSize*idx)* DpSize + DpSize/2); + curImagValue = ldexp( fracSlope * (double)(*pInData), fixedExp ) + bias; + } + } + break; + case SS_BOOLEAN: + { + const boolean_T *pInData = ((const boolean_T *)(cData)); + + pInData += (i+frameSize*idx) * adjIndexIfComplex; + + curRealValue = ldexp( fracSlope * (double)(*pInData), fixedExp ) + bias; + if (var->data.complex) { + curImagValue = ldexp( fracSlope * (double)(*pInData), fixedExp ) + bias; + } + } + break; + default: + { + /* For biglong */ + const char *pInData = (const char *)(cData); + int dtSize = bitsPerChunk*numOfChunk/8; + pInData += ((i+frameSize*idx) * adjIndexIfComplex) * dtSize; + + curRealValue = rt_GetDblValueFromOverSizedData(pInData, bitsPerChunk, numOfChunk, + isSigned, fracSlope, fixedExp, bias); + if (var->data.complex) { + curImagValue = rt_GetDblValueFromOverSizedData((pInData+dtSize), bitsPerChunk, numOfChunk, + isSigned, fracSlope, fixedExp, bias); + } + } + break; + } /* -- end of switch -- */ + } + } else { + /* if out of range, just fill NaN or 0 */ + if(dTypeID == SS_DOUBLE || dTypeID == SS_SINGLE){ + /* vijay 4/11/2013: DO NOT CALL ldexp() with NaN below as it causes + * lcc-win64 to generate inf instead of NaN as output. + * Just use rtNaN directly */ + curRealValue = rtNaN; + } + else{ + curRealValue = ldexp( 0, fixedExp ) + bias; + } + if (var->data.complex) { + /* fill 0 in imaginary part*/ + curImagValue = ldexp( 0, fixedExp ) + bias; + } + } + + switch ( dataTypeIdLoggingTo ) + { + case SS_DOUBLE: + { + *((real_T *)currRealRow) = (real_T)curRealValue; + + if (var->data.complex) { + + *((real_T *)currImagRow) = (real_T)curImagValue; + } + } + break; + case SS_SINGLE: + { + *((real32_T *)currRealRow) = (real32_T)curRealValue; + + if (var->data.complex) { + + *((real32_T *)currImagRow) = (real32_T)curImagValue; + } + } + break; + case SS_INT8: + { + *((int8_T *)currRealRow) = (int8_T)curRealValue; + + if (var->data.complex) { + + *((int8_T *)currImagRow) = (int8_T)curImagValue; + } + } + break; + case SS_UINT8: + { + *((uint8_T *)currRealRow) = (uint8_T)curRealValue; + + if (var->data.complex) { + + *((uint8_T *)currImagRow) = (uint8_T)curImagValue; + } + } + break; + case SS_INT16: + { + *((int16_T *)currRealRow) = (int16_T)curRealValue; + + if (var->data.complex) { + + *((int16_T *)currImagRow) = (int16_T)curImagValue; + } + } + break; + case SS_UINT16: + { + *((uint16_T *)currRealRow) = (uint16_T)curRealValue; + + if (var->data.complex) { + + *((uint16_T *)currImagRow) = (uint16_T)curImagValue; + } + } + break; + case SS_INT32: + { + *((int32_T *)currRealRow) = (int32_T)curRealValue; + + if (var->data.complex) { + + *((int32_T *)currImagRow) = (int32_T)curImagValue; + } + } + break; + case SS_UINT32: + { + *((uint32_T *)currRealRow) = (uint32_T)curRealValue; + + if (var->data.complex) { + + *((uint32_T *)currImagRow) = (uint32_T)curImagValue; + } + } + break; + case SS_BOOLEAN: + { + *((boolean_T *)currRealRow) = (boolean_T)(curRealValue != 0.0); + + if (var->data.complex) { + + *((boolean_T *)currImagRow) = (boolean_T)(curImagValue != 0.0); + } + } + break; + } /* -- end of switch -- */ + + currRealRow += elSize; + if (var->data.complex) { + currImagRow += elSize; + } + } + } + + if(isVarDims){ /* update "valueDimensions" field */ + for(j = 0; j < logWidth_valDims; j ++){ + int32_T currDimsVal=0; + switch (currDimsSizePtr[j]) { + case 1: + currDimsVal = (**(((const uint8_T * const *) currDimsPtr)+j)); + break; + case 2: + currDimsVal = (**(((const uint16_T * const *) currDimsPtr)+j)); + break; + case 4: + currDimsVal = (**(((const uint32_T * const *) currDimsPtr)+j)); + break; + } + offset_valDims = (size_t)(elSize_valDims *( var->rowIdx + nRows_valDims * j)); + currValDimsRow = ((char_T*) (var->valDims->dimsData)) + offset_valDims; + + /* convert int_T to real_T */ + currentSigDims = (real_T) currDimsVal; + (void) memcpy(currValDimsRow, ¤tSigDims, elSize_valDims); + currValDimsRow += elSize_valDims; + } + } + + ++var->rowIdx; + } + + return; + +} /* end rt_UpdateLogVar */ + + +#ifdef __cplusplus +} +#endif + + + + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Function: rt_UpdateStructLogVar ============================================= + * Abstract: + * Called to log data for a structure log variable. + */ +void rt_UpdateStructLogVar(StructLogVar *var, const real_T *t, const void *data) +{ + LogVar *values = var->signals.values; + const char_T *signal = data; + boolean_T *isVarDims = var->signals.isVarDims; + int i = 0; + + /* time */ + if (var->logTime) { + rt_UpdateLogVar(var->time, t, false); + } + + /* signals */ + while (values) { + size_t elSz = values->data.elSize; + + rt_UpdateLogVar(values, signal, isVarDims[i]); + + if (values->data.complex) elSz *= 2; + signal += elSz * values->data.nCols; + + values = values->next; + i++; + } + +} /* end rt_UpdateStructLogVar */ + + +#ifdef __cplusplus +} +#endif + + + + +#ifdef __cplusplus +extern "C" { +#endif + +/* + * g1614989:Refactoring this function to accept number of elements + * instead of accepting signalInfo and index. + */ +void* rt_getTempMemory(LogVar* var, int_T numEls); + +void* rt_getTempMemory(LogVar* var, int_T numEls) +{ + size_t elSize = var->data.elSize; + size_t cmplxMult = var->data.complex ? 2 : 1; + /* + * g1689750: With multiword suport for mat file logging in row major array layout, we need to allocate more space to + * store the data when the transpose operation is being performed. The additional space is required to store multiple + * chunks that each multi word contains. + */ + size_t numOfChunks = var->data.dataTypeConvertInfo.conversionNeeded ? var->data.dataTypeConvertInfo.numOfChunk : 1; + void* tempMemory = malloc(elSize * numEls * cmplxMult * numOfChunks); + return tempMemory; +} + +/* +* g1614989:This function processes the signal data if a function pointer is available and then logs the data. +* If a function pointer is not present, signal data is logged without any processing. +* The idx parameter specifies which information from the SignalInfo to be used for processing and logging. +* When idx is -1, the provided signal info is to be used for processing and logging the data. +*/ +void rt_preProcessAndLogDataWithIndex(const RTWLogSignalInfo *signalInfo, int_T idx, LogVar* val, const void * data, boolean_T isVarDims); + +void rt_preProcessAndLogDataWithIndex(const RTWLogSignalInfo *signalInfo, int_T idx, LogVar* val, const void * data, boolean_T isVarDims) +{ + RTWPreprocessingFcnPtr preprocessingPtr = NULL; + int_T numEls = -1; + if (idx == -1) { + preprocessingPtr = *(signalInfo->preprocessingPtrs); + numEls = *(signalInfo->numCols); + } + else { + preprocessingPtr = signalInfo->preprocessingPtrs[idx]; + numEls = signalInfo->numCols[idx]; + } + + if (preprocessingPtr != NULL) { + void* curData = rt_getTempMemory(val, numEls); + preprocessingPtr(curData, data); + rt_UpdateLogVar(val, curData, isVarDims); + free(curData); + } + else { + rt_UpdateLogVar(val, data, isVarDims); + } +} + +/* +* g1614989:This function is called when each signal has a specific RTWLogSignalInfo structure defined. +*/ + +void rt_preProcessAndLogData(RTWLogSignalInfo signalInfo, LogVar* val, const void * data, boolean_T isVarDims); + +void rt_preProcessAndLogData(RTWLogSignalInfo signalInfo, LogVar* val, const void * data, boolean_T isVarDims) +{ + rt_preProcessAndLogDataWithIndex(&signalInfo, -1, val, data, isVarDims); +} + +/* Function: rt_UpdateTXYLogVars =============================================== + * Abstract: + * Update the xFinal,T,X,Y variables that are being logged. + */ +const char_T *rt_UpdateTXYLogVars(RTWLogInfo *li, time_T *tPtr) +{ + return rt_UpdateTXXFYLogVars(li, tPtr, true); +} + +/* Function: rt_UpdateTXXFYLogVars ============================================= + * Abstract: + * Update xFinal and/or the T,X,Y variables that are being logged + */ +const char_T *rt_UpdateTXXFYLogVars(RTWLogInfo *li, time_T *tPtr, boolean_T updateTXY) +{ + LogInfo *logInfo = rtliGetLogInfo(li); + int_T matrixFormat = (rtliGetLogFormat(li) == 0); + const RTWLogSignalInfo* yInfo = rtliGetLogYSignalInfo(li); + const RTWLogSignalInfo* xInfo = rtliGetLogXSignalInfo(li); + + /* time */ + if (logInfo->t != NULL && updateTXY) { + rt_UpdateLogVar(logInfo->t, tPtr, false); + } + + if (matrixFormat) { /* MATRIX_FORMAT */ + /* states */ + if (logInfo->x != NULL || logInfo->xFinal != NULL) { + int8_T** segAddr = _rtliGetLogXSignalPtrs(li); + const int_T *segLengths = xInfo->numCols; + int_T nSegments = xInfo->numSignals; + RTWPreprocessingFcnPtr* preprocessingPtrs = xInfo->preprocessingPtrs; + + if (logInfo->x != NULL && updateTXY) { + const char_T *errorMessage = rt_UpdateLogVarWithDiscontiguousData(logInfo->x, segAddr, + segLengths, nSegments, + preprocessingPtrs); + if (errorMessage != NULL) return(errorMessage); + } + if (logInfo->xFinal != NULL) { + const char_T *errorMessage = rt_UpdateLogVarWithDiscontiguousData(logInfo->xFinal, segAddr, + segLengths, nSegments, + preprocessingPtrs); + if (errorMessage != NULL) return(errorMessage); + } + } + /* outputs */ + if (logInfo->y != NULL && updateTXY) { + LogVar **var = (LogVar**) (logInfo->y); + int_T ny = logInfo->ny; + int_T i; + int yIdx; + LogSignalPtrsType data = rtliGetLogYSignalPtrs(li); + + for (i = 0, yIdx = 0; i < ny; i++) { + if (data[i] != NULL) { + /* + When outputs are logged in Matrix format, + no variable-size signal logging is allowed. + */ + /* g1614989:Code refactoring and fix for logging issue. + * Function pointer is now identified by using + * Y Signal Info instead of iterating over preprocessing + * function pointers. + */ + rt_preProcessAndLogData(yInfo[yIdx], var[yIdx], data[i], false); + yIdx++; + } + } + } + } else { /* STRUCTURE_FORMAT */ + /* states */ + if (logInfo->x != NULL && updateTXY) { + int_T i; + StructLogVar *var = logInfo->x; + LogVar *val = var->signals.values; + int_T nsig = var->signals.numSignals; + LogSignalPtrsType data = rtliGetLogXSignalPtrs(li); + + /* time */ + if (var->logTime) { + rt_UpdateLogVar(var->time, tPtr, false); + } + + /* signals */ + for (i = 0; i < nsig; i++) { + /* g1614989:Code refactoring and fix for logging issue. + * Function pointer is now identified by using + * X Signal Info instead of iterating over preprocessing + * function pointers. + */ + rt_preProcessAndLogDataWithIndex(xInfo, i, val, data[i], false); + val = val->next; + } + } + + /* outputs */ + if (logInfo->y != NULL && updateTXY) { + int_T ny = logInfo->ny; + LogSignalPtrsType data = rtliGetLogYSignalPtrs(li); + StructLogVar **var = (StructLogVar**) (logInfo->y); + + if (ny == 1) { + int_T i; + int_T dataIdx; + LogVar *val = var[0]->signals.values; + int_T nsig = var[0]->signals.numSignals; + boolean_T *isVarDims = var[0]->signals.isVarDims; + + /* time */ + if (var[0]->logTime) { + rt_UpdateLogVar(var[0]->time, tPtr, false); + } + + /* signals */ + for (i = 0, dataIdx = 0; i < nsig; i++) { + while (data[dataIdx] == NULL) { + ++dataIdx; + } + /* g1614989:Code refactoring and fix for logging issue. + * Function pointer is now identified by using + * Y Signal Info instead of iterating over preprocessing + * function pointers. + */ + rt_preProcessAndLogDataWithIndex(yInfo, i, val, data[dataIdx], isVarDims[i]); + dataIdx++; + val = val->next; + } + } else { + int_T i; + int_T dataIdx; + + for (i = 0, dataIdx = 0; i < ny && var[i] != NULL; i++) { + LogVar *val = var[i]->signals.values; + boolean_T *isVarDims = var[i]->signals.isVarDims; + + /* time */ + if (var[i]->logTime) { + rt_UpdateLogVar(var[i]->time, tPtr, false); + } + + /* signals */ + while (data[dataIdx] == NULL) { + ++dataIdx; + } + /* g1614989:Code refactoring and fix for logging issue. + * Function pointer is now identified by using + * Y Signal Info instead of iterating over preprocessing + * function pointers. + */ + rt_preProcessAndLogData(yInfo[i], val, data[dataIdx], isVarDims[0]); + dataIdx++; + val = val->next; + } + } + } + /* final state */ + if (logInfo->xFinal != NULL) { + StructLogVar *xf = logInfo->xFinal; + LogVar *val = xf->signals.values; + int_T nsig = xf->signals.numSignals; + int_T i; + + /* time */ + if (xf->logTime) { + rt_UpdateLogVar(xf->time, tPtr, false); + } + + /* signals */ + for (i = 0; i < nsig; i++) { + LogSignalPtrsType data = rtliGetLogXSignalPtrs(li); + /* g1614989:Code refactoring and fix for logging issue. + * Function pointer is now identified by using + * X Signal Info instead of iterating over preprocessing + * function pointers. + */ + rt_preProcessAndLogDataWithIndex(xInfo, i, val, data[i], false); + val = val->next; + } + } + } + return(NULL); +} /* end rt_UpdateTXXFYLogVars */ + + +#ifdef __cplusplus +} +#endif + + + + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Function: rt_StopDataLoggingImpl ======================================= + * Abstract: + * Write logged data to model.mat and free memory. + */ +void rt_StopDataLoggingImpl(const char_T *file, RTWLogInfo *li, boolean_T isRaccel) +{ + FILE *fptr; + LogInfo *logInfo = (LogInfo*) rtliGetLogInfo(li); + LogVar *var = logInfo->logVarsList; + StructLogVar *svar = logInfo->structLogVarsList; + /* At this time, verbose is only needed if running rapid accelerator + * simulations. */ + int verbose = isRaccel ? 0: 1; + + boolean_T emptyFile = 1; /* assume */ + boolean_T errFlag = 0; + const char_T *msg; + + /******************************* + * Create MAT file with header * + *******************************/ + if ((fptr=fopen(file,"w+b")) == NULL) { + (void)fprintf(stderr,"*** Error opening %s",file); + goto EXIT_POINT; + } + if (rt_WriteMat5FileHeader(fptr)) { + (void)fprintf(stderr,"*** Error writing to %s",file); + goto EXIT_POINT; + } + + /************************************************** + * First log all the variables in the LogVar list * + **************************************************/ + while (var != NULL) { + if ( (msg = rt_FixupLogVar(var,verbose)) != NULL ) { + (void)fprintf(stderr,"*** Error writing %s due to: %s\n",file,msg); + errFlag = 1; + break; + } + if (var->nDataPoints > 0 || isRaccel) { + MatItem item; + + item.type = matMATRIX; + item.nbytes = 0; /* not yet known */ + item.data = &(var->data); + if (rt_WriteItemToMatFile(fptr, &item, MATRIX_ITEM)) { + (void)fprintf(stderr,"*** Error writing log variable %s to " + "file %s",var->data.name, file); + errFlag = 1; + break; + } + emptyFile = 0; + } + var = var->next; + } + /* free up some memory by destroying the log var list here */ + rt_DestroyLogVar(logInfo->logVarsList); + logInfo->logVarsList = NULL; + + /******************************************************* + * Next log all the variables in the StructLogVar list * + *******************************************************/ + while (svar != NULL) { + MatItem item; + + if (svar->logTime) { + var = svar->time; + if ( (msg = rt_FixupLogVar(var,verbose)) != NULL ) { + (void)fprintf(stderr, "*** Error writing %s due to: %s\n", + file, msg); + errFlag = 1; + break; + } + } + + var = svar->signals.values; + while (var) { + if ( (msg = rt_FixupLogVar(var,verbose)) != NULL ) { + (void)fprintf(stderr, "*** Error writing %s due to: %s\n", + file, msg); + errFlag = 1; + break; + } + var = var->next; + } + + item.type = matMATRIX; + item.nbytes = 0; /* not yet known */ + item.data = svar; + + if (rt_WriteItemToMatFile(fptr, &item, STRUCT_LOG_VAR_ITEM)) { + (void)fprintf(stderr,"*** Error writing structure log variable " + "%s to file %s",svar->name, file); + errFlag = 1; + break; + } + emptyFile = 0; + + svar = svar->next; + } + + /****************** + * Close the file * + ******************/ + (void)fclose(fptr); + if (emptyFile || errFlag) { + (void)remove(file); + } else { + if( verbose ) { + (void)printf("** created %s **\n\n", file); + } + } + + EXIT_POINT: + + /**************** + * free logInfo * + ****************/ + rt_DestroyLogVar(logInfo->logVarsList); + logInfo->logVarsList = NULL; + rt_DestroyStructLogVar(logInfo->structLogVarsList); + logInfo->structLogVarsList = NULL; + FREE(logInfo->y); + logInfo->y = NULL; + FREE(logInfo); + rtliSetLogInfo(li,NULL); + +} /* end rt_StopDataLoggingImpl */ + + +#ifdef __cplusplus +} +#endif + + +#ifdef __cplusplus +extern "C" { +#endif + + +/* Function: rt_StopDataLogging ================================================ + * Abstract: + * Write logged data to model.mat and free memory. + */ +void rt_StopDataLogging(const char_T *file, RTWLogInfo *li) +{ + rt_StopDataLoggingImpl(file,li,false); + +} /* end rt_StopDataLogging */ + + +#ifdef __cplusplus +} +#endif + +#else /*!defined(MAT_FILE) || (defined(MAT_FILE) && MAT_FILE == 1)*/ + +#define rt_StartDataLogging(li, finalTime, stepSize, errStatus) NULL /* do nothing */ +#define rt_UpdateTXYLogVars(li, tPtr) NULL /* do nothing */ +#define rt_StopDataLogging(file, li); /* do nothing */ + +#endif /*!defined(MAT_FILE) || (defined(MAT_FILE) && MAT_FILE == 1)*/ + + + +/* [eof] rt_logging.c */ + +/* LocalWords: Tfinal MAXNAM nonfinite DType PWS RSim Fixup logvar DDEFAULT th + * LocalWords: curr Realloc realloc inp biglong vijay ldexp TXY eof XFinal th + * LocalWords: TXXFY NULL + */ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/rtw/c/src/rt_logging.h b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/rtw/c/src/rt_logging.h new file mode 100644 index 0000000..c6507e5 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/rtw/c/src/rt_logging.h @@ -0,0 +1,285 @@ +/* Copyright 2012-2015 The MathWorks, Inc. */ + +#ifndef rt_logging_h +#define rt_logging_h + +#if defined(_MSC_VER) +# pragma once +#endif +#if defined(__GNUC__) && (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ > 3)) +# pragma once +#endif + +#if !defined(MAT_FILE) || (defined(MAT_FILE) && MAT_FILE == 1) + +#include /* size_t */ +#include "rtwtypes.h" +#include "builtin_typeid_types.h" +#include "multiword_types.h" +#include "rt_mxclassid.h" +#include "rtw_matlogging.h" + +#ifndef TMW_NAME_LENGTH_MAX +#define TMW_NAME_LENGTH_MAX 64 +#endif +#define mxMAXNAM TMW_NAME_LENGTH_MAX /* maximum name length */ + +/*=========* + * Defines * + *=========*/ + +/* + * Logging related functions and data structures + */ +typedef double MatReal; /* "real" data type used in model.mat */ +typedef struct LogVar_Tag LogVar; +typedef struct StructLogVar_Tag StructLogVar; + +typedef struct MatrixData_Tag { + char_T name[mxMAXNAM]; /* Name of the variable */ + int_T nRows; /* number of rows */ + int_T nCols; /* number of columns */ + int_T nDims; /* number of dimensions */ + int_T _dims[2]; /* most cases, dimensions are 2 */ + int_T *dims; /* dimensions of the log variable we + write to at each simulation time step. + E.g: (1) Non-frame data - + Signal dimension = [2 X 3] + numDims = 2 + dims[0] = 2, dims[1] = 3 + (2) Frame data - + Signal dimension = [2 X 3] + numDims = 1 + dims[0] = 3 */ + void *re; /* pointer to real part of the data */ + void *im; /* pointer to imaginary part, if complex */ + DTypeId dTypeID; /* data type id */ + size_t elSize; /* element size in bytes */ + + RTWLogDataTypeConvert dataTypeConvertInfo; + + mxClassID mxID; /* mxId corresponding to this dTypeID */ + uint32_T logical; /* is this a logical array ? */ + uint32_T complex; /* is this a complex matrix? */ + uint32_T frameData; /* is this data frame based? */ + uint32_T frameSize; /* is this data frame based? */ +} MatrixData; + +typedef struct ValDimsData_Tag { + char_T name[mxMAXNAM]; /* Name of the variable */ + int_T nRows; /* number of rows */ + int_T nCols; /* number of columns */ + void **currSigDims; /* dimensions of current output */ + int_T *currSigDimsSize; /* size in bytes of current sig dims */ + real_T *dimsData; /* pointer to the value of dimension */ +} ValDimsData; + +struct LogVar_Tag { + MatrixData data; /* Container for name, data etc., */ + ValDimsData *valDims; /* field of valueDimensions + 1. If all logging signals are fixed-size, + then we set this field to NULL; + 2. If any logging signal is variable-size, + then this field will be needed: + 1) For fixed-size signal, this field is + an empty matrix; + 2) Otherwise, it contains the dimension + information of the logging signal. + */ + int_T rowIdx; /* current row index */ + int_T wrapped; /* number of times the circular buffer + * has wrapped around */ + int_T nDataPoints; /* total number of data points logged */ + int_T usingDefaultBufSize; /* used to print a message at end */ + int_T okayToRealloc; /* reallocate during sim? */ + int_T decimation; /* decimation factor */ + int_T numHits; /* decimation hit count */ + + int_T *coords; + int_T *strides; + int_T *currStrides; /* coords, strides and currStrides will be + needed when logging variable-size + signal to calculate whether the + currently logging value is in the range. + If the current signal is fixed-size, + these pointers will be set to NULLs; + otherwise, we allocate memory for them. + (the size will be nDims in this case) + */ + + LogVar *next; +}; + +typedef struct SignalsStruct_Tag { + int_T numActiveFields; /* number of active fields */ + const char_T *fieldNames; + int_T numSignals; + LogVar *values; + MatrixData *dimensions; + MatrixData *labels; + MatrixData *plotStyles; + MatrixData *titles; + MatrixData *blockNames; + MatrixData *stateNames; + MatrixData *crossMdlRef; + + boolean_T logValueDimensions; /* If there's any variable-size signal + we also should log 'valueDimensions' + field */ + boolean_T *isVarDims; /* is this signal a variable-size signal? */ +} SignalsStruct; + +struct StructLogVar_Tag { + char_T name[mxMAXNAM]; /* Name of the ML Struct variable */ + int_T numActiveFields; /* number of active fields */ + boolean_T logTime; + void *time; + SignalsStruct signals; + MatrixData *blockName; + + StructLogVar *next; +}; + +#define matUNKNOWN 0 +#define matINT8 1 +#define matUINT8 2 +#define matINT16 3 +#define matUINT16 4 +#define matINT32 5 +#define matUINT32 6 +#define matFLOAT 7 +#define matDOUBLE 9 +#define matINT64 12 +#define matUINT64 13 +#define matMATRIX 14 + +/* status of logging "valueDimensions" field */ +/* + NO_LOGVALDIMS: + No need to log valueDimensions: + All signals are fixed-sized. + + LOGVALDIMS_EMPTYMX: + Signals with mixed dimension modes, + and the signal logged currently + is fixed-sized. So set valueDimensions + field to an empty matrix. + + LOGVALDIMS_VARDIMS: + Signal logged currently is variable-sized. +*/ +typedef enum { + NO_LOGVALDIMS, + LOGVALDIMS_EMPTYMX, + LOGVALDIMS_VARDIMS +} LogValDimsStat; + + + +#ifdef __cplusplus +extern "C" { +#endif + +extern mxClassID rt_GetMxIdFromDTypeIdForRSim(BuiltInDTypeId dTypeID); + +extern mxClassID rt_GetMxIdFromDTypeId(BuiltInDTypeId dTypeID); + +extern LogVar *rt_CreateLogVarWithConvert( + RTWLogInfo *li, + const real_T startTime, + const real_T finalTime, + const real_T inStepSize, + const char_T **errStatus, + const char_T *varName, + BuiltInDTypeId inpDataTypeID, + const RTWLogDataTypeConvert *pDataTypeConvertInfo, + int_T logical, + int_T complex, + int_T frameData, + int_T nCols, + int_T nDims, + const int_T *dims, + LogValDimsStat logValDimsStat, + void **currSigDims, + int_T *currSigDimsSize, + int_T maxRows, + int_T decimation, + real_T sampleTime, + int_T appendToLogVarsList); + + +extern LogVar *rt_CreateLogVar(RTWLogInfo *li, + const real_T startTime, + const real_T finalTime, + const real_T inStepSize, + const char_T **errStatus, + const char_T *varName, + BuiltInDTypeId inpDataTypeID, + int_T logical, + int_T complex, + int_T frameData, + int_T nCols, + int_T nDims, + const int_T *dims, + LogValDimsStat logValDimsStat, + void **currSigDims, + int_T *currSigDimsSize, + int_T maxRows, + int_T decimation, + real_T sampleTime, + int_T appendToLogVarsList); + +extern StructLogVar *rt_CreateStructLogVar(RTWLogInfo *li, + const real_T startTime, + const real_T finalTime, + const real_T inStepSize, + const char_T **errStatus, + const char_T *varName, + boolean_T logTime, + int_T maxRows, + int_T decimation, + real_T sampleTime, + const RTWLogSignalInfo *sigInfo, + const char_T *blockName); + + +extern const char_T *rt_StartDataLoggingWithStartTime(RTWLogInfo *li, + const real_T startTime, + const real_T finalTime, + const real_T stepSize, + const char_T **errStatus); + +extern const char_T *rt_StartDataLogging(RTWLogInfo *li, + const real_T finalTime, + const real_T stepSize, + const char_T **errStatus); + +extern void rt_UpdateLogVar(LogVar *var, const void *data, boolean_T isVarDims); + +extern void rt_UpdateStructLogVar(StructLogVar *var, const real_T *t, const void *data); + +extern const char_T *rt_UpdateTXYLogVars(RTWLogInfo *li, time_T *tPtr); +extern const char_T *rt_UpdateTXXFYLogVars(RTWLogInfo *li, time_T *tPtr, boolean_T updateTXY); + +extern void rt_StopDataLoggingImpl(const char_T *file, RTWLogInfo *li, boolean_T isRaccel); + +extern void rt_StopDataLogging(const char_T *file, RTWLogInfo *li); + + +#ifdef __cplusplus +} +#endif + + +#else /*!defined(MAT_FILE) || (defined(MAT_FILE) && MAT_FILE == 1)*/ + +#define rt_StartDataLogging(li, finalTime, stepSize, errStatus) NULL /* do nothing */ +#define rt_UpdateTXYLogVars(li, tPtr) NULL /* do nothing */ +#define rt_StopDataLogging(file, li); /* do nothing */ + +#endif /*!defined(MAT_FILE) || (defined(MAT_FILE) && MAT_FILE == 1)*/ + +#endif /* rt_logging_h */ + +/* LocalWords: curr LOGVALDIMS EMPTYMX VARDIMS + */ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/rtw/c/src/rt_mxclassid.h b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/rtw/c/src/rt_mxclassid.h new file mode 100644 index 0000000..f1c2dfc --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/rtw/c/src/rt_mxclassid.h @@ -0,0 +1,37 @@ +/* Copyright 1994-2004 The MathWorks, Inc. + * + * File : rt_mxclassid.h + * Abstract: + * Definition of enum mxClassID + * + */ + + +#ifndef __rt_mxclassid_h__ +#define __rt_mxclassid_h__ + +typedef enum { + mxUNKNOWN_CLASS = 0, + mxCELL_CLASS = 1, + mxSTRUCT_CLASS, + mxLOGICAL_CLASS, + mxCHAR_CLASS, + mxRESERVED5_CLASS, /* mxVOID_CLASS */ + mxDOUBLE_CLASS, + mxSINGLE_CLASS, + mxINT8_CLASS, + mxUINT8_CLASS, + mxINT16_CLASS, + mxUINT16_CLASS, + mxINT32_CLASS, + mxUINT32_CLASS, + mxINT64_CLASS, /* place holder - future enhancements */ + mxUINT64_CLASS, /* place holder - future enhancements */ + mxRESERVED16_CLASS, /* mxFUNCTION_CLASS */ + mxRESERVED17_CLASS, /* mxOPAQUE_CLASS */ + mxOBJECT_CLASS +} mxClassID; + +#endif /* __rt_mxclassid_h__ */ + +/* [EOF] rt_mxclass_id.h */ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/rtw_continuous.h b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/rtw_continuous.h new file mode 100644 index 0000000..c20df6d --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/rtw_continuous.h @@ -0,0 +1,131 @@ +/* Copyright 1990-2014 The MathWorks, Inc. */ + +/* + * File: rtw_continuous.h + * + * Abstract: + * Type definitions for continuous-time support. + * + */ + +#ifndef RTW_CONTINUOUS_H__ +#define RTW_CONTINUOUS_H__ + +#ifdef MATLAB_MEX_FILE +#include "tmwtypes.h" +#else +#include "rtwtypes.h" +#endif + +/* For models registering MassMatrix */ +typedef enum { + SS_MATRIX_NONE, + SS_MATRIX_CONSTANT, + SS_MATRIX_TIMEDEP, + SS_MATRIX_STATEDEP +} ssMatrixType; + +typedef enum { + SOLVER_MODE_AUTO, /* only occurs in + mdlInitializeSizes/mdlInitializeSampleTimes */ + SOLVER_MODE_SINGLETASKING, + SOLVER_MODE_MULTITASKING +} SolverMode; + +typedef enum { + MINOR_TIME_STEP, + MAJOR_TIME_STEP +} SimTimeStep; + +/* ============================================================================= + * Model methods object + * ============================================================================= + */ +typedef void (*rtMdlInitializeSizesFcn)(void *rtModel); +typedef void (*rtMdlInitializeSampleTimesFcn)(void *rtModel); +typedef void (*rtMdlStartFcn)(void *rtModel); +typedef void (*rtMdlOutputsFcn)(void *rtModel, int_T tid); +typedef void (*rtMdlUpdateFcn)(void *rtModel, int_T tid); +typedef void (*rtMdlDerivativesFcn)(void *rtModel); +typedef void (*rtMdlProjectionFcn)(void *rtModel); +typedef void (*rtMdlMassMatrixFcn)(void *rtModel); +typedef void (*rtMdlForcingFunctionFcn)(void *rtModel); +typedef void (*rtMdlTerminateFcn)(void *rtModel); +#ifdef RT_MALLOC +typedef real_T (*rtMdlDiscreteEventsFcn)(void *pModel, + int_T rtmNumSampTimes, + void *rtmTimingData, + int_T *rtmSampleHitPtr, + int_T *rtmPerTaskSampleHits); +#endif + +typedef struct _RTWRTModelMethodsInfo_tag { + void *rtModelPtr; + rtMdlInitializeSizesFcn rtmInitSizesFcn; + rtMdlInitializeSampleTimesFcn rtmInitSampTimesFcn; + rtMdlStartFcn rtmStartFcn; + rtMdlOutputsFcn rtmOutputsFcn; + rtMdlUpdateFcn rtmUpdateFcn; + rtMdlDerivativesFcn rtmDervisFcn; + rtMdlProjectionFcn rtmProjectionFcn; + rtMdlMassMatrixFcn rtmMassMatrixFcn; + rtMdlForcingFunctionFcn rtmForcingFunctionFcn; + rtMdlTerminateFcn rtmTerminateFcn; +#ifdef RT_MALLOC + rtMdlDiscreteEventsFcn rtmDiscreteEventsFcn; +#endif +} RTWRTModelMethodsInfo; + +#define rtmiSetRTModelPtr(M,rtmp) ((M).rtModelPtr = (rtmp)) +#define rtmiGetRTModelPtr(M) (M).rtModelPtr + +#define rtmiSetInitSizesFcn(M,fp) \ + ((M).rtmInitSizesFcn = ((rtMdlInitializeSizesFcn)(fp))) +#define rtmiSetInitSampTimesFcn(M,fp) \ + ((M).rtmInitSampTimesFcn = ((rtMdlInitializeSampleTimesFcn)(fp))) +#define rtmiSetStartFcn(M,fp) \ + ((M).rtmStartFcn = ((rtMdlStartFcn)(fp))) +#define rtmiSetOutputsFcn(M,fp) \ + ((M).rtmOutputsFcn = ((rtMdlOutputsFcn)(fp))) +#define rtmiSetUpdateFcn(M,fp) \ + ((M).rtmUpdateFcn = ((rtMdlUpdateFcn)(fp))) +#define rtmiSetDervisFcn(M,fp) \ + ((M).rtmDervisFcn = ((rtMdlDerivativesFcn)(fp))) +#define rtmiSetProjectionFcn(M,fp) \ + ((M).rtmProjectionFcn = ((rtMdlProjectionFcn)(fp))) +#define rtmiSetMassMatrixFcn(M,fp) \ + ((M).rtmMassMatrixFcn = ((rtMdlMassMatrixFcn)(fp))) +#define rtmiSetForcingFunctionFcn(M,fp) \ + ((M).rtmForcingFunctionFcn = ((rtMdlForcingFunctionFcn)(fp))) +#define rtmiSetTerminateFcn(M,fp) \ + ((M).rtmTerminateFcn = ((rtMdlTerminateFcn)(fp))) +#ifdef RT_MALLOC +#define rtmiSetDiscreteEventsFcn(M,fp) \ + ((M).rtmDiscreteEventsFcn = ((rtMdlDiscreteEventsFcn)(fp))) +#endif + +#define rtmiInitializeSizes(M) \ + ((*(M).rtmInitSizesFcn)((M).rtModelPtr)) +#define rtmiInitializeSampleTimes(M) \ + ((*(M).rtmInitSampTimesFcn)((M).rtModelPtr)) +#define rtmiStart(M) \ + ((*(M).rtmStartFcn)((M).rtModelPtr)) +#define rtmiOutputs(M, tid) \ + ((*(M).rtmOutputsFcn)((M).rtModelPtr,tid)) +#define rtmiUpdate(M, tid) \ + ((*(M).rtmUpdateFcn)((M).rtModelPtr,tid)) +#define rtmiDerivatives(M) \ + ((*(M).rtmDervisFcn)((M).rtModelPtr)) +#define rtmiProjection(M) \ + ((*(M).rtmProjectionFcn)((M).rtModelPtr)) +#define rtmiMassMatrix(M) \ + ((*(M).rtmMassMatrixFcn)((M).rtModelPtr)) +#define rtmiForcingFunction(M) \ + ((*(M).rtmForcingFunctionFcn)((M).rtModelPtr)) +#define rtmiTerminate(M) \ + ((*(M).rtmTerminateFcn)((M).rtModelPtr)) +#ifdef RT_MALLOC +#define rtmiDiscreteEvents(M,x1,x2,x3,x4) \ + ((*(M).rtmDiscreteEventsFcn)((M).rtModelPtr,(x1),(x2),(x3),(x4))) +#endif +#endif /* __RTW_CONTINUOUS_H__ */ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/rtw_extmode.h b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/rtw_extmode.h new file mode 100644 index 0000000..49329eb --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/rtw_extmode.h @@ -0,0 +1,91 @@ +/* Copyright 1990-2013 The MathWorks, Inc. */ + +/* + * File: rtw_extmode.h + * + * Abstract: + * Type definitions for Simulink External Mode support. + */ + +#ifndef RTW_EXTMODE_H__ +#define RTW_EXTMODE_H__ + +#ifndef _RTWEXTMODEINFO +# define _RTWEXTMODEINFO + typedef struct _RTWExtModeInfo_tag RTWExtModeInfo; +#endif + +/* ============================================================================= + * External mode object + * ============================================================================= + */ +struct _RTWExtModeInfo_tag { + + void *subSysActiveVectorAddr; /* Array of addresses pointing to + * the active vector slots for sub-systems. + * Sub-systems store information about their + * state in their extmode active vector. + */ + uint32_T *checksumsPtr; /* Pointer to the model's checksums array + */ + const void **mdlMappingInfoPtr;/* Pointer to the model's mapping info + * pointer + */ + +#if !defined(ENABLE_SLEXEC_SSBRIDGE) + void *tPtr; /* Copy of model's time pointer */ +#else + void *simStruct; /* simulink execution (raccel/rsim) needs simstruct */ +#endif + + int32_T tFinalTicks; /* Used with integer only code, holds the + * number of base rate ticks representing + * the final time (final time in seconds + * divided by base rate step size). + */ + +}; + +/* gnat 3.12a2 doesn't like use "/" as line continuation here */ +#define rteiSetSubSystemActiveVectorAddresses(E,addr) ((E)->subSysActiveVectorAddr = ((void *)addr)) +#define rteiGetSubSystemActiveVectorAddresses(E) ((E)->subSysActiveVectorAddr) +#define rteiGetAddrOfSubSystemActiveVector(E,idx) ((int8_T*)((int8_T**)((E)->subSysActiveVectorAddr))[idx]) + +#define rteiSetModelMappingInfoPtr(E,mip) ((E)->mdlMappingInfoPtr = (mip)) +#define rteiGetModelMappingInfo(E) (*((E)->mdlMappingInfoPtr)) + +#define rteiSetChecksumsPtr(E,cp) ((E)->checksumsPtr = (cp)) +#define rteiGetChecksum0(E) (E)->checksumsPtr[0] +#define rteiGetChecksum1(E) (E)->checksumsPtr[1] +#define rteiGetChecksum2(E) (E)->checksumsPtr[2] +#define rteiGetChecksum3(E) (E)->checksumsPtr[3] + +#define rteiGetTFinalTicks(E) ((int32_T)((E)->tFinalTicks)) +#define rteiGetPtrTFinalTicks(E) ((int32_T *)(&((E)->tFinalTicks))) + +#if defined(ENABLE_SLEXEC_SSBRIDGE) + #include "slexec_simbridge.h" +#else + #define rteiSetTPtr(E,p) ((E)->tPtr = (p)) + #define rteiGetT(E) ((time_T *)(E)->tPtr)[0] +#endif + +/* + * UNUSED_PARAMETER(x) + * Used to specify that a function parameter (argument) is required but not + * accessed by the function body. + */ +#ifndef UNUSED_PARAMETER +# if defined(__LCC__) +# define UNUSED_PARAMETER(x) /* do nothing */ +# else +/* + * This is the semi-ANSI standard way of indicating that a + * unused function parameter is required. + */ +# define UNUSED_PARAMETER(x) (void) (x) +# endif +#endif + +#endif /* __RTW_EXTMODE_H__ */ + diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/rtw_matlogging.h b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/rtw_matlogging.h new file mode 100644 index 0000000..74f4d64 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/rtw_matlogging.h @@ -0,0 +1,187 @@ +/* Copyright 1990-2015 The MathWorks, Inc. */ + +/* + * File: rtw_matlogging.h + * + * Abstract: + * Type definitions for MAT-file logging support. + */ + +#ifndef RTW_MATLOGGING_H__ +#define RTW_MATLOGGING_H__ + +#include "sl_types_def.h" /* DTypeId */ + +/* + * The RTWLogSignalInfo and RTWLogInfo structures are for use by + * the Real-Time Workshop and should not be used by S-functions. + */ +typedef const int8_T * const * LogSignalPtrsType; + +#ifndef NO_FLOATS /* ERT integer-only */ + +typedef struct RTWLogDataTypeConvert_tag { + + int conversionNeeded; + BuiltInDTypeId dataTypeIdLoggingTo; + DTypeId dataTypeIdOriginal; + int bitsPerChunk; + int numOfChunk; + unsigned int isSigned; + real_T fracSlope; + int fixedExp; + real_T bias; + +} RTWLogDataTypeConvert; + +typedef void (*RTWPreprocessingFcnPtr)(void*, const void*); + +typedef struct RTWLogSignalInfo_tag { + int_T numSignals; + int_T *numCols; + int_T *numDims; + int_T *dims; + boolean_T *isVarDims; /* Dimension Mode: true -- VarDims / false -- fixed dims */ + void **currSigDims; /* current signal dimensions */ + int_T *currSigDimsSize; /* Size of currSigDims in bytes */ + BuiltInDTypeId *dataTypes; + int_T *complexSignals; + int_T *frameData; + RTWPreprocessingFcnPtr* preprocessingPtrs; + + union { + const char_T** cptr; + char_T** ptr; + } labels; + + char_T *titles; + int_T *titleLengths; + int_T *plotStyles; + + union { + const char_T** cptr; + char_T** ptr; + } blockNames; + + union { + const char_T** cptr; + char_T** ptr; + } stateNames; + + boolean_T *crossMdlRef; + + RTWLogDataTypeConvert *dataTypeConvert; + +} RTWLogSignalInfo; + +/* ============================================================================= + * Logging object + * ============================================================================= + */ +typedef struct _RTWLogInfo_tag { + void *logInfo; /* Pointer to a book keeping structure * + * used in rtwlog.c */ + + union { + LogSignalPtrsType cptr; /* Pointers to the memory location */ + int8_T** ptr; /* of the data to be logged into the * + * states structure. Not used if * + * logging data in matrix format. */ + + } logXSignalPtrs; + + union { + LogSignalPtrsType cptr; /* Pointers to the memory location */ + int8_T** ptr; /* of the data to be logged into the * + * outputs structure. Not used if * + * logging data in matrix format. */ + } logYSignalPtrs; + + int_T logFormat; /* matrix=0, struct=1, or strut_wo_time=2 */ + + int_T logMaxRows; /* Max number of rows (0 for no limit) */ + int_T logDecimation; /* Data logging interval */ + + const char_T *logVarNameModifier;/* pre(post)fix string modifier for the * + * log variable names */ + + const char_T *logT; /* Name of variable to log time */ + const char_T *logX; /* Name of variable to log states */ + const char_T *logXFinal; /* Name of variable to log final state */ + const char_T *logY; /* Name of variable(s) to log outputs */ + const char_T *logSL; /* Name of variable(s) to log signal logging */ + + union { /* Info about the states */ + const RTWLogSignalInfo *cptr; + RTWLogSignalInfo *ptr; + } logXSignalInfo; + + union {/* Info about the outputs */ + const RTWLogSignalInfo *cptr; + RTWLogSignalInfo *ptr; + }logYSignalInfo; + + void (*mdlLogData)(void *rtli, void *tPtr); + void (*mdlLogDataIfInInterval)(void *rtli, void *tPtr, boolean_T isInInterval); + + const void * mmi; /* Add the ModelMapping Info to the LogInfo + * so we can get at it for state logging */ + void * loggingInterval; + +} RTWLogInfo; + +#endif + +/* Macros associated with RTWLogInfo */ +#define rtliGetLogInfo(rtli) ((LogInfo*)(rtli)->logInfo) +#define rtliSetLogInfo(rtli,ptr) ((rtli)->logInfo = ((void *)ptr)) + +#define rtliGetLogFormat(rtli) (rtli)->logFormat +#define rtliSetLogFormat(rtli,f) ((rtli)->logFormat = (f)) + +#define rtliGetLogVarNameModifier(rtli) (rtli)->logVarNameModifier +#define rtliSetLogVarNameModifier(rtli,name) ((rtli)->logVarNameModifier=(name)) + +#define rtliGetLogMaxRows(rtli) (rtli)->logMaxRows +#define rtliSetLogMaxRows(rtli,num) ((rtli)->logMaxRows = (num)) + +#define rtliGetLogDecimation(rtli) (rtli)->logDecimation +#define rtliSetLogDecimation(rtli,l) ((rtli)->logDecimation = (l)) + +#define rtliGetLogT(rtli) (rtli)->logT +#define rtliSetLogT(rtli,lt) ((rtli)->logT = (lt)) + +#define rtliGetLogX(rtli) (rtli)->logX +#define rtliSetLogX(rtli,lx) ((rtli)->logX = (lx)) + +#define rtliGetLogY(rtli) (rtli)->logY +#define rtliSetLogY(rtli,ly) ((rtli)->logY = (ly)) + +#define rtliGetLogXFinal(rtli) (rtli)->logXFinal +#define rtliSetLogXFinal(rtli,lxf) ((rtli)->logXFinal = (lxf)) + +#define rtliGetLogXSignalInfo(rtli) (rtli)->logXSignalInfo.cptr +#define rtliSetLogXSignalInfo(rtli,lxi) ((rtli)->logXSignalInfo.cptr = (lxi)) +#define _rtliGetLogXSignalInfo(rtli) (rtli)->logXSignalInfo.ptr + +#define rtliGetLogYSignalInfo(rtli) (rtli)->logYSignalInfo.cptr +#define rtliSetLogYSignalInfo(rtli,lyi) ((rtli)->logYSignalInfo.cptr = (lyi)) +#define _rtliGetLogYSignalInfo(rtli) (rtli)->logYSignalInfo.ptr + +#define rtliGetLogXSignalPtrs(rtli) (rtli)->logXSignalPtrs.cptr +#define rtliSetLogXSignalPtrs(rtli,lxp) ((rtli)->logXSignalPtrs.cptr = (lxp)) +#define _rtliGetLogXSignalPtrs(rtli) (rtli)->logXSignalPtrs.ptr + +#define rtliGetLogYSignalPtrs(rtli) (rtli)->logYSignalPtrs.cptr +#define rtliSetLogYSignalPtrs(rtli,lyp) ((rtli)->logYSignalPtrs.cptr = (lyp)) +#define _rtliGetLogYSignalPtrs(rtli) (rtli)->logYSignalPtrs.ptr + +#define rtliGetMMI(rtli) (rtli)->mmi +#define rtliSetMMI(rtli,mmiIn) ((rtli)->mmi = ((void *)mmiIn)) + +#define rtliGetLoggingInterval(rtli) (rtli)->loggingInterval + +/* ========================================================================== */ + +#endif /* __RTW_MATLOGGING_H__ */ + diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/rtw_solver.h b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/rtw_solver.h new file mode 100644 index 0000000..66774a9 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/rtw_solver.h @@ -0,0 +1,259 @@ +/* + * File: rtw_solver.h + * + * Abstract: + * Type definitions for continuous-time solver support. + * + */ + +/* Copyright 1990-2017 The MathWorks, Inc. */ + +#ifndef RTW_SOLVER_H__ +#define RTW_SOLVER_H__ + +#include "rtw_continuous.h" + +/* ============================================================================= + * Solver object + * ============================================================================= + */ +#ifndef NO_FLOATS /* ERT integer-only */ +/* + * Enum for solver tolerance + */ +typedef enum { + SL_SOLVER_TOLERANCE_AUTO = 0, /* Set Automatically by Solver */ + SL_SOLVER_TOLERANCE_LOCAL = 1, /* Set Locally, e.g., by Blocks */ + SL_SOLVER_TOLERANCE_GLOBAL = 2, /* Set Globally, e.g., by Block Diagram */ + SL_SOLVER_TOLERANCE_UNDEFINED = 255 /* Signal uninitialized */ +} SL_SolverToleranceControlFlag_T; + + +/* + * Enum for jacobian method control + */ +typedef enum { + SL_JM_BD_AUTO = 0, + SL_JM_BD_SPARSE_PERTURBATION, + SL_JM_BD_FULL_PERTURBATION, + SL_JM_BD_SPARSE_ANALYTICAL, + SL_JM_BD_FULL_ANALYTICAL +} slJmBdControl; + + +typedef struct _ssSolverInfo_tag { + void *rtModelPtr; + + SimTimeStep *simTimeStepPtr; + void *solverData; + const char_T *solverName; + boolean_T isVariableStepSolver; + boolean_T solverNeedsReset; + SolverMode solverMode; + + time_T solverStopTime; + time_T *stepSizePtr; + time_T minStepSize; + time_T maxStepSize; + time_T fixedStepSize; + + int_T solverShapePreserveControl; + int_T solverMaxConsecutiveMinStep; + int_T maxNumMinSteps; + int_T solverMaxOrder; + real_T solverConsecutiveZCsStepRelTol; + int_T solverMaxConsecutiveZCs; + + int_T solverExtrapolationOrder; + int_T solverNumberNewtonIterations; + + int_T solverRefineFactor; + real_T solverRelTol; + real_T unused_real_T_1; + + real_T **dXPtr; + time_T **tPtr; + + int_T *numContStatesPtr; + real_T **contStatesPtr; + + int_T* numPeriodicContStatesPtr; + int_T** periodicContStateIndicesPtr; + real_T** periodicContStateRangesPtr; + + real_T* zcSignalVector; + uint8_T* zcEventsVector; + uint8_T* zcSignalAttrib; + int_T zcSignalVectorLength; + uint8_T* reserved; + + boolean_T foundContZcEvents; + boolean_T isAtLeftPostOfContZcEvent; + boolean_T isAtRightPostOfContZcEvent; + boolean_T adaptiveZcDetection; + + int_T numZcSignals; + + boolean_T stateProjection; + boolean_T robustResetMethod; /* user's preference */ + boolean_T updateJacobianAtReset; /* S-Fcn request (sticky) */ + boolean_T consistencyChecking; + + ssMatrixType massMatrixType; + int_T massMatrixNzMax; + int_T* massMatrixIr; + int_T* massMatrixJc; + real_T* massMatrixPr; + + const char_T **errStatusPtr; + + RTWRTModelMethodsInfo *modelMethodsPtr; + real_T zcThreshold; + int_T zeroCrossAlgorithm; + int_T consecutiveZCsError; + boolean_T CTOutputIncnstWithState; + boolean_T isComputingJacobian; + slJmBdControl solverJacobianMethodControl; + int_T ignoredZcDiagnostic; + int_T maskedZcDiagnostic; + boolean_T isOutputMethodComputed; +} ssSolverInfo; + +/* Support old name RTWSolverInfo */ +typedef ssSolverInfo RTWSolverInfo; + +#define rtsiSetRTModelPtr(S,rtmp) ((S)->rtModelPtr = (rtmp)) +#define rtsiGetRTModelPtr(S) (S)->rtModelPtr + +#define rtsiSetSimTimeStepPtr(S,stp) ((S)->simTimeStepPtr = (stp)) +#define rtsiGetSimTimeStepPtr(S) ((S)->simTimeStepPtr) +#define rtsiGetSimTimeStep(S) *((S)->simTimeStepPtr) +#define rtsiSetSimTimeStep(S,st) (*((S)->simTimeStepPtr) = (st)) + +#define rtsiSetSolverData(S,sd) ((S)->solverData = (sd)) +#define rtsiGetSolverData(S) (S)->solverData + +#define rtsiSetSolverName(S,sn) ((S)->solverName = (sn)) +#define rtsiGetSolverName(S) (S)->solverName + +#define rtsiSetVariableStepSolver(S,vs) ((S)->isVariableStepSolver = (vs)) +#define rtsiIsVariableStepSolver(S) (S)->isVariableStepSolver + +#define rtsiSetSolverNeedsReset(S,sn) ((S)->solverNeedsReset = (sn)) +#define rtsiGetSolverNeedsReset(S) (S)->solverNeedsReset + +#define rtsiSetContTimeOutputInconsistentWithStateAtMajorStep(S,sn) ((S)->CTOutputIncnstWithState = (sn)) +#define rtsiGetContTimeOutputInconsistentWithStateAtMajorStep(S) (S)->CTOutputIncnstWithState + +#define rtsiSetBlkStateChange(S,sn) ((S)->CTOutputIncnstWithState = (sn)) +#define rtsiGetBlkStateChange(S) (S)->CTOutputIncnstWithState + +#define rtsiSetBlockStateForSolverChangedAtMajorStep(S,sn) ((S)->solverNeedsReset = (sn)) +#define rtsiGetBlockStateForSolverChangedAtMajorStep(S) (S)->solverNeedsReset + +#define rtsiSetSolverMode(S,sm) ((S)->solverMode = (sm)) +#define rtsiGetSolverMode(S) (S)->solverMode + +#define rtsiSetSolverStopTime(S,st) ((S)->solverStopTime = (st)) +#define rtsiGetSolverStopTime(S) (S)->solverStopTime + +#define rtsiSetStepSizePtr(S,ssp) ((S)->stepSizePtr = (ssp)) +#define rtsiSetStepSize(S,ss) (*((S)->stepSizePtr) = (ss)) +#define rtsiGetStepSize(S) *((S)->stepSizePtr) + +#define rtsiSetMinStepSize(S,ss) (((S)->minStepSize = (ss))) +#define rtsiGetMinStepSize(S) (S)->minStepSize + +#define rtsiSetMaxStepSize(S,ss) ((S)->maxStepSize = (ss)) +#define rtsiGetMaxStepSize(S) (S)->maxStepSize + +#define rtsiSetFixedStepSize(S,ss) ((S)->fixedStepSize = (ss)) +#define rtsiGetFixedStepSize(S) (S)->fixedStepSize + +#define rtsiSetMaxNumMinSteps(S,mns) ((S)->maxNumMinSteps = (mns)) +#define rtsiGetMaxNumMinSteps(S) (S)->maxNumMinSteps + +#define rtsiSetSolverMaxOrder(S,smo) ((S)->solverMaxOrder = (smo)) +#define rtsiGetSolverMaxOrder(S) (S)->solverMaxOrder + +#define rtsiSetSolverJacobianMethodControl(S,smcm) (ssGetSolverInfo(S)->solverJacobianMethodControl = (smcm)) +#define rtsiGetSolverJacobianMethodControl(S) ssGetSolverInfo(S)->solverJacobianMethodControl + +#define rtsiSetSolverShapePreserveControl(S,smcm) (ssGetSolverInfo(S)->solverShapePreserveControl = (smcm)) +#define rtsiGetSolverShapePreserveControl(S) ssGetSolverInfo(S)->solverShapePreserveControl + +#define rtsiSetSolverConsecutiveZCsStepRelTol(S,scr) (ssGetSolverInfo(S)->solverConsecutiveZCsStepRelTol = (scr)) +#define rtsiGetSolverConsecutiveZCsStepRelTol(S) ssGetSolverInfo(S)->solverConsecutiveZCsStepRelTol + +#define rtsiSetSolverMaxConsecutiveZCs(S,smcz) (ssGetSolverInfo(S)->solverMaxConsecutiveZCs = (smcz)) +#define rtsiGetSolverMaxConsecutiveZCs(S) ssGetSolverInfo(S)->solverMaxConsecutiveZCs + +#define rtsiSetSolverMaxConsecutiveMinStep(S,smcm) (ssGetSolverInfo(S)->solverMaxConsecutiveMinStep = (smcm)) +#define rtsiGetSolverMaxConsecutiveMinStep(S) ssGetSolverInfo(S)->solverMaxConsecutiveMinStep + +#define rtsiSetSolverExtrapolationOrder(S,seo) ((S)->solverExtrapolationOrder = (seo)) +#define rtsiGetSolverExtrapolationOrder(S) (S)->solverExtrapolationOrder + +#define rtsiSetSolverNumberNewtonIterations(S,nni) ((S)->solverNumberNewtonIterations = (nni)) +#define rtsiGetSolverNumberNewtonIterations(S) (S)->solverNumberNewtonIterations + +#define rtsiSetSolverRefineFactor(S,smo) ((S)->solverRefineFactor = (smo)) +#define rtsiGetSolverRefineFactor(S) (S)->solverRefineFactor + +#define rtsiSetSolverRelTol(S,smo) ((S)->solverRelTol = (smo)) +#define rtsiGetSolverRelTol(S) (S)->solverRelTol + +#define rtsiSetSolverMassMatrixType(S,type) ((S)->massMatrixType = (type)) +#define rtsiGetSolverMassMatrixType(S) (S)->massMatrixType + +#define rtsiSetSolverMassMatrixNzMax(S,nzMax) ((S)->massMatrixNzMax = (nzMax)) +#define rtsiGetSolverMassMatrixNzMax(S) (S)->massMatrixNzMax + +#define rtsiSetSolverMassMatrixIr(S,ir) ((S)->massMatrixIr = (ir)) +#define rtsiGetSolverMassMatrixIr(S) (S)->massMatrixIr + +#define rtsiSetSolverMassMatrixJc(S,jc) ((S)->massMatrixJc = (jc)) +#define rtsiGetSolverMassMatrixJc(S) (S)->massMatrixJc + +#define rtsiSetSolverMassMatrixPr(S,pr) ((S)->massMatrixPr = (pr)) +#define rtsiGetSolverMassMatrixPr(S) (S)->massMatrixPr + +#define rtsiSetdXPtr(S,dxp) ((S)->dXPtr = (dxp)) +#define rtsiSetdX(S,dx) (*((S)->dXPtr) = (dx)) +#define rtsiGetdX(S) *((S)->dXPtr) + +#define rtsiSetTPtr(S,tp) ((S)->tPtr = (tp)) +#define rtsiSetT(S,t) ((*((S)->tPtr))[0] = (t)) +#define rtsiGetT(S) (*((S)->tPtr))[0] + +#define rtsiSetContStatesPtr(S,cp) ((S)->contStatesPtr = (cp)) +#define rtsiGetContStates(S) *((S)->contStatesPtr) + +#define rtsiSetNumContStatesPtr(S,cp) ((S)->numContStatesPtr = (cp)) +#define rtsiGetNumContStates(S) *((S)->numContStatesPtr) + +#define rtsiSetNumPeriodicContStatesPtr(S,cp) ((S)->numPeriodicContStatesPtr = (cp)) +#define rtsiGetNumPeriodicContStates(S) *((S)->numPeriodicContStatesPtr) + +#define rtsiSetPeriodicContStateIndicesPtr(S,cp) ((S)->periodicContStateIndicesPtr = (cp)) +#define rtsiGetPeriodicContStateIndices(S) *((S)->periodicContStateIndicesPtr) + +#define rtsiSetPeriodicContStateRangesPtr(S,cp) ((S)->periodicContStateRangesPtr = (cp)) +#define rtsiGetPeriodicContStateRanges(S) *((S)->periodicContStateRangesPtr) + +#define rtsiSetErrorStatusPtr(S,esp) ((S)->errStatusPtr = (esp)) +#define rtsiSetErrorStatus(S,es) (*((S)->errStatusPtr) = (es)) +#define rtsiGetErrorStatus(S) *((S)->errStatusPtr) + +#define rtsiSetModelMethodsPtr(S,mmp) ((S)->modelMethodsPtr = (mmp)) +#define rtsiGetModelMethodsPtr(S) (S)->modelMethodsPtr + +#define rtsiSetSolverComputingJacobian(S,val) ((S)->isComputingJacobian = (val)) +#define rtsiIsSolverComputingJacobian(S) (S)->isComputingJacobian + +#define rtsiSetSolverOutputComputed(S,val) ((S)->isOutputMethodComputed = (val)) +#define rtsiIsSolverOutputComputed(S) (S)->isOutputMethodComputed + +#endif /* !NO_FLOATS */ + +#endif /* RTW_SOLVER_H__ */ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/simstruc_types.h b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/simstruc_types.h new file mode 100644 index 0000000..8afa63b --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/simstruc_types.h @@ -0,0 +1,379 @@ +/* Copyright 1990-2017 The MathWorks, Inc. */ + +/* + * + * File: simstruc_types.h + * + * Abstract: + * The embedded code formats do not include simstruc.h, but + * need these common types. + */ + +#ifndef __SIMSTRUC_TYPES_H__ +#define __SIMSTRUC_TYPES_H__ + +/** From R2017a onwards, by default, MEX-files build + * using the 64-bit matrix API. + * If you do not explicitly specify the -compatibleArrayDims flag with to build + * using the 32-bit matrix API, or the -largeArrayDims flag to build + * using 64-bit matrix API via the MEX command, then + * override the default behavior by defining MX_COMPAT_32 + * explicitly. This applies only for code that + * include simstruc.h + * + */ +#if defined(MATLAB_MEX_FILE) + #if !defined(MX_COMPAT_32) && !defined(MX_COMPAT_64) && defined(USE_MEX_CMD) + #if defined(tmwtypes_h) + forceCompilationError tmwtypesbeforesimstrucdetected; + #else + #define MX_COMPAT_32 + #endif + #endif +#include "tmwtypes.h" +#else +#include "rtwtypes.h" +#endif + +#include "sl_types_def.h" + +/* Additional types required for Simulink External Mode */ +#ifndef fcn_call_T +# define fcn_call_T real_T +#endif +#ifndef action_T +# define action_T real_T +#endif + + +/* + * UNUSED_PARAMETER(x) + * Used to specify that a function parameter (argument) is required but not + * accessed by the function body. + */ +#ifndef UNUSED_PARAMETER +# if defined(__LCC__) +# define UNUSED_PARAMETER(x) /* do nothing */ +# else +/* + * This is the semi-ANSI standard way of indicating that a + * unused function parameter is required. + */ +# define UNUSED_PARAMETER(x) (void) (x) +# endif +#endif + +#define UNUSED_ARG(arg) UNUSED_PARAMETER(arg) + +typedef enum +{ + SS_SIMMODE_NORMAL, /* Running a "normal" Simulink simulation */ + SS_SIMMODE_SIZES_CALL_ONLY, /* Block edit eval to obtain number of ports */ + SS_SIMMODE_RTWGEN, /* Generating code */ + SS_SIMMODE_EXTERNAL /* External mode simulation */ +} SS_SimMode; + +typedef enum +{ + SS_SIMTYPE_UNKNOWN = -1, + SS_SIMTYPE_SIM, + SS_SIMTYPE_MODEL_API, + SS_SIMTYPE_LINEARIZATION, + SS_SIMTYPE_RTW, + SS_SIMTYPE_EXTERNAL +} SS_SimType; + +/* Must be used when SS_SimMode is SS_SIMMODE_RTWGEN */ +typedef enum +{ + SS_RTWGEN_UNKNOWN, + SS_RTWGEN_RTW_CODE, /* Code generation for RTW */ + SS_RTWGEN_ACCELERATOR, /* Code generation for accelerator */ + SS_RTWGEN_MODELREFERENCE_SIM_TARGET, /*Code Generation for Model Reference Sim Target*/ + SS_RTWGEN_MODELREFERENCE_RTW_TARGET /*Code Generation for Model Reference RTW Target*/ +} RTWGenMode; + +/*=====================================* + * Simulation Status * + *=====================================*/ + +typedef enum +{ + SIMSTATUS_STOPPED, + SIMSTATUS_UPDATING, + SIMSTATUS_INITIALIZING, + SIMSTATUS_RUNNING, + SIMSTATUS_PAUSED_IN_DEBUGGER, + SIMSTATUS_PAUSED, + SIMSTATUS_TERMINATING, + SIMSTATUS_COMPILED, + + /* Must be last */ + SIMSTATUS_EXTERNAL +} SS_SimStatus; + + +/* The following section is inlined from coder_model_reference_types.h */ +#ifndef MODEL_REFERENCE_TYPES +#define MODEL_REFERENCE_TYPES + +/* + * This structure is used by model reference to + * communicate timing information through the hierarchy. + */ +typedef struct _rtTimingBridge_tag rtTimingBridge; + +struct _rtTimingBridge_tag +{ + + uint32_T nTasks; + + uint32_T** clockTick; + uint32_T** clockTickH; + + uint32_T* taskCounter; + + real_T** taskTime; + + boolean_T** rateTransition; + + boolean_T *firstInitCond; +}; + +typedef struct _rtCtrlRateMdlRefTiming_tag rtCtrlRateMdlRefTiming; + +struct _rtCtrlRateMdlRefTiming_tag +{ + + uint32_T firstCtrlRateTID; + uint32_T* numTicksToNextHitForCtrlRate; + +}; + +#endif /* MODEL_REFERENCE_TYPES */ + +#ifndef ZERO_CROSSING_TYPES_H +#define ZERO_CROSSING_TYPES_H + +/* Trigger directions: falling, either, and rising */ +typedef enum +{ + FALLING_ZERO_CROSSING = -1, + ANY_ZERO_CROSSING = 0, + RISING_ZERO_CROSSING = 1 +} ZCDirection; + +/* Previous state of a trigger signal */ +typedef uint8_T ZCSigState; + +/* Initial value of a trigger zero crossing signal */ +#define UNINITIALIZED_ZCSIG 0x03U +#define NEG_ZCSIG 0x02U +#define POS_ZCSIG 0x01U +#define ZERO_ZCSIG 0x00U + +/* Current state of a trigger signal */ +typedef enum +{ + FALLING_ZCEVENT = -1, + NO_ZCEVENT = 0, + RISING_ZCEVENT = 1 +} ZCEventType; + +#endif /* ZERO_CROSSING_TYPES_H */ + +/* Detail zerocrossing event for removing double detection */ +#ifndef ZERO_CROSSING_EVENT_TYPES +#define ZERO_CROSSING_EVENT_TYPES + +#define ZC_EVENT_NUL 0x00 +#define ZC_EVENT_N2P 0x01 +#define ZC_EVENT_N2Z 0x02 +#define ZC_EVENT_Z2P 0x04 +#define ZC_EVENT_P2N 0x08 +#define ZC_EVENT_P2Z 0x10 +#define ZC_EVENT_Z2N 0x20 +#define ZC_EVENT_ALL_UP (ZC_EVENT_N2P | ZC_EVENT_N2Z | ZC_EVENT_Z2P ) +#define ZC_EVENT_ALL_DN (ZC_EVENT_P2N | ZC_EVENT_P2Z | ZC_EVENT_Z2N ) +#define ZC_EVENT_ALL (ZC_EVENT_ALL_UP | ZC_EVENT_ALL_DN ) + +#endif /* ZERO_CROSSING_EVENT_TYPES */ + +#define SS_START_MTH_PORT_ACCESS_UNSET 2 +#include "rtw_matlogging.h" +#include "rtw_extmode.h" +#include "rtw_continuous.h" +#include "rtw_solver.h" +#include "sysran_types.h" + +typedef int_T CSignal_T; + +/* DimsInfo_T structure is for S-functions */ +#ifndef _DIMSINFO_T +#define _DIMSINFO_T +struct DimsInfo_tag +{ + int width; /* number of elements */ + int numDims; /* number of dimensions */ + int *dims; /* dimensions */ + struct DimsInfo_tag *nextSigDims; /* for composite signals */ +}; + +typedef struct DimsInfo_tag DimsInfo_T; + +typedef int_T ssFcnCallErr_T; + +/* + * DECL_AND_INIT_DIMSINFO(variableName): + * Macro for setting up a DimsInfo in an S-function to DYNAMIC_DIMENSION. + * This macro must be placed at the start of a declaration, for example: + * + * static void mdlInitializeSizes(SimStruct *S) + * { + * DECL_AND_INIT_DIMSINFO(diminfo1); + * + * ssSetNumSFcnParams(S, 0); + * + * } + * + * The reason that this macro must be placed in the declaration section of a + * function or other scope is that this macro **creates** a local variable of + * the specified name with type DimsInfo_T. The variable is initialized + * to DYNAMIC_DIMENSION. + */ +#define DECL_AND_INIT_DIMSINFO(variableName) \ + DimsInfo_T variableName = {-1,-1,NULL,NULL} +#endif /* _DIMSINFO_T */ + + +/* + * Enumeration of work vector used as flag values. + */ +typedef enum +{ + SS_DWORK_USED_AS_DWORK = 0, /* default */ + SS_DWORK_USED_AS_DSTATE, /* will be logged, loaded, etc */ + SS_DWORK_USED_AS_SCRATCH, /* will be reused */ + SS_DWORK_USED_AS_MODE /* replace mode with dwork */ +} ssDWorkUsageType; + +#define SS_NUM_DWORK_USAGE_TYPES 3 + +/* + * DWork structure for S-Functions, one for each dwork. + */ +struct _ssDWorkRecord +{ + int_T width; + DTypeId dataTypeId; + CSignal_T complexSignal; + void *array; + const char_T *name; + ssDWorkUsageType usedAs; +}; + +#include "sl_sample_time_defs.h" + + +/* ========================================================================== */ + +/* + * Lightweight structure for holding a real, sparse matrix + * as used by the analytical Jacobian methods. + */ +typedef struct SparseHeader_Tag +{ + int_T mRows; /* number of rows */ + int_T nCols; /* number of cols */ + int_T nzMax; /* size of *pr, *ir */ + int_T *Ir; /* row indices */ + int_T *Jc; /* column offsets */ +#ifndef NO_FLOATS + real_T *Pr; /* nonzero entries */ +#else + void *Pr; +#endif +} SparseHeader; + +/*========================* + * Setup for multitasking * + *========================*/ + +/* + * Let MT be synonym for MULTITASKING (to shorten command line for DOS) + */ +#if defined(MT) +# if MT == 0 +# undef MT +# else +# define MULTITASKING 1 +# endif +#endif + +#if defined(MULTITASKING) && MULTITASKING == 0 +# undef MULTITASKING +#endif + +#if defined(MULTITASKING) && !defined(TID01EQ) +# define TID01EQ 0 +#endif + +/* + * Undefine MULTITASKING if there is only one task or there are two + * tasks and the sample times are equal (case of continuous and one discrete + * with equal rates). + */ +#if defined(NUMST) && defined(MULTITASKING) +# if NUMST == 1 || (NUMST == 2 && TID01EQ == 1) +# undef MULTITASKING +# endif +#endif + +typedef enum +{ + SS_UNKNOWN_INTERPOLATION = -1, + SS_ZOH_INTERPOLATION = 1, + SS_LINEAR_INTERPOLATION = 2 +} SSLoggerInterpMethod; + +typedef enum +{ + SS_MODEL_DATA_LOGS = 1, + SS_DATASET_FORMAT = 2, + SS_LOG_FORMAT_MIXED = 3, + SS_ARRAY_FORMAT = 4, + SS_STRUCTURE_FORMAT = 5, + SS_STRUCTUREWITHTIME_FORMAT = 6 +} SSLoggingSaveFormat; + +/*======================================================* + * Types for Simulink Functions access from S-functions * + *======================================================*/ + +#ifndef SIMULINK_FUNCTION_TYPES +#define SIMULINK_FUNCTION_TYPES +typedef struct _ssFcnCallExecArgInfo_tag { + void *dataPtr; + int_T dataSize; + void *reserved; +} _ssFcnCallExecArgInfo; + +typedef struct _ssFcnCallExecData_tag { + const char *fcnName; + void *reserved; +} _ssFcnCallExecData; + +typedef struct _ssFcnCallExecArgs_tag { + int_T numInArgs; + int_T numOutArgs; + _ssFcnCallExecArgInfo *inArgs; + _ssFcnCallExecArgInfo *outArgs; + _ssFcnCallExecData *execData; + void *reserved; +} _ssFcnCallExecArgs; + +typedef _ssFcnCallExecArgs ssFcnCallExecArgs; + +#endif /* SIMULINK_FUNCTION_TYPES */ + +#endif /* __SIMSTRUC_TYPES_H__ */ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/sl_sample_time_defs.h b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/sl_sample_time_defs.h new file mode 100644 index 0000000..2c9da7b --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/sl_sample_time_defs.h @@ -0,0 +1,51 @@ +/* Copyright 2010-2013 The MathWorks, Inc. */ + +/* + * File: sl_sample_time_defs.h + * + * Abstract: + * This file contains sample time related definitions (typedefs, macros, etc.) + * prototypes that are used both by User S-Functions and inside Simulink. + */ + +#ifndef __SL_SAMPLE_TIME_DEFS_H__ +#define __SL_SAMPLE_TIME_DEFS_H__ + +/* + * INHERITED_SAMPLE_TIME - Specify for blocks that inherit their sample + * time from the block that feeds their input. + * + * CONTINUOUS_SAMPLE_TIME - A continuous sample time indicates that the + * block executes every simulation step. + * + * VARIABLE_SAMPLE_TIME - Specifies that this sample time is discrete + * with a varying period. + * + * FIXED_IN_MINOR_STEP_OFFSET - This can be specified for the offset of either + * the inherited or continuous sample time + * indicating that the output does not change + * in minor steps. + */ +#define INHERITED_SAMPLE_TIME ((real_T)-1.0) +#define CONTINUOUS_SAMPLE_TIME ((real_T)0.0) +#define VARIABLE_SAMPLE_TIME ((real_T)-2.0) +#define FIXED_IN_MINOR_STEP_OFFSET ((real_T)1.0) + + +typedef enum{ + SS_TIMESOURCE_BASERATE, /* async task does not manage time, + reads absolute time from base rate */ + SS_TIMESOURCE_SELF, /* async task manage it own independent + timer */ + SS_TIMESOURCE_CALLER, /* async task read time from its upstream + task */ + SS_TIMESOURCE_SELF_INTERNAL, /* If an async task periodically executes, + * the task may choose to maintain internal timer + * by incrementing at each execution */ + SS_INVALID_TIMESOURCE +} slTimeSource; + +/* Value/representation of an unknown tid */ +#define UNKNOWN_TID (-5) + +#endif diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/sl_types_def.h b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/sl_types_def.h new file mode 100644 index 0000000..26fe090 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/sl_types_def.h @@ -0,0 +1,89 @@ +/* Copyright 2009-2015 The MathWorks, Inc. */ + +/* + * File: sl_types_def.h + * + * Abstract: + * The embedded RTW code formats do not include simstruc.h, but + * needs these common types. + * Generated from sl_types_def.tpl. + */ + +#ifndef __SL_TYPES_DEF_H__ +#define __SL_TYPES_DEF_H__ + +#ifdef MATLAB_MEX_FILE +#include "tmwtypes.h" +#else +#include "rtwtypes.h" +#endif + +/* The following section is inlined from builtin_typeid_types.h */ +#ifndef BUILTIN_TYPEID_TYPES +#define BUILTIN_TYPEID_TYPES + +/* Enumeration of built-in data types */ +typedef enum +{ + SS_DOUBLE = 0, /* real_T */ + SS_SINGLE = 1, /* real32_T */ + SS_INT8 = 2, /* int8_T */ + SS_UINT8 = 3, /* uint8_T */ + SS_INT16 = 4, /* int16_T */ + SS_UINT16 = 5, /* uint16_T */ + SS_INT32 = 6, /* int32_T */ + SS_UINT32 = 7, /* uint32_T */ + SS_BOOLEAN = 8 /* boolean_T */ +} BuiltInDTypeId; + +#define SS_NUM_BUILT_IN_DTYPE ((int_T)SS_BOOLEAN+1) + +#ifndef _DTYPEID +# define _DTYPEID +/* Enumeration for MAT-file logging code */ +typedef int_T DTypeId; +#endif + +#endif /* BUILTIN_TYPEID_TYPES */ + +typedef enum +{ + SS_FCN_CALL = 9, + SS_INTEGER = 10, + SS_POINTER = 11, + SS_INTERNAL_DTYPE2 = 12, + SS_TIMER_UINT32_PAIR = 13 + + /* if last in list changes also update define below */ + +} PreDefinedDTypeId; + +#define SS_DOUBLE_UINT32 SS_TIMER_UINT32_PAIR + +#define SS_NUM_PREDEFINED_DTYPES 5 + +#ifndef SYMBOLIC_DIMS_ID +#define SYMBOLIC_DIMS_ID +typedef int_T SymbDimsId; +#endif /* SYMBOLIC_DIMS_ID */ + +#ifndef PRE_DEFINED_SYMBOLIC_DIMS_IDS +#define PRE_DEFINED_SYMBOLIC_DIMS_IDS +/* + * Definition of Simulink builtin symbolic dimensions IDs + */ +enum +{ + SL_INVALID_SYMBDIMS_ID = -2, + SL_INHERIT = -1, /* must be the same as DYNAMICALLY_TYPED = -1 */ + SL_NOSYMBDIMS = 0 +}; +#endif /* PRE_DEFINED_SYMBOLIC_DIMS_IDS */ + +/* + * DYNAMICALLY_TYPED - Specify for input/output port data types that can + * accept a variety of data types. + */ +#define DYNAMICALLY_TYPED (-1) + +#endif /* __SL_TYPES_DEF_H__ */ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/sysran_types.h b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/sysran_types.h new file mode 100644 index 0000000..aa94e15 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/R2018b/simulink/include/sysran_types.h @@ -0,0 +1,114 @@ +/* Copyright 2004-2016 The MathWorks, Inc. */ + +/* + * File: sysran_types.h + * + * Abstract: + * This files defines the enum and the macros to do with the system ran + * breadcrumbs + * + * This file is used both by Simulink and some of the generated code + */ + +#ifndef SIMSTRUCT_SYSRAN_TYPES_H +#define SIMSTRUCT_SYSRAN_TYPES_H + +/* Subsystem run state -- used by Model Reference simulation target */ +typedef enum { + SUBSYS_RAN_BC_DISABLE, + SUBSYS_RAN_BC_ENABLE, + SUBSYS_RAN_BC_DISABLE_TO_ENABLE, + SUBSYS_RAN_BC_ENABLE_TO_DISABLE, + SUBSYS_RAN_BC_ONE_SHOT +} SubSystemRanBCTransition; + +/* This is the data type of the dwork entry for the system ran breadcrumb */ +typedef int8_T sysRanDType; + +/* + * System ran breadcrumb macros + * + * Clearing macro. 2 callers + * i) top of the sim-loop + * ii) top of each Outputs function for External mode + * + * + * Here is the basic idea: + * If a system is DISABLED, it stays DISABLED. + * For any other state, assume ENABLE_TO_DISABLE, + * If it runs then the OutputFcn will move it to ENABLE + * otherwise it will come back as ENABLE_TO_DISABLE(hence it never ran) + * + * DISABLE -> DISABLE (latched) + * ENABLE -> ENABLE_TO_DISABLE (assume) + * ENABLE_TO_DISABLE -> DISABLE (new latch) + * DISABLE_TO_ENABLE -> ENABLE (new enable) + * ONE_SHOT -> DISABLE (by definition) + * + * Note: These macros are called both by Simulink and the generated code + */ + +/* sr stands for SystemRan, BC stands for BreadCrumb */ +#define srClearBC(state) \ +{ \ + SubSystemRanBCTransition prevState = (SubSystemRanBCTransition) state; \ + SubSystemRanBCTransition newState = SUBSYS_RAN_BC_DISABLE; \ + \ + switch(prevState) { \ + case SUBSYS_RAN_BC_DISABLE: \ + newState = SUBSYS_RAN_BC_DISABLE; \ + break; \ + case SUBSYS_RAN_BC_ENABLE: \ + newState = SUBSYS_RAN_BC_ENABLE_TO_DISABLE; \ + break; \ + case SUBSYS_RAN_BC_DISABLE_TO_ENABLE: \ + newState = SUBSYS_RAN_BC_ENABLE_TO_DISABLE; \ + break; \ + case SUBSYS_RAN_BC_ENABLE_TO_DISABLE: \ + newState = SUBSYS_RAN_BC_DISABLE; \ + break; \ + case SUBSYS_RAN_BC_ONE_SHOT: \ + newState = SUBSYS_RAN_BC_DISABLE; \ + break; \ + } \ + state = newState; \ +} + +/* + * Update macro + * + * Called by the OutputFcn of all conditionally exec'd subsystems + * from subsystm.cpp and commonbodlib.tlc + * + * DISABLE -> DISABLE_ENABLE (new enable) + * ENABLE_TO_DISABLE -> ENABLE (must have run last time step) + * All other state -> should really be an assert + * + */ +/* sr stands for SystemRan, BC stands for BreadCrumb */ +#define srUpdateBC(state) \ +{ \ + SubSystemRanBCTransition prevState = (SubSystemRanBCTransition) state; \ + SubSystemRanBCTransition newState = prevState; \ + \ + switch(prevState) { \ + case SUBSYS_RAN_BC_DISABLE: \ + newState = SUBSYS_RAN_BC_DISABLE_TO_ENABLE; \ + break; \ + case SUBSYS_RAN_BC_ENABLE_TO_DISABLE: \ + newState = SUBSYS_RAN_BC_ENABLE; \ + break; \ + case SUBSYS_RAN_BC_ENABLE: \ + case SUBSYS_RAN_BC_DISABLE_TO_ENABLE: \ + case SUBSYS_RAN_BC_ONE_SHOT: \ + break; \ + } \ + state = newState; \ +} + +#endif /* SIMSTRUCT_SYSRAN_TYPES_H */ + +/* EOF sysran_types.h */ + +/* LocalWords: sr exec'd subsystm commonbodlib + */ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/builtin_typeid_types.h b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/builtin_typeid_types.h new file mode 100644 index 0000000..ee6ab7b --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/builtin_typeid_types.h @@ -0,0 +1,40 @@ +/* + * builtin_typeid_types.h + * + * Academic License - for use in teaching, academic research, and meeting + * course requirements at degree granting institutions only. Not for + * government, commercial, or other organizational use. + * + * Code generation for model "Control_System". + * + * Model version : 1.97 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Fri Jun 24 14:53:49 2022 + */ + +#ifndef BUILTIN_TYPEID_TYPES_H +#define BUILTIN_TYPEID_TYPES_H +#include "rtwtypes.h" +#ifndef BUILTIN_TYPEID_TYPES +#define BUILTIN_TYPEID_TYPES + +/* Enumeration of built-in data types */ +typedef enum { + SS_DOUBLE = 0, /* real_T */ + SS_SINGLE = 1, /* real32_T */ + SS_INT8 = 2, /* int8_T */ + SS_UINT8 = 3, /* uint8_T */ + SS_INT16 = 4, /* int16_T */ + SS_UINT16 = 5, /* uint16_T */ + SS_INT32 = 6, /* int32_T */ + SS_UINT32 = 7, /* uint32_T */ + SS_BOOLEAN = 8 /* boolean_T */ +} BuiltInDTypeId; + +#define SS_NUM_BUILT_IN_DTYPE ((int_T)SS_BOOLEAN+1) + +/* Enumeration for MAT-file logging code */ +typedef int_T DTypeId; + +#endif /* BUILTIN_TYPEID_TYPES */ +#endif /* BUILTIN_TYPEID_TYPES_H */ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/checksummap.mat b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/checksummap.mat new file mode 100644 index 0000000..ce46e23 Binary files /dev/null and b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/checksummap.mat differ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/builtin_typeid_types_h.html b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/builtin_typeid_types_h.html new file mode 100644 index 0000000..3ef5563 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/builtin_typeid_types_h.html @@ -0,0 +1,98 @@ + + + + + + + + + + +
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
1/*
2 * builtin_typeid_types.h
3 *
4 * Academic License - for use in teaching, academic research, and meeting
5 * course requirements at degree granting institutions only. Not for
6 * government, commercial, or other organizational use.
7 *
8 * Code generation for model "Control_System".
9 *
10 * Model version : 1.97
11 * Simulink Coder version : 9.0 (R2018b) 24-May-2018
12 * C source code generated on : Fri Jun 24 14:53:49 2022
13 */
14
15#ifndef BUILTIN_TYPEID_TYPES_H
16#define BUILTIN_TYPEID_TYPES_H
17#include "rtwtypes.h"
18#ifndef BUILTIN_TYPEID_TYPES
19#define BUILTIN_TYPEID_TYPES
20
21/* Enumeration of built-in data types */
22typedef enum {
23 SS_DOUBLE = 0, /* real_T */
24 SS_SINGLE = 1, /* real32_T */
25 SS_INT8 = 2, /* int8_T */
26 SS_UINT8 = 3, /* uint8_T */
27 SS_INT16 = 4, /* int16_T */
28 SS_UINT16 = 5, /* uint16_T */
29 SS_INT32 = 6, /* int32_T */
30 SS_UINT32 = 7, /* uint32_T */
31 SS_BOOLEAN = 8 /* boolean_T */
32} BuiltInDTypeId;
33
34#define SS_NUM_BUILT_IN_DTYPE ((int_T)SS_BOOLEAN+1)
35
36/* Enumeration for MAT-file logging code */
37typedef int_T DTypeId;
38
39#endif /* BUILTIN_TYPEID_TYPES */
40#endif /* BUILTIN_TYPEID_TYPES_H */
41
+
+ + diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/css/coder_app.css b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/css/coder_app.css new file mode 100644 index 0000000..e0a124a --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/css/coder_app.css @@ -0,0 +1,196 @@ +/* Copyright 2013-2014 The MathWorks, Inc. */ +pre#code { + font-family: Consolas, Courier; + font-size: small; +} + +.ct { + font-style: italic; + color: #117755 +} /* comment */ +.pp { + font-weight:bold; + color: #992211 +} /* preprocessor */ +.kw, .br { + font-weight:bold; + color: #112266 +} /* keyword or brace */ +.dt { + font-weight:bold; + color: #112266 +} /* data type */ +.tk { + font-style: normal; + color: #112266 +} /* regular token */ +pre#code a.req { + text-decoration: none; + color: #112266 +} +pre#code a.req_active { + cursor: pointer; + text-decoration: underline; +} +pre#code a.req_active:hover { + cursor: pointer; + color: blue; + text-decoration: underline +} +pre#code a.blk { + text-decoration: none; +} +pre#code a.blk_active { + cursor: pointer; + text-decoration: underline; +} +pre#code a.blk_active:hover { + cursor: pointer; + color: blue; + text-decoration: underline +} +a.hilite { + font-style: normal; + color: black; + background-color: #ffff99; +} /* highlight token */ +tr.hilite { + font-style: normal; + color: black; + background-color: #aff +} /* highlight row */ +a.hiliteToken, tr.hiliteToken, td.hiliteToken { + background-color: #ffff99; +} +.hiliteCurrentLine, tr.hiliteCurrentLine > td { + font-style: normal; + color: black; + background-color: #aff; + border-top: dashed darkblue 1px; + border-bottom: dashed darkblue 1px; +} +tr.hiliteCurrentLine > td:first-child { + border-left: dashed darkblue 1px; +} +tr.hiliteCurrentLine > td:last-child { + border-right: dashed darkblue 1px; +} + +span.hiliteTotalLine { + font-style: normal; + color: #aff; +} +span.hiliteCurrentLine { + font-style: normal; + color: #ffff99; +} +a.tk { + text-decoration: none; +} +a.tk:hover { + text-decoration: none; +} +a.active { + text-decoration: underline; +} +a.active:hover { + cursor: pointer; + color: blue; + text-decoration: underline +} /* hyperlink */ +table.code { + border: 0px +} +table.code td { + vertical-align: top; +} +table.code td.highlightedCurrent { + background-color: #819FF7; +} +table.code > tr:first { + text-align: right; +} /* hyperlink */ + +ul.popup_attrib_list { + list-style-type:none; + display: block; + margin: 0; + padding: 0; +} +ul.popup_attrib_list li { + list-style-type:none; + display: inline; + margin: 0 18px 0 0; + padding: 0; +} +.highlighted { + background-color:yellow; +} +a:class1 { + color: -webkit-link; + text-decoration: underline; + cursor: hand; +} +.scroll +{ + height:80px; + overflow:scroll; + overflow-x:hidden; +} +div#popup_window { + position: absolute; + background-color: rgb(203,203,255); + border: solid 3px #ECECEC; + border-radius: 5px; + /* shadow box around the window*/ + -moz-box-shadow: 0 3px 3px rgba(0,0,0,0.4), inset 0 1px #FFF; + -webkit-box-shadow: 0 3px 3px rgba(0,0,0,0.4), inset 0 1px #FFF; + box-shadow: 0 3px 3px rgba(0,0,0,0.4), inset 0 1px #FFF; + padding: 2px; +} +div#popup_window a { + text-decoration: none; + color: green; +} +div#popup_window a:hover { + cursor: pointer; + text-decoration: underline; + color: blue; +} +div#popup_window tr.selected { + background-color: #ffff99; +} +div#token_usage_nav { + border-bottom: 1px solid gray; +} +table#token_usage_details { + cellpadding: 100px; + table-layout:fixed; + border: 0px; +} +.token_usage_details_tabrow { + width: 40px; +} +table#token_usage_details td { + padding-right: 5em; + padding-left: 1em; +} +.token_usage_details_tabrow:hover { + background-color: gray; +} +.nav_table td.hidden { + display: none; +} +table#codeTbl tr td { + color: #112266 +} +table#codeTbl tr td { + padding-left: 10px; +} +table#codeTbl tr td:first-child { + font-style: italic; + color: #888888; + text-align: right; + padding-left:0px; +} + diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/inspect.html b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/inspect.html new file mode 100644 index 0000000..b628c7a --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/inspect.html @@ -0,0 +1,33 @@ + + + + + + + + + + + + + +
+ + diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/js/coder_app.js b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/js/coder_app.js new file mode 100644 index 0000000..1f3aad6 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/js/coder_app.js @@ -0,0 +1,518 @@ +/* Copyright 2013-2016 The MathWorks, Inc. */ +function queryByClassName(className, elem) { + if (!elem) elem = document.body; + if (typeof elem.querySelectorAll === "function") { + return elem.querySelectorAll("."+className); + } else { + return elem.getElementsByClass(className); + } +} + +function nav_token_usage_details(direction) { + var els = queryByClassName("token_usage_details_tabrow"); + var selectedIdx = 0; + var selectedClassName = "selected"; + for (selectedIdx; selectedIdx < els.length; selectedIdx++) { + if (els[selectedIdx].classList.contains(selectedClassName)) { + break; + } + } + var nextIdx = selectedIdx; + if (direction === -1 && selectedIdx > 0) { + nextIdx = selectedIdx-1; + } else if (direction === 1 && selectedIdx < els.length - 1) { + nextIdx = selectedIdx + 1; + } + if (nextIdx !== selectedIdx) { + els[selectedIdx].classList.remove(selectedClassName); + els[nextIdx].classList.add(selectedClassName); + els[nextIdx].scrollIntoView(alignWithTop=false); + } + return false; +} + +function tabrowClicked(event) { +} + +function popupOnload() { + var els = queryByClassName("token_usage_details_tabrow"); + for (var i=0; i" + + top.rtwGetFileName(link2Src) + ""; + var bodyNode = document.body; + bodyNode.insertBefore(link, bodyNode.firstElementChild); + } + top.updateHyperlinks(); + // update fileSelector frame + if (top.fileSelector) { + var o = top.fileSelector.document.getElementById('fileSelector'); + if (o) { + o.value = filename; + } + } + // add links to line numbers + var hasLineFlag = null; + if (top.TraceInfoLineFlag && top.TraceInfoLineFlag.instance) { + hasLineFlag = true; + } else { + hasLineFlag = false; + } + + if(hasLineFlag) { + var lines = queryByClassName("ln", codeElement); + var lineTraceFlag = top.TraceInfoLineFlag.instance.lineTraceFlag; + var lineNo = null; + for (var i=0; i= 0; --i) { + var childNode = trNode.childNodes[i]; + if (childNode.tagName.toUpperCase() === "TD") { + return childNode.childNodes; + } + } + return null; +} + +// see g1225075 +function fixBoxStyleFnHeaderLineWidths() { + // Match strings like "/**********/" which is the top line of + // a box-style function comment header + var reBoxHeader = /\/\*+\//; + + // Match strings like "' */" which is the contents of the text + // element originally generated in the report to pad the width of + // the line. + var rePadding = /'\s*\*\//; + + // All block identifier elements in the report page + blkLineElts = queryByClassName("blk"); + for (var i = 0; i < blkLineElts.length; ++i) { + var origPadding = blkLineElts[i].nextSibling; + if (origPadding.textContent.match(rePadding)) { + var spanElt = findParent(blkLineElts[i], { tagName: "span", className: "ct" }); + if (!spanElt) { + continue; + } + + // The numbered line in the report containing block identifier "i" + var tableRowElt = findParent(spanElt, { tagName: "tr" }); + if (!tableRowElt) { + continue; + } + + // Loop backward through table rows (i.e., report lines) looking + // for the "/***************/" start of the header. When found save + // its pixel width. Not actually the width of the itself but + // the span inside its last . This is will determine the real + // padding that is needed for proper alignment regardless of font + // or CKJ characters. + var targetWidth = 0; + var sanity = Number.MAX_VALUE; + var node = tableRowElt.previousSibling; + while (node && (sanity-- > 0)) { + var lastCellContents = getLastTableCellContents(node); + if (lastCellContents) { + if (lastCellContents.length === 0) { + break; + } + if (lastCellContents[0].textContent.match(reBoxHeader)) { + targetWidth = lastCellContents[0].offsetWidth; + break; + } + } + node = node.previousSibling; + } + + // If applying a new padding (i.e., targetWidth > 0), replace + // the original padding "' */' (a single text element) with + // two text elements and a span in between. The span will be the + // new pixel-accurate padding. + if (targetWidth > 0) { + var singleQuoteNode = document.createTextNode("'"); + var spacerNode = document.createElement('span'); + origPadding.textContent = "*/"; + origPadding.parentNode.insertBefore(spacerNode, origPadding); + origPadding.parentNode.insertBefore(singleQuoteNode, spacerNode); + + var padWidth = targetWidth - spanElt.offsetWidth; + spacerNode.style.display = 'inline-block'; + spacerNode.style.width = String(padWidth) + "px"; + spacerNode.style.height = '1em'; // cursor won't work w/o some height + spacerNode.style.cursor = 'text'; + } + } + } +} + +// the onload function for source file +function srcFileOnload() { + var codeElement = document.getElementById("codeTbl"); + var insertFunction = getInsertFunction(codeElement); + try { + var els = codeElement.getElementsByTagName("tr"); + for (var i = 0; i < els.length; i++) { + registerDelayedOnMouseOver(els[i], lineOnMouseIn, lineOnMouseOut); + } + updateToken(codeElement); + } catch (err) {}; + insertFunction(); + // add code to model hyperlinks for all tokens + var filename = location.pathname.split(/\//); + filename = filename[filename.length-1]; + // highlight the filename in the TOC frame + if (top.rtwreport_contents_frame && top.hiliteByFileName(top.rtwreport_document_frame.document.location.href)) { + // remove the highlights in the TOC frame if filename is hilite successfully + top.removeHiliteTOC(top.rtwreport_contents_frame); + } + + // annotate code with code coverage data + if (typeof rtwannotate === 'function') { + rtwannotate(filename.replace(/.html$/,"_cov.xml")); + } + + fixBoxStyleFnHeaderLineWidths(); + + // highlight token and row + if (top.RTW_TraceInfo.instance && top.RTW_TraceArgs.instance) { + var i; + // find the highlight file name + var fileIdx = top.RTW_TraceArgs.instance.getFileIdx(filename); + var ids=[], rows=[]; + if (typeof fileIdx !== "undefined") { + ids = top.RTW_TraceArgs.instance.getIDs(fileIdx); + rows = top.RTW_TraceArgs.instance.getRows(fileIdx); + // highlight rows in file + for (i=0; i 0) + top.RTW_TraceInfo.instance.setInitLocation(filename,rows[0]); + else { + top.toggleNavSideBar("off"); + return; + } + } + + // display navigation side bar + if (top.rtwreport_nav_frame) top.rtwreport_nav_frame.location.reload(); + if (rows.length>0) { + top.toggleNavSideBar("on"); + top.toggleNavToolBar("on"); + } else { + top.toggleNavSideBar("off"); + } + } + top.scrollToLineBasedOnHash(document.location.hash); + function getHash() { + var loc; + var aHash=""; + var topDocObj = top.window.document; + // get the hash value from location. + loc = topDocObj.location; + loc = loc.search || loc.hash; + aHash = loc.substring(1); + aHash = decodeURI(aHash); + return aHash; + } +} + +function createPopup(filename, evt) { + var anchorObj = evt.currentTarget; + if (anchorObj.children.length > 0) + return; + var filename = location.pathname.split(/\//); + filename = filename[filename.length-1]; + var windowObj = top.getInspectWindow(); + var propObj = top.getInspectData(filename, anchorObj); + var navObj = top.getInspectLink(filename, location.pathname, anchorObj); + if (propObj) { + windowObj.appendChild(propObj); + windowObj.style.left = "0px"; + if (anchorObj.parentElement.nodeName === "TD" && + anchorObj.parentElement.parentElement.nodeName === "TR") { + anchorObj.parentElement.parentElement.lastChild.insertBefore(windowObj, + anchorObj.parentElement.parentElement.lastChild.lastChild.nextSibling); + var left = Math.min(evt.clientX , window.innerWidth - windowObj.scrollWidth - 30); + left = Math.max(0, left); + windowObj.style.left = "" + left + "px"; + } + } +}; + +function destroyPopup(anchorObj) { + var popWindow = document.getElementById("popup_window"); + if (popWindow) { + popWindow.parentElement.removeChild(popWindow); + } +}; diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/multiword_types_h.html b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/multiword_types_h.html new file mode 100644 index 0000000..3850c48 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/multiword_types_h.html @@ -0,0 +1,1200 @@ + + + + + + + + + + +
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
1/*
2 * multiword_types.h
3 *
4 * Academic License - for use in teaching, academic research, and meeting
5 * course requirements at degree granting institutions only. Not for
6 * government, commercial, or other organizational use.
7 *
8 * Code generation for model "Control_System".
9 *
10 * Model version : 1.97
11 * Simulink Coder version : 9.0 (R2018b) 24-May-2018
12 * C source code generated on : Fri Jun 24 14:53:49 2022
13 */
14
15#ifndef MULTIWORD_TYPES_H
16#define MULTIWORD_TYPES_H
17#include "rtwtypes.h"
18
19/*
20 * Definitions supporting external data access
21 */
22typedef int64_T chunk_T;
23typedef uint64_T uchunk_T;
24
25/*
26 * MultiWord supporting definitions
27 */
28typedef long long longlong_T;
29
30/*
31 * MultiWord types
32 */
33typedef struct {
34 uint64_T chunks[2];
35} int128m_T;
36
37typedef struct {
38 int128m_T re;
39 int128m_T im;
40} cint128m_T;
41
42typedef struct {
43 uint64_T chunks[2];
44} uint128m_T;
45
46typedef struct {
47 uint128m_T re;
48 uint128m_T im;
49} cuint128m_T;
50
51typedef struct {
52 uint64_T chunks[3];
53} int192m_T;
54
55typedef struct {
56 int192m_T re;
57 int192m_T im;
58} cint192m_T;
59
60typedef struct {
61 uint64_T chunks[3];
62} uint192m_T;
63
64typedef struct {
65 uint192m_T re;
66 uint192m_T im;
67} cuint192m_T;
68
69typedef struct {
70 uint64_T chunks[4];
71} int256m_T;
72
73typedef struct {
74 int256m_T re;
75 int256m_T im;
76} cint256m_T;
77
78typedef struct {
79 uint64_T chunks[4];
80} uint256m_T;
81
82typedef struct {
83 uint256m_T re;
84 uint256m_T im;
85} cuint256m_T;
86
87typedef struct {
88 uint64_T chunks[5];
89} int320m_T;
90
91typedef struct {
92 int320m_T re;
93 int320m_T im;
94} cint320m_T;
95
96typedef struct {
97 uint64_T chunks[5];
98} uint320m_T;
99
100typedef struct {
101 uint320m_T re;
102 uint320m_T im;
103} cuint320m_T;
104
105typedef struct {
106 uint64_T chunks[6];
107} int384m_T;
108
109typedef struct {
110 int384m_T re;
111 int384m_T im;
112} cint384m_T;
113
114typedef struct {
115 uint64_T chunks[6];
116} uint384m_T;
117
118typedef struct {
119 uint384m_T re;
120 uint384m_T im;
121} cuint384m_T;
122
123typedef struct {
124 uint64_T chunks[7];
125} int448m_T;
126
127typedef struct {
128 int448m_T re;
129 int448m_T im;
130} cint448m_T;
131
132typedef struct {
133 uint64_T chunks[7];
134} uint448m_T;
135
136typedef struct {
137 uint448m_T re;
138 uint448m_T im;
139} cuint448m_T;
140
141typedef struct {
142 uint64_T chunks[8];
143} int512m_T;
144
145typedef struct {
146 int512m_T re;
147 int512m_T im;
148} cint512m_T;
149
150typedef struct {
151 uint64_T chunks[8];
152} uint512m_T;
153
154typedef struct {
155 uint512m_T re;
156 uint512m_T im;
157} cuint512m_T;
158
159typedef struct {
160 uint64_T chunks[9];
161} int576m_T;
162
163typedef struct {
164 int576m_T re;
165 int576m_T im;
166} cint576m_T;
167
168typedef struct {
169 uint64_T chunks[9];
170} uint576m_T;
171
172typedef struct {
173 uint576m_T re;
174 uint576m_T im;
175} cuint576m_T;
176
177typedef struct {
178 uint64_T chunks[10];
179} int640m_T;
180
181typedef struct {
182 int640m_T re;
183 int640m_T im;
184} cint640m_T;
185
186typedef struct {
187 uint64_T chunks[10];
188} uint640m_T;
189
190typedef struct {
191 uint640m_T re;
192 uint640m_T im;
193} cuint640m_T;
194
195typedef struct {
196 uint64_T chunks[11];
197} int704m_T;
198
199typedef struct {
200 int704m_T re;
201 int704m_T im;
202} cint704m_T;
203
204typedef struct {
205 uint64_T chunks[11];
206} uint704m_T;
207
208typedef struct {
209 uint704m_T re;
210 uint704m_T im;
211} cuint704m_T;
212
213typedef struct {
214 uint64_T chunks[12];
215} int768m_T;
216
217typedef struct {
218 int768m_T re;
219 int768m_T im;
220} cint768m_T;
221
222typedef struct {
223 uint64_T chunks[12];
224} uint768m_T;
225
226typedef struct {
227 uint768m_T re;
228 uint768m_T im;
229} cuint768m_T;
230
231typedef struct {
232 uint64_T chunks[13];
233} int832m_T;
234
235typedef struct {
236 int832m_T re;
237 int832m_T im;
238} cint832m_T;
239
240typedef struct {
241 uint64_T chunks[13];
242} uint832m_T;
243
244typedef struct {
245 uint832m_T re;
246 uint832m_T im;
247} cuint832m_T;
248
249typedef struct {
250 uint64_T chunks[14];
251} int896m_T;
252
253typedef struct {
254 int896m_T re;
255 int896m_T im;
256} cint896m_T;
257
258typedef struct {
259 uint64_T chunks[14];
260} uint896m_T;
261
262typedef struct {
263 uint896m_T re;
264 uint896m_T im;
265} cuint896m_T;
266
267typedef struct {
268 uint64_T chunks[15];
269} int960m_T;
270
271typedef struct {
272 int960m_T re;
273 int960m_T im;
274} cint960m_T;
275
276typedef struct {
277 uint64_T chunks[15];
278} uint960m_T;
279
280typedef struct {
281 uint960m_T re;
282 uint960m_T im;
283} cuint960m_T;
284
285typedef struct {
286 uint64_T chunks[16];
287} int1024m_T;
288
289typedef struct {
290 int1024m_T re;
291 int1024m_T im;
292} cint1024m_T;
293
294typedef struct {
295 uint64_T chunks[16];
296} uint1024m_T;
297
298typedef struct {
299 uint1024m_T re;
300 uint1024m_T im;
301} cuint1024m_T;
302
303typedef struct {
304 uint64_T chunks[17];
305} int1088m_T;
306
307typedef struct {
308 int1088m_T re;
309 int1088m_T im;
310} cint1088m_T;
311
312typedef struct {
313 uint64_T chunks[17];
314} uint1088m_T;
315
316typedef struct {
317 uint1088m_T re;
318 uint1088m_T im;
319} cuint1088m_T;
320
321typedef struct {
322 uint64_T chunks[18];
323} int1152m_T;
324
325typedef struct {
326 int1152m_T re;
327 int1152m_T im;
328} cint1152m_T;
329
330typedef struct {
331 uint64_T chunks[18];
332} uint1152m_T;
333
334typedef struct {
335 uint1152m_T re;
336 uint1152m_T im;
337} cuint1152m_T;
338
339typedef struct {
340 uint64_T chunks[19];
341} int1216m_T;
342
343typedef struct {
344 int1216m_T re;
345 int1216m_T im;
346} cint1216m_T;
347
348typedef struct {
349 uint64_T chunks[19];
350} uint1216m_T;
351
352typedef struct {
353 uint1216m_T re;
354 uint1216m_T im;
355} cuint1216m_T;
356
357typedef struct {
358 uint64_T chunks[20];
359} int1280m_T;
360
361typedef struct {
362 int1280m_T re;
363 int1280m_T im;
364} cint1280m_T;
365
366typedef struct {
367 uint64_T chunks[20];
368} uint1280m_T;
369
370typedef struct {
371 uint1280m_T re;
372 uint1280m_T im;
373} cuint1280m_T;
374
375typedef struct {
376 uint64_T chunks[21];
377} int1344m_T;
378
379typedef struct {
380 int1344m_T re;
381 int1344m_T im;
382} cint1344m_T;
383
384typedef struct {
385 uint64_T chunks[21];
386} uint1344m_T;
387
388typedef struct {
389 uint1344m_T re;
390 uint1344m_T im;
391} cuint1344m_T;
392
393typedef struct {
394 uint64_T chunks[22];
395} int1408m_T;
396
397typedef struct {
398 int1408m_T re;
399 int1408m_T im;
400} cint1408m_T;
401
402typedef struct {
403 uint64_T chunks[22];
404} uint1408m_T;
405
406typedef struct {
407 uint1408m_T re;
408 uint1408m_T im;
409} cuint1408m_T;
410
411typedef struct {
412 uint64_T chunks[23];
413} int1472m_T;
414
415typedef struct {
416 int1472m_T re;
417 int1472m_T im;
418} cint1472m_T;
419
420typedef struct {
421 uint64_T chunks[23];
422} uint1472m_T;
423
424typedef struct {
425 uint1472m_T re;
426 uint1472m_T im;
427} cuint1472m_T;
428
429typedef struct {
430 uint64_T chunks[24];
431} int1536m_T;
432
433typedef struct {
434 int1536m_T re;
435 int1536m_T im;
436} cint1536m_T;
437
438typedef struct {
439 uint64_T chunks[24];
440} uint1536m_T;
441
442typedef struct {
443 uint1536m_T re;
444 uint1536m_T im;
445} cuint1536m_T;
446
447typedef struct {
448 uint64_T chunks[25];
449} int1600m_T;
450
451typedef struct {
452 int1600m_T re;
453 int1600m_T im;
454} cint1600m_T;
455
456typedef struct {
457 uint64_T chunks[25];
458} uint1600m_T;
459
460typedef struct {
461 uint1600m_T re;
462 uint1600m_T im;
463} cuint1600m_T;
464
465typedef struct {
466 uint64_T chunks[26];
467} int1664m_T;
468
469typedef struct {
470 int1664m_T re;
471 int1664m_T im;
472} cint1664m_T;
473
474typedef struct {
475 uint64_T chunks[26];
476} uint1664m_T;
477
478typedef struct {
479 uint1664m_T re;
480 uint1664m_T im;
481} cuint1664m_T;
482
483typedef struct {
484 uint64_T chunks[27];
485} int1728m_T;
486
487typedef struct {
488 int1728m_T re;
489 int1728m_T im;
490} cint1728m_T;
491
492typedef struct {
493 uint64_T chunks[27];
494} uint1728m_T;
495
496typedef struct {
497 uint1728m_T re;
498 uint1728m_T im;
499} cuint1728m_T;
500
501typedef struct {
502 uint64_T chunks[28];
503} int1792m_T;
504
505typedef struct {
506 int1792m_T re;
507 int1792m_T im;
508} cint1792m_T;
509
510typedef struct {
511 uint64_T chunks[28];
512} uint1792m_T;
513
514typedef struct {
515 uint1792m_T re;
516 uint1792m_T im;
517} cuint1792m_T;
518
519typedef struct {
520 uint64_T chunks[29];
521} int1856m_T;
522
523typedef struct {
524 int1856m_T re;
525 int1856m_T im;
526} cint1856m_T;
527
528typedef struct {
529 uint64_T chunks[29];
530} uint1856m_T;
531
532typedef struct {
533 uint1856m_T re;
534 uint1856m_T im;
535} cuint1856m_T;
536
537typedef struct {
538 uint64_T chunks[30];
539} int1920m_T;
540
541typedef struct {
542 int1920m_T re;
543 int1920m_T im;
544} cint1920m_T;
545
546typedef struct {
547 uint64_T chunks[30];
548} uint1920m_T;
549
550typedef struct {
551 uint1920m_T re;
552 uint1920m_T im;
553} cuint1920m_T;
554
555typedef struct {
556 uint64_T chunks[31];
557} int1984m_T;
558
559typedef struct {
560 int1984m_T re;
561 int1984m_T im;
562} cint1984m_T;
563
564typedef struct {
565 uint64_T chunks[31];
566} uint1984m_T;
567
568typedef struct {
569 uint1984m_T re;
570 uint1984m_T im;
571} cuint1984m_T;
572
573typedef struct {
574 uint64_T chunks[32];
575} int2048m_T;
576
577typedef struct {
578 int2048m_T re;
579 int2048m_T im;
580} cint2048m_T;
581
582typedef struct {
583 uint64_T chunks[32];
584} uint2048m_T;
585
586typedef struct {
587 uint2048m_T re;
588 uint2048m_T im;
589} cuint2048m_T;
590
591#endif /* MULTIWORD_TYPES_H */
592
+
+ + diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/nav.html b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/nav.html new file mode 100644 index 0000000..64f68db --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/nav.html @@ -0,0 +1,14 @@ + + + + + + + + + diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/navToolbar.html b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/navToolbar.html new file mode 100644 index 0000000..d07c72e --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/navToolbar.html @@ -0,0 +1,69 @@ + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtGetInf_c.html b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtGetInf_c.html new file mode 100644 index 0000000..7c83afd --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtGetInf_c.html @@ -0,0 +1,294 @@ + + + + + + + + + + +
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
1/*
2 * rtGetInf.c
3 *
4 * Academic License - for use in teaching, academic research, and meeting
5 * course requirements at degree granting institutions only. Not for
6 * government, commercial, or other organizational use.
7 *
8 * Code generation for model "VelocityControl".
9 *
10 * Model version : 1.33
11 * Simulink Coder version : 9.0 (R2018b) 24-May-2018
12 * C source code generated on : Fri Jun 24 14:47:46 2022
13 */
14
15/*
16 * Abstract:
17 * Function to initialize non-finite, Inf
18 */
19#include "rtGetInf.h"
20#define NumBitsPerChar 8U
21
22/*
23 * Initialize rtInf needed by the generated code.
24 * Inf is initialized as non-signaling. Assumes IEEE.
25 */
26real_T rtGetInf(void)
27{
28 size_t bitsPerReal = sizeof(real_T) * (NumBitsPerChar);
29 real_T inf = 0.0;
30 if (bitsPerReal == 32U) {
31 inf = rtGetInfF();
32 } else {
33 uint16_T one = 1U;
34 enum {
35 LittleEndian,
36 BigEndian
37 } machByteOrder = (*((uint8_T *) &one) == 1U) ? LittleEndian : BigEndian;
38 switch (machByteOrder) {
39 case LittleEndian:
40 {
41 union {
42 LittleEndianIEEEDouble bitVal;
43 real_T fltVal;
44 } tmpVal;
45
46 tmpVal.bitVal.words.wordH = 0x7FF00000U;
47 tmpVal.bitVal.words.wordL = 0x00000000U;
48 inf = tmpVal.fltVal;
49 break;
50 }
51
52 case BigEndian:
53 {
54 union {
55 BigEndianIEEEDouble bitVal;
56 real_T fltVal;
57 } tmpVal;
58
59 tmpVal.bitVal.words.wordH = 0x7FF00000U;
60 tmpVal.bitVal.words.wordL = 0x00000000U;
61 inf = tmpVal.fltVal;
62 break;
63 }
64 }
65 }
66
67 return inf;
68}
69
70/*
71 * Initialize rtInfF needed by the generated code.
72 * Inf is initialized as non-signaling. Assumes IEEE.
73 */
74real32_T rtGetInfF(void)
75{
76 IEEESingle infF;
77 infF.wordL.wordLuint = 0x7F800000U;
78 return infF.wordL.wordLreal;
79}
80
81/*
82 * Initialize rtMinusInf needed by the generated code.
83 * Inf is initialized as non-signaling. Assumes IEEE.
84 */
85real_T rtGetMinusInf(void)
86{
87 size_t bitsPerReal = sizeof(real_T) * (NumBitsPerChar);
88 real_T minf = 0.0;
89 if (bitsPerReal == 32U) {
90 minf = rtGetMinusInfF();
91 } else {
92 uint16_T one = 1U;
93 enum {
94 LittleEndian,
95 BigEndian
96 } machByteOrder = (*((uint8_T *) &one) == 1U) ? LittleEndian : BigEndian;
97 switch (machByteOrder) {
98 case LittleEndian:
99 {
100 union {
101 LittleEndianIEEEDouble bitVal;
102 real_T fltVal;
103 } tmpVal;
104
105 tmpVal.bitVal.words.wordH = 0xFFF00000U;
106 tmpVal.bitVal.words.wordL = 0x00000000U;
107 minf = tmpVal.fltVal;
108 break;
109 }
110
111 case BigEndian:
112 {
113 union {
114 BigEndianIEEEDouble bitVal;
115 real_T fltVal;
116 } tmpVal;
117
118 tmpVal.bitVal.words.wordH = 0xFFF00000U;
119 tmpVal.bitVal.words.wordL = 0x00000000U;
120 minf = tmpVal.fltVal;
121 break;
122 }
123 }
124 }
125
126 return minf;
127}
128
129/*
130 * Initialize rtMinusInfF needed by the generated code.
131 * Inf is initialized as non-signaling. Assumes IEEE.
132 */
133real32_T rtGetMinusInfF(void)
134{
135 IEEESingle minfF;
136 minfF.wordL.wordLuint = 0xFF800000U;
137 return minfF.wordL.wordLreal;
138}
139
+
+ + diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtGetInf_h.html b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtGetInf_h.html new file mode 100644 index 0000000..99d666a --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtGetInf_h.html @@ -0,0 +1,70 @@ + + + + + + + + + + +
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
1/*
2 * rtGetInf.h
3 *
4 * Academic License - for use in teaching, academic research, and meeting
5 * course requirements at degree granting institutions only. Not for
6 * government, commercial, or other organizational use.
7 *
8 * Code generation for model "VelocityControl".
9 *
10 * Model version : 1.33
11 * Simulink Coder version : 9.0 (R2018b) 24-May-2018
12 * C source code generated on : Fri Jun 24 14:47:46 2022
13 */
14
15#ifndef RTW_HEADER_rtGetInf_h_
16#define RTW_HEADER_rtGetInf_h_
17#include <stddef.h>
18#include "rtwtypes.h"
19#include "rt_nonfinite.h"
20
21extern real_T rtGetInf(void);
22extern real32_T rtGetInfF(void);
23extern real_T rtGetMinusInf(void);
24extern real32_T rtGetMinusInfF(void);
25
26#endif /* RTW_HEADER_rtGetInf_h_ */
27
+
+ + diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtGetNaN_c.html b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtGetNaN_c.html new file mode 100644 index 0000000..4c4d338 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtGetNaN_c.html @@ -0,0 +1,214 @@ + + + + + + + + + + +
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
1/*
2 * rtGetNaN.c
3 *
4 * Academic License - for use in teaching, academic research, and meeting
5 * course requirements at degree granting institutions only. Not for
6 * government, commercial, or other organizational use.
7 *
8 * Code generation for model "VelocityControl".
9 *
10 * Model version : 1.33
11 * Simulink Coder version : 9.0 (R2018b) 24-May-2018
12 * C source code generated on : Fri Jun 24 14:47:46 2022
13 */
14
15/*
16 * Abstract:
17 * Function to initialize non-finite, NaN
18 */
19#include "rtGetNaN.h"
20#define NumBitsPerChar 8U
21
22/*
23 * Initialize rtNaN needed by the generated code.
24 * NaN is initialized as non-signaling. Assumes IEEE.
25 */
26real_T rtGetNaN(void)
27{
28 size_t bitsPerReal = sizeof(real_T) * (NumBitsPerChar);
29 real_T nan = 0.0;
30 if (bitsPerReal == 32U) {
31 nan = rtGetNaNF();
32 } else {
33 uint16_T one = 1U;
34 enum {
35 LittleEndian,
36 BigEndian
37 } machByteOrder = (*((uint8_T *) &one) == 1U) ? LittleEndian : BigEndian;
38 switch (machByteOrder) {
39 case LittleEndian:
40 {
41 union {
42 LittleEndianIEEEDouble bitVal;
43 real_T fltVal;
44 } tmpVal;
45
46 tmpVal.bitVal.words.wordH = 0xFFF80000U;
47 tmpVal.bitVal.words.wordL = 0x00000000U;
48 nan = tmpVal.fltVal;
49 break;
50 }
51
52 case BigEndian:
53 {
54 union {
55 BigEndianIEEEDouble bitVal;
56 real_T fltVal;
57 } tmpVal;
58
59 tmpVal.bitVal.words.wordH = 0x7FFFFFFFU;
60 tmpVal.bitVal.words.wordL = 0xFFFFFFFFU;
61 nan = tmpVal.fltVal;
62 break;
63 }
64 }
65 }
66
67 return nan;
68}
69
70/*
71 * Initialize rtNaNF needed by the generated code.
72 * NaN is initialized as non-signaling. Assumes IEEE.
73 */
74real32_T rtGetNaNF(void)
75{
76 IEEESingle nanF = { { 0 } };
77
78 uint16_T one = 1U;
79 enum {
80 LittleEndian,
81 BigEndian
82 } machByteOrder = (*((uint8_T *) &one) == 1U) ? LittleEndian : BigEndian;
83 switch (machByteOrder) {
84 case LittleEndian:
85 {
86 nanF.wordL.wordLuint = 0xFFC00000U;
87 break;
88 }
89
90 case BigEndian:
91 {
92 nanF.wordL.wordLuint = 0x7FFFFFFFU;
93 break;
94 }
95 }
96
97 return nanF.wordL.wordLreal;
98}
99
+
+ + diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtGetNaN_h.html b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtGetNaN_h.html new file mode 100644 index 0000000..62478a8 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtGetNaN_h.html @@ -0,0 +1,66 @@ + + + + + + + + + + +
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
1/*
2 * rtGetNaN.h
3 *
4 * Academic License - for use in teaching, academic research, and meeting
5 * course requirements at degree granting institutions only. Not for
6 * government, commercial, or other organizational use.
7 *
8 * Code generation for model "VelocityControl".
9 *
10 * Model version : 1.33
11 * Simulink Coder version : 9.0 (R2018b) 24-May-2018
12 * C source code generated on : Fri Jun 24 14:47:46 2022
13 */
14
15#ifndef RTW_HEADER_rtGetNaN_h_
16#define RTW_HEADER_rtGetNaN_h_
17#include <stddef.h>
18#include "rtwtypes.h"
19#include "rt_nonfinite.h"
20
21extern real_T rtGetNaN(void);
22extern real32_T rtGetNaNF(void);
23
24#endif /* RTW_HEADER_rtGetNaN_h_ */
25
+
+ + diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rt_nonfinite_c.html b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rt_nonfinite_c.html new file mode 100644 index 0000000..a32d04d --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rt_nonfinite_c.html @@ -0,0 +1,194 @@ + + + + + + + + + + +
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
1/*
2 * rt_nonfinite.c
3 *
4 * Academic License - for use in teaching, academic research, and meeting
5 * course requirements at degree granting institutions only. Not for
6 * government, commercial, or other organizational use.
7 *
8 * Code generation for model "VelocityControl".
9 *
10 * Model version : 1.33
11 * Simulink Coder version : 9.0 (R2018b) 24-May-2018
12 * C source code generated on : Fri Jun 24 14:47:46 2022
13 */
14
15/*
16 * Abstract:
17 * Function to initialize non-finites,
18 * (Inf, NaN and -Inf).
19 */
20#include "rt_nonfinite.h"
21#include "rtGetNaN.h"
22#include "rtGetInf.h"
23#define NumBitsPerChar 8U
24
25real_T rtInf;
26real_T rtMinusInf;
27real_T rtNaN;
28real32_T rtInfF;
29real32_T rtMinusInfF;
30real32_T rtNaNF;
31
32/*
33 * Initialize the rtInf, rtMinusInf, and rtNaN needed by the
34 * generated code. NaN is initialized as non-signaling. Assumes IEEE.
35 */
36void rt_InitInfAndNaN(size_t realSize)
37{
38 (void) (realSize);
39 rtNaN = rtGetNaN();
40 rtNaNF = rtGetNaNF();
41 rtInf = rtGetInf();
42 rtInfF = rtGetInfF();
43 rtMinusInf = rtGetMinusInf();
44 rtMinusInfF = rtGetMinusInfF();
45}
46
47/* Test if value is infinite */
48boolean_T rtIsInf(real_T value)
49{
50 return (boolean_T)((value==rtInf || value==rtMinusInf) ? 1U : 0U);
51}
52
53/* Test if single-precision value is infinite */
54boolean_T rtIsInfF(real32_T value)
55{
56 return (boolean_T)(((value)==rtInfF || (value)==rtMinusInfF) ? 1U : 0U);
57}
58
59/* Test if value is not a number */
60boolean_T rtIsNaN(real_T value)
61{
62 boolean_T result = (boolean_T) 0;
63 size_t bitsPerReal = sizeof(real_T) * (NumBitsPerChar);
64 if (bitsPerReal == 32U) {
65 result = rtIsNaNF((real32_T)value);
66 } else {
67 union {
68 LittleEndianIEEEDouble bitVal;
69 real_T fltVal;
70 } tmpVal;
71
72 tmpVal.fltVal = value;
73 result = (boolean_T)((tmpVal.bitVal.words.wordH & 0x7FF00000) == 0x7FF00000 &&
74 ( (tmpVal.bitVal.words.wordH & 0x000FFFFF) != 0 ||
75 (tmpVal.bitVal.words.wordL != 0) ));
76 }
77
78 return result;
79}
80
81/* Test if single-precision value is not a number */
82boolean_T rtIsNaNF(real32_T value)
83{
84 IEEESingle tmp;
85 tmp.wordL.wordLreal = value;
86 return (boolean_T)( (tmp.wordL.wordLuint & 0x7F800000) == 0x7F800000 &&
87 (tmp.wordL.wordLuint & 0x007FFFFF) != 0 );
88}
89
+
+ + diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rt_nonfinite_h.html b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rt_nonfinite_h.html new file mode 100644 index 0000000..2385faa --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rt_nonfinite_h.html @@ -0,0 +1,122 @@ + + + + + + + + + + +
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
1/*
2 * rt_nonfinite.h
3 *
4 * Academic License - for use in teaching, academic research, and meeting
5 * course requirements at degree granting institutions only. Not for
6 * government, commercial, or other organizational use.
7 *
8 * Code generation for model "VelocityControl".
9 *
10 * Model version : 1.33
11 * Simulink Coder version : 9.0 (R2018b) 24-May-2018
12 * C source code generated on : Fri Jun 24 14:47:46 2022
13 */
14
15#ifndef RTW_HEADER_rt_nonfinite_h_
16#define RTW_HEADER_rt_nonfinite_h_
17#include <stddef.h>
18#include "rtwtypes.h"
19
20extern real_T rtInf;
21extern real_T rtMinusInf;
22extern real_T rtNaN;
23extern real32_T rtInfF;
24extern real32_T rtMinusInfF;
25extern real32_T rtNaNF;
26extern void rt_InitInfAndNaN(size_t realSize);
27extern boolean_T rtIsInf(real_T value);
28extern boolean_T rtIsInfF(real32_T value);
29extern boolean_T rtIsNaN(real_T value);
30extern boolean_T rtIsNaNF(real32_T value);
31typedef struct {
32 struct {
33 uint32_T wordH;
34 uint32_T wordL;
35 } words;
36} BigEndianIEEEDouble;
37
38typedef struct {
39 struct {
40 uint32_T wordL;
41 uint32_T wordH;
42 } words;
43} LittleEndianIEEEDouble;
44
45typedef struct {
46 union {
47 real32_T wordLreal;
48 uint32_T wordLuint;
49 } wordL;
50} IEEESingle;
51
52#endif /* RTW_HEADER_rt_nonfinite_h_ */
53
+
+ + diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtwreport.css b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtwreport.css new file mode 100644 index 0000000..c9ff02b --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtwreport.css @@ -0,0 +1,257 @@ +/* Copyright 2011-2016 The MathWorks, Inc. */ +body,p,table {font-family: calibri, verdana, sans-serif;} +button,.buton {font-family: calibri, verdana, sans-serif;} +button,.button {font-size: small;} +.small_font {font-size: small;} +h1 { font-weight: normal; color: #000066; } +td { vertical-align: top } +th { background-color: #eeeeee; text-align: left; } +a:link { color: #0033cc; } +a:visited { color: #666666; } +input { font-family: sans-serif, verdana, calibri; } +table { + background-color: #ffffff; + width: 100%; +} + +table.toc, table.button, table.panel { + border-style: none; +} + +/* LineNumber */ +.LN { + font-style: italic; + color: #888888; +} + +/* Comment */ +.CT { + font-style: italic; + color: #117755; +} + +/* PreProcessor */ +PP { + /* font-weight: bold; */ + color: #992211; +} + +/* Keyword */ +.KW { + /* font-weight: bold; */ + color: #0000FF; +} + +/* Datatype */ +.DT { + /* font-weight: bold; */ + color: #112266 +} + +.highlighted { + background-color: yellow; +} + +.highlightedCurrent { + background-color: #819FF7; +} + +input.search { + background-color: #ffffff; +} + +input.failedSearch { + background-color: #F78181; +} + +/* ensure that code2model links are comment green */ +a.code2model:link { + color: #117755; + font-style: italic; +} +a.code2model:visited{ + color: #117755; + font-style: italic; +} + +.toc td, .button td, .panel td { + border-style: none; + padding: 4px; +} + +h1 { font-weight: normal; color: #000066; } +td { vertical-align: top } +th { background-color: #eeeeee; text-align: left; } +a:link { color: #0033cc; } +a:visited { color: #666666; } + +/******* table *******/ +/* default table style */ +table.AltRow { + border-collapse: collapse; border: none; border-spacing: 0pt; + border-top: solid #4F81BD 1.0pt; border-bottom: solid #4F81BD 1.0pt; +} +table.AltRow th, table.AltRow td { padding: 2pt 8pt 2pt 2pt } +/* default alternating row style */ +table.AltRow tr.even td { background-color:#D3DFEE; border:none;} +table.AltRow tr.odd td { background-color:#FFFFFF; border:none;} +/* tr class="heading" */ +table.AltRow tr.heading td, table.AltRow th { + background-color:#FFFFFF; font-weight:bold; border:none; + border-bottom: solid #4F81BD 1.0pt; +} +/* table class="FirstColumn" */ +table.FirstColumn td:first-child { font-weight:bold } +/* table class="TotalRow" */ +table.TotalRow tr:last-child { font-weight:bold } +table.TotalRow tr:last-child td { border-top: solid #4F81BD 1.0pt } + +a.closeButton { + background:-webkit-gradient( linear, left top, left bottom, color-stop(0.05, #f9f9f9), color-stop(1, #e9e9e9) ); + background:-moz-linear-gradient( center top, #f9f9f9 5%, #e9e9e9 100% ); + filter:progid:DXImageTransform.Microsoft.gradient(startColorstr='#f9f9f9', endColorstr='#e9e9e9'); + background-color:#f9f9f9; + -webkit-border-top-left-radius:20px; + -moz-border-radius-topleft:20px; + border-top-left-radius:20px; + -webkit-border-top-right-radius:20px; + -moz-border-radius-topright:20px; + border-top-right-radius:20px; + -webkit-border-bottom-right-radius:20px; + -moz-border-radius-bottomright:20px; + border-bottom-right-radius:20px; + -webkit-border-bottom-left-radius:20px; + -moz-border-radius-bottomleft:20px; + border-bottom-left-radius:20px; + text-indent:0; + border:2px solid #dcdcdc; + display:inline-block; + color:#454143; + font-family:Arial; + font-size:15px; + font-weight:bold; + font-style:normal; + height:20px; + line-height:20px; + width:20px; + text-decoration:none; + text-align:center; + cursor: pointer; +} +a.closeButton:hover { + background:-webkit-gradient( linear, left top, left bottom, color-stop(0.05, #e9e9e9), color-stop(1, #f9f9f9) ); + background:-moz-linear-gradient( center top, #e9e9e9 5%, #f9f9f9 100% ); + filter:progid:DXImageTransform.Microsoft.gradient(startColorstr='#e9e9e9', endColorstr='#f9f9f9'); + background-color:#e9e9e9; +} +a.closeButton:active { + position:relative; + top:1px; +} + +.button { + -moz-box-shadow:inset 0px 1px 0px 0px #ffffff; + -webkit-box-shadow:inset 0px 1px 0px 0px #ffffff; + box-shadow:inset 0px 1px 0px 0px #ffffff; + background:-webkit-gradient( linear, left top, left bottom, color-stop(0.05, #ededed), color-stop(1, #dfdfdf) ); + background:-moz-linear-gradient( center top, #ededed 5%, #dfdfdf 100% ); + filter:progid:DXImageTransform.Microsoft.gradient(startColorstr='#ededed', endColorstr='#dfdfdf'); + background-color:#ededed; + -webkit-border-top-left-radius:5px; + -moz-border-radius-topleft:5px; + border-top-left-radius:5px; + -webkit-border-top-right-radius:5px; + -moz-border-radius-topright:5px; + border-top-right-radius:5px; + -webkit-border-bottom-right-radius:5px; + -moz-border-radius-bottomright:5px; + border-bottom-right-radius:5px; + -webkit-border-bottom-left-radius:5px; + -moz-border-radius-bottomleft:5px; + border-bottom-left-radius:5px; + text-indent:0px; + border:1px solid #dcdcdc; + display:inline-block; + color:black; + font-family:Arial; + font-size:12px; + font-weight:bold; + font-style:normal; + height:12px; + line-height:12px; + width:45px; + text-decoration:none; + text-align:center; + text-shadow:1px 1px 0px #ffffff; +} +.button:hover { + background:-webkit-gradient( linear, left top, left bottom, color-stop(0.05, #dfdfdf), color-stop(1, #ededed) ); + background:-moz-linear-gradient( center top, #dfdfdf 5%, #ededed 100% ); + filter:progid:DXImageTransform.Microsoft.gradient(startColorstr='#dfdfdf', endColorstr='#ededed'); + background-color:#dfdfdf; +}.button:active { + position:relative; + top:1px; +}.button:disabled { + color:#777777; +} + +ul.nav_list { + list-style-type:none; + display: block; + margin: 0; + padding: 0; +} +ul.nav_list li { + list-style-type:none; + display: inline; + margin: 0 18px 0 0; + padding: 0; +} + +.nav_toolbar { + background-color: #aff; + margin-top: 0; +} + +.inspect_body { + margin: 0; + margin-bottom: 0; + display: inline; + vertical-align:middle; +} + +table.nav_table { + background-color: #aff; + border: none; + width: 100%; + display: inline; + vertical-align:middle; +} + +table#rtwIdTracePanel > tr > td { + white-space: nowrap; + table-layout:fixed; + vertical-align:middle; +} + +table.nav_table > button { + height: 20px; +} +select#fileSelector { + padding: 5px; + font-size: 16px; + line-height: 1; + border-radius: 0; + height: 34px; +} + +.treeTable table{ + table-layout: fixed; +} +.treeTable td:first-child > span{ + display: inline-block; + text-overflow: ellipsis; + overflow: hidden; + width: 100%; +} diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtwreport_utils.js b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtwreport_utils.js new file mode 100644 index 0000000..f58fb49 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtwreport_utils.js @@ -0,0 +1,92 @@ +// Copyright 2011-2013 The MathWorks, Inc. + + +function local_onload() { + if (typeof top.rtwreport_document_frame !== "undefined") { + var docObj = window.document; + var alink = docObj.getElementById("linkToText_plain"); + if (alink) { + alink.href = "matlab:coder.internal.editUrlTextFile('" + alink.href + "')"; + } + alink = docObj.getElementById("linkToCS"); + if (alink) { + alink.href = "matlab:coder.internal.viewCodeConfigsetFromReport('" + alink.href + "');"; + } + } +} + +var utils = (function() { + + // Load via Microsoft.XMLDOM--for older versions of IE + function loadXML_MSXMLDOM(filename, callback, async) { + if (navigator.appName == "Microsoft Internet Explorer") { + // Internet Explorer 5/6 + try { + var xmlDoc = new ActiveXObject("Microsoft.XMLDOM"); + xmlDoc.async = async; + xmlDoc.onreadystatechange = function() { + if (xmlDoc.readyState == 4) { + callback(xmlDoc); + } + } + xmlDoc.load(filename); + return true; + } catch(e) { + } + } + return false; + } + + // Load via XMLHttpRequest + function loadXML_XHR(filename, callback, async) { + if (window.XMLHttpRequest) { + try { + var xhr = new XMLHttpRequest(); + xhr.onreadystatechange = function() { + if (this.readyState == 4) { + callback(this.responseXML); + } + } + xhr.open("GET", filename, async); + xhr.send(""); + return true; + } catch(e) { + if (navigator.appName === "Netscape" && e.code === 1012) { + // file not found: ignore + return true; + } + } + } + return false; + } + + return { + trimText: function(s) { + // In IE9, String.trim not present + if (s && s.trim) { + return s.trim(); + } + else { + return s; + } + }, + getText: function(elt) { + // In IE9, use 'text' property rather than 'textContent' + return elt.textContent ? elt.textContent : elt.text; + }, + loadXML: function(filename, callback, options) { + var async = !!options && typeof(options["async"]) !== "undefined" ? options.async : true; + if (!loadXML_XHR(filename, callback, async)) { + if (!loadXML_MSXMLDOM(filename, callback, async)) { + return false; + } + } + return true; + } + }; +})(); + +function code2model(sid) { + utils.loadXML("http://localhost:31415/matlab/feval/coder.internal.code2model?arguments=[\"" + sid + "\"]", function() {}); + //window.location.href = "matlab:coder.internal.code2model('" + sid + "')"; +} diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtwtypes_h.html b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtwtypes_h.html new file mode 100644 index 0000000..7281fb2 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/rtwtypes_h.html @@ -0,0 +1,164 @@ + + + + + + + + + + +
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
1/*
2 * rtwtypes.h
3 *
4 * Academic License - for use in teaching, academic research, and meeting
5 * course requirements at degree granting institutions only. Not for
6 * government, commercial, or other organizational use.
7 *
8 * Code generation for model "PositionControl".
9 *
10 * Model version : 1.33
11 * Simulink Coder version : 9.0 (R2018b) 24-May-2018
12 * C source code generated on : Fri Jun 24 14:47:43 2022
13 */
14
15#ifndef RTWTYPES_H
16#define RTWTYPES_H
17#include "tmwtypes.h"
18#include "simstruc_types.h"
19#ifndef POINTER_T
20# define POINTER_T
21
22typedef void * pointer_T;
23
24#endif
25
26/* Logical type definitions */
27#if (!defined(__cplusplus))
28# ifndef false
29# define false (0U)
30# endif
31
32# ifndef true
33# define true (1U)
34# endif
35#endif
36
37#ifndef INT64_T
38#define INT64_T
39
40typedef long long int64_T;
41
42#endif
43
44#ifndef UINT64_T
45#define UINT64_T
46
47typedef unsigned long long uint64_T;
48
49#endif
50
51/*===========================================================================*
52 * Additional complex number type definitions *
53 *===========================================================================*/
54#ifndef CINT64_T
55#define CINT64_T
56
57typedef struct {
58 int64_T re;
59 int64_T im;
60} cint64_T;
61
62#endif
63
64#ifndef CUINT64_T
65#define CUINT64_T
66
67typedef struct {
68 uint64_T re;
69 uint64_T im;
70} cuint64_T;
71
72#endif
73#endif /* RTWTYPES_H */
74
+
+ + diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/spinner.gif b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/spinner.gif new file mode 100644 index 0000000..e4ab783 Binary files /dev/null and b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/html/spinner.gif differ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/multiword_types.h b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/multiword_types.h new file mode 100644 index 0000000..7de4fef --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/multiword_types.h @@ -0,0 +1,591 @@ +/* + * multiword_types.h + * + * Academic License - for use in teaching, academic research, and meeting + * course requirements at degree granting institutions only. Not for + * government, commercial, or other organizational use. + * + * Code generation for model "Control_System". + * + * Model version : 1.97 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Fri Jun 24 14:53:49 2022 + */ + +#ifndef MULTIWORD_TYPES_H +#define MULTIWORD_TYPES_H +#include "rtwtypes.h" + +/* + * Definitions supporting external data access + */ +typedef int64_T chunk_T; +typedef uint64_T uchunk_T; + +/* + * MultiWord supporting definitions + */ +typedef long long longlong_T; + +/* + * MultiWord types + */ +typedef struct { + uint64_T chunks[2]; +} int128m_T; + +typedef struct { + int128m_T re; + int128m_T im; +} cint128m_T; + +typedef struct { + uint64_T chunks[2]; +} uint128m_T; + +typedef struct { + uint128m_T re; + uint128m_T im; +} cuint128m_T; + +typedef struct { + uint64_T chunks[3]; +} int192m_T; + +typedef struct { + int192m_T re; + int192m_T im; +} cint192m_T; + +typedef struct { + uint64_T chunks[3]; +} uint192m_T; + +typedef struct { + uint192m_T re; + uint192m_T im; +} cuint192m_T; + +typedef struct { + uint64_T chunks[4]; +} int256m_T; + +typedef struct { + int256m_T re; + int256m_T im; +} cint256m_T; + +typedef struct { + uint64_T chunks[4]; +} uint256m_T; + +typedef struct { + uint256m_T re; + uint256m_T im; +} cuint256m_T; + +typedef struct { + uint64_T chunks[5]; +} int320m_T; + +typedef struct { + int320m_T re; + int320m_T im; +} cint320m_T; + +typedef struct { + uint64_T chunks[5]; +} uint320m_T; + +typedef struct { + uint320m_T re; + uint320m_T im; +} cuint320m_T; + +typedef struct { + uint64_T chunks[6]; +} int384m_T; + +typedef struct { + int384m_T re; + int384m_T im; +} cint384m_T; + +typedef struct { + uint64_T chunks[6]; +} uint384m_T; + +typedef struct { + uint384m_T re; + uint384m_T im; +} cuint384m_T; + +typedef struct { + uint64_T chunks[7]; +} int448m_T; + +typedef struct { + int448m_T re; + int448m_T im; +} cint448m_T; + +typedef struct { + uint64_T chunks[7]; +} uint448m_T; + +typedef struct { + uint448m_T re; + uint448m_T im; +} cuint448m_T; + +typedef struct { + uint64_T chunks[8]; +} int512m_T; + +typedef struct { + int512m_T re; + int512m_T im; +} cint512m_T; + +typedef struct { + uint64_T chunks[8]; +} uint512m_T; + +typedef struct { + uint512m_T re; + uint512m_T im; +} cuint512m_T; + +typedef struct { + uint64_T chunks[9]; +} int576m_T; + +typedef struct { + int576m_T re; + int576m_T im; +} cint576m_T; + +typedef struct { + uint64_T chunks[9]; +} uint576m_T; + +typedef struct { + uint576m_T re; + uint576m_T im; +} cuint576m_T; + +typedef struct { + uint64_T chunks[10]; +} int640m_T; + +typedef struct { + int640m_T re; + int640m_T im; +} cint640m_T; + +typedef struct { + uint64_T chunks[10]; +} uint640m_T; + +typedef struct { + uint640m_T re; + uint640m_T im; +} cuint640m_T; + +typedef struct { + uint64_T chunks[11]; +} int704m_T; + +typedef struct { + int704m_T re; + int704m_T im; +} cint704m_T; + +typedef struct { + uint64_T chunks[11]; +} uint704m_T; + +typedef struct { + uint704m_T re; + uint704m_T im; +} cuint704m_T; + +typedef struct { + uint64_T chunks[12]; +} int768m_T; + +typedef struct { + int768m_T re; + int768m_T im; +} cint768m_T; + +typedef struct { + uint64_T chunks[12]; +} uint768m_T; + +typedef struct { + uint768m_T re; + uint768m_T im; +} cuint768m_T; + +typedef struct { + uint64_T chunks[13]; +} int832m_T; + +typedef struct { + int832m_T re; + int832m_T im; +} cint832m_T; + +typedef struct { + uint64_T chunks[13]; +} uint832m_T; + +typedef struct { + uint832m_T re; + uint832m_T im; +} cuint832m_T; + +typedef struct { + uint64_T chunks[14]; +} int896m_T; + +typedef struct { + int896m_T re; + int896m_T im; +} cint896m_T; + +typedef struct { + uint64_T chunks[14]; +} uint896m_T; + +typedef struct { + uint896m_T re; + uint896m_T im; +} cuint896m_T; + +typedef struct { + uint64_T chunks[15]; +} int960m_T; + +typedef struct { + int960m_T re; + int960m_T im; +} cint960m_T; + +typedef struct { + uint64_T chunks[15]; +} uint960m_T; + +typedef struct { + uint960m_T re; + uint960m_T im; +} cuint960m_T; + +typedef struct { + uint64_T chunks[16]; +} int1024m_T; + +typedef struct { + int1024m_T re; + int1024m_T im; +} cint1024m_T; + +typedef struct { + uint64_T chunks[16]; +} uint1024m_T; + +typedef struct { + uint1024m_T re; + uint1024m_T im; +} cuint1024m_T; + +typedef struct { + uint64_T chunks[17]; +} int1088m_T; + +typedef struct { + int1088m_T re; + int1088m_T im; +} cint1088m_T; + +typedef struct { + uint64_T chunks[17]; +} uint1088m_T; + +typedef struct { + uint1088m_T re; + uint1088m_T im; +} cuint1088m_T; + +typedef struct { + uint64_T chunks[18]; +} int1152m_T; + +typedef struct { + int1152m_T re; + int1152m_T im; +} cint1152m_T; + +typedef struct { + uint64_T chunks[18]; +} uint1152m_T; + +typedef struct { + uint1152m_T re; + uint1152m_T im; +} cuint1152m_T; + +typedef struct { + uint64_T chunks[19]; +} int1216m_T; + +typedef struct { + int1216m_T re; + int1216m_T im; +} cint1216m_T; + +typedef struct { + uint64_T chunks[19]; +} uint1216m_T; + +typedef struct { + uint1216m_T re; + uint1216m_T im; +} cuint1216m_T; + +typedef struct { + uint64_T chunks[20]; +} int1280m_T; + +typedef struct { + int1280m_T re; + int1280m_T im; +} cint1280m_T; + +typedef struct { + uint64_T chunks[20]; +} uint1280m_T; + +typedef struct { + uint1280m_T re; + uint1280m_T im; +} cuint1280m_T; + +typedef struct { + uint64_T chunks[21]; +} int1344m_T; + +typedef struct { + int1344m_T re; + int1344m_T im; +} cint1344m_T; + +typedef struct { + uint64_T chunks[21]; +} uint1344m_T; + +typedef struct { + uint1344m_T re; + uint1344m_T im; +} cuint1344m_T; + +typedef struct { + uint64_T chunks[22]; +} int1408m_T; + +typedef struct { + int1408m_T re; + int1408m_T im; +} cint1408m_T; + +typedef struct { + uint64_T chunks[22]; +} uint1408m_T; + +typedef struct { + uint1408m_T re; + uint1408m_T im; +} cuint1408m_T; + +typedef struct { + uint64_T chunks[23]; +} int1472m_T; + +typedef struct { + int1472m_T re; + int1472m_T im; +} cint1472m_T; + +typedef struct { + uint64_T chunks[23]; +} uint1472m_T; + +typedef struct { + uint1472m_T re; + uint1472m_T im; +} cuint1472m_T; + +typedef struct { + uint64_T chunks[24]; +} int1536m_T; + +typedef struct { + int1536m_T re; + int1536m_T im; +} cint1536m_T; + +typedef struct { + uint64_T chunks[24]; +} uint1536m_T; + +typedef struct { + uint1536m_T re; + uint1536m_T im; +} cuint1536m_T; + +typedef struct { + uint64_T chunks[25]; +} int1600m_T; + +typedef struct { + int1600m_T re; + int1600m_T im; +} cint1600m_T; + +typedef struct { + uint64_T chunks[25]; +} uint1600m_T; + +typedef struct { + uint1600m_T re; + uint1600m_T im; +} cuint1600m_T; + +typedef struct { + uint64_T chunks[26]; +} int1664m_T; + +typedef struct { + int1664m_T re; + int1664m_T im; +} cint1664m_T; + +typedef struct { + uint64_T chunks[26]; +} uint1664m_T; + +typedef struct { + uint1664m_T re; + uint1664m_T im; +} cuint1664m_T; + +typedef struct { + uint64_T chunks[27]; +} int1728m_T; + +typedef struct { + int1728m_T re; + int1728m_T im; +} cint1728m_T; + +typedef struct { + uint64_T chunks[27]; +} uint1728m_T; + +typedef struct { + uint1728m_T re; + uint1728m_T im; +} cuint1728m_T; + +typedef struct { + uint64_T chunks[28]; +} int1792m_T; + +typedef struct { + int1792m_T re; + int1792m_T im; +} cint1792m_T; + +typedef struct { + uint64_T chunks[28]; +} uint1792m_T; + +typedef struct { + uint1792m_T re; + uint1792m_T im; +} cuint1792m_T; + +typedef struct { + uint64_T chunks[29]; +} int1856m_T; + +typedef struct { + int1856m_T re; + int1856m_T im; +} cint1856m_T; + +typedef struct { + uint64_T chunks[29]; +} uint1856m_T; + +typedef struct { + uint1856m_T re; + uint1856m_T im; +} cuint1856m_T; + +typedef struct { + uint64_T chunks[30]; +} int1920m_T; + +typedef struct { + int1920m_T re; + int1920m_T im; +} cint1920m_T; + +typedef struct { + uint64_T chunks[30]; +} uint1920m_T; + +typedef struct { + uint1920m_T re; + uint1920m_T im; +} cuint1920m_T; + +typedef struct { + uint64_T chunks[31]; +} int1984m_T; + +typedef struct { + int1984m_T re; + int1984m_T im; +} cint1984m_T; + +typedef struct { + uint64_T chunks[31]; +} uint1984m_T; + +typedef struct { + uint1984m_T re; + uint1984m_T im; +} cuint1984m_T; + +typedef struct { + uint64_T chunks[32]; +} int2048m_T; + +typedef struct { + int2048m_T re; + int2048m_T im; +} cint2048m_T; + +typedef struct { + uint64_T chunks[32]; +} uint2048m_T; + +typedef struct { + uint2048m_T re; + uint2048m_T im; +} cuint2048m_T; + +#endif /* MULTIWORD_TYPES_H */ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtGetInf.c b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtGetInf.c new file mode 100644 index 0000000..5efad22 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtGetInf.c @@ -0,0 +1,138 @@ +/* + * rtGetInf.c + * + * Academic License - for use in teaching, academic research, and meeting + * course requirements at degree granting institutions only. Not for + * government, commercial, or other organizational use. + * + * Code generation for model "VelocityControl". + * + * Model version : 1.33 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Fri Jun 24 14:47:46 2022 + */ + +/* + * Abstract: + * Function to initialize non-finite, Inf + */ +#include "rtGetInf.h" +#define NumBitsPerChar 8U + +/* + * Initialize rtInf needed by the generated code. + * Inf is initialized as non-signaling. Assumes IEEE. + */ +real_T rtGetInf(void) +{ + size_t bitsPerReal = sizeof(real_T) * (NumBitsPerChar); + real_T inf = 0.0; + if (bitsPerReal == 32U) { + inf = rtGetInfF(); + } else { + uint16_T one = 1U; + enum { + LittleEndian, + BigEndian + } machByteOrder = (*((uint8_T *) &one) == 1U) ? LittleEndian : BigEndian; + switch (machByteOrder) { + case LittleEndian: + { + union { + LittleEndianIEEEDouble bitVal; + real_T fltVal; + } tmpVal; + + tmpVal.bitVal.words.wordH = 0x7FF00000U; + tmpVal.bitVal.words.wordL = 0x00000000U; + inf = tmpVal.fltVal; + break; + } + + case BigEndian: + { + union { + BigEndianIEEEDouble bitVal; + real_T fltVal; + } tmpVal; + + tmpVal.bitVal.words.wordH = 0x7FF00000U; + tmpVal.bitVal.words.wordL = 0x00000000U; + inf = tmpVal.fltVal; + break; + } + } + } + + return inf; +} + +/* + * Initialize rtInfF needed by the generated code. + * Inf is initialized as non-signaling. Assumes IEEE. + */ +real32_T rtGetInfF(void) +{ + IEEESingle infF; + infF.wordL.wordLuint = 0x7F800000U; + return infF.wordL.wordLreal; +} + +/* + * Initialize rtMinusInf needed by the generated code. + * Inf is initialized as non-signaling. Assumes IEEE. + */ +real_T rtGetMinusInf(void) +{ + size_t bitsPerReal = sizeof(real_T) * (NumBitsPerChar); + real_T minf = 0.0; + if (bitsPerReal == 32U) { + minf = rtGetMinusInfF(); + } else { + uint16_T one = 1U; + enum { + LittleEndian, + BigEndian + } machByteOrder = (*((uint8_T *) &one) == 1U) ? LittleEndian : BigEndian; + switch (machByteOrder) { + case LittleEndian: + { + union { + LittleEndianIEEEDouble bitVal; + real_T fltVal; + } tmpVal; + + tmpVal.bitVal.words.wordH = 0xFFF00000U; + tmpVal.bitVal.words.wordL = 0x00000000U; + minf = tmpVal.fltVal; + break; + } + + case BigEndian: + { + union { + BigEndianIEEEDouble bitVal; + real_T fltVal; + } tmpVal; + + tmpVal.bitVal.words.wordH = 0xFFF00000U; + tmpVal.bitVal.words.wordL = 0x00000000U; + minf = tmpVal.fltVal; + break; + } + } + } + + return minf; +} + +/* + * Initialize rtMinusInfF needed by the generated code. + * Inf is initialized as non-signaling. Assumes IEEE. + */ +real32_T rtGetMinusInfF(void) +{ + IEEESingle minfF; + minfF.wordL.wordLuint = 0xFF800000U; + return minfF.wordL.wordLreal; +} diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtGetInf.h b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtGetInf.h new file mode 100644 index 0000000..788ed74 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtGetInf.h @@ -0,0 +1,26 @@ +/* + * rtGetInf.h + * + * Academic License - for use in teaching, academic research, and meeting + * course requirements at degree granting institutions only. Not for + * government, commercial, or other organizational use. + * + * Code generation for model "VelocityControl". + * + * Model version : 1.33 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Fri Jun 24 14:47:46 2022 + */ + +#ifndef RTW_HEADER_rtGetInf_h_ +#define RTW_HEADER_rtGetInf_h_ +#include +#include "rtwtypes.h" +#include "rt_nonfinite.h" + +extern real_T rtGetInf(void); +extern real32_T rtGetInfF(void); +extern real_T rtGetMinusInf(void); +extern real32_T rtGetMinusInfF(void); + +#endif /* RTW_HEADER_rtGetInf_h_ */ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtGetNaN.c b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtGetNaN.c new file mode 100644 index 0000000..c340ea1 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtGetNaN.c @@ -0,0 +1,98 @@ +/* + * rtGetNaN.c + * + * Academic License - for use in teaching, academic research, and meeting + * course requirements at degree granting institutions only. Not for + * government, commercial, or other organizational use. + * + * Code generation for model "VelocityControl". + * + * Model version : 1.33 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Fri Jun 24 14:47:46 2022 + */ + +/* + * Abstract: + * Function to initialize non-finite, NaN + */ +#include "rtGetNaN.h" +#define NumBitsPerChar 8U + +/* + * Initialize rtNaN needed by the generated code. + * NaN is initialized as non-signaling. Assumes IEEE. + */ +real_T rtGetNaN(void) +{ + size_t bitsPerReal = sizeof(real_T) * (NumBitsPerChar); + real_T nan = 0.0; + if (bitsPerReal == 32U) { + nan = rtGetNaNF(); + } else { + uint16_T one = 1U; + enum { + LittleEndian, + BigEndian + } machByteOrder = (*((uint8_T *) &one) == 1U) ? LittleEndian : BigEndian; + switch (machByteOrder) { + case LittleEndian: + { + union { + LittleEndianIEEEDouble bitVal; + real_T fltVal; + } tmpVal; + + tmpVal.bitVal.words.wordH = 0xFFF80000U; + tmpVal.bitVal.words.wordL = 0x00000000U; + nan = tmpVal.fltVal; + break; + } + + case BigEndian: + { + union { + BigEndianIEEEDouble bitVal; + real_T fltVal; + } tmpVal; + + tmpVal.bitVal.words.wordH = 0x7FFFFFFFU; + tmpVal.bitVal.words.wordL = 0xFFFFFFFFU; + nan = tmpVal.fltVal; + break; + } + } + } + + return nan; +} + +/* + * Initialize rtNaNF needed by the generated code. + * NaN is initialized as non-signaling. Assumes IEEE. + */ +real32_T rtGetNaNF(void) +{ + IEEESingle nanF = { { 0 } }; + + uint16_T one = 1U; + enum { + LittleEndian, + BigEndian + } machByteOrder = (*((uint8_T *) &one) == 1U) ? LittleEndian : BigEndian; + switch (machByteOrder) { + case LittleEndian: + { + nanF.wordL.wordLuint = 0xFFC00000U; + break; + } + + case BigEndian: + { + nanF.wordL.wordLuint = 0x7FFFFFFFU; + break; + } + } + + return nanF.wordL.wordLreal; +} diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtGetNaN.h b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtGetNaN.h new file mode 100644 index 0000000..037eb82 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtGetNaN.h @@ -0,0 +1,24 @@ +/* + * rtGetNaN.h + * + * Academic License - for use in teaching, academic research, and meeting + * course requirements at degree granting institutions only. Not for + * government, commercial, or other organizational use. + * + * Code generation for model "VelocityControl". + * + * Model version : 1.33 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Fri Jun 24 14:47:46 2022 + */ + +#ifndef RTW_HEADER_rtGetNaN_h_ +#define RTW_HEADER_rtGetNaN_h_ +#include +#include "rtwtypes.h" +#include "rt_nonfinite.h" + +extern real_T rtGetNaN(void); +extern real32_T rtGetNaNF(void); + +#endif /* RTW_HEADER_rtGetNaN_h_ */ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rt_nonfinite.c b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rt_nonfinite.c new file mode 100644 index 0000000..0364fda --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rt_nonfinite.c @@ -0,0 +1,88 @@ +/* + * rt_nonfinite.c + * + * Academic License - for use in teaching, academic research, and meeting + * course requirements at degree granting institutions only. Not for + * government, commercial, or other organizational use. + * + * Code generation for model "VelocityControl". + * + * Model version : 1.33 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Fri Jun 24 14:47:46 2022 + */ + +/* + * Abstract: + * Function to initialize non-finites, + * (Inf, NaN and -Inf). + */ +#include "rt_nonfinite.h" +#include "rtGetNaN.h" +#include "rtGetInf.h" +#define NumBitsPerChar 8U + +real_T rtInf; +real_T rtMinusInf; +real_T rtNaN; +real32_T rtInfF; +real32_T rtMinusInfF; +real32_T rtNaNF; + +/* + * Initialize the rtInf, rtMinusInf, and rtNaN needed by the + * generated code. NaN is initialized as non-signaling. Assumes IEEE. + */ +void rt_InitInfAndNaN(size_t realSize) +{ + (void) (realSize); + rtNaN = rtGetNaN(); + rtNaNF = rtGetNaNF(); + rtInf = rtGetInf(); + rtInfF = rtGetInfF(); + rtMinusInf = rtGetMinusInf(); + rtMinusInfF = rtGetMinusInfF(); +} + +/* Test if value is infinite */ +boolean_T rtIsInf(real_T value) +{ + return (boolean_T)((value==rtInf || value==rtMinusInf) ? 1U : 0U); +} + +/* Test if single-precision value is infinite */ +boolean_T rtIsInfF(real32_T value) +{ + return (boolean_T)(((value)==rtInfF || (value)==rtMinusInfF) ? 1U : 0U); +} + +/* Test if value is not a number */ +boolean_T rtIsNaN(real_T value) +{ + boolean_T result = (boolean_T) 0; + size_t bitsPerReal = sizeof(real_T) * (NumBitsPerChar); + if (bitsPerReal == 32U) { + result = rtIsNaNF((real32_T)value); + } else { + union { + LittleEndianIEEEDouble bitVal; + real_T fltVal; + } tmpVal; + + tmpVal.fltVal = value; + result = (boolean_T)((tmpVal.bitVal.words.wordH & 0x7FF00000) == 0x7FF00000 && + ( (tmpVal.bitVal.words.wordH & 0x000FFFFF) != 0 || + (tmpVal.bitVal.words.wordL != 0) )); + } + + return result; +} + +/* Test if single-precision value is not a number */ +boolean_T rtIsNaNF(real32_T value) +{ + IEEESingle tmp; + tmp.wordL.wordLreal = value; + return (boolean_T)( (tmp.wordL.wordLuint & 0x7F800000) == 0x7F800000 && + (tmp.wordL.wordLuint & 0x007FFFFF) != 0 ); +} diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rt_nonfinite.h b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rt_nonfinite.h new file mode 100644 index 0000000..07f7f95 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rt_nonfinite.h @@ -0,0 +1,52 @@ +/* + * rt_nonfinite.h + * + * Academic License - for use in teaching, academic research, and meeting + * course requirements at degree granting institutions only. Not for + * government, commercial, or other organizational use. + * + * Code generation for model "VelocityControl". + * + * Model version : 1.33 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Fri Jun 24 14:47:46 2022 + */ + +#ifndef RTW_HEADER_rt_nonfinite_h_ +#define RTW_HEADER_rt_nonfinite_h_ +#include +#include "rtwtypes.h" + +extern real_T rtInf; +extern real_T rtMinusInf; +extern real_T rtNaN; +extern real32_T rtInfF; +extern real32_T rtMinusInfF; +extern real32_T rtNaNF; +extern void rt_InitInfAndNaN(size_t realSize); +extern boolean_T rtIsInf(real_T value); +extern boolean_T rtIsInfF(real32_T value); +extern boolean_T rtIsNaN(real_T value); +extern boolean_T rtIsNaNF(real32_T value); +typedef struct { + struct { + uint32_T wordH; + uint32_T wordL; + } words; +} BigEndianIEEEDouble; + +typedef struct { + struct { + uint32_T wordL; + uint32_T wordH; + } words; +} LittleEndianIEEEDouble; + +typedef struct { + union { + real32_T wordLreal; + uint32_T wordLuint; + } wordL; +} IEEESingle; + +#endif /* RTW_HEADER_rt_nonfinite_h_ */ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtwshared.rsp b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtwshared.rsp new file mode 100644 index 0000000..a72ee4f --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtwshared.rsp @@ -0,0 +1,3 @@ +..\slprj\grt\_sharedutils\rtGetInf.c +..\slprj\grt\_sharedutils\rtGetNaN.c +..\slprj\grt\_sharedutils\rt_nonfinite.c diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtwtypes.h b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtwtypes.h new file mode 100644 index 0000000..94845d8 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtwtypes.h @@ -0,0 +1,73 @@ +/* + * rtwtypes.h + * + * Academic License - for use in teaching, academic research, and meeting + * course requirements at degree granting institutions only. Not for + * government, commercial, or other organizational use. + * + * Code generation for model "PositionControl". + * + * Model version : 1.33 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Fri Jun 24 14:47:43 2022 + */ + +#ifndef RTWTYPES_H +#define RTWTYPES_H +#include "tmwtypes.h" +#include "simstruc_types.h" +#ifndef POINTER_T +# define POINTER_T + +typedef void * pointer_T; + +#endif + +/* Logical type definitions */ +#if (!defined(__cplusplus)) +# ifndef false +# define false (0U) +# endif + +# ifndef true +# define true (1U) +# endif +#endif + +#ifndef INT64_T +#define INT64_T + +typedef long long int64_T; + +#endif + +#ifndef UINT64_T +#define UINT64_T + +typedef unsigned long long uint64_T; + +#endif + +/*===========================================================================* + * Additional complex number type definitions * + *===========================================================================*/ +#ifndef CINT64_T +#define CINT64_T + +typedef struct { + int64_T re; + int64_T im; +} cint64_T; + +#endif + +#ifndef CUINT64_T +#define CUINT64_T + +typedef struct { + uint64_T re; + uint64_T im; +} cuint64_T; + +#endif +#endif /* RTWTYPES_H */ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtwtypeschksum.mat b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtwtypeschksum.mat new file mode 100644 index 0000000..46427b8 Binary files /dev/null and b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/rtwtypeschksum.mat differ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/shared_file.dmr b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/shared_file.dmr new file mode 100644 index 0000000..2cbcf75 Binary files /dev/null and b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/shared_file.dmr differ diff --git a/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/tflSUInfo.mat b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/tflSUInfo.mat new file mode 100644 index 0000000..0bf1260 Binary files /dev/null and b/Examples/epos_matlab/src/simulinkcode/Matlab/_sharedutils/tflSUInfo.mat differ diff --git a/Examples/epos_matlab/src/simulinkcode/controller/Control_System.c b/Examples/epos_matlab/src/simulinkcode/controller/Control_System.c new file mode 100644 index 0000000..6c38d42 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/controller/Control_System.c @@ -0,0 +1,733 @@ +/* + * Control_System.c + * + * Academic License - for use in teaching, academic research, and meeting + * course requirements at degree granting institutions only. Not for + * government, commercial, or other organizational use. + * + * Code generation for model "Control_System". + * + * Model version : 1.119 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Tue Jun 28 17:20:04 2022 + * + * Target selection: grt.tlc + * Note: GRT includes extra infrastructure and instrumentation for prototyping + * Embedded hardware selection: ARM Compatible->ARM Cortex + * Code generation objective: Execution efficiency + * Validation result: Not run + */ + +#include "Control_System.h" +#include "Control_System_private.h" + +/* Block signals (default storage) */ +B_Control_System_T Control_System_B; + +/* Continuous states */ +X_Control_System_T Control_System_X; + +/* Block states (default storage) */ +DW_Control_System_T Control_System_DW; + +/* External inputs (root inport signals with default storage) */ +ExtU_Control_System_T Control_System_U; + +/* External outputs (root outports fed by signals with default storage) */ +ExtY_Control_System_T Control_System_Y; + +/* Real-time model */ +RT_MODEL_Control_System_T Control_System_M_; +RT_MODEL_Control_System_T *const Control_System_M = &Control_System_M_; + +/* Forward declaration for local functions */ +static void Control_Syst_SystemCore_release(dsp_simulink_MovingAverage_Co_T *obj); +static void Control_Syste_SystemCore_delete(dsp_simulink_MovingAverage_Co_T *obj); +static void matlabCodegenHandle_matlabCodeg(dsp_simulink_MovingAverage_Co_T *obj); + +/* + * This function updates continuous states using the ODE3 fixed-step + * solver algorithm + */ +static void rt_ertODEUpdateContinuousStates(RTWSolverInfo *si ) +{ + /* Solver Matrices */ + static const real_T rt_ODE3_A[3] = { + 1.0/2.0, 3.0/4.0, 1.0 + }; + + static const real_T rt_ODE3_B[3][3] = { + { 1.0/2.0, 0.0, 0.0 }, + + { 0.0, 3.0/4.0, 0.0 }, + + { 2.0/9.0, 1.0/3.0, 4.0/9.0 } + }; + + time_T t = rtsiGetT(si); + time_T tnew = rtsiGetSolverStopTime(si); + time_T h = rtsiGetStepSize(si); + real_T *x = rtsiGetContStates(si); + ODE3_IntgData *id = (ODE3_IntgData *)rtsiGetSolverData(si); + real_T *y = id->y; + real_T *f0 = id->f[0]; + real_T *f1 = id->f[1]; + real_T *f2 = id->f[2]; + real_T hB[3]; + int_T i; + int_T nXc = 5; + rtsiSetSimTimeStep(si,MINOR_TIME_STEP); + + /* Save the state values at time t in y, we'll use x as ynew. */ + (void) memcpy(y, x, + (uint_T)nXc*sizeof(real_T)); + + /* Assumes that rtsiSetT and ModelOutputs are up-to-date */ + /* f0 = f(t,y) */ + rtsiSetdX(si, f0); + Control_System_derivatives(); + + /* f(:,2) = feval(odefile, t + hA(1), y + f*hB(:,1), args(:)(*)); */ + hB[0] = h * rt_ODE3_B[0][0]; + for (i = 0; i < nXc; i++) { + x[i] = y[i] + (f0[i]*hB[0]); + } + + rtsiSetT(si, t + h*rt_ODE3_A[0]); + rtsiSetdX(si, f1); + Control_System_step(); + Control_System_derivatives(); + + /* f(:,3) = feval(odefile, t + hA(2), y + f*hB(:,2), args(:)(*)); */ + for (i = 0; i <= 1; i++) { + hB[i] = h * rt_ODE3_B[1][i]; + } + + for (i = 0; i < nXc; i++) { + x[i] = y[i] + (f0[i]*hB[0] + f1[i]*hB[1]); + } + + rtsiSetT(si, t + h*rt_ODE3_A[1]); + rtsiSetdX(si, f2); + Control_System_step(); + Control_System_derivatives(); + + /* tnew = t + hA(3); + ynew = y + f*hB(:,3); */ + for (i = 0; i <= 2; i++) { + hB[i] = h * rt_ODE3_B[2][i]; + } + + for (i = 0; i < nXc; i++) { + x[i] = y[i] + (f0[i]*hB[0] + f1[i]*hB[1] + f2[i]*hB[2]); + } + + rtsiSetT(si, tnew); + rtsiSetSimTimeStep(si,MAJOR_TIME_STEP); +} + +static void Control_Syst_SystemCore_release(dsp_simulink_MovingAverage_Co_T *obj) +{ + dsp_private_SlidingWindowAver_T *obj_0; + if ((obj->isInitialized == 1) && obj->isSetupComplete) { + obj_0 = obj->pStatistic; + if (obj_0->isInitialized == 1) { + obj_0->isInitialized = 2; + } + + obj->NumChannels = -1; + } +} + +static void Control_Syste_SystemCore_delete(dsp_simulink_MovingAverage_Co_T *obj) +{ + Control_Syst_SystemCore_release(obj); +} + +static void matlabCodegenHandle_matlabCodeg(dsp_simulink_MovingAverage_Co_T *obj) +{ + if (!obj->matlabCodegenIsDeleted) { + obj->matlabCodegenIsDeleted = true; + Control_Syste_SystemCore_delete(obj); + } +} + +/* Model step function */ +void Control_System_step(void) +{ + real_T Torque_Meas; + real_T Vel_Meas; + real_T Pos_Meas; + real_T Torque_Ref; + real_T csumrev[3]; + int32_T Torque_Ref_tmp; + if (rtmIsMajorTimeStep(Control_System_M)) { + /* set solver stop time */ + if (!(Control_System_M->Timing.clockTick0+1)) { + rtsiSetSolverStopTime(&Control_System_M->solverInfo, + ((Control_System_M->Timing.clockTickH0 + 1) * + Control_System_M->Timing.stepSize0 * 4294967296.0)); + } else { + rtsiSetSolverStopTime(&Control_System_M->solverInfo, + ((Control_System_M->Timing.clockTick0 + 1) * + Control_System_M->Timing.stepSize0 + + Control_System_M->Timing.clockTickH0 * + Control_System_M->Timing.stepSize0 * 4294967296.0)); + } + } /* end MajorTimeStep */ + + /* Update absolute time of base rate at minor time step */ + if (rtmIsMinorTimeStep(Control_System_M)) { + Control_System_M->Timing.t[0] = rtsiGetT(&Control_System_M->solverInfo); + } + + /* MATLAB Function: '/Measurement Function' incorporates: + * Inport: '/User_ControlMode' + * Inport: '/pos_meas_rad' + * Inport: '/torque_meas_Nm' + * Inport: '/vel_meas_rads' + */ + if (Control_System_U.User_ControlMode == 1.0) { + Control_System_B.ausgabe_g[0] = Control_System_U.torque_meas_Nm; + Control_System_B.ausgabe_g[1] = Control_System_U.vel_meas_rads; + Control_System_B.ausgabe_g[2] = Control_System_U.pos_meas_rad; + } else if (Control_System_U.User_ControlMode == 2.0) { + Control_System_B.ausgabe_g[0] = Control_System_U.torque_meas_Nm; + Control_System_B.ausgabe_g[1] = Control_System_U.vel_meas_rads; + Control_System_B.ausgabe_g[2] = 0.0; + } else if (Control_System_U.User_ControlMode == 3.0) { + Control_System_B.ausgabe_g[0] = Control_System_U.torque_meas_Nm; + Control_System_B.ausgabe_g[1] = 0.0; + Control_System_B.ausgabe_g[2] = 0.0; + } else { + Control_System_B.ausgabe_g[0] = 0.0; + Control_System_B.ausgabe_g[1] = 0.0; + Control_System_B.ausgabe_g[2] = 0.0; + } + + /* End of MATLAB Function: '/Measurement Function' */ + + /* Gain: '/Gain1' incorporates: + * Inport: '/User_Pos [deg]' + */ + Torque_Meas = 0.017453292519943295 * Control_System_U.User_Posdeg; + + /* Gain: '/rpm to rad//s' incorporates: + * Inport: '/User_Vel [rpm]' + */ + Vel_Meas = 0.10471975511965977 * Control_System_U.User_Velrpm; + + /* MATLAB Function: '/User Input Function' incorporates: + * Inport: '/User_ControlMode' + * Inport: '/User_Torque [Nm]' + */ + Pos_Meas = Control_System_U.User_TorqueNm; + Control_System_B.ausgabe[0] = 0.0; + Control_System_B.ausgabe[1] = 0.0; + Control_System_B.ausgabe[2] = 0.0; + if (Torque_Meas > 3.3107963267948968) { + Torque_Meas = 3.3107963267948968; + } else { + if (Torque_Meas < -0.16920367320510343) { + Torque_Meas = -0.16920367320510343; + } + } + + if (Vel_Meas > 2.304) { + Vel_Meas = 2.304; + } else { + if (Vel_Meas < -2.304) { + Vel_Meas = -2.304; + } + } + + if (Control_System_U.User_TorqueNm > 0.7) { + Pos_Meas = 0.7; + } else { + if (Control_System_U.User_TorqueNm < -0.7) { + Pos_Meas = -0.7; + } + } + + if (Control_System_U.User_ControlMode == 1.0) { + Control_System_B.ausgabe[2] = Torque_Meas; + } else if (Control_System_U.User_ControlMode == 2.0) { + Control_System_B.ausgabe[1] = Vel_Meas; + } else { + if (Control_System_U.User_ControlMode == 3.0) { + Control_System_B.ausgabe[0] = Pos_Meas; + } + } + + /* End of MATLAB Function: '/User Input Function' */ + if (rtmIsMajorTimeStep(Control_System_M)) { + /* Delay: '/Delay' */ + Control_System_B.Delay = Control_System_DW.Delay_DSTATE; + } + + /* MATLAB Function: '/EnableMotor' incorporates: + * Inport: '/pos_meas_rad' + * Inport: '/vel_meas_rads' + */ + Torque_Meas = 0.7; + Vel_Meas = -0.7; + Control_System_B.enableMotor = (Control_System_B.Delay >= 1.0); + if ((Control_System_U.pos_meas_rad > 3.3107963267948968) || + (Control_System_U.pos_meas_rad < -0.16920367320510343)) { + Control_System_B.enableMotor = 0.0; + } else if ((Control_System_U.pos_meas_rad < 3.136263401595464) && + (Control_System_U.vel_meas_rads > 2.304)) { + Torque_Meas = 0.7 - (Control_System_U.vel_meas_rads - 2.304); + } else if ((Control_System_U.pos_meas_rad > 0.0053292519943295147) && + (Control_System_U.vel_meas_rads < -2.304)) { + Vel_Meas = (-2.304 - Control_System_U.vel_meas_rads) + -0.7; + } else if ((Control_System_U.pos_meas_rad > 3.136263401595464) && + (Control_System_U.vel_meas_rads < 1.152)) { + Torque_Meas = (3.3107963267948968 - Control_System_U.pos_meas_rad) * 0.7 / + 0.17453292519943295; + } else if ((Control_System_U.pos_meas_rad > 3.136263401595464) && + (Control_System_U.vel_meas_rads > 1.152)) { + Torque_Meas = (3.3107963267948968 - Control_System_U.pos_meas_rad) * -0.7 / + 0.17453292519943295; + } else if ((Control_System_U.pos_meas_rad < 0.0053292519943295147) && + (Control_System_U.vel_meas_rads > -1.152)) { + Vel_Meas = (Control_System_U.pos_meas_rad - -0.16920367320510343) * -0.7 / + 0.17453292519943295; + } else { + if ((Control_System_U.pos_meas_rad < 0.0053292519943295147) && + (Control_System_U.vel_meas_rads < -1.152)) { + Vel_Meas = (Control_System_U.pos_meas_rad - -0.16920367320510343) * 0.7 / + 0.17453292519943295; + } + } + + /* End of MATLAB Function: '/EnableMotor' */ + if (rtmIsMajorTimeStep(Control_System_M)) { + /* SignalConversion: '/HiddenBuf_InsertedFor_Subsystem_at_inport_7' */ + Control_System_B.HiddenBuf_InsertedFor_Subsystem = + Control_System_B.enableMotor; + + /* Outputs for Enabled SubSystem: '/Subsystem' incorporates: + * EnablePort: '/Enable' + */ + if (rtmIsMajorTimeStep(Control_System_M)) { + if (Control_System_B.HiddenBuf_InsertedFor_Subsystem > 0.0) { + if (!Control_System_DW.Subsystem_MODE) { + Control_System_DW.Subsystem_MODE = true; + } + } else { + if (Control_System_DW.Subsystem_MODE) { + /* Disable for ModelReference: '/Position Ctr' */ + PositionControl_Disable + (&(Control_System_DW.PositionCtr_InstanceData.rtdw)); + + /* Disable for ModelReference: '/Velocity Ctr (Cascaded)' */ + VelocityControl_Disable + (&(Control_System_DW.VelocityCtrCascaded_InstanceDat.rtdw)); + + /* Disable for ModelReference: '/Velocity Ctr' */ + VelocityControl_Disable + (&(Control_System_DW.VelocityCtr_InstanceData.rtdw)); + Control_System_DW.Subsystem_MODE = false; + } + } + } + + /* End of Outputs for SubSystem: '/Subsystem' */ + } + + /* Outputs for Enabled SubSystem: '/Subsystem' incorporates: + * EnablePort: '/Enable' + */ + if (Control_System_DW.Subsystem_MODE) { + /* RelationalOperator: '/Compare' incorporates: + * Constant: '/Constant' + * Inport: '/User_ControlMode' + */ + Control_System_B.Compare = (uint8_T)(Control_System_U.User_ControlMode == + 1.0); + + /* ModelReference: '/Position Ctr' */ + PositionControl(&(Control_System_DW.PositionCtr_InstanceData.rtm), + &Control_System_B.ausgabe[2], &Control_System_B.ausgabe_g[2], + &Control_System_B.Compare, &Control_System_B.PositionCtr, + &(Control_System_DW.PositionCtr_InstanceData.rtb), + &(Control_System_DW.PositionCtr_InstanceData.rtdw), + &(Control_System_X.PositionCtr_CSTATE)); + + /* ModelReference: '/Velocity Ctr (Cascaded)' */ + VelocityControl(&(Control_System_DW.VelocityCtrCascaded_InstanceDat.rtm), + &Control_System_B.PositionCtr, &Control_System_B.ausgabe_g[1], + &Control_System_B.Compare, + &Control_System_B.VelocityCtrCascaded, + &(Control_System_DW.VelocityCtrCascaded_InstanceDat.rtb), + &(Control_System_DW.VelocityCtrCascaded_InstanceDat.rtdw), + &(Control_System_X.VelocityCtrCascaded_CSTATE)); + + /* RelationalOperator: '/Compare' incorporates: + * Constant: '/Constant' + * Inport: '/User_ControlMode' + */ + Control_System_B.Compare_g = (uint8_T)(Control_System_U.User_ControlMode == + 2.0); + + /* ModelReference: '/Velocity Ctr' */ + VelocityControl(&(Control_System_DW.VelocityCtr_InstanceData.rtm), + &Control_System_B.ausgabe[1], &Control_System_B.ausgabe_g[1], + &Control_System_B.Compare_g, &Control_System_B.VelocityCtr, + &(Control_System_DW.VelocityCtr_InstanceData.rtb), + &(Control_System_DW.VelocityCtr_InstanceData.rtdw), + &(Control_System_X.VelocityCtr_CSTATE)); + + /* MultiPortSwitch: '/Multiport Switch' incorporates: + * Inport: '/User_ControlMode' + */ + switch ((int32_T)Control_System_U.User_ControlMode) { + case 1: + Control_System_B.MultiportSwitch = Control_System_B.VelocityCtrCascaded; + break; + + case 2: + Control_System_B.MultiportSwitch = Control_System_B.VelocityCtr; + break; + + default: + Control_System_B.MultiportSwitch = Control_System_B.ausgabe[0]; + break; + } + + /* End of MultiPortSwitch: '/Multiport Switch' */ + } + + /* End of Outputs for SubSystem: '/Subsystem' */ + + /* MATLAB Function: '/Torque Limitation' */ + if (Control_System_B.enableMotor == 0.0) { + Torque_Meas = 0.0; + } else { + if (!(Control_System_B.MultiportSwitch > Torque_Meas)) { + if (Control_System_B.MultiportSwitch < Vel_Meas) { + Torque_Meas = Vel_Meas; + } else { + Torque_Meas = Control_System_B.MultiportSwitch; + } + } + } + + /* End of MATLAB Function: '/Torque Limitation' */ + + /* MATLABSystem: '/Moving Average' */ + if (Control_System_DW.obj.TunablePropsChanged) { + Control_System_DW.obj.TunablePropsChanged = false; + } + + if (Control_System_DW.obj.pStatistic->isInitialized != 1) { + Control_System_DW.obj.pStatistic->isSetupComplete = false; + Control_System_DW.obj.pStatistic->isInitialized = 1; + Control_System_DW.obj.pStatistic->pCumSum = 0.0; + Control_System_DW.obj.pStatistic->pCumRevIndex = 1.0; + Control_System_DW.obj.pStatistic->isSetupComplete = true; + Control_System_DW.obj.pStatistic->pCumSum = 0.0; + Control_System_DW.obj.pStatistic->pCumSumRev[0] = 0.0; + Control_System_DW.obj.pStatistic->pCumSumRev[0] = 0.0; + Control_System_DW.obj.pStatistic->pCumSumRev[1] = 0.0; + Control_System_DW.obj.pStatistic->pCumSumRev[1] = 0.0; + Control_System_DW.obj.pStatistic->pCumSumRev[2] = 0.0; + Control_System_DW.obj.pStatistic->pCumSumRev[2] = 0.0; + Control_System_DW.obj.pStatistic->pCumRevIndex = 1.0; + } + + Vel_Meas = Control_System_DW.obj.pStatistic->pCumRevIndex; + Pos_Meas = Control_System_DW.obj.pStatistic->pCumSum; + csumrev[0] = Control_System_DW.obj.pStatistic->pCumSumRev[0]; + csumrev[1] = Control_System_DW.obj.pStatistic->pCumSumRev[1]; + csumrev[2] = Control_System_DW.obj.pStatistic->pCumSumRev[2]; + Pos_Meas += Torque_Meas; + Torque_Ref_tmp = (int32_T)Vel_Meas - 1; + Torque_Ref = csumrev[Torque_Ref_tmp] + Pos_Meas; + csumrev[Torque_Ref_tmp] = Torque_Meas; + if (Vel_Meas != 3.0) { + Vel_Meas++; + } else { + Vel_Meas = 1.0; + Pos_Meas = 0.0; + csumrev[1] += csumrev[2]; + csumrev[0] += csumrev[1]; + } + + Control_System_DW.obj.pStatistic->pCumSum = Pos_Meas; + Control_System_DW.obj.pStatistic->pCumSumRev[0] = csumrev[0]; + Control_System_DW.obj.pStatistic->pCumSumRev[1] = csumrev[1]; + Control_System_DW.obj.pStatistic->pCumSumRev[2] = csumrev[2]; + Control_System_DW.obj.pStatistic->pCumRevIndex = Vel_Meas; + + /* Outport: '/Output_Torque' incorporates: + * MATLABSystem: '/Moving Average' + */ + Control_System_Y.Output_Torque = Torque_Ref / 4.0; + if (rtmIsMajorTimeStep(Control_System_M)) { + /* Delay: '/Delay1' */ + Control_System_B.Delay1 = Control_System_DW.Delay1_DSTATE; + } + + /* Sum: '/Add1' incorporates: + * Inport: '/Unlock_Motor' + * Sum: '/Add' + */ + Control_System_B.Add1 = (Control_System_U.Unlock_Motor - + Control_System_B.Delay1) + Control_System_B.enableMotor; + if (rtmIsMajorTimeStep(Control_System_M)) { + if (rtmIsMajorTimeStep(Control_System_M)) { + /* Update for Delay: '/Delay' */ + Control_System_DW.Delay_DSTATE = Control_System_B.Add1; + } + + /* Update for Enabled SubSystem: '/Subsystem' incorporates: + * EnablePort: '/Enable' + */ + if (Control_System_DW.Subsystem_MODE) { + /* Update for ModelReference: '/Position Ctr' */ + PositionControl_Update(&(Control_System_DW.PositionCtr_InstanceData.rtm), + &(Control_System_DW.PositionCtr_InstanceData.rtb), + &(Control_System_DW.PositionCtr_InstanceData.rtdw)); + + /* Update for ModelReference: '/Velocity Ctr (Cascaded)' */ + VelocityControl_Update + (&(Control_System_DW.VelocityCtrCascaded_InstanceDat.rtm), + &(Control_System_DW.VelocityCtrCascaded_InstanceDat.rtb), + &(Control_System_DW.VelocityCtrCascaded_InstanceDat.rtdw)); + + /* Update for ModelReference: '/Velocity Ctr' */ + VelocityControl_Update(&(Control_System_DW.VelocityCtr_InstanceData.rtm), + &(Control_System_DW.VelocityCtr_InstanceData.rtb), + &(Control_System_DW.VelocityCtr_InstanceData.rtdw)); + } + + /* End of Update for SubSystem: '/Subsystem' */ + if (rtmIsMajorTimeStep(Control_System_M)) { + /* Update for Delay: '/Delay1' incorporates: + * Inport: '/Unlock_Motor' + */ + Control_System_DW.Delay1_DSTATE = Control_System_U.Unlock_Motor; + } + } /* end MajorTimeStep */ + + if (rtmIsMajorTimeStep(Control_System_M)) { + rt_ertODEUpdateContinuousStates(&Control_System_M->solverInfo); + + /* Update absolute time for base rate */ + /* The "clockTick0" counts the number of times the code of this task has + * been executed. The absolute time is the multiplication of "clockTick0" + * and "Timing.stepSize0". Size of "clockTick0" ensures timer will not + * overflow during the application lifespan selected. + * Timer of this task consists of two 32 bit unsigned integers. + * The two integers represent the low bits Timing.clockTick0 and the high bits + * Timing.clockTickH0. When the low bit overflows to 0, the high bits increment. + */ + if (!(++Control_System_M->Timing.clockTick0)) { + ++Control_System_M->Timing.clockTickH0; + } + + Control_System_M->Timing.t[0] = rtsiGetSolverStopTime + (&Control_System_M->solverInfo); + + { + /* Update absolute timer for sample time: [0.001s, 0.0s] */ + /* The "clockTick1" counts the number of times the code of this task has + * been executed. The resolution of this integer timer is 0.001, which is the step size + * of the task. Size of "clockTick1" ensures timer will not overflow during the + * application lifespan selected. + * Timer of this task consists of two 32 bit unsigned integers. + * The two integers represent the low bits Timing.clockTick1 and the high bits + * Timing.clockTickH1. When the low bit overflows to 0, the high bits increment. + */ + Control_System_M->Timing.clockTick1++; + if (!Control_System_M->Timing.clockTick1) { + Control_System_M->Timing.clockTickH1++; + } + } + } /* end MajorTimeStep */ +} + +/* Derivatives for root system: '' */ +void Control_System_derivatives(void) +{ + /* Derivatives for Enabled SubSystem: '/Subsystem' */ + if (Control_System_DW.Subsystem_MODE) { + /* Derivatives for ModelReference: '/Position Ctr' */ + PositionControl_Deriv(&(Control_System_DW.PositionCtr_InstanceData.rtb), + &(Control_System_DW.PositionCtr_InstanceData.rtdw), + &(((XDot_Control_System_T *) Control_System_M->derivs + )->PositionCtr_CSTATE)); + + /* Derivatives for ModelReference: '/Velocity Ctr (Cascaded)' */ + VelocityControl_Deriv + (&(Control_System_DW.VelocityCtrCascaded_InstanceDat.rtb), + &(Control_System_DW.VelocityCtrCascaded_InstanceDat.rtdw), + &(((XDot_Control_System_T *) Control_System_M->derivs) + ->VelocityCtrCascaded_CSTATE)); + + /* Derivatives for ModelReference: '/Velocity Ctr' */ + VelocityControl_Deriv(&(Control_System_DW.VelocityCtr_InstanceData.rtb), + &(Control_System_DW.VelocityCtr_InstanceData.rtdw), + &(((XDot_Control_System_T *) Control_System_M->derivs + )->VelocityCtr_CSTATE)); + } else { + { + real_T *dx; + int_T i; + dx = (real_T *) &(((XDot_Control_System_T *) Control_System_M->derivs) + ->PositionCtr_CSTATE); + for (i=0; i < 5; i++) { + dx[i] = 0.0; + } + } + } + + /* End of Derivatives for SubSystem: '/Subsystem' */ +} + +/* Model initialize function */ +void Control_System_initialize(void) +{ + /* Registration code */ + + /* initialize real-time model */ + (void) memset((void *)Control_System_M, 0, + sizeof(RT_MODEL_Control_System_T)); + + { + /* Setup solver object */ + rtsiSetSimTimeStepPtr(&Control_System_M->solverInfo, + &Control_System_M->Timing.simTimeStep); + rtsiSetTPtr(&Control_System_M->solverInfo, &rtmGetTPtr(Control_System_M)); + rtsiSetStepSizePtr(&Control_System_M->solverInfo, + &Control_System_M->Timing.stepSize0); + rtsiSetdXPtr(&Control_System_M->solverInfo, &Control_System_M->derivs); + rtsiSetContStatesPtr(&Control_System_M->solverInfo, (real_T **) + &Control_System_M->contStates); + rtsiSetNumContStatesPtr(&Control_System_M->solverInfo, + &Control_System_M->Sizes.numContStates); + rtsiSetNumPeriodicContStatesPtr(&Control_System_M->solverInfo, + &Control_System_M->Sizes.numPeriodicContStates); + rtsiSetPeriodicContStateIndicesPtr(&Control_System_M->solverInfo, + &Control_System_M->periodicContStateIndices); + rtsiSetPeriodicContStateRangesPtr(&Control_System_M->solverInfo, + &Control_System_M->periodicContStateRanges); + rtsiSetErrorStatusPtr(&Control_System_M->solverInfo, (&rtmGetErrorStatus + (Control_System_M))); + rtsiSetRTModelPtr(&Control_System_M->solverInfo, Control_System_M); + } + + rtsiSetSimTimeStep(&Control_System_M->solverInfo, MAJOR_TIME_STEP); + Control_System_M->intgData.y = Control_System_M->odeY; + Control_System_M->intgData.f[0] = Control_System_M->odeF[0]; + Control_System_M->intgData.f[1] = Control_System_M->odeF[1]; + Control_System_M->intgData.f[2] = Control_System_M->odeF[2]; + Control_System_M->contStates = ((X_Control_System_T *) &Control_System_X); + rtsiSetSolverData(&Control_System_M->solverInfo, (void *) + &Control_System_M->intgData); + rtsiSetSolverName(&Control_System_M->solverInfo,"ode3"); + rtmSetTPtr(Control_System_M, &Control_System_M->Timing.tArray[0]); + Control_System_M->Timing.stepSize0 = 0.001; + + /* block I/O */ + (void) memset(((void *) &Control_System_B), 0, + sizeof(B_Control_System_T)); + + /* states (continuous) */ + { + (void) memset((void *)&Control_System_X, 0, + sizeof(X_Control_System_T)); + } + + /* states (dwork) */ + (void) memset((void *)&Control_System_DW, 0, + sizeof(DW_Control_System_T)); + + /* external inputs */ + (void)memset(&Control_System_U, 0, sizeof(ExtU_Control_System_T)); + + /* external outputs */ + Control_System_Y.Output_Torque = 0.0; + + /* Model Initialize function for ModelReference Block: '/Position Ctr' */ + PositionControl_initialize(rtmGetErrorStatusPointer(Control_System_M), + rtmGetStopRequestedPtr(Control_System_M), &(Control_System_M->solverInfo), + &(Control_System_DW.PositionCtr_InstanceData.rtm), + &(Control_System_DW.PositionCtr_InstanceData.rtb), + &(Control_System_DW.PositionCtr_InstanceData.rtdw)); + + /* Model Initialize function for ModelReference Block: '/Velocity Ctr' */ + VelocityControl_initialize(rtmGetErrorStatusPointer(Control_System_M), + rtmGetStopRequestedPtr(Control_System_M), &(Control_System_M->solverInfo), + &(Control_System_DW.VelocityCtr_InstanceData.rtm), + &(Control_System_DW.VelocityCtr_InstanceData.rtb), + &(Control_System_DW.VelocityCtr_InstanceData.rtdw)); + + /* Model Initialize function for ModelReference Block: '/Velocity Ctr (Cascaded)' */ + VelocityControl_initialize(rtmGetErrorStatusPointer(Control_System_M), + rtmGetStopRequestedPtr(Control_System_M), &(Control_System_M->solverInfo), + &(Control_System_DW.VelocityCtrCascaded_InstanceDat.rtm), + &(Control_System_DW.VelocityCtrCascaded_InstanceDat.rtb), + &(Control_System_DW.VelocityCtrCascaded_InstanceDat.rtdw)); + + /* Start for MATLABSystem: '/Moving Average' */ + Control_System_DW.obj.matlabCodegenIsDeleted = true; + Control_System_DW.obj.isInitialized = 0; + Control_System_DW.obj.NumChannels = -1; + Control_System_DW.obj.matlabCodegenIsDeleted = false; + Control_System_DW.objisempty = true; + Control_System_DW.obj.isSetupComplete = false; + Control_System_DW.obj.isInitialized = 1; + Control_System_DW.obj.NumChannels = 1; + Control_System_DW.gobj_0.isInitialized = 0; + Control_System_DW.obj.pStatistic = &Control_System_DW.gobj_0; + Control_System_DW.obj.isSetupComplete = true; + Control_System_DW.obj.TunablePropsChanged = false; + + /* InitializeConditions for Delay: '/Delay' */ + Control_System_DW.Delay_DSTATE = 0.0; + + /* InitializeConditions for Delay: '/Delay1' */ + Control_System_DW.Delay1_DSTATE = 0.0; + + /* SystemInitialize for Enabled SubSystem: '/Subsystem' */ + /* SystemInitialize for ModelReference: '/Position Ctr' */ + PositionControl_Init(&Control_System_B.PositionCtr, + &(Control_System_DW.PositionCtr_InstanceData.rtdw), + &(Control_System_X.PositionCtr_CSTATE)); + + /* SystemInitialize for ModelReference: '/Velocity Ctr (Cascaded)' */ + VelocityControl_Init(&Control_System_B.VelocityCtrCascaded, + &(Control_System_DW.VelocityCtrCascaded_InstanceDat.rtdw), + &(Control_System_X.VelocityCtrCascaded_CSTATE)); + + /* SystemInitialize for ModelReference: '/Velocity Ctr' */ + VelocityControl_Init(&Control_System_B.VelocityCtr, + &(Control_System_DW.VelocityCtr_InstanceData.rtdw), + &(Control_System_X.VelocityCtr_CSTATE)); + + /* SystemInitialize for Outport: '/u' */ + Control_System_B.MultiportSwitch = 0.0; + + /* End of SystemInitialize for SubSystem: '/Subsystem' */ + + /* InitializeConditions for MATLABSystem: '/Moving Average' */ + if (Control_System_DW.obj.pStatistic->isInitialized == 1) { + Control_System_DW.obj.pStatistic->pCumSum = 0.0; + Control_System_DW.obj.pStatistic->pCumSumRev[0] = 0.0; + Control_System_DW.obj.pStatistic->pCumSumRev[1] = 0.0; + Control_System_DW.obj.pStatistic->pCumSumRev[2] = 0.0; + Control_System_DW.obj.pStatistic->pCumRevIndex = 1.0; + } + + /* End of InitializeConditions for MATLABSystem: '/Moving Average' */ +} + +/* Model terminate function */ +void Control_System_terminate(void) +{ + /* Terminate for MATLABSystem: '/Moving Average' */ + matlabCodegenHandle_matlabCodeg(&Control_System_DW.obj); +} diff --git a/Examples/epos_matlab/src/simulinkcode/controller/Control_System.h b/Examples/epos_matlab/src/simulinkcode/controller/Control_System.h new file mode 100644 index 0000000..85a5ae3 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/controller/Control_System.h @@ -0,0 +1,342 @@ +/* + * Control_System.h + * + * Academic License - for use in teaching, academic research, and meeting + * course requirements at degree granting institutions only. Not for + * government, commercial, or other organizational use. + * + * Code generation for model "Control_System". + * + * Model version : 1.119 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Tue Jun 28 17:20:04 2022 + * + * Target selection: grt.tlc + * Note: GRT includes extra infrastructure and instrumentation for prototyping + * Embedded hardware selection: ARM Compatible->ARM Cortex + * Code generation objective: Execution efficiency + * Validation result: Not run + */ + +#ifndef RTW_HEADER_Control_System_h_ +#define RTW_HEADER_Control_System_h_ +#include +#ifndef Control_System_COMMON_INCLUDES_ +# define Control_System_COMMON_INCLUDES_ +#include "rtwtypes.h" +#include "rtw_continuous.h" +#include "rtw_solver.h" +#endif /* Control_System_COMMON_INCLUDES_ */ + +#include "Control_System_types.h" + +/* Shared type includes */ +#include "multiword_types.h" + +/* Child system includes */ +#include "VelocityControl.h" +#include "PositionControl.h" + +/* Macros for accessing real-time model data structure */ +#ifndef rtmGetContStateDisabled +# define rtmGetContStateDisabled(rtm) ((rtm)->contStateDisabled) +#endif + +#ifndef rtmSetContStateDisabled +# define rtmSetContStateDisabled(rtm, val) ((rtm)->contStateDisabled = (val)) +#endif + +#ifndef rtmGetContStates +# define rtmGetContStates(rtm) ((rtm)->contStates) +#endif + +#ifndef rtmSetContStates +# define rtmSetContStates(rtm, val) ((rtm)->contStates = (val)) +#endif + +#ifndef rtmGetContTimeOutputInconsistentWithStateAtMajorStepFlag +# define rtmGetContTimeOutputInconsistentWithStateAtMajorStepFlag(rtm) ((rtm)->CTOutputIncnstWithState) +#endif + +#ifndef rtmSetContTimeOutputInconsistentWithStateAtMajorStepFlag +# define rtmSetContTimeOutputInconsistentWithStateAtMajorStepFlag(rtm, val) ((rtm)->CTOutputIncnstWithState = (val)) +#endif + +#ifndef rtmGetDerivCacheNeedsReset +# define rtmGetDerivCacheNeedsReset(rtm) ((rtm)->derivCacheNeedsReset) +#endif + +#ifndef rtmSetDerivCacheNeedsReset +# define rtmSetDerivCacheNeedsReset(rtm, val) ((rtm)->derivCacheNeedsReset = (val)) +#endif + +#ifndef rtmGetIntgData +# define rtmGetIntgData(rtm) ((rtm)->intgData) +#endif + +#ifndef rtmSetIntgData +# define rtmSetIntgData(rtm, val) ((rtm)->intgData = (val)) +#endif + +#ifndef rtmGetOdeF +# define rtmGetOdeF(rtm) ((rtm)->odeF) +#endif + +#ifndef rtmSetOdeF +# define rtmSetOdeF(rtm, val) ((rtm)->odeF = (val)) +#endif + +#ifndef rtmGetOdeY +# define rtmGetOdeY(rtm) ((rtm)->odeY) +#endif + +#ifndef rtmSetOdeY +# define rtmSetOdeY(rtm, val) ((rtm)->odeY = (val)) +#endif + +#ifndef rtmGetPeriodicContStateIndices +# define rtmGetPeriodicContStateIndices(rtm) ((rtm)->periodicContStateIndices) +#endif + +#ifndef rtmSetPeriodicContStateIndices +# define rtmSetPeriodicContStateIndices(rtm, val) ((rtm)->periodicContStateIndices = (val)) +#endif + +#ifndef rtmGetPeriodicContStateRanges +# define rtmGetPeriodicContStateRanges(rtm) ((rtm)->periodicContStateRanges) +#endif + +#ifndef rtmSetPeriodicContStateRanges +# define rtmSetPeriodicContStateRanges(rtm, val) ((rtm)->periodicContStateRanges = (val)) +#endif + +#ifndef rtmGetZCCacheNeedsReset +# define rtmGetZCCacheNeedsReset(rtm) ((rtm)->zCCacheNeedsReset) +#endif + +#ifndef rtmSetZCCacheNeedsReset +# define rtmSetZCCacheNeedsReset(rtm, val) ((rtm)->zCCacheNeedsReset = (val)) +#endif + +#ifndef rtmGetdX +# define rtmGetdX(rtm) ((rtm)->derivs) +#endif + +#ifndef rtmSetdX +# define rtmSetdX(rtm, val) ((rtm)->derivs = (val)) +#endif + +#ifndef rtmGetErrorStatus +# define rtmGetErrorStatus(rtm) ((rtm)->errorStatus) +#endif + +#ifndef rtmSetErrorStatus +# define rtmSetErrorStatus(rtm, val) ((rtm)->errorStatus = (val)) +#endif + +#ifndef rtmGetErrorStatusPointer +# define rtmGetErrorStatusPointer(rtm) ((const char_T **)(&((rtm)->errorStatus))) +#endif + +#ifndef rtmGetStopRequested +# define rtmGetStopRequested(rtm) ((rtm)->Timing.stopRequestedFlag) +#endif + +#ifndef rtmSetStopRequested +# define rtmSetStopRequested(rtm, val) ((rtm)->Timing.stopRequestedFlag = (val)) +#endif + +#ifndef rtmGetStopRequestedPtr +# define rtmGetStopRequestedPtr(rtm) (&((rtm)->Timing.stopRequestedFlag)) +#endif + +#ifndef rtmGetT +# define rtmGetT(rtm) (rtmGetTPtr((rtm))[0]) +#endif + +#ifndef rtmGetTPtr +# define rtmGetTPtr(rtm) ((rtm)->Timing.t) +#endif + +/* Block signals (default storage) */ +typedef struct { + real_T Delay; /* '/Delay' */ + real_T HiddenBuf_InsertedFor_Subsystem;/* '/EnableMotor' */ + real_T Delay1; /* '/Delay1' */ + real_T Add1; /* '/Add1' */ + real_T ausgabe[3]; /* '/User Input Function' */ + real_T PositionCtr; /* '/Position Ctr' */ + real_T VelocityCtrCascaded; /* '/Velocity Ctr (Cascaded)' */ + real_T VelocityCtr; /* '/Velocity Ctr' */ + real_T MultiportSwitch; /* '/Multiport Switch' */ + real_T ausgabe_g[3]; /* '/Measurement Function' */ + real_T enableMotor; /* '/EnableMotor' */ + uint8_T Compare; /* '/Compare' */ + uint8_T Compare_g; /* '/Compare' */ +} B_Control_System_T; + +/* Block states (default storage) for system '' */ +typedef struct { + dsp_simulink_MovingAverage_Co_T obj; /* '/Moving Average' */ + dsp_private_SlidingWindowAver_T gobj_0;/* '/Moving Average' */ + dsp_private_SlidingWindowAver_T gobj_1;/* '/Moving Average' */ + real_T Delay_DSTATE; /* '/Delay' */ + real_T Delay1_DSTATE; /* '/Delay1' */ + boolean_T objisempty; /* '/Moving Average' */ + boolean_T Subsystem_MODE; /* '/Subsystem' */ + MdlrefDW_PositionControl_T PositionCtr_InstanceData;/* '/Position Ctr' */ + MdlrefDW_VelocityControl_T VelocityCtrCascaded_InstanceDat;/* '/Velocity Ctr (Cascaded)' */ + MdlrefDW_VelocityControl_T VelocityCtr_InstanceData;/* '/Velocity Ctr' */ +} DW_Control_System_T; + +/* Continuous states (default storage) */ +typedef struct { + X_PositionControl_n_T PositionCtr_CSTATE;/* '/Position Ctr' */ + X_VelocityControl_n_T VelocityCtrCascaded_CSTATE;/* '/Velocity Ctr (Cascaded)' */ + X_VelocityControl_n_T VelocityCtr_CSTATE;/* '/Velocity Ctr' */ +} X_Control_System_T; + +/* State derivatives (default storage) */ +typedef struct { + XDot_PositionControl_n_T PositionCtr_CSTATE;/* '/Position Ctr' */ + XDot_VelocityControl_n_T VelocityCtrCascaded_CSTATE;/* '/Velocity Ctr (Cascaded)' */ + XDot_VelocityControl_n_T VelocityCtr_CSTATE;/* '/Velocity Ctr' */ +} XDot_Control_System_T; + +/* State disabled */ +typedef struct { + XDis_PositionControl_n_T PositionCtr_CSTATE;/* '/Position Ctr' */ + XDis_VelocityControl_n_T VelocityCtrCascaded_CSTATE;/* '/Velocity Ctr (Cascaded)' */ + XDis_VelocityControl_n_T VelocityCtr_CSTATE;/* '/Velocity Ctr' */ +} XDis_Control_System_T; + +#ifndef ODE3_INTG +#define ODE3_INTG + +/* ODE3 Integration Data */ +typedef struct { + real_T *y; /* output */ + real_T *f[3]; /* derivatives */ +} ODE3_IntgData; + +#endif + +/* External inputs (root inport signals with default storage) */ +typedef struct { + real_T Unlock_Motor; /* '/Unlock_Motor' */ + real_T User_ControlMode; /* '/User_ControlMode' */ + real_T User_Posdeg; /* '/User_Pos [deg]' */ + real_T User_Velrpm; /* '/User_Vel [rpm]' */ + real_T User_TorqueNm; /* '/User_Torque [Nm]' */ + real_T torque_meas_Nm; /* '/torque_meas_Nm' */ + real_T vel_meas_rads; /* '/vel_meas_rads' */ + real_T pos_meas_rad; /* '/pos_meas_rad' */ +} ExtU_Control_System_T; + +/* External outputs (root outports fed by signals with default storage) */ +typedef struct { + real_T Output_Torque; /* '/Output_Torque' */ +} ExtY_Control_System_T; + +/* Real-time Model Data Structure */ +struct tag_RTM_Control_System_T { + const char_T *errorStatus; + RTWSolverInfo solverInfo; + X_Control_System_T *contStates; + int_T *periodicContStateIndices; + real_T *periodicContStateRanges; + real_T *derivs; + boolean_T *contStateDisabled; + boolean_T zCCacheNeedsReset; + boolean_T derivCacheNeedsReset; + boolean_T CTOutputIncnstWithState; + real_T odeY[5]; + real_T odeF[3][5]; + ODE3_IntgData intgData; + + /* + * Sizes: + * The following substructure contains sizes information + * for many of the model attributes such as inputs, outputs, + * dwork, sample times, etc. + */ + struct { + int_T numContStates; + int_T numPeriodicContStates; + int_T numSampTimes; + } Sizes; + + /* + * Timing: + * The following substructure contains information regarding + * the timing information for the model. + */ + struct { + uint32_T clockTick0; + uint32_T clockTickH0; + time_T stepSize0; + uint32_T clockTick1; + uint32_T clockTickH1; + SimTimeStep simTimeStep; + boolean_T stopRequestedFlag; + time_T *t; + time_T tArray[2]; + } Timing; +}; + +/* Block signals (default storage) */ +extern B_Control_System_T Control_System_B; + +/* Continuous states (default storage) */ +extern X_Control_System_T Control_System_X; + +/* Block states (default storage) */ +extern DW_Control_System_T Control_System_DW; + +/* External inputs (root inport signals with default storage) */ +extern ExtU_Control_System_T Control_System_U; + +/* External outputs (root outports fed by signals with default storage) */ +extern ExtY_Control_System_T Control_System_Y; + +/* Model entry point functions */ +extern void Control_System_initialize(void); +extern void Control_System_step(void); +extern void Control_System_terminate(void); + +/* Real-time Model object */ +extern RT_MODEL_Control_System_T *const Control_System_M; + +/*- + * These blocks were eliminated from the model due to optimizations: + * + * Block '/Scope' : Unused code path elimination + * Block '/Scope' : Unused code path elimination + */ + +/*- + * The generated code includes comments that allow you to trace directly + * back to the appropriate location in the model. The basic format + * is /block_name, where system is the system number (uniquely + * assigned by Simulink) and block_name is the name of the block. + * + * Use the MATLAB hilite_system command to trace the generated code back + * to the model. For example, + * + * hilite_system('') - opens system 3 + * hilite_system('/Kp') - opens and selects block Kp which resides in S3 + * + * Here is the system hierarchy for this model + * + * '' : 'Control_System' + * '' : 'Control_System/Degrees to Radians' + * '' : 'Control_System/EnableMotor' + * '' : 'Control_System/Measurement Function' + * '' : 'Control_System/Subsystem' + * '' : 'Control_System/Subsystem1' + * '' : 'Control_System/Torque Limitation' + * '' : 'Control_System/User Input Function' + * '' : 'Control_System/Subsystem/Compare To Constant' + * '' : 'Control_System/Subsystem/Compare To Constant1' + */ +#endif /* RTW_HEADER_Control_System_h_ */ diff --git a/arduino/examples/subsystem/Subsystem_private.h b/Examples/epos_matlab/src/simulinkcode/controller/Control_System_private.h similarity index 62% rename from arduino/examples/subsystem/Subsystem_private.h rename to Examples/epos_matlab/src/simulinkcode/controller/Control_System_private.h index f57f9ce..c3e7634 100644 --- a/arduino/examples/subsystem/Subsystem_private.h +++ b/Examples/epos_matlab/src/simulinkcode/controller/Control_System_private.h @@ -1,25 +1,25 @@ /* - * Subsystem_private.h + * Control_System_private.h * * Academic License - for use in teaching, academic research, and meeting * course requirements at degree granting institutions only. Not for * government, commercial, or other organizational use. * - * Code generation for model "Subsystem". + * Code generation for model "Control_System". * - * Model version : 1.11 - * Simulink Coder version : 9.3 (R2020a) 18-Nov-2019 - * C source code generated on : Wed Mar 24 19:21:59 2021 + * Model version : 1.119 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Tue Jun 28 17:20:04 2022 * * Target selection: grt.tlc * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Atmel->AVR (8-bit) + * Embedded hardware selection: ARM Compatible->ARM Cortex * Code generation objective: Execution efficiency * Validation result: Not run */ -#ifndef RTW_HEADER_Subsystem_private_h_ -#define RTW_HEADER_Subsystem_private_h_ +#ifndef RTW_HEADER_Control_System_private_h_ +#define RTW_HEADER_Control_System_private_h_ #include "rtwtypes.h" #include "multiword_types.h" @@ -37,6 +37,6 @@ #endif /* private model entry point functions */ -extern void Subsystem_derivatives(void); +extern void Control_System_derivatives(void); -#endif /* RTW_HEADER_Subsystem_private_h_ */ +#endif /* RTW_HEADER_Control_System_private_h_ */ diff --git a/Examples/epos_matlab/src/simulinkcode/controller/Control_System_types.h b/Examples/epos_matlab/src/simulinkcode/controller/Control_System_types.h new file mode 100644 index 0000000..65d656c --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/controller/Control_System_types.h @@ -0,0 +1,65 @@ +/* + * Control_System_types.h + * + * Academic License - for use in teaching, academic research, and meeting + * course requirements at degree granting institutions only. Not for + * government, commercial, or other organizational use. + * + * Code generation for model "Control_System". + * + * Model version : 1.119 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Tue Jun 28 17:20:04 2022 + * + * Target selection: grt.tlc + * Note: GRT includes extra infrastructure and instrumentation for prototyping + * Embedded hardware selection: ARM Compatible->ARM Cortex + * Code generation objective: Execution efficiency + * Validation result: Not run + */ + +#ifndef RTW_HEADER_Control_System_types_h_ +#define RTW_HEADER_Control_System_types_h_ +#include "rtwtypes.h" +#include "multiword_types.h" +#ifndef typedef_dsp_private_SlidingWindowAver_T +#define typedef_dsp_private_SlidingWindowAver_T + +typedef struct { + int32_T isInitialized; + boolean_T isSetupComplete; + real_T pCumSum; + real_T pCumSumRev[3]; + real_T pCumRevIndex; +} dsp_private_SlidingWindowAver_T; + +#endif /*typedef_dsp_private_SlidingWindowAver_T*/ + +#ifndef typedef_cell_wrap_Control_System_T +#define typedef_cell_wrap_Control_System_T + +typedef struct { + uint32_T f1[8]; +} cell_wrap_Control_System_T; + +#endif /*typedef_cell_wrap_Control_System_T*/ + +#ifndef typedef_dsp_simulink_MovingAverage_Co_T +#define typedef_dsp_simulink_MovingAverage_Co_T + +typedef struct { + boolean_T matlabCodegenIsDeleted; + int32_T isInitialized; + boolean_T isSetupComplete; + boolean_T TunablePropsChanged; + cell_wrap_Control_System_T inputVarSize; + dsp_private_SlidingWindowAver_T *pStatistic; + int32_T NumChannels; +} dsp_simulink_MovingAverage_Co_T; + +#endif /*typedef_dsp_simulink_MovingAverage_Co_T*/ + +/* Forward declaration for rtModel */ +typedef struct tag_RTM_Control_System_T RT_MODEL_Control_System_T; + +#endif /* RTW_HEADER_Control_System_types_h_ */ diff --git a/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/PositionControl.c b/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/PositionControl.c new file mode 100644 index 0000000..0e1f860 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/PositionControl.c @@ -0,0 +1,240 @@ +/* + * Code generation for system model 'PositionControl' + * + * Model : PositionControl + * Model version : 1.70 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Tue Jun 28 17:43:40 2022 + * + * Note that the functions contained in this file are part of a Simulink + * model, and are not self-contained algorithms. + */ + +#include "PositionControl.h" +#include "PositionControl_private.h" + +/* System initialize for referenced model: 'PositionControl' */ +void PositionControl_Init(real_T *rty_dphi_refrads, DW_PositionControl_f_T + *localDW, X_PositionControl_n_T *localX) +{ + /* InitializeConditions for Integrator: '/Filter' */ + localX->Filter_CSTATE = 0.0; + + /* InitializeConditions for Integrator: '/Integrator' */ + localX->Integrator_CSTATE = 0.0; + + /* InitializeConditions for Integrator: '/Filter' */ + localX->Filter_CSTATE_f = 0.0; + + /* InitializeConditions for Memory: '/Memory' */ + localDW->Memory_PreviousInput = false; + + /* SystemInitialize for Outport: '/dphi_ref [rad//s]' */ + *rty_dphi_refrads = 0.0; +} + +/* System reset for referenced model: 'PositionControl' */ +void PositionControl_Reset(DW_PositionControl_f_T *localDW, + X_PositionControl_n_T *localX) +{ + /* InitializeConditions for Integrator: '/Filter' */ + localX->Filter_CSTATE = 0.0; + + /* InitializeConditions for Integrator: '/Integrator' */ + localX->Integrator_CSTATE = 0.0; + + /* InitializeConditions for Integrator: '/Filter' */ + localX->Filter_CSTATE_f = 0.0; + + /* InitializeConditions for Memory: '/Memory' */ + localDW->Memory_PreviousInput = false; +} + +/* Disable for referenced model: 'PositionControl' */ +void PositionControl_Disable(DW_PositionControl_f_T *localDW) +{ + if (localDW->TmpModelReferenceSubsystem_MODE) { + localDW->TmpModelReferenceSubsystem_MODE = false; + } +} + +/* Outputs for referenced model: 'PositionControl' */ +void PositionControl(RT_MODEL_PositionControl_T * const PositionControl_M, const + real_T *rtu_phi_refrad, const real_T *rtu_phirad, const + uint8_T *rtu_Enable, real_T *rty_dphi_refrads, + B_PositionControl_c_T *localB, DW_PositionControl_f_T + *localDW, X_PositionControl_n_T *localX) +{ + real_T rtb_Filter; + real_T rtb_ZeroGain; + boolean_T rtb_NotEqual; + if (rtmIsMajorTimeStep(PositionControl_M) && rtmIsMajorTimeStep + (PositionControl_M)) { + if (*rtu_Enable > 0) { + if (!localDW->TmpModelReferenceSubsystem_MODE) { + PositionControl_Reset(localDW, localX); + localDW->TmpModelReferenceSubsystem_MODE = true; + } + } else { + PositionControl_Disable(localDW); + } + } + + if (localDW->TmpModelReferenceSubsystem_MODE) { + /* Sum: '/Sum' */ + rtb_Filter = *rtu_phi_refrad - *rtu_phirad; + + /* Gain: '/Filter Coefficient' incorporates: + * Gain: '/Derivative Gain' + * Integrator: '/Filter' + * Sum: '/SumD' + */ + localB->FilterCoefficient = (0.117155864593637 * rtb_Filter - + localX->Filter_CSTATE) * 2.70289040596724; + + /* Sum: '/Sum' incorporates: + * Gain: '/Proportional Gain' + */ + rtb_Filter = 1.7740510896785 * rtb_Filter + localB->FilterCoefficient; + + /* Saturate: '/Saturation' */ + if (rtb_Filter > 2.304) { + *rty_dphi_refrads = 2.304; + } else if (rtb_Filter < -2.304) { + *rty_dphi_refrads = -2.304; + } else { + *rty_dphi_refrads = rtb_Filter; + } + + /* End of Saturate: '/Saturation' */ + + /* Gain: '/Filter Coefficient' incorporates: + * Integrator: '/Filter' + * Sum: '/SumD' + */ + localB->FilterCoefficient_a = (0.0 - localX->Filter_CSTATE_f) * + 266.160326879404; + + /* Sum: '/Sum' incorporates: + * Integrator: '/Integrator' + */ + rtb_Filter = localX->Integrator_CSTATE + localB->FilterCoefficient_a; + + /* Gain: '/ZeroGain' */ + rtb_ZeroGain = 0.0 * rtb_Filter; + + /* DeadZone: '/DeadZone' */ + if (rtb_Filter > 2.304) { + rtb_Filter -= 2.304; + } else if (rtb_Filter >= -2.304) { + rtb_Filter = 0.0; + } else { + rtb_Filter -= -2.304; + } + + /* End of DeadZone: '/DeadZone' */ + + /* RelationalOperator: '/NotEqual' */ + rtb_NotEqual = (rtb_ZeroGain != rtb_Filter); + + /* Signum: '/SignPreSat' */ + if (rtb_Filter < 0.0) { + rtb_Filter = -1.0; + } else if (rtb_Filter > 0.0) { + rtb_Filter = 1.0; + } else if (rtb_Filter == 0.0) { + rtb_Filter = 0.0; + } else { + rtb_Filter = (rtNaN); + } + + /* End of Signum: '/SignPreSat' */ + + /* Logic: '/AND3' incorporates: + * DataTypeConversion: '/DataTypeConv1' + * RelationalOperator: '/Equal1' + */ + localB->AND3 = (rtb_NotEqual && ((int8_T)rtb_Filter == 0)); + if (rtmIsMajorTimeStep(PositionControl_M)) { + /* Switch: '/Switch' incorporates: + * Constant: '/Constant1' + */ + localB->Switch = 0.0; + } + } +} + +/* Update for referenced model: 'PositionControl' */ +void PositionControl_Update(RT_MODEL_PositionControl_T * const PositionControl_M, + B_PositionControl_c_T *localB, DW_PositionControl_f_T *localDW) +{ + if (localDW->TmpModelReferenceSubsystem_MODE && rtmIsMajorTimeStep + (PositionControl_M)) { + /* Update for Memory: '/Memory' */ + localDW->Memory_PreviousInput = localB->AND3; + } +} + +/* Derivatives for referenced model: 'PositionControl' */ +void PositionControl_Deriv(B_PositionControl_c_T *localB, DW_PositionControl_f_T + *localDW, XDot_PositionControl_n_T *localXdot) +{ + if (localDW->TmpModelReferenceSubsystem_MODE) { + /* Derivatives for Integrator: '/Filter' */ + localXdot->Filter_CSTATE = localB->FilterCoefficient; + + /* Derivatives for Integrator: '/Integrator' */ + localXdot->Integrator_CSTATE = localB->Switch; + + /* Derivatives for Integrator: '/Filter' */ + localXdot->Filter_CSTATE_f = localB->FilterCoefficient_a; + } else { + { + real_T *dx; + int_T i; + dx = &(localXdot->Filter_CSTATE); + for (i=0; i < 3; i++) { + dx[i] = 0.0; + } + } + } +} + +/* Model initialize function */ +void PositionControl_initialize(const char_T **rt_errorStatus, boolean_T + *rt_stopRequested, RTWSolverInfo *rt_solverInfo, RT_MODEL_PositionControl_T * + const PositionControl_M, B_PositionControl_c_T *localB, DW_PositionControl_f_T + *localDW) +{ + /* Registration code */ + + /* initialize non-finites */ + rt_InitInfAndNaN(sizeof(real_T)); + + /* initialize real-time model */ + (void) memset((void *)PositionControl_M, 0, + sizeof(RT_MODEL_PositionControl_T)); + + /* initialize error status */ + rtmSetErrorStatusPointer(PositionControl_M, rt_errorStatus); + + /* initialize stop requested flag */ + rtmSetStopRequestedPtr(PositionControl_M, rt_stopRequested); + + /* initialize RTWSolverInfo */ + PositionControl_M->solverInfo = (rt_solverInfo); + + /* Set the Timing fields to the appropriate data in the RTWSolverInfo */ + rtmSetSimTimeStepPointer(PositionControl_M, rtsiGetSimTimeStepPtr + (PositionControl_M->solverInfo)); + PositionControl_M->Timing.stepSize0 = (rtsiGetStepSize + (PositionControl_M->solverInfo)); + + /* block I/O */ + (void) memset(((void *) localB), 0, + sizeof(B_PositionControl_c_T)); + + /* states (dwork) */ + (void) memset((void *)localDW, 0, + sizeof(DW_PositionControl_f_T)); +} diff --git a/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/PositionControl.h b/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/PositionControl.h new file mode 100644 index 0000000..f545bf0 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/PositionControl.h @@ -0,0 +1,319 @@ +/* + * Code generation for system model 'PositionControl' + * For more details, see corresponding source file PositionControl.c + * + */ + +#ifndef RTW_HEADER_PositionControl_h_ +#define RTW_HEADER_PositionControl_h_ +#include +#ifndef PositionControl_COMMON_INCLUDES_ +# define PositionControl_COMMON_INCLUDES_ +#include "rtwtypes.h" +#include "rtw_continuous.h" +#include "rtw_solver.h" +#endif /* PositionControl_COMMON_INCLUDES_ */ + +#include "PositionControl_types.h" + +/* Shared type includes */ +#include "multiword_types.h" +#include "rtGetNaN.h" +#include "rt_nonfinite.h" +#include "rtGetInf.h" + +/* Block signals for model 'PositionControl' */ +typedef struct { + real_T FilterCoefficient; /* '/Filter Coefficient' */ + real_T FilterCoefficient_a; /* '/Filter Coefficient' */ + real_T Switch; /* '/Switch' */ + boolean_T AND3; /* '/AND3' */ +} B_PositionControl_c_T; + +/* Block states (default storage) for model 'PositionControl' */ +typedef struct { + boolean_T Memory_PreviousInput; /* '/Memory' */ + boolean_T TmpModelReferenceSubsystem_MODE;/* synthesized block */ +} DW_PositionControl_f_T; + +/* Continuous states for model 'PositionControl' */ +typedef struct { + real_T Filter_CSTATE; /* '/Filter' */ + real_T Integrator_CSTATE; /* '/Integrator' */ + real_T Filter_CSTATE_f; /* '/Filter' */ +} X_PositionControl_n_T; + +/* State derivatives for model 'PositionControl' */ +typedef struct { + real_T Filter_CSTATE; /* '/Filter' */ + real_T Integrator_CSTATE; /* '/Integrator' */ + real_T Filter_CSTATE_f; /* '/Filter' */ +} XDot_PositionControl_n_T; + +/* State Disabled for model 'PositionControl' */ +typedef struct { + boolean_T Filter_CSTATE; /* '/Filter' */ + boolean_T Integrator_CSTATE; /* '/Integrator' */ + boolean_T Filter_CSTATE_f; /* '/Filter' */ +} XDis_PositionControl_n_T; + +/* Real-time Model Data Structure */ +struct tag_RTM_PositionControl_T { + const char_T **errorStatus; + RTWSolverInfo *solverInfo; + + /* + * Timing: + * The following substructure contains information regarding + * the timing information for the model. + */ + struct { + time_T stepSize0; + SimTimeStep *simTimeStep; + boolean_T *stopRequestedFlag; + } Timing; +}; + +typedef struct { + B_PositionControl_c_T rtb; + DW_PositionControl_f_T rtdw; + RT_MODEL_PositionControl_T rtm; +} MdlrefDW_PositionControl_T; + +/* Model reference registration function */ +extern void PositionControl_initialize(const char_T **rt_errorStatus, boolean_T * + rt_stopRequested, RTWSolverInfo *rt_solverInfo, RT_MODEL_PositionControl_T * + const PositionControl_M, B_PositionControl_c_T *localB, DW_PositionControl_f_T + *localDW); +extern void PositionControl_Init(real_T *rty_dphi_refrads, + DW_PositionControl_f_T *localDW, X_PositionControl_n_T *localX); +extern void PositionControl_Reset(DW_PositionControl_f_T *localDW, + X_PositionControl_n_T *localX); +extern void PositionControl_Deriv(B_PositionControl_c_T *localB, + DW_PositionControl_f_T *localDW, XDot_PositionControl_n_T *localXdot); +extern void PositionControl_Disable(DW_PositionControl_f_T *localDW); +extern void PositionControl_Update(RT_MODEL_PositionControl_T * const + PositionControl_M, B_PositionControl_c_T *localB, DW_PositionControl_f_T + *localDW); +extern void PositionControl(RT_MODEL_PositionControl_T * const PositionControl_M, + const real_T *rtu_phi_refrad, const real_T *rtu_phirad, const uint8_T + *rtu_Enable, real_T *rty_dphi_refrads, B_PositionControl_c_T *localB, + DW_PositionControl_f_T *localDW, X_PositionControl_n_T *localX); + +/*- + * These blocks were eliminated from the model due to optimizations: + * + * Block '/Saturation' : Unused code path elimination + */ + +/*- + * The generated code includes comments that allow you to trace directly + * back to the appropriate location in the model. The basic format + * is /block_name, where system is the system number (uniquely + * assigned by Simulink) and block_name is the name of the block. + * + * Use the MATLAB hilite_system command to trace the generated code back + * to the model. For example, + * + * hilite_system('') - opens system 3 + * hilite_system('/Kp') - opens and selects block Kp which resides in S3 + * + * Here is the system hierarchy for this model + * + * '' : 'PositionControl' + * '' : 'PositionControl/PID Controller' + * '' : 'PositionControl/PID Controller1' + * '' : 'PositionControl/PID Controller/Anti-windup' + * '' : 'PositionControl/PID Controller/D Gain' + * '' : 'PositionControl/PID Controller/Filter' + * '' : 'PositionControl/PID Controller/Filter ICs' + * '' : 'PositionControl/PID Controller/I Gain' + * '' : 'PositionControl/PID Controller/Ideal P Gain' + * '' : 'PositionControl/PID Controller/Ideal P Gain Fdbk' + * '' : 'PositionControl/PID Controller/Integrator' + * '' : 'PositionControl/PID Controller/Integrator ICs' + * '' : 'PositionControl/PID Controller/N Copy' + * '' : 'PositionControl/PID Controller/N Gain' + * '' : 'PositionControl/PID Controller/P Copy' + * '' : 'PositionControl/PID Controller/Parallel P Gain' + * '' : 'PositionControl/PID Controller/Reset Signal' + * '' : 'PositionControl/PID Controller/Saturation' + * '' : 'PositionControl/PID Controller/Saturation Fdbk' + * '' : 'PositionControl/PID Controller/Sum' + * '' : 'PositionControl/PID Controller/Sum Fdbk' + * '' : 'PositionControl/PID Controller/Tracking Mode' + * '' : 'PositionControl/PID Controller/Tracking Mode Sum' + * '' : 'PositionControl/PID Controller/postSat Signal' + * '' : 'PositionControl/PID Controller/preSat Signal' + * '' : 'PositionControl/PID Controller/Anti-windup/Back Calculation' + * '' : 'PositionControl/PID Controller/Anti-windup/Cont. Clamping Ideal' + * '' : 'PositionControl/PID Controller/Anti-windup/Cont. Clamping Parallel' + * '' : 'PositionControl/PID Controller/Anti-windup/Disabled' + * '' : 'PositionControl/PID Controller/Anti-windup/Disc. Clamping Ideal' + * '' : 'PositionControl/PID Controller/Anti-windup/Disc. Clamping Parallel' + * '' : 'PositionControl/PID Controller/Anti-windup/Passthrough' + * '' : 'PositionControl/PID Controller/D Gain/Disabled' + * '' : 'PositionControl/PID Controller/D Gain/External Parameters' + * '' : 'PositionControl/PID Controller/D Gain/Internal Parameters' + * '' : 'PositionControl/PID Controller/Filter/Cont. Filter' + * '' : 'PositionControl/PID Controller/Filter/Differentiator' + * '' : 'PositionControl/PID Controller/Filter/Disabled' + * '' : 'PositionControl/PID Controller/Filter/Disc. Backward Euler Filter' + * '' : 'PositionControl/PID Controller/Filter/Disc. Forward Euler Filter' + * '' : 'PositionControl/PID Controller/Filter/Disc. Trapezoidal Filter' + * '' : 'PositionControl/PID Controller/Filter ICs/Disabled' + * '' : 'PositionControl/PID Controller/Filter ICs/External IC' + * '' : 'PositionControl/PID Controller/Filter ICs/Internal IC - Differentiator' + * '' : 'PositionControl/PID Controller/Filter ICs/Internal IC - Filter' + * '' : 'PositionControl/PID Controller/I Gain/Disabled' + * '' : 'PositionControl/PID Controller/I Gain/External Parameters' + * '' : 'PositionControl/PID Controller/I Gain/Internal Parameters' + * '' : 'PositionControl/PID Controller/Ideal P Gain/External Parameters' + * '' : 'PositionControl/PID Controller/Ideal P Gain/Internal Parameters' + * '' : 'PositionControl/PID Controller/Ideal P Gain/Passthrough' + * '' : 'PositionControl/PID Controller/Ideal P Gain Fdbk/Disabled' + * '' : 'PositionControl/PID Controller/Ideal P Gain Fdbk/External Parameters' + * '' : 'PositionControl/PID Controller/Ideal P Gain Fdbk/Internal Parameters' + * '' : 'PositionControl/PID Controller/Ideal P Gain Fdbk/Passthrough' + * '' : 'PositionControl/PID Controller/Integrator/Continuous' + * '' : 'PositionControl/PID Controller/Integrator/Disabled' + * '' : 'PositionControl/PID Controller/Integrator/Discrete' + * '' : 'PositionControl/PID Controller/Integrator ICs/Disabled' + * '' : 'PositionControl/PID Controller/Integrator ICs/External IC' + * '' : 'PositionControl/PID Controller/Integrator ICs/Internal IC' + * '' : 'PositionControl/PID Controller/N Copy/Disabled' + * '' : 'PositionControl/PID Controller/N Copy/Disabled wSignal Specification' + * '' : 'PositionControl/PID Controller/N Copy/External Parameters' + * '' : 'PositionControl/PID Controller/N Copy/Internal Parameters' + * '' : 'PositionControl/PID Controller/N Gain/Disabled' + * '' : 'PositionControl/PID Controller/N Gain/External Parameters' + * '' : 'PositionControl/PID Controller/N Gain/Internal Parameters' + * '' : 'PositionControl/PID Controller/N Gain/Passthrough' + * '' : 'PositionControl/PID Controller/P Copy/Disabled' + * '' : 'PositionControl/PID Controller/P Copy/External Parameters Ideal' + * '' : 'PositionControl/PID Controller/P Copy/Internal Parameters Ideal' + * '' : 'PositionControl/PID Controller/Parallel P Gain/Disabled' + * '' : 'PositionControl/PID Controller/Parallel P Gain/External Parameters' + * '' : 'PositionControl/PID Controller/Parallel P Gain/Internal Parameters' + * '' : 'PositionControl/PID Controller/Parallel P Gain/Passthrough' + * '' : 'PositionControl/PID Controller/Reset Signal/Disabled' + * '' : 'PositionControl/PID Controller/Reset Signal/External Reset' + * '' : 'PositionControl/PID Controller/Saturation/Enabled' + * '' : 'PositionControl/PID Controller/Saturation/Passthrough' + * '' : 'PositionControl/PID Controller/Saturation Fdbk/Disabled' + * '' : 'PositionControl/PID Controller/Saturation Fdbk/Enabled' + * '' : 'PositionControl/PID Controller/Saturation Fdbk/Passthrough' + * '' : 'PositionControl/PID Controller/Sum/Passthrough_I' + * '' : 'PositionControl/PID Controller/Sum/Passthrough_P' + * '' : 'PositionControl/PID Controller/Sum/Sum_PD' + * '' : 'PositionControl/PID Controller/Sum/Sum_PI' + * '' : 'PositionControl/PID Controller/Sum/Sum_PID' + * '' : 'PositionControl/PID Controller/Sum Fdbk/Disabled' + * '' : 'PositionControl/PID Controller/Sum Fdbk/Enabled' + * '' : 'PositionControl/PID Controller/Sum Fdbk/Passthrough' + * '' : 'PositionControl/PID Controller/Tracking Mode/Disabled' + * '' : 'PositionControl/PID Controller/Tracking Mode/Enabled' + * '' : 'PositionControl/PID Controller/Tracking Mode Sum/Passthrough' + * '' : 'PositionControl/PID Controller/Tracking Mode Sum/Tracking Mode' + * '' : 'PositionControl/PID Controller/postSat Signal/Feedback_Path' + * '' : 'PositionControl/PID Controller/postSat Signal/Forward_Path' + * '' : 'PositionControl/PID Controller/preSat Signal/Feedback_Path' + * '' : 'PositionControl/PID Controller/preSat Signal/Forward_Path' + * '' : 'PositionControl/PID Controller1/Anti-windup' + * '' : 'PositionControl/PID Controller1/D Gain' + * '' : 'PositionControl/PID Controller1/Filter' + * '' : 'PositionControl/PID Controller1/Filter ICs' + * '' : 'PositionControl/PID Controller1/I Gain' + * '' : 'PositionControl/PID Controller1/Ideal P Gain' + * '' : 'PositionControl/PID Controller1/Ideal P Gain Fdbk' + * '' : 'PositionControl/PID Controller1/Integrator' + * '' : 'PositionControl/PID Controller1/Integrator ICs' + * '' : 'PositionControl/PID Controller1/N Copy' + * '' : 'PositionControl/PID Controller1/N Gain' + * '' : 'PositionControl/PID Controller1/P Copy' + * '' : 'PositionControl/PID Controller1/Parallel P Gain' + * '' : 'PositionControl/PID Controller1/Reset Signal' + * '' : 'PositionControl/PID Controller1/Saturation' + * '' : 'PositionControl/PID Controller1/Saturation Fdbk' + * '' : 'PositionControl/PID Controller1/Sum' + * '' : 'PositionControl/PID Controller1/Sum Fdbk' + * '' : 'PositionControl/PID Controller1/Tracking Mode' + * '' : 'PositionControl/PID Controller1/Tracking Mode Sum' + * '' : 'PositionControl/PID Controller1/postSat Signal' + * '' : 'PositionControl/PID Controller1/preSat Signal' + * '' : 'PositionControl/PID Controller1/Anti-windup/Back Calculation' + * '' : 'PositionControl/PID Controller1/Anti-windup/Cont. Clamping Ideal' + * '' : 'PositionControl/PID Controller1/Anti-windup/Cont. Clamping Parallel' + * '' : 'PositionControl/PID Controller1/Anti-windup/Disabled' + * '' : 'PositionControl/PID Controller1/Anti-windup/Disc. Clamping Ideal' + * '' : 'PositionControl/PID Controller1/Anti-windup/Disc. Clamping Parallel' + * '' : 'PositionControl/PID Controller1/Anti-windup/Passthrough' + * '' : 'PositionControl/PID Controller1/D Gain/Disabled' + * '' : 'PositionControl/PID Controller1/D Gain/External Parameters' + * '' : 'PositionControl/PID Controller1/D Gain/Internal Parameters' + * '' : 'PositionControl/PID Controller1/Filter/Cont. Filter' + * '' : 'PositionControl/PID Controller1/Filter/Differentiator' + * '' : 'PositionControl/PID Controller1/Filter/Disabled' + * '' : 'PositionControl/PID Controller1/Filter/Disc. Backward Euler Filter' + * '' : 'PositionControl/PID Controller1/Filter/Disc. Forward Euler Filter' + * '' : 'PositionControl/PID Controller1/Filter/Disc. Trapezoidal Filter' + * '' : 'PositionControl/PID Controller1/Filter ICs/Disabled' + * '' : 'PositionControl/PID Controller1/Filter ICs/External IC' + * '' : 'PositionControl/PID Controller1/Filter ICs/Internal IC - Differentiator' + * '' : 'PositionControl/PID Controller1/Filter ICs/Internal IC - Filter' + * '' : 'PositionControl/PID Controller1/I Gain/Disabled' + * '' : 'PositionControl/PID Controller1/I Gain/External Parameters' + * '' : 'PositionControl/PID Controller1/I Gain/Internal Parameters' + * '' : 'PositionControl/PID Controller1/Ideal P Gain/External Parameters' + * '' : 'PositionControl/PID Controller1/Ideal P Gain/Internal Parameters' + * '' : 'PositionControl/PID Controller1/Ideal P Gain/Passthrough' + * '' : 'PositionControl/PID Controller1/Ideal P Gain Fdbk/Disabled' + * '' : 'PositionControl/PID Controller1/Ideal P Gain Fdbk/External Parameters' + * '' : 'PositionControl/PID Controller1/Ideal P Gain Fdbk/Internal Parameters' + * '' : 'PositionControl/PID Controller1/Ideal P Gain Fdbk/Passthrough' + * '' : 'PositionControl/PID Controller1/Integrator/Continuous' + * '' : 'PositionControl/PID Controller1/Integrator/Disabled' + * '' : 'PositionControl/PID Controller1/Integrator/Discrete' + * '' : 'PositionControl/PID Controller1/Integrator ICs/Disabled' + * '' : 'PositionControl/PID Controller1/Integrator ICs/External IC' + * '' : 'PositionControl/PID Controller1/Integrator ICs/Internal IC' + * '' : 'PositionControl/PID Controller1/N Copy/Disabled' + * '' : 'PositionControl/PID Controller1/N Copy/Disabled wSignal Specification' + * '' : 'PositionControl/PID Controller1/N Copy/External Parameters' + * '' : 'PositionControl/PID Controller1/N Copy/Internal Parameters' + * '' : 'PositionControl/PID Controller1/N Gain/Disabled' + * '' : 'PositionControl/PID Controller1/N Gain/External Parameters' + * '' : 'PositionControl/PID Controller1/N Gain/Internal Parameters' + * '' : 'PositionControl/PID Controller1/N Gain/Passthrough' + * '' : 'PositionControl/PID Controller1/P Copy/Disabled' + * '' : 'PositionControl/PID Controller1/P Copy/External Parameters Ideal' + * '' : 'PositionControl/PID Controller1/P Copy/Internal Parameters Ideal' + * '' : 'PositionControl/PID Controller1/Parallel P Gain/Disabled' + * '' : 'PositionControl/PID Controller1/Parallel P Gain/External Parameters' + * '' : 'PositionControl/PID Controller1/Parallel P Gain/Internal Parameters' + * '' : 'PositionControl/PID Controller1/Parallel P Gain/Passthrough' + * '' : 'PositionControl/PID Controller1/Reset Signal/Disabled' + * '' : 'PositionControl/PID Controller1/Reset Signal/External Reset' + * '' : 'PositionControl/PID Controller1/Saturation/Enabled' + * '' : 'PositionControl/PID Controller1/Saturation/Passthrough' + * '' : 'PositionControl/PID Controller1/Saturation Fdbk/Disabled' + * '' : 'PositionControl/PID Controller1/Saturation Fdbk/Enabled' + * '' : 'PositionControl/PID Controller1/Saturation Fdbk/Passthrough' + * '' : 'PositionControl/PID Controller1/Sum/Passthrough_I' + * '' : 'PositionControl/PID Controller1/Sum/Passthrough_P' + * '' : 'PositionControl/PID Controller1/Sum/Sum_PD' + * '' : 'PositionControl/PID Controller1/Sum/Sum_PI' + * '' : 'PositionControl/PID Controller1/Sum/Sum_PID' + * '' : 'PositionControl/PID Controller1/Sum Fdbk/Disabled' + * '' : 'PositionControl/PID Controller1/Sum Fdbk/Enabled' + * '' : 'PositionControl/PID Controller1/Sum Fdbk/Passthrough' + * '' : 'PositionControl/PID Controller1/Tracking Mode/Disabled' + * '' : 'PositionControl/PID Controller1/Tracking Mode/Enabled' + * '' : 'PositionControl/PID Controller1/Tracking Mode Sum/Passthrough' + * '' : 'PositionControl/PID Controller1/Tracking Mode Sum/Tracking Mode' + * '' : 'PositionControl/PID Controller1/postSat Signal/Feedback_Path' + * '' : 'PositionControl/PID Controller1/postSat Signal/Forward_Path' + * '' : 'PositionControl/PID Controller1/preSat Signal/Feedback_Path' + * '' : 'PositionControl/PID Controller1/preSat Signal/Forward_Path' + */ +#endif /* RTW_HEADER_PositionControl_h_ */ diff --git a/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/PositionControl_private.h b/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/PositionControl_private.h new file mode 100644 index 0000000..91f0e29 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/PositionControl_private.h @@ -0,0 +1,79 @@ +/* + * PositionControl_private.h + * + * Academic License - for use in teaching, academic research, and meeting + * course requirements at degree granting institutions only. Not for + * government, commercial, or other organizational use. + * + * Code generation for model "PositionControl". + * + * Model version : 1.70 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Tue Jun 28 17:43:40 2022 + * + * Target selection: grt.tlc + * Note: GRT includes extra infrastructure and instrumentation for prototyping + * Embedded hardware selection: ARM Compatible->ARM Cortex + * Code generation objectives: Unspecified + * Validation result: Not run + */ + +#ifndef RTW_HEADER_PositionControl_private_h_ +#define RTW_HEADER_PositionControl_private_h_ +#include "rtwtypes.h" +#include "multiword_types.h" + +/* Private macros used by the generated code to access rtModel */ +#ifndef rtmIsMajorTimeStep +# define rtmIsMajorTimeStep(rtm) ((rtmGetSimTimeStep((rtm))) == MAJOR_TIME_STEP) +#endif + +#ifndef rtmIsMinorTimeStep +# define rtmIsMinorTimeStep(rtm) ((rtmGetSimTimeStep((rtm))) == MINOR_TIME_STEP) +#endif + +/* Macros for accessing real-time model data structure */ +#ifndef rtmGetErrorStatus +# define rtmGetErrorStatus(rtm) (*((rtm)->errorStatus)) +#endif + +#ifndef rtmSetErrorStatus +# define rtmSetErrorStatus(rtm, val) (*((rtm)->errorStatus) = (val)) +#endif + +#ifndef rtmGetErrorStatusPointer +# define rtmGetErrorStatusPointer(rtm) (rtm)->errorStatus +#endif + +#ifndef rtmSetErrorStatusPointer +# define rtmSetErrorStatusPointer(rtm, val) ((rtm)->errorStatus = (val)) +#endif + +#ifndef rtmGetSimTimeStep +# define rtmGetSimTimeStep(rtm) (*((rtm)->Timing.simTimeStep)) +#endif + +#ifndef rtmGetSimTimeStepPointer +# define rtmGetSimTimeStepPointer(rtm) (rtm)->Timing.simTimeStep +#endif + +#ifndef rtmSetSimTimeStepPointer +# define rtmSetSimTimeStepPointer(rtm, val) ((rtm)->Timing.simTimeStep = (val)) +#endif + +#ifndef rtmGetStopRequested +# define rtmGetStopRequested(rtm) (*((rtm)->Timing.stopRequestedFlag)) +#endif + +#ifndef rtmSetStopRequested +# define rtmSetStopRequested(rtm, val) (*((rtm)->Timing.stopRequestedFlag) = (val)) +#endif + +#ifndef rtmGetStopRequestedPtr +# define rtmGetStopRequestedPtr(rtm) ((rtm)->Timing.stopRequestedFlag) +#endif + +#ifndef rtmSetStopRequestedPtr +# define rtmSetStopRequestedPtr(rtm, val) ((rtm)->Timing.stopRequestedFlag = (val)) +#endif +#endif /* RTW_HEADER_PositionControl_private_h_ */ diff --git a/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/PositionControl_types.h b/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/PositionControl_types.h new file mode 100644 index 0000000..dbec1af --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/PositionControl_types.h @@ -0,0 +1,27 @@ +/* + * PositionControl_types.h + * + * Academic License - for use in teaching, academic research, and meeting + * course requirements at degree granting institutions only. Not for + * government, commercial, or other organizational use. + * + * Code generation for model "PositionControl". + * + * Model version : 1.70 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Tue Jun 28 17:43:40 2022 + * + * Target selection: grt.tlc + * Note: GRT includes extra infrastructure and instrumentation for prototyping + * Embedded hardware selection: ARM Compatible->ARM Cortex + * Code generation objectives: Unspecified + * Validation result: Not run + */ + +#ifndef RTW_HEADER_PositionControl_types_h_ +#define RTW_HEADER_PositionControl_types_h_ + +/* Forward declaration for rtModel */ +typedef struct tag_RTM_PositionControl_T RT_MODEL_PositionControl_T; + +#endif /* RTW_HEADER_PositionControl_types_h_ */ diff --git a/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/VelocityControl.c b/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/VelocityControl.c new file mode 100644 index 0000000..0930138 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/VelocityControl.c @@ -0,0 +1,224 @@ +/* + * Code generation for system model 'VelocityControl' + * + * Model : VelocityControl + * Model version : 1.74 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Tue Jun 28 17:43:44 2022 + * + * Note that the functions contained in this file are part of a Simulink + * model, and are not self-contained algorithms. + */ + +#include "VelocityControl.h" +#include "VelocityControl_private.h" + +/* System initialize for referenced model: 'VelocityControl' */ +void VelocityControl_Init(real_T *rty_tau_mNm, DW_VelocityControl_f_T *localDW, + X_VelocityControl_n_T *localX) +{ + /* InitializeConditions for Integrator: '/Integrator' */ + localX->Integrator_CSTATE = 0.0; + + /* InitializeConditions for Memory: '/Memory' */ + localDW->Memory_PreviousInput = false; + + /* SystemInitialize for Outport: '/tau_m [Nm]' */ + *rty_tau_mNm = 0.0; +} + +/* System reset for referenced model: 'VelocityControl' */ +void VelocityControl_Reset(DW_VelocityControl_f_T *localDW, + X_VelocityControl_n_T *localX) +{ + /* InitializeConditions for Integrator: '/Integrator' */ + localX->Integrator_CSTATE = 0.0; + + /* InitializeConditions for Memory: '/Memory' */ + localDW->Memory_PreviousInput = false; +} + +/* Disable for referenced model: 'VelocityControl' */ +void VelocityControl_Disable(DW_VelocityControl_f_T *localDW) +{ + if (localDW->TmpModelReferenceSubsystem_MODE) { + localDW->TmpModelReferenceSubsystem_MODE = false; + } +} + +/* Outputs for referenced model: 'VelocityControl' */ +void VelocityControl(RT_MODEL_VelocityControl_T * const VelocityControl_M, const + real_T *rtu_dphi_refrads, const real_T *rtu_dphirads, const + uint8_T *rtu_Enable, real_T *rty_tau_mNm, + B_VelocityControl_c_T *localB, DW_VelocityControl_f_T + *localDW, X_VelocityControl_n_T *localX) +{ + real_T rtb_IntegralGain; + real_T rtb_Sum; + real_T rtb_SignPreIntegrator; + boolean_T rtb_NotEqual; + real_T rtb_IntegralGain_0; + if (rtmIsMajorTimeStep(VelocityControl_M) && rtmIsMajorTimeStep + (VelocityControl_M)) { + if (*rtu_Enable > 0) { + if (!localDW->TmpModelReferenceSubsystem_MODE) { + VelocityControl_Reset(localDW, localX); + localDW->TmpModelReferenceSubsystem_MODE = true; + } + } else { + VelocityControl_Disable(localDW); + } + } + + if (localDW->TmpModelReferenceSubsystem_MODE) { + /* Sum: '/Sum' */ + rtb_IntegralGain = *rtu_dphi_refrads - *rtu_dphirads; + + /* Sum: '/Sum' incorporates: + * Gain: '/Proportional Gain' + * Integrator: '/Integrator' + */ + rtb_Sum = 0.382327477488715 * rtb_IntegralGain + localX->Integrator_CSTATE; + + /* DeadZone: '/DeadZone' */ + if (rtb_Sum > 0.7) { + rtb_SignPreIntegrator = rtb_Sum - 0.7; + } else if (rtb_Sum >= -0.7) { + rtb_SignPreIntegrator = 0.0; + } else { + rtb_SignPreIntegrator = rtb_Sum - -0.7; + } + + /* End of DeadZone: '/DeadZone' */ + + /* RelationalOperator: '/NotEqual' incorporates: + * Gain: '/ZeroGain' + */ + rtb_NotEqual = (0.0 * rtb_Sum != rtb_SignPreIntegrator); + + /* Signum: '/SignPreSat' */ + if (rtb_SignPreIntegrator < 0.0) { + rtb_SignPreIntegrator = -1.0; + } else if (rtb_SignPreIntegrator > 0.0) { + rtb_SignPreIntegrator = 1.0; + } else if (rtb_SignPreIntegrator == 0.0) { + rtb_SignPreIntegrator = 0.0; + } else { + rtb_SignPreIntegrator = (rtNaN); + } + + /* End of Signum: '/SignPreSat' */ + + /* Gain: '/Integral Gain' */ + rtb_IntegralGain *= 1.14452871958655; + + /* Signum: '/SignPreIntegrator' */ + if (rtb_IntegralGain < 0.0) { + rtb_IntegralGain_0 = -1.0; + } else if (rtb_IntegralGain > 0.0) { + rtb_IntegralGain_0 = 1.0; + } else if (rtb_IntegralGain == 0.0) { + rtb_IntegralGain_0 = 0.0; + } else { + rtb_IntegralGain_0 = (rtNaN); + } + + /* End of Signum: '/SignPreIntegrator' */ + + /* Logic: '/AND3' incorporates: + * DataTypeConversion: '/DataTypeConv1' + * DataTypeConversion: '/DataTypeConv2' + * RelationalOperator: '/Equal1' + */ + localB->AND3 = (rtb_NotEqual && ((int8_T)rtb_SignPreIntegrator == (int8_T) + rtb_IntegralGain_0)); + if (rtmIsMajorTimeStep(VelocityControl_M)) { + /* Memory: '/Memory' */ + localB->Memory = localDW->Memory_PreviousInput; + } + + /* Switch: '/Switch' incorporates: + * Constant: '/Constant1' + */ + if (localB->Memory) { + localB->Switch = 0.0; + } else { + localB->Switch = rtb_IntegralGain; + } + + /* End of Switch: '/Switch' */ + + /* Saturate: '/Saturation' */ + if (rtb_Sum > 0.7) { + *rty_tau_mNm = 0.7; + } else if (rtb_Sum < -0.7) { + *rty_tau_mNm = -0.7; + } else { + *rty_tau_mNm = rtb_Sum; + } + + /* End of Saturate: '/Saturation' */ + } +} + +/* Update for referenced model: 'VelocityControl' */ +void VelocityControl_Update(RT_MODEL_VelocityControl_T * const VelocityControl_M, + B_VelocityControl_c_T *localB, DW_VelocityControl_f_T *localDW) +{ + if (localDW->TmpModelReferenceSubsystem_MODE && rtmIsMajorTimeStep + (VelocityControl_M)) { + /* Update for Memory: '/Memory' */ + localDW->Memory_PreviousInput = localB->AND3; + } +} + +/* Derivatives for referenced model: 'VelocityControl' */ +void VelocityControl_Deriv(B_VelocityControl_c_T *localB, DW_VelocityControl_f_T + *localDW, XDot_VelocityControl_n_T *localXdot) +{ + if (localDW->TmpModelReferenceSubsystem_MODE) { + /* Derivatives for Integrator: '/Integrator' */ + localXdot->Integrator_CSTATE = localB->Switch; + } else { + localXdot->Integrator_CSTATE = 0.0; + } +} + +/* Model initialize function */ +void VelocityControl_initialize(const char_T **rt_errorStatus, boolean_T + *rt_stopRequested, RTWSolverInfo *rt_solverInfo, RT_MODEL_VelocityControl_T * + const VelocityControl_M, B_VelocityControl_c_T *localB, DW_VelocityControl_f_T + *localDW) +{ + /* Registration code */ + + /* initialize non-finites */ + rt_InitInfAndNaN(sizeof(real_T)); + + /* initialize real-time model */ + (void) memset((void *)VelocityControl_M, 0, + sizeof(RT_MODEL_VelocityControl_T)); + + /* initialize error status */ + rtmSetErrorStatusPointer(VelocityControl_M, rt_errorStatus); + + /* initialize stop requested flag */ + rtmSetStopRequestedPtr(VelocityControl_M, rt_stopRequested); + + /* initialize RTWSolverInfo */ + VelocityControl_M->solverInfo = (rt_solverInfo); + + /* Set the Timing fields to the appropriate data in the RTWSolverInfo */ + rtmSetSimTimeStepPointer(VelocityControl_M, rtsiGetSimTimeStepPtr + (VelocityControl_M->solverInfo)); + VelocityControl_M->Timing.stepSize0 = (rtsiGetStepSize + (VelocityControl_M->solverInfo)); + + /* block I/O */ + (void) memset(((void *) localB), 0, + sizeof(B_VelocityControl_c_T)); + + /* states (dwork) */ + (void) memset((void *)localDW, 0, + sizeof(DW_VelocityControl_f_T)); +} diff --git a/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/VelocityControl.h b/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/VelocityControl.h new file mode 100644 index 0000000..00b7f17 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/VelocityControl.h @@ -0,0 +1,209 @@ +/* + * Code generation for system model 'VelocityControl' + * For more details, see corresponding source file VelocityControl.c + * + */ + +#ifndef RTW_HEADER_VelocityControl_h_ +#define RTW_HEADER_VelocityControl_h_ +#include +#ifndef VelocityControl_COMMON_INCLUDES_ +# define VelocityControl_COMMON_INCLUDES_ +#include "rtwtypes.h" +#include "rtw_continuous.h" +#include "rtw_solver.h" +#endif /* VelocityControl_COMMON_INCLUDES_ */ + +#include "VelocityControl_types.h" + +/* Shared type includes */ +#include "multiword_types.h" +#include "rtGetNaN.h" +#include "rt_nonfinite.h" +#include "rtGetInf.h" + +/* Block signals for model 'VelocityControl' */ +typedef struct { + real_T Switch; /* '/Switch' */ + boolean_T AND3; /* '/AND3' */ + boolean_T Memory; /* '/Memory' */ +} B_VelocityControl_c_T; + +/* Block states (default storage) for model 'VelocityControl' */ +typedef struct { + boolean_T Memory_PreviousInput; /* '/Memory' */ + boolean_T TmpModelReferenceSubsystem_MODE;/* synthesized block */ +} DW_VelocityControl_f_T; + +/* Continuous states for model 'VelocityControl' */ +typedef struct { + real_T Integrator_CSTATE; /* '/Integrator' */ +} X_VelocityControl_n_T; + +/* State derivatives for model 'VelocityControl' */ +typedef struct { + real_T Integrator_CSTATE; /* '/Integrator' */ +} XDot_VelocityControl_n_T; + +/* State Disabled for model 'VelocityControl' */ +typedef struct { + boolean_T Integrator_CSTATE; /* '/Integrator' */ +} XDis_VelocityControl_n_T; + +/* Real-time Model Data Structure */ +struct tag_RTM_VelocityControl_T { + const char_T **errorStatus; + RTWSolverInfo *solverInfo; + + /* + * Timing: + * The following substructure contains information regarding + * the timing information for the model. + */ + struct { + time_T stepSize0; + SimTimeStep *simTimeStep; + boolean_T *stopRequestedFlag; + } Timing; +}; + +typedef struct { + B_VelocityControl_c_T rtb; + DW_VelocityControl_f_T rtdw; + RT_MODEL_VelocityControl_T rtm; +} MdlrefDW_VelocityControl_T; + +/* Model reference registration function */ +extern void VelocityControl_initialize(const char_T **rt_errorStatus, boolean_T * + rt_stopRequested, RTWSolverInfo *rt_solverInfo, RT_MODEL_VelocityControl_T * + const VelocityControl_M, B_VelocityControl_c_T *localB, DW_VelocityControl_f_T + *localDW); +extern void VelocityControl_Init(real_T *rty_tau_mNm, DW_VelocityControl_f_T + *localDW, X_VelocityControl_n_T *localX); +extern void VelocityControl_Reset(DW_VelocityControl_f_T *localDW, + X_VelocityControl_n_T *localX); +extern void VelocityControl_Deriv(B_VelocityControl_c_T *localB, + DW_VelocityControl_f_T *localDW, XDot_VelocityControl_n_T *localXdot); +extern void VelocityControl_Disable(DW_VelocityControl_f_T *localDW); +extern void VelocityControl_Update(RT_MODEL_VelocityControl_T * const + VelocityControl_M, B_VelocityControl_c_T *localB, DW_VelocityControl_f_T + *localDW); +extern void VelocityControl(RT_MODEL_VelocityControl_T * const VelocityControl_M, + const real_T *rtu_dphi_refrads, const real_T *rtu_dphirads, const uint8_T + *rtu_Enable, real_T *rty_tau_mNm, B_VelocityControl_c_T *localB, + DW_VelocityControl_f_T *localDW, X_VelocityControl_n_T *localX); + +/*- + * The generated code includes comments that allow you to trace directly + * back to the appropriate location in the model. The basic format + * is /block_name, where system is the system number (uniquely + * assigned by Simulink) and block_name is the name of the block. + * + * Use the MATLAB hilite_system command to trace the generated code back + * to the model. For example, + * + * hilite_system('') - opens system 3 + * hilite_system('/Kp') - opens and selects block Kp which resides in S3 + * + * Here is the system hierarchy for this model + * + * '' : 'VelocityControl' + * '' : 'VelocityControl/PID Controller' + * '' : 'VelocityControl/PID Controller/Anti-windup' + * '' : 'VelocityControl/PID Controller/D Gain' + * '' : 'VelocityControl/PID Controller/Filter' + * '' : 'VelocityControl/PID Controller/Filter ICs' + * '' : 'VelocityControl/PID Controller/I Gain' + * '' : 'VelocityControl/PID Controller/Ideal P Gain' + * '' : 'VelocityControl/PID Controller/Ideal P Gain Fdbk' + * '' : 'VelocityControl/PID Controller/Integrator' + * '' : 'VelocityControl/PID Controller/Integrator ICs' + * '' : 'VelocityControl/PID Controller/N Copy' + * '' : 'VelocityControl/PID Controller/N Gain' + * '' : 'VelocityControl/PID Controller/P Copy' + * '' : 'VelocityControl/PID Controller/Parallel P Gain' + * '' : 'VelocityControl/PID Controller/Reset Signal' + * '' : 'VelocityControl/PID Controller/Saturation' + * '' : 'VelocityControl/PID Controller/Saturation Fdbk' + * '' : 'VelocityControl/PID Controller/Sum' + * '' : 'VelocityControl/PID Controller/Sum Fdbk' + * '' : 'VelocityControl/PID Controller/Tracking Mode' + * '' : 'VelocityControl/PID Controller/Tracking Mode Sum' + * '' : 'VelocityControl/PID Controller/postSat Signal' + * '' : 'VelocityControl/PID Controller/preSat Signal' + * '' : 'VelocityControl/PID Controller/Anti-windup/Back Calculation' + * '' : 'VelocityControl/PID Controller/Anti-windup/Cont. Clamping Ideal' + * '' : 'VelocityControl/PID Controller/Anti-windup/Cont. Clamping Parallel' + * '' : 'VelocityControl/PID Controller/Anti-windup/Disabled' + * '' : 'VelocityControl/PID Controller/Anti-windup/Disc. Clamping Ideal' + * '' : 'VelocityControl/PID Controller/Anti-windup/Disc. Clamping Parallel' + * '' : 'VelocityControl/PID Controller/Anti-windup/Passthrough' + * '' : 'VelocityControl/PID Controller/D Gain/Disabled' + * '' : 'VelocityControl/PID Controller/D Gain/External Parameters' + * '' : 'VelocityControl/PID Controller/D Gain/Internal Parameters' + * '' : 'VelocityControl/PID Controller/Filter/Cont. Filter' + * '' : 'VelocityControl/PID Controller/Filter/Differentiator' + * '' : 'VelocityControl/PID Controller/Filter/Disabled' + * '' : 'VelocityControl/PID Controller/Filter/Disc. Backward Euler Filter' + * '' : 'VelocityControl/PID Controller/Filter/Disc. Forward Euler Filter' + * '' : 'VelocityControl/PID Controller/Filter/Disc. Trapezoidal Filter' + * '' : 'VelocityControl/PID Controller/Filter ICs/Disabled' + * '' : 'VelocityControl/PID Controller/Filter ICs/External IC' + * '' : 'VelocityControl/PID Controller/Filter ICs/Internal IC - Differentiator' + * '' : 'VelocityControl/PID Controller/Filter ICs/Internal IC - Filter' + * '' : 'VelocityControl/PID Controller/I Gain/Disabled' + * '' : 'VelocityControl/PID Controller/I Gain/External Parameters' + * '' : 'VelocityControl/PID Controller/I Gain/Internal Parameters' + * '' : 'VelocityControl/PID Controller/Ideal P Gain/External Parameters' + * '' : 'VelocityControl/PID Controller/Ideal P Gain/Internal Parameters' + * '' : 'VelocityControl/PID Controller/Ideal P Gain/Passthrough' + * '' : 'VelocityControl/PID Controller/Ideal P Gain Fdbk/Disabled' + * '' : 'VelocityControl/PID Controller/Ideal P Gain Fdbk/External Parameters' + * '' : 'VelocityControl/PID Controller/Ideal P Gain Fdbk/Internal Parameters' + * '' : 'VelocityControl/PID Controller/Ideal P Gain Fdbk/Passthrough' + * '' : 'VelocityControl/PID Controller/Integrator/Continuous' + * '' : 'VelocityControl/PID Controller/Integrator/Disabled' + * '' : 'VelocityControl/PID Controller/Integrator/Discrete' + * '' : 'VelocityControl/PID Controller/Integrator ICs/Disabled' + * '' : 'VelocityControl/PID Controller/Integrator ICs/External IC' + * '' : 'VelocityControl/PID Controller/Integrator ICs/Internal IC' + * '' : 'VelocityControl/PID Controller/N Copy/Disabled' + * '' : 'VelocityControl/PID Controller/N Copy/Disabled wSignal Specification' + * '' : 'VelocityControl/PID Controller/N Copy/External Parameters' + * '' : 'VelocityControl/PID Controller/N Copy/Internal Parameters' + * '' : 'VelocityControl/PID Controller/N Gain/Disabled' + * '' : 'VelocityControl/PID Controller/N Gain/External Parameters' + * '' : 'VelocityControl/PID Controller/N Gain/Internal Parameters' + * '' : 'VelocityControl/PID Controller/N Gain/Passthrough' + * '' : 'VelocityControl/PID Controller/P Copy/Disabled' + * '' : 'VelocityControl/PID Controller/P Copy/External Parameters Ideal' + * '' : 'VelocityControl/PID Controller/P Copy/Internal Parameters Ideal' + * '' : 'VelocityControl/PID Controller/Parallel P Gain/Disabled' + * '' : 'VelocityControl/PID Controller/Parallel P Gain/External Parameters' + * '' : 'VelocityControl/PID Controller/Parallel P Gain/Internal Parameters' + * '' : 'VelocityControl/PID Controller/Parallel P Gain/Passthrough' + * '' : 'VelocityControl/PID Controller/Reset Signal/Disabled' + * '' : 'VelocityControl/PID Controller/Reset Signal/External Reset' + * '' : 'VelocityControl/PID Controller/Saturation/Enabled' + * '' : 'VelocityControl/PID Controller/Saturation/Passthrough' + * '' : 'VelocityControl/PID Controller/Saturation Fdbk/Disabled' + * '' : 'VelocityControl/PID Controller/Saturation Fdbk/Enabled' + * '' : 'VelocityControl/PID Controller/Saturation Fdbk/Passthrough' + * '' : 'VelocityControl/PID Controller/Sum/Passthrough_I' + * '' : 'VelocityControl/PID Controller/Sum/Passthrough_P' + * '' : 'VelocityControl/PID Controller/Sum/Sum_PD' + * '' : 'VelocityControl/PID Controller/Sum/Sum_PI' + * '' : 'VelocityControl/PID Controller/Sum/Sum_PID' + * '' : 'VelocityControl/PID Controller/Sum Fdbk/Disabled' + * '' : 'VelocityControl/PID Controller/Sum Fdbk/Enabled' + * '' : 'VelocityControl/PID Controller/Sum Fdbk/Passthrough' + * '' : 'VelocityControl/PID Controller/Tracking Mode/Disabled' + * '' : 'VelocityControl/PID Controller/Tracking Mode/Enabled' + * '' : 'VelocityControl/PID Controller/Tracking Mode Sum/Passthrough' + * '' : 'VelocityControl/PID Controller/Tracking Mode Sum/Tracking Mode' + * '' : 'VelocityControl/PID Controller/postSat Signal/Feedback_Path' + * '' : 'VelocityControl/PID Controller/postSat Signal/Forward_Path' + * '' : 'VelocityControl/PID Controller/preSat Signal/Feedback_Path' + * '' : 'VelocityControl/PID Controller/preSat Signal/Forward_Path' + */ +#endif /* RTW_HEADER_VelocityControl_h_ */ diff --git a/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/VelocityControl_private.h b/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/VelocityControl_private.h new file mode 100644 index 0000000..6d77886 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/VelocityControl_private.h @@ -0,0 +1,79 @@ +/* + * VelocityControl_private.h + * + * Academic License - for use in teaching, academic research, and meeting + * course requirements at degree granting institutions only. Not for + * government, commercial, or other organizational use. + * + * Code generation for model "VelocityControl". + * + * Model version : 1.74 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Tue Jun 28 17:43:44 2022 + * + * Target selection: grt.tlc + * Note: GRT includes extra infrastructure and instrumentation for prototyping + * Embedded hardware selection: ARM Compatible->ARM Cortex + * Code generation objectives: Unspecified + * Validation result: Not run + */ + +#ifndef RTW_HEADER_VelocityControl_private_h_ +#define RTW_HEADER_VelocityControl_private_h_ +#include "rtwtypes.h" +#include "multiword_types.h" + +/* Private macros used by the generated code to access rtModel */ +#ifndef rtmIsMajorTimeStep +# define rtmIsMajorTimeStep(rtm) ((rtmGetSimTimeStep((rtm))) == MAJOR_TIME_STEP) +#endif + +#ifndef rtmIsMinorTimeStep +# define rtmIsMinorTimeStep(rtm) ((rtmGetSimTimeStep((rtm))) == MINOR_TIME_STEP) +#endif + +/* Macros for accessing real-time model data structure */ +#ifndef rtmGetErrorStatus +# define rtmGetErrorStatus(rtm) (*((rtm)->errorStatus)) +#endif + +#ifndef rtmSetErrorStatus +# define rtmSetErrorStatus(rtm, val) (*((rtm)->errorStatus) = (val)) +#endif + +#ifndef rtmGetErrorStatusPointer +# define rtmGetErrorStatusPointer(rtm) (rtm)->errorStatus +#endif + +#ifndef rtmSetErrorStatusPointer +# define rtmSetErrorStatusPointer(rtm, val) ((rtm)->errorStatus = (val)) +#endif + +#ifndef rtmGetSimTimeStep +# define rtmGetSimTimeStep(rtm) (*((rtm)->Timing.simTimeStep)) +#endif + +#ifndef rtmGetSimTimeStepPointer +# define rtmGetSimTimeStepPointer(rtm) (rtm)->Timing.simTimeStep +#endif + +#ifndef rtmSetSimTimeStepPointer +# define rtmSetSimTimeStepPointer(rtm, val) ((rtm)->Timing.simTimeStep = (val)) +#endif + +#ifndef rtmGetStopRequested +# define rtmGetStopRequested(rtm) (*((rtm)->Timing.stopRequestedFlag)) +#endif + +#ifndef rtmSetStopRequested +# define rtmSetStopRequested(rtm, val) (*((rtm)->Timing.stopRequestedFlag) = (val)) +#endif + +#ifndef rtmGetStopRequestedPtr +# define rtmGetStopRequestedPtr(rtm) ((rtm)->Timing.stopRequestedFlag) +#endif + +#ifndef rtmSetStopRequestedPtr +# define rtmSetStopRequestedPtr(rtm, val) ((rtm)->Timing.stopRequestedFlag = (val)) +#endif +#endif /* RTW_HEADER_VelocityControl_private_h_ */ diff --git a/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/VelocityControl_types.h b/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/VelocityControl_types.h new file mode 100644 index 0000000..daa3304 --- /dev/null +++ b/Examples/epos_matlab/src/simulinkcode/controller/referenced_model_includes/VelocityControl_types.h @@ -0,0 +1,27 @@ +/* + * VelocityControl_types.h + * + * Academic License - for use in teaching, academic research, and meeting + * course requirements at degree granting institutions only. Not for + * government, commercial, or other organizational use. + * + * Code generation for model "VelocityControl". + * + * Model version : 1.74 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Tue Jun 28 17:43:44 2022 + * + * Target selection: grt.tlc + * Note: GRT includes extra infrastructure and instrumentation for prototyping + * Embedded hardware selection: ARM Compatible->ARM Cortex + * Code generation objectives: Unspecified + * Validation result: Not run + */ + +#ifndef RTW_HEADER_VelocityControl_types_h_ +#define RTW_HEADER_VelocityControl_types_h_ + +/* Forward declaration for rtModel */ +typedef struct tag_RTM_VelocityControl_T RT_MODEL_VelocityControl_T; + +#endif /* RTW_HEADER_VelocityControl_types_h_ */ diff --git a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/rtmodel.h b/Examples/epos_matlab/src/simulinkcode/controller/rtmodel.h similarity index 62% rename from zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/rtmodel.h rename to Examples/epos_matlab/src/simulinkcode/controller/rtmodel.h index d33c353..d4bb885 100644 --- a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/rtmodel.h +++ b/Examples/epos_matlab/src/simulinkcode/controller/rtmodel.h @@ -1,29 +1,29 @@ -/* - * rtmodel.h: - * - * Academic License - for use in teaching, academic research, and meeting - * course requirements at degree granting institutions only. Not for - * government, commercial, or other organizational use. - * - * Code generation for model "Atomic". - * - * Model version : 4.4 - * Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 - * C source code generated on : Wed Jun 16 17:30:13 2021 - * - * Target selection: grt.tlc - * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Intel->x86-64 (Windows64) - * Code generation objectives: Unspecified - * Validation result: Not run - */ - -#ifndef RTW_HEADER_rtmodel_h_ -#define RTW_HEADER_rtmodel_h_ - -/* - * Includes the appropriate headers when we are using rtModel - */ -#include "Atomic.h" -#define GRTINTERFACE 0 -#endif /* RTW_HEADER_rtmodel_h_ */ +/* + * rtmodel.h: + * + * Academic License - for use in teaching, academic research, and meeting + * course requirements at degree granting institutions only. Not for + * government, commercial, or other organizational use. + * + * Code generation for model "Control_System". + * + * Model version : 1.119 + * Simulink Coder version : 9.0 (R2018b) 24-May-2018 + * C source code generated on : Tue Jun 28 17:20:04 2022 + * + * Target selection: grt.tlc + * Note: GRT includes extra infrastructure and instrumentation for prototyping + * Embedded hardware selection: ARM Compatible->ARM Cortex + * Code generation objective: Execution efficiency + * Validation result: Not run + */ + +#ifndef RTW_HEADER_rtmodel_h_ +#define RTW_HEADER_rtmodel_h_ + +/* + * Includes the appropriate headers when we are using rtModel + */ +#include "Control_System.h" +#define GRTINTERFACE 0 +#endif /* RTW_HEADER_rtmodel_h_ */ diff --git a/zephyr/epos_controller/stm32f4_disco.overlay b/Examples/epos_matlab/stm32f4_disco.overlay similarity index 77% rename from zephyr/epos_controller/stm32f4_disco.overlay rename to Examples/epos_matlab/stm32f4_disco.overlay index bc7dd94..e36ff83 100644 --- a/zephyr/epos_controller/stm32f4_disco.overlay +++ b/Examples/epos_matlab/stm32f4_disco.overlay @@ -34,14 +34,33 @@ // #address-cells = <1>; // #size-cells = <0>; + &can2 { status = "disabled"; }; +&dma1 { + status = "okay"; + dma-requests = <8>; +}; + +&usart2 { + status = "okay"; + current-speed = < 0xe1000 >; + dmas = <&dma1 5 4 0x440 0x3>, + <&dma1 6 4 0x440 0x3>; + dma-names = "rx", "tx"; +}; + / { chosen { zephyr,can-primary = &can1; + zephyr,shell-uart = &usart2; + }; + aliases { + usart2 = &usart2; }; -}; \ No newline at end of file +}; + diff --git a/Examples/epos_parameter_identification/CMakeLists.txt b/Examples/epos_parameter_identification/CMakeLists.txt new file mode 100644 index 0000000..cc6db85 --- /dev/null +++ b/Examples/epos_parameter_identification/CMakeLists.txt @@ -0,0 +1,11 @@ +# Find Zephyr. This also loads Zephyr's build system. +cmake_minimum_required(VERSION 3.13.1) +find_package(Zephyr) +project(epos_controller_mainTest) + +target_sources(app PRIVATE + src/main.cpp + ../../Library/epos4/epos4.cpp +) + +include_directories(../../Library/epos4) \ No newline at end of file diff --git a/zephyr/epos_controller_model/Kconfig b/Examples/epos_parameter_identification/Kconfig similarity index 100% rename from zephyr/epos_controller_model/Kconfig rename to Examples/epos_parameter_identification/Kconfig diff --git a/Examples/epos_parameter_identification/ReadmeNiko.txt b/Examples/epos_parameter_identification/ReadmeNiko.txt new file mode 100644 index 0000000..bc9720a --- /dev/null +++ b/Examples/epos_parameter_identification/ReadmeNiko.txt @@ -0,0 +1,5 @@ +Dieses Projekt soll zum Testen der Can-Kommunikation und das Verfahrens des Motors mittels PPM OHNE simulink model verwendet werden. + +Interessant -> Funktioniert tx_callback(int ?,..-) + +Motor bewegt sich im PPM modus \ No newline at end of file diff --git a/zephyr/epos_controller/prj.conf b/Examples/epos_parameter_identification/prj.conf similarity index 69% rename from zephyr/epos_controller/prj.conf rename to Examples/epos_parameter_identification/prj.conf index 5b15c9b..82ed777 100644 --- a/zephyr/epos_controller/prj.conf +++ b/Examples/epos_parameter_identification/prj.conf @@ -7,5 +7,8 @@ CONFIG_LOG=y CONFIG_DEBUG_OPTIMIZATIONS=y CONFIG_CPLUSPLUS=y -CONFIG_NEWLIB_LIBC_FLOAT_PRINTF=y -CONFIG_CBPRINTF_FP_SUPPORT=y \ No newline at end of file + +CONFIG_PM=y +CONFIG_DMA=y +CONFIG_DMA_STM32=y +CONFIG_UART_ASYNC_API=y \ No newline at end of file diff --git a/Examples/epos_parameter_identification/src/.vscode/c_cpp_properties.json b/Examples/epos_parameter_identification/src/.vscode/c_cpp_properties.json new file mode 100644 index 0000000..166e479 --- /dev/null +++ b/Examples/epos_parameter_identification/src/.vscode/c_cpp_properties.json @@ -0,0 +1,21 @@ +{ + "configurations": [ + { + "name": "Win32", + "includePath": [ + "${workspaceFolder}/**", + "${workspaceFolder}/epos4" + ], + "defines": [ + "_DEBUG", + "UNICODE", + "_UNICODE" + ], + "cStandard": "c17", + "cppStandard": "c++17", + "intelliSenseMode": "windows-msvc-x64", + "compilerArgs": [] + } + ], + "version": 4 +} \ No newline at end of file diff --git a/Examples/epos_parameter_identification/src/main.cpp b/Examples/epos_parameter_identification/src/main.cpp new file mode 100644 index 0000000..2007073 --- /dev/null +++ b/Examples/epos_parameter_identification/src/main.cpp @@ -0,0 +1,294 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#ifdef CONFIG_UART_ASYNC_API +#include +#include +#endif + +#include "epos4.h" + +#define RX_THREAD_STACK_SIZE 512 +#define RX_THREAD_PRIORITY 2 +#define STATE_POLL_THREAD_STACK_SIZE 512 +#define STATE_POLL_THREAD_PRIORITY 2 +#define LED_MSG_ID 0x10 +#define COUNTER_MSG_ID 0x12345 +#define SET_LED 1 +#define RESET_LED 0 +#define SLEEP_TIME K_MSEC(250) + +K_THREAD_STACK_DEFINE(rx_thread_stack, RX_THREAD_STACK_SIZE); + + +#define CAN_DEVICE_LABEL DT_PROP(DT_ALIAS(can_dev), label) +const struct device* can_dev; +// const struct device *can_dev = DEVICE_DT_GET(DT_CHOSEN(zephyr_can_primary)); + +// uart config +#define UART_DEVICE_NODE DT_ALIAS(usart2) +const struct device *uart_dev = DEVICE_DT_GET(UART_DEVICE_NODE); + +epos4* epos4_1_pointer = NULL; + +struct k_thread rx_thread_data; +struct k_thread poll_state_thread_data; +struct k_work state_change_work; +enum can_state current_state; +struct can_bus_err_cnt current_err_cnt; + + +CAN_MSGQ_DEFINE(my_can_msgq1, 100); +CAN_MSGQ_DEFINE(my_can_msgq2, 100); +struct zcan_frame rx_frame; + +struct k_timer sync_timer; +struct k_timer print_timer; +extern void sync_function(struct k_timer *timer_id); + +unsigned char torque_value[2] = {0}; + +int counter_1 = 0; +bool count_checker = true; +uint32_t diff; +uint8_t send_data[2000]; +uint8_t send_data_tmp[100]; +uint32_t glob_counter = 0; +int glob_counter_int = 0; + +int32_t vvaa = 100; + +struct k_mutex blocker_can; + + + +void tx_irq_callback_main(const struct device *CAN_INTERFACE, int error_flags, void *arg) +{ + k_mutex_unlock(epos4_1_pointer->_blocker_can); + // char *sender = (char *)arg; + // + // if (error_flags) { + // printk("Sendig main [%d]\nSender: %s\n", error_flags, sender); + // } +} +void sync_function(struct k_timer *timer_id) +{ + // Overwrite + int32_t tmp_pos = epos4_1_pointer->position; + int32_t tmp_tor = epos4_1_pointer->torque; + + epos4_1_pointer->sync(); + + + // epos4 inc. to position in rad === 0.00000756309 | 120000 inc. === 104 Grad + float ac_pos = (((float)(tmp_pos))*(0.00000756309)); + float ac_tor = (((float)(tmp_tor))); + + uint32_t int_pos = (uint32_t)(epos4_1_pointer->position); + // uint32_t int_tor = (uint32_t)(epos4_1_pointer->velocity); + uint16_t int_tor = (uint16_t)(epos4_1_pointer->torque); + + uint8_t *time_pointer; + uint8_t *pos_pointer; + uint8_t *tor_pointer; + + time_pointer = (uint8_t *)(&glob_counter); + pos_pointer = (uint8_t *)(&int_pos); + tor_pointer = (uint8_t *)(&int_tor); + + int16_t int16_tor = 0; + int8_t *pointer_tor; + + if( glob_counter_int >= 0 && glob_counter_int < 1000 ) int16_tor = 0; + if( glob_counter_int >= 1000 && glob_counter_int < 2000 ) int16_tor = 200; + if( glob_counter_int >= 2000 && glob_counter_int < 4000 ) int16_tor = 0; + if( glob_counter_int >= 4000 && glob_counter_int < 4500 ) int16_tor = 300; + if( glob_counter_int >= 5000 && glob_counter_int < 5500 ) int16_tor = 0; + if( glob_counter_int >= 5500 && glob_counter_int < 5900 ) int16_tor = -100; + if( glob_counter_int >= 5900 && glob_counter_int < 10000 ) int16_tor = 0; + + if( glob_counter_int >= 10000 && glob_counter_int < 11000 ) int16_tor = 200; + if( glob_counter_int >= 11000 && glob_counter_int < 11500 ) int16_tor = 0; + if( glob_counter_int >= 11500 && glob_counter_int < 12000 ) int16_tor = -100; + if( glob_counter_int >= 12000 && glob_counter_int < 12500 ) int16_tor = 0; + if( glob_counter_int >= 12500 && glob_counter_int < 14500 ) int16_tor = 150; + if( glob_counter_int >= 14500 && glob_counter_int < 20000 ) int16_tor = 0; + if( glob_counter_int >= 20000 || glob_counter_int < 0 ) glob_counter_int = 0; + + pointer_tor = (int8_t *)(&int16_tor); + + struct zcan_frame frame = { + .id = 0x401, + .rtr = CAN_DATAFRAME, + .id_type = CAN_STANDARD_IDENTIFIER, + .dlc = 2, + .data = {pointer_tor[0],pointer_tor[1]} + // .data = {0x0,0x0} + }; + + int tester = glob_counter%4; + int tester_1 = tester*25; + + send_data_tmp[(tester_1)] = 'D'; + send_data_tmp[(tester_1)+1] = '='; + send_data_tmp[(tester_1)+2] = 'x'; + send_data_tmp[(tester_1)+3] = time_pointer[0]; + send_data_tmp[(tester_1)+4] = time_pointer[1]; + send_data_tmp[(tester_1)+5] = time_pointer[2]; + send_data_tmp[(tester_1)+6] = time_pointer[3]; + send_data_tmp[(tester_1)+7] = 'x'; + send_data_tmp[(tester_1)+8] = '='; + send_data_tmp[(tester_1)+9] = pos_pointer[0]; + send_data_tmp[(tester_1)+10] = pos_pointer[1]; + send_data_tmp[(tester_1)+11] = pos_pointer[2]; + send_data_tmp[(tester_1)+12] = pos_pointer[3]; + send_data_tmp[(tester_1)+13] = 'x'; + send_data_tmp[(tester_1)+14] = '='; + send_data_tmp[(tester_1)+15] = tor_pointer[0]; + send_data_tmp[(tester_1)+16] = tor_pointer[1]; + send_data_tmp[(tester_1)+17] = 0x0; + send_data_tmp[(tester_1)+18] = 0x0; + send_data_tmp[(tester_1)+19] = 'x'; + send_data_tmp[(tester_1)+20] = '='; + send_data_tmp[(tester_1)+21] = pointer_tor[0]; + send_data_tmp[(tester_1)+22] = pointer_tor[1]; + send_data_tmp[(tester_1)+23] = '\r'; + send_data_tmp[(tester_1)+24] = '\n'; + + + // my_union.float_variable = 0; + + if( tester == 3 ){ + uart_tx(uart_dev, send_data_tmp, 100, 0); + } + + // printk("%d,%02x,%02x,%02x,%02x\n",my_union.float_variable,my_union.bytes_array[3],my_union.bytes_array[2],my_union.bytes_array[1],my_union.bytes_array[0]); + // printk("Data===0.0,%f,%f+\n",ac_pos,ac_tor); + + // if( 0 != can_send(epos4_1_pointer->_can_interface, &frame, K_FOREVER, tx_irq_callback_main, NULL) ) + + k_mutex_lock(epos4_1_pointer->_blocker_can, K_FOREVER); + + uint32_t start_time = k_cycle_get_32(); + int can_send_return = can_send(epos4_1_pointer->_can_interface, &frame, K_FOREVER, tx_irq_callback_main, NULL); + //int can_send_return = 0; + uint32_t end_time = k_cycle_get_32(); + + + if(can_send_return != 0){ + //uint32_t asdf = (uint32_t)(can_send_return); + //uint8_t *asdf_t; + //asdf_t = (uint8_t *)(&asdf); + // + //uint8_t err_msg[5] = {asdf_t[0],asdf_t[1],asdf_t[2],asdf_t[3],'\n'}; + //uart_tx(epos4_1_pointer->_can_interface, err_msg, 5, 0); + } + glob_counter += 1; + glob_counter_int += 1; +} +void serial_cb(const struct device *dev, struct uart_event *evt, void *user_data) +{ +} +void rx_callback_function(const struct device *dev, struct zcan_frame *frame, void *user_data) +{ + + // uint8_t err_msg[2] = {'S','\n'}; + // uart_tx(uart_dev, err_msg, 2, 0); + epos4_1_pointer->reciveCANdataSPO((char*)(frame->data)); +} + +void main(void) +{ + // init uart dev + if ( !device_is_ready(uart_dev) ) { + printk("uart devices not ready\n"); + return; + } + + uart_callback_set(uart_dev, serial_cb, NULL); + + epos4 epos4_1(0x581,0x601, can_dev, &my_can_msgq1, &my_can_msgq2, &rx_frame, &blocker_can); + epos4_1_pointer = &epos4_1; + epos4_1_pointer->_can_interface = device_get_binding("CAN_1"); + + if (!device_is_ready(epos4_1_pointer->_can_interface)) { + printk("CAN: Device %s not ready.\n", epos4_1_pointer->_can_interface->name); + return; + }else{ + printk("CAN device %s is ready...\n", epos4_1_pointer->_can_interface->name); + } + can_set_mode(epos4_1_pointer->_can_interface, CAN_MODE_NORMAL); + + + k_mutex_init(epos4_1_pointer->_blocker_can); + + // Setting up the filters + + const struct zcan_filter my_filter = { + .id = 0x581, + .rtr = CAN_DATAFRAME, + .id_type = CAN_STANDARD_IDENTIFIER, + .id_mask = CAN_STD_ID_MASK, + .rtr_mask = 1 + }; + int filter_id; + + filter_id = can_add_rx_filter_msgq(epos4_1_pointer->_can_interface, &my_can_msgq1, &my_filter); + if (filter_id < 0) { + printk("Unable to attach isr [%d]", filter_id); + return; + } + + const struct zcan_filter spo_recieve = { + .id = 0x181, + .rtr = CAN_DATAFRAME, + .id_type = CAN_STANDARD_IDENTIFIER, + .id_mask = CAN_STD_ID_MASK, + .rtr_mask = 1 + }; + int spo_recieve_filter_id; + + spo_recieve_filter_id = can_add_rx_filter(epos4_1_pointer->_can_interface, rx_callback_function, NULL, &spo_recieve); + // spo_recieve_filter_id = can_add_rx_filter_msgq(epos4_1_pointer->_can_interface, &my_can_msgq2, &spo_recieve); + if (spo_recieve_filter_id < 0) { + printk("Unable to attach isr [%d]", spo_recieve_filter_id); + return; + } + + k_sleep(K_MSEC(500)); + + printk(" ------------------------------- \n"); + printk("Start init ... \n"); + epos4_1_pointer->init(); + printk("\ndone!\nStart init CST-Mode ... \n"); + epos4_1_pointer->initCST(); + printk("\ndone!\n"); + + + + + k_msgq_cleanup(&my_can_msgq1); + k_msgq_cleanup(&my_can_msgq2); + + k_sleep(K_MSEC(1000)); + + k_timer_init( &sync_timer, sync_function, NULL); + k_timer_start( &sync_timer, K_MSEC(0), K_MSEC(1) ); + + + // k_timer_init( &print_timer, print_function, NULL); + // k_timer_start( &print_timer, K_MSEC(0), K_MSEC(100) ); + + while(1) + { + //k_sleep(K_MSEC(5000)); + //epos4_1_pointer->readStatusword(); + } +} diff --git a/Examples/epos_parameter_identification/stm32f4_disco.overlay b/Examples/epos_parameter_identification/stm32f4_disco.overlay new file mode 100644 index 0000000..e36ff83 --- /dev/null +++ b/Examples/epos_parameter_identification/stm32f4_disco.overlay @@ -0,0 +1,66 @@ +&can1 { + status = "okay"; + pinctrl-0 = <&can1_rx_pd0 &can1_tx_pd1>; + bus-speed = <125000>; + + // compatible = "st,stm32-can"; + // #address-cells = <1>; + // #size-cells = <0>; + // reg = <0x40006400 0x400>; + // interrupts = <19 0>, <20 0>, <21 0>, <22 0>; + // interrupt-names = "TX", "RX0", "RX1", "SCE"; + // clocks = <&rcc 2 0x02000000>; + // status = "disabled"; + // label = "CAN_1"; + // bus-speed = <125000>; + // sjw = <1>; + prop-seg = <2>; + phase-seg1 = <7>; + phase-seg2 = <6>; +}; + +// compatible = "microchip,mcp2515"; +// spi-max-frequency = <1000000>; +// int-gpios = <&arduino_header 8 GPIO_ACTIVE_LOW>; /* D2 */ +// status = "okay"; +// label = "CAN_1"; +// reg = <0x0>; +// osc-freq = <16000000>; +// bus-speed = <125000>; +// sjw = <1>; +// prop-seg = <2>; +// phase-seg1 = <7>; +// phase-seg2 = <6>; +// #address-cells = <1>; +// #size-cells = <0>; + + +&can2 { + status = "disabled"; +}; + +&dma1 { + status = "okay"; + dma-requests = <8>; +}; + +&usart2 { + status = "okay"; + current-speed = < 0xe1000 >; + dmas = <&dma1 5 4 0x440 0x3>, + <&dma1 6 4 0x440 0x3>; + dma-names = "rx", "tx"; +}; + +/ { + + chosen { + zephyr,can-primary = &can1; + zephyr,shell-uart = &usart2; + }; + aliases { + usart2 = &usart2; + }; + +}; + diff --git a/zephyr/epos_controller/src/epos4/epos4.cpp b/Library/epos4/epos4.cpp similarity index 61% rename from zephyr/epos_controller/src/epos4/epos4.cpp rename to Library/epos4/epos4.cpp index 21cd1c4..ae9f008 100644 --- a/zephyr/epos_controller/src/epos4/epos4.cpp +++ b/Library/epos4/epos4.cpp @@ -10,16 +10,24 @@ uint8_t tmp_type; int32_t velo_inti = 0x00; -void tx_irq_callback(uint32_t error_flags, void *arg) -{ - char *sender = (char *)arg; +void tx_irq_callback(const struct device *CAN_INTERFACE, int error_flags, void *arg) +{ + if (error_flags) { + // printk("Sendig failed [%d]\nSender: \n", error_flags); + } +} - if (error_flags) { - printk("Sendig failed [%d]\nSender: %s\n", error_flags, sender); - } +void tx_irq_callback_mutex(const struct device *CAN_INTERFACE, int error_flags, void *arg) +{ + struct k_mutex *sender = (struct k_mutex *)arg; + k_mutex_unlock(sender); + // + // if (error_flags) { + // printk("Sendig failed [%d]\nSender: %s\n", error_flags, sender); + // } } -epos4::epos4(uint32_t canid_epos, uint32_t canid_self, const struct device *CAN_INTERFACE, struct k_msgq *my_can_msgq1, struct k_msgq *my_can_msgq2, struct zcan_frame *rx_frame): +epos4::epos4(uint32_t canid_epos, uint32_t canid_self, const struct device *CAN_INTERFACE, struct k_msgq *my_can_msgq1, struct k_msgq *my_can_msgq2, struct zcan_frame *rx_frame, struct k_mutex *blocker_can): _canid_epos(canid_epos), _canid_self(canid_self), _softwareVersion(0), @@ -27,8 +35,15 @@ epos4::epos4(uint32_t canid_epos, uint32_t canid_self, const struct device *CAN_ _can_interface(CAN_INTERFACE), _my_can_msgq1(my_can_msgq1), _my_can_msgq2(my_can_msgq2), + _blocker_can(blocker_can), _rx_frame(rx_frame){} +/** + * @brief Inizialization of the controller. + * + * @details Depending on the status of the Epos4, it must be activated with a different "DeviceControlCommand". + * The exact flowchart for this can be taken from the Epos4 documentation. + */ void epos4::init() { // get state of drive @@ -99,7 +114,6 @@ void epos4::init() } k_msgq_cleanup(epos4::_my_can_msgq1); - printk("\n --> Start SI config ... \n"); epos4::initSI(); k_msgq_cleanup(epos4::_my_can_msgq1); @@ -110,35 +124,78 @@ void epos4::init() k_msgq_cleanup(epos4::_my_can_msgq1); printk(" done!\n"); - printk(" --- EPOS enabled --- "); } +/** + * @brief Abstration of the CAN interface. + * + * @details In most cases where data is sent via the CAn interface, this function is used. + * This way it is easier to adapt the CAN interface in case of changes in the Zephyr source code. + */ +void epos4::sendFrame(uint8_t *data_pointer, uint8_t size, uint32_t canid) +{ + zcan_frame frame; + frame.id = canid; + frame.rtr = CAN_DATAFRAME; + frame.id_type = CAN_STANDARD_IDENTIFIER; + frame.dlc = size; + memcpy(frame.data, data_pointer, size); + + can_send(epos4::_can_interface, &frame, K_FOREVER, tx_irq_callback, NULL); +} + +/** + * @brief Configure the SI units on the Epos4. + * + * @details For different accuracies and value ranges, the power of ten of the measured values can be specified on the Epos4. + * For details look in the Epos4 Firmware specs 6.2.115 SI unit position and 6.2.116 SI unit velocity + */ void epos4::initSI() { + epos4::writeControlword(0x00, epos4::dcc_shutdown); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - char velocity_si[8] = {0x22, 0xA9, 0x60, 0x00, 0x00, 0x47, 0xB4, 0xFD}; // FD is maximum + // 0xFAB44700 + // 0x00B44700 + uint8_t velocity_si[8] = {0x22, 0xA9, 0x60, 0x00, 0x00, 0x47, 0xB4, 0xFD}; // FD is maximum + + epos4::sendFrame(velocity_si, 8, epos4::_canid_self); + + //// max.: 0x2625A0 --> 2.500.000 + uint8_t digital_encode_1_resolution[8] = {0x22, 0x10, 0x30, 0x01, 0xA0, 0x25, 0x26, 0x00}; + epos4::sendFrame(digital_encode_1_resolution, 8, epos4::_canid_self); - can_write(epos4::_can_interface,(uint8_t*)velocity_si,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); + k_sleep(K_MSEC(100)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); + k_sleep(K_MSEC(100)); + epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); + + } +/** + * @brief Inizialize the Profile Position mode + * + * @details Before using an operating mode on the Epos, it must be activated. The following functions serve this purpose. + * The different operating modes and how they work can be found in the Epos4 documentation. + * @{ + */ void epos4::initPPM() { printk("Set Operationmode"); - unsigned char data0[8] = {0x22, 0x60, 0x60, 0x00, 0x01, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + uint8_t data0[8] = {0x22, 0x60, 0x60, 0x00, 0x01, 0x00, 0x00, 0x00}; + epos4::sendFrame(data0, 8, epos4::_canid_self); + // can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); k_sleep(K_MSEC(10)); @@ -160,15 +217,18 @@ void epos4::initPPM() void epos4::initCSP() { printk("Set Operationmode to CSP"); - unsigned char data0[8] = {0x22, 0x60, 0x60, 0x00, 0x08, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + uint8_t data0[8] = {0x22, 0x60, 0x60, 0x00, 0x08, 0x00, 0x00, 0x00}; + epos4::sendFrame(data0, 8, epos4::_canid_self); + // can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); // Interpolation time period value - unsigned char data01[8] = {0x22, 0xC2, 0x60, 0x01, 0x0A, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + uint8_t data01[8] = {0x22, 0xC2, 0x60, 0x01, 0x0A, 0x00, 0x00, 0x00}; + epos4::sendFrame(data01, 8, epos4::_canid_self); + // can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); @@ -189,15 +249,19 @@ void epos4::initCSP() void epos4::initCSV() { printk("Set Operationmode to CSV"); - unsigned char data0[8] = {0x22, 0x60, 0x60, 0x00, 0x09, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + uint8_t data0[8] = {0x22, 0x60, 0x60, 0x00, 0x09, 0x00, 0x00, 0x00}; + epos4::sendFrame(data0, 8, epos4::_canid_self); + // can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); // Interpolation time period value - unsigned char data01[8] = {0x22, 0xC2, 0x60, 0x01, 0x0A, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data01,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + uint8_t data01[8] = {0x22, 0xC2, 0x60, 0x01, 0x0A, 0x00, 0x00, 0x00}; + epos4::sendFrame(data01, 8, epos4::_canid_self); + // can_write(epos4::_can_interface,(uint8_t*)data01,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); @@ -217,8 +281,9 @@ void epos4::initCSV() void epos4::initCST() { printk("\n --> Set Operationmode to CST\n"); - unsigned char data0[8] = {0x22, 0x60, 0x60, 0x00, 0x0A, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + uint8_t data0[8] = {0x22, 0x60, 0x60, 0x00, 0x0A, 0x00, 0x00, 0x00}; + epos4::sendFrame(data0, 8, epos4::_canid_self); + // can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); @@ -226,8 +291,10 @@ void epos4::initCST() // Interpolation time period value // Firmware spec. 6.2.121.1 Interpolation time period value ( 0x0a ==> 10ms ) - unsigned char data01[8] = {0x22, 0xC2, 0x60, 0x01, 0x0A, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data01,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + // Firmware spec. 6.2.121.1 Interpolation time period value ( 0x01 ==> 1ms ) + uint8_t data01[8] = {0x22, 0xC2, 0x60, 0x01, 0x01, 0x00, 0x00, 0x00}; + epos4::sendFrame(data01, 8, epos4::_canid_self); + // can_write(epos4::_can_interface,(uint8_t*)data01,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); @@ -245,8 +312,16 @@ void epos4::initCST() k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); } +/** @} */ - +/** + * @brief Syncronization function for the cyclic modes. + * + * @details In the cyclic modes, the Epos4 expects new values at regular intervals. + * This function only sends a sync frame so that the Epos4 knows that we are still synced and can send the new measured values. + * Due to a bug in the Zephyr CAN interface the send function for the CAN interface was protected with a mutex. + * The mutex is removed as soon as 'tx_irq_callback_mutex' is called. This ensures that only when zephyr has left the send routine for CAN, a new CAN frame is tried to be sent. + */ void epos4::sync() { struct zcan_frame frame = { @@ -256,17 +331,28 @@ void epos4::sync() .dlc = 1, .data = {0x00} }; - - if( 0 != can_send(epos4::_can_interface, &frame, K_FOREVER, tx_irq_callback, NULL) ) - { - printk("\n --- Error while sending sync frame --- \n"); - } - k_msgq_get(epos4::_my_can_msgq2, epos4::_rx_frame, K_FOREVER); - char *dat = (char*)(epos4::_rx_frame->data); - epos4::reciveCANdataSPO( dat ); - // epos4::printFrame( epos4::_rx_frame ); - k_msgq_cleanup(epos4::_my_can_msgq2); + /* + get unlocked after 'tx_irq_callback_mutex' + */ + k_mutex_lock(epos4::_blocker_can, K_FOREVER); + + int can_send_return = can_send(epos4::_can_interface, &frame, K_FOREVER, tx_irq_callback_mutex, epos4::_blocker_can); + + // Some Printout if error + if(can_send_return != 0){ + //uint32_t asdf = (uint32_t)(can_send_return); + //uint8_t *asdf_t; + //asdf_t = (uint8_t *)(&asdf); + // + //uint8_t err_msg[5] = {asdf_t[0],asdf_t[1],asdf_t[2],asdf_t[3],'\n'}; + //uart_tx(epos4_1_pointer->_can_interface, err_msg, 5, 0); + } + // k_msgq_get(epos4::_my_can_msgq2, epos4::_rx_frame, K_USEC(100)); + // + // epos4::reciveCANdataSPO( (char*)(epos4::_rx_frame->data) ); + // // epos4::printFrame( epos4::_rx_frame ); + // k_msgq_cleanup( epos4::_my_can_msgq2 ); } @@ -279,15 +365,26 @@ void epos4::reciveCANdata(char *frame) epos4::_state_of_drive = statusword & 0b01101111; } } + +/** + * @brief Save the measured values of the Epic in Cyclic mode + * + * @details In the cyclic modes, new measured values are sent at regular time intervals. + * Depending on the 'measure_mode', position and speed or position and torque are sent and stored. + */ void epos4::reciveCANdataSPO(char *frame) { int32_t *pos = (int32_t *)frame; - int16_t *tor = (int16_t *)(frame+4); - epos4::position = *pos; - epos4::torque = *tor; -} + if( epos4::measure_mode == 0 ){ + int32_t *vel = (int32_t *)(frame+4); + epos4::velocity = *vel; + }else{ + int16_t *tor = (int16_t *)(frame+4); + epos4::torque = *tor; + } +} /** * @brief Send a controlword with SDO communication @@ -300,20 +397,18 @@ void epos4::reciveCANdataSPO(char *frame) */ void epos4::writeControlword(unsigned char highByte, unsigned char lowByte) { - unsigned char data[8] = {0x2B, 0x40, 0x60, 0x00, lowByte, highByte, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + unsigned char data[8] = {0x2B, 0x40, 0x60, 0x00, lowByte, highByte, 0x00, 0x00}; + epos4::sendFrame(data, 8, epos4::_canid_self); } void epos4::readStatusword() { unsigned char data[8] = {0x40, 0x41, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00}; printk("\n --> ask for statusword\n"); + epos4::sendFrame(data, 8, epos4::_canid_self); - can_write(epos4::_can_interface,(uint8_t*)data,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - printk(" Sended\n"); - k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); char *dat = (char*)(epos4::_rx_frame->data); @@ -329,7 +424,6 @@ void epos4::readStatusword() } - void epos4::printFrame(struct zcan_frame *frame) { char *dat = (char*)(frame->data); @@ -348,14 +442,17 @@ void epos4::moveToPosition(uint8_t *position) // position is an 32 bit integer. Wen give the uint8 here because we can interate on the bytes from the uint32 printk("Starte move to position ... "); - unsigned char data[8] = {0x22, 0x7A, 0x60, 0x00, position[3], position[2], position[1], position[0]}; + uint8_t data[8] = {0x22, 0x7A, 0x60, 0x00, position[3], position[2], position[1], position[0]}; //unsigned char data[8] = {0x22, 0x7A, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame(data, 8, epos4::_canid_self); + // can_write(epos4::_can_interface,(uint8_t*)data,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); k_sleep(K_MSEC(10)); - unsigned char data1[8] = {0x22, 0x40, 0x60, 0x00, 0x1F, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data1,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + uint8_t data1[8] = {0x22, 0x40, 0x60, 0x00, 0x1F, 0x00, 0x00, 0x00}; + epos4::sendFrame(data1, 8, epos4::_canid_self); + + // can_write(epos4::_can_interface,(uint8_t*)data1,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); k_sleep(K_MSEC(10)); @@ -380,76 +477,88 @@ void epos4::moveToPosition(uint32_t *posList, uint8_t len) n2[1] = (posList[i]) >> 16; n2[0] = (posList[i]) >> 24; - moveToPosition(n2); + epos4::moveToPosition(n2); k_sleep(K_MSEC(1)); // printk("Toggle new poisition ..."); epos4::writeControlword(0x00, 0x0F); - k_sleep(K_MSEC(1)); + k_sleep(K_MSEC(2000)); } } +/** + * @brief Configuration of the PDOs of the Epos4 + * + * @details The PDO objects of the Epos4 must be configured in a certain way. + * Several frames must be sent per PDO for configuration. + * Which ones exactly and in which sequence can be looked up in the Epos4 documentation. + * In the epos4.h the PDO frames can be adapted to generate other behavior. + */ void epos4::configPDO() { // State Maschinbe of MNT Service to Pre Operational to checnge PDOs - can_write(epos4::_can_interface,(uint8_t*)(epos4::enter_preoperational),2,0x00,CAN_DATAFRAME,K_FOREVER); + + epos4::sendFrame((uint8_t*)(epos4::enter_preoperational),2, 0x00); k_sleep(K_MSEC(10)); // Config of TxPDO 1 - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_transmissiontype_TxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_transmissiontype_TxPDO1), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_inhibit_time_TxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_inhibit_time_TxPDO1), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_null_TxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_number_of_mapped_objects_null_TxPDO1), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_first_mapped_obj_position_TxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_first_mapped_obj_position_TxPDO1), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_first_mapped_obj_velocity_TxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + if( epos4::measure_mode == 0 ){ + epos4::sendFrame((uint8_t*)(epos4::pdo_first_mapped_obj_velocity_TxPDO1), 8, epos4::_canid_self); + }else{ + epos4::sendFrame((uint8_t*)(epos4::pdo_first_mapped_obj_torque_TxPDO1), 8, epos4::_canid_self); + } k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_TxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_number_of_mapped_objects_TxPDO1), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); // Config of TxPDO 2 - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_transmissiontype_TxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_transmissiontype_TxPDO2), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_inhibit_time_TxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_inhibit_time_TxPDO2), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_null_TxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_number_of_mapped_objects_null_TxPDO2), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_first_mapped_obj_torque_TxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_first_mapped_obj_torque_TxPDO2), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_TxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_number_of_mapped_objects_TxPDO2), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); @@ -458,74 +567,73 @@ void epos4::configPDO() { // Config of RxPDO 1 - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_transmissiontype_RxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_transmissiontype_RxPDO1), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_null_RxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_number_of_mapped_objects_null_RxPDO1), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_first_mapped_obj_position_RxPDO3),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_first_mapped_obj_position_RxPDO3), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_RxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_number_of_mapped_objects_RxPDO1), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); // Config of RxPDO 2 - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_transmissiontype_RxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_transmissiontype_RxPDO2), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_null_RxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_number_of_mapped_objects_null_RxPDO2), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_first_mapped_obj_position_RxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_first_mapped_obj_position_RxPDO2), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_RxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_number_of_mapped_objects_RxPDO2), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); // Config of RxPDO 3 - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_transmissiontype_RxPDO3),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_transmissiontype_RxPDO3), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_null_RxPDO3),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_number_of_mapped_objects_null_RxPDO3), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_first_mapped_obj_position_RxPDO3),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_first_mapped_obj_position_RxPDO3), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_RxPDO3),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::pdo_number_of_mapped_objects_RxPDO3), 8, epos4::_canid_self); k_sleep(K_MSEC(10)); k_msgq_get(epos4::_my_can_msgq1, epos4::_rx_frame, K_FOREVER); epos4::printFrame( epos4::_rx_frame ); - // Set Statemaschine of NMT service back to Operational - can_write(epos4::_can_interface,(uint8_t*)(epos4::start_remotenode),2,0x00,CAN_DATAFRAME,K_FOREVER); + epos4::sendFrame((uint8_t*)(epos4::start_remotenode), 2, 0x00); k_sleep(K_MSEC(100)); printk("TPDO Configured!"); @@ -582,39 +690,4 @@ void epos4::getRevisionNumber(uint16_t* software_version, uint16_t* application_ } } } - -void epos4::checkReceivedData(unsigned char *data, uint8_t *len, uint32_t *id, uint8_t *type, bool *check) -{ - - - if (CAN_MSGAVAIL == epos4::_can_interface->checkReceive()) - { - epos4::_can_interface->readMsgBuf(len, data); - *id = epos4::_can_interface->getCanId(); - *type = (epos4::_can_interface->isExtendedFrame() << 0) | - (epos4::_can_interface->isRemoteRequest() << 1); - if(check) *check = true; - - }else{ - if(check) *check = false; - *id = 0x0; - } -} - -void epos4::printCANframe(unsigned char *data, uint8_t *len, uint32_t *id, uint8_t *type) -{ - printk(*id, HEX); - printk(" | "); - - char buffer[2] = {0}; - - for( uint8_t i = 0; i < *len; i += 1 ) - { - // printk(data[i],HEX); - sprintf(buffer, "%02x", data[i]); - printk(buffer); - printk(" "); - } - printk(""); -} */ diff --git a/zephyr/epos_controller/src/epos4/epos4.h b/Library/epos4/epos4.h similarity index 86% rename from zephyr/epos_controller/src/epos4/epos4.h rename to Library/epos4/epos4.h index 8e087c5..39f4681 100644 --- a/zephyr/epos_controller/src/epos4/epos4.h +++ b/Library/epos4/epos4.h @@ -3,6 +3,7 @@ #include #include +#include #include #include #include @@ -12,7 +13,7 @@ class epos4 { public: - epos4(uint32_t canid_epos, uint32_t canid_self, const struct device *CAN_INTERFACE, struct k_msgq *my_can_msgq1, struct k_msgq *my_can_msgq2, struct zcan_frame *rx_frame); + epos4(uint32_t canid_epos, uint32_t canid_self, const struct device *CAN_INTERFACE, struct k_msgq *my_can_msgq1, struct k_msgq *my_can_msgq2, struct zcan_frame *rx_frame, struct k_mutex *blocker_can); void init(); void initSI(); @@ -33,14 +34,24 @@ class epos4 void checkReceivedData(unsigned char *data, uint8_t *len, uint32_t *id, uint8_t *type,bool *check=NULL); void printCANframe(unsigned char *data, uint8_t *len, uint32_t *id, uint8_t *type); - - + void sendFrame(uint8_t *data_pointer, uint8_t size, uint32_t canid = 0x00); const struct device *_can_interface; + struct k_mutex *_blocker_can; int32_t position = 0x00; int32_t velocity = 0x00; int16_t torque = 0x00; + /** + * @addtogroup DeviceControlCommands + * @brief Device Control Commands + * @details With the measuring mode we can decide which measured values are sent cyclically by the Epos controller. When zero, it sends the position and speed. When unequal zero, it sends position and torque. + * @{ + */ + int16_t measure_mode = 0; + /** @} */ + + bool data_mutex = true; int _softwareVersion; int _hardwareVersion; @@ -98,6 +109,7 @@ class epos4 * @addtogroup TxPDO config * @brief set config for transmition pdos * @details For more details look in the EPOS4 Communication Firmaware Specification - 6.2.21 Transmit PDO 1 parameter + * * @{ */ // TxPDO 1 @@ -105,9 +117,11 @@ class epos4 unsigned char pdo_inhibit_time_TxPDO1[8] = {0x22, 0x00, 0x18, 0x03, 0x01, 0x00, 0x00, 0x00}; unsigned char pdo_number_of_mapped_objects_TxPDO1[8] = {0x22, 0x00, 0x1A, 0x00, 0x02, 0x00, 0x00, 0x00}; unsigned char pdo_number_of_mapped_objects_null_TxPDO1[8] = {0x22, 0x00, 0x1A, 0x00, 0x00, 0x00, 0x00, 0x00}; - unsigned char pdo_first_mapped_obj_position_TxPDO1[8] = {0x23, 0x00, 0x1A, 0x01, 0x20, 0x00, 0x64, 0x60}; // 104 Grad = 120000 inc - //unsigned char pdo_first_mapped_obj_velocity_TxPDO1[8] = {0x23, 0x00, 0x1A, 0x02, 0x20, 0x00, 0x6C, 0x60}; // e-10 rpm - unsigned char pdo_first_mapped_obj_velocity_TxPDO1[8] = {0x22, 0x00, 0x1A, 0x02, 0x10, 0x00, 0x77, 0x60}; // e-10 rpm + + unsigned char pdo_first_mapped_obj_position_TxPDO1[8] = {0x23, 0x00, 0x1A, 0x01, 0x20, 0x00, 0x64, 0x60}; // 104 Grad = 120000 inc + //unsigned char pdo_first_mapped_obj_velocity_TxPDO1[8] = {0x23, 0x00, 0x1A, 0x02, 0x20, 0x00, 0x6C, 0x60}; // velocity [mrpm] | 6.2.98 Velocity actual value + unsigned char pdo_first_mapped_obj_velocity_TxPDO1[8] = {0x23, 0x00, 0x1A, 0x02, 0x20, 0x01, 0xE5, 0x60}; // velocity [mrpm] | 6.2.124.1 Velocity actual value sensor 1 + unsigned char pdo_first_mapped_obj_torque_TxPDO1[8] = {0x22, 0x00, 0x1A, 0x02, 0x10, 0x00, 0x77, 0x60}; // torque*10**(-6) [Nm] // TxPDO 2 unsigned char pdo_transmissiontype_TxPDO2[8] = {0x22, 0x01, 0x18, 0x02, 0x01, 0x00, 0x00, 0x00}; @@ -150,6 +164,7 @@ class epos4 struct k_msgq *_my_can_msgq1; struct k_msgq *_my_can_msgq2; struct zcan_frame *_rx_frame; + }; diff --git a/README.md b/README.md index bf3c235..2b10707 100644 --- a/README.md +++ b/README.md @@ -1,51 +1,55 @@ -**Over the past six months, we have refined our documentation for intere purposes and made it more detailed. This will be published in the next few weeks.** -# epos4 +# Epos4 on Zephyr -This project allows the control of one or more EPOS4 motor controllers from Maxon via CAN. +This project enables the control of one or more EPOS4 motor controllers from Maxon via CAN. -The control can be done via a microcontroller with CAN interface. In this project, an Arduino example (Arduino Uno and MEGA) and a Zephyr project were implemented. Zephyr was run on a STM32F407G-DISC1 with an external CAN transiever. -For easier handling with CAN, a C++ class was implemented that provides various functions to communicate with the EPOS4. The class was adapted for Arduino and Zephyr. +The control can be done via a microcontroller with CAN interface. In the current version the libary is only implemented for Zephyr. In the past the project was also run on an Arduino. Please have a look at the first release. Zephyr was run on a STM32F407G-DISC1 with an external CAN transiever. +For an easier handling with CAN a C++ class was implemented, which provides different functions to communicate with the EPOS4. -## arduino-seeed implementation +For copyright reasons there is no public detailed documentation about the project. Most of the code is commented inline. Especially the examples. +Since the lib was developed for Zephyr it is recommended to have some experience with it. Furthermore you should be familiar with the CAN interface of EPOS4. The documents added here can help. -Libary for the Arduino (tested on the Arduino UNO 8 bit) with the CAN-BUS Shield V2.0 with the MCP2515. The attached mcp2515_can.h and mcp2515_can_dfs.h were used. +## General +Zephyr version 3.1.0 was used in the project. A Zephyr installation is required to use the code. -Implemented are different PDO and SDO send functions. For the state machine of the EPOS4 the epos4::init() was written, which queries the current state and switches on the EPOS4 accordingly. +For a specific version you can call `west init` as follows: +``` +west init -m https://github.com/zephyrproject-rtos/zephyr --mr zephyr-v3.1.0 +``` -For the "Profile Position Mode" (PPM), the "Cyclic Synchronous Position Mode" (CSP), the "Cyclic Synchronous Velocity Mode" (CSV) and the "Cyclic Synchronous Torque Mode" init functions were written and test functions were provided in the .ino file. Depending on the test function (or use of own functions) the corresponding mode must be initialized before. +The Epos4 works in different operating modes. Of these, an interface has been implemented for "profile position mode" (PPM), "cyclic synchronous position" (CSP), "cyclic synchronous velocity" (CSV) and "cyclic synchronous torque" (CST). Check the `epos4.h` for more information. -When initializing the epos4 object the configPDO function is called which sets the TxPDOs and RxPDOs according to the variables in the epos4.h file. +There are 3 different applications in Examples. -In the example, note that no interraupts were used for the timing of the synchronisation except for the cst_test function. +1. **epos_basic** is an example application where the EPOS is operated in CST mode. It receives a predefined sequence of torques. -In general, the libary for the arduino contains the same functionality as the zephyr implementation. The only difference is the function to send a CAN frame. In a future generalisation, a call back function could be defined which implements this functionality outside the libary. +2. **epos_matlab** is also an example application in CST mode. Instead of an arbitrary sequence, the EPOS is operated here in a closed control loop. The manipulated variables are calculated using a model that was created in Simulink and generated with the Simulink code to C code. -## zephyr implementation +3. **epos_parameter_identification** is also an example application in CST mode. Here a torque trajectory is specified. The initial position or speed is measured and all relevant data is sent via the UART interface. This way the hardware can be identified. -Generally, the same applies as described in the Arduino section. The implementation on zephyr is an extension. +**epos_matlab** is described in more detail below: +Zephyr is an open-source real-time operating system developed by the Linux Foundation for the IoT domain. More information and a detailed documentation can be found at: https://docs.zephyrproject.org/latest/ For an easy start into the development I recommend to reprogram an introductory tutorial from the docs. -There are 3 different applications in epos4_zephyr. +Since Zephyr uses cmake, the compiling information is specified via the [CMakeLists.txt](Examples/epos_matlab/CMakeLists.txt). There, among other things, the EPOS4 library and all C-generated files from Simulink are made known to the compiler. +Simulink generates the files depending on the name of the respective subsystem. If the CMakeLists is not to be processed, care must be taken to name the corresponding subsystem in Simulink in the same way. -1. **epos_controller** is the main application and shows exemplarily how a subsystem (named Atmoic) from Simulink (code generated in C without MAT file logging) can be integrated into a closed loop. An example without a subsystem of Simulink is given in main.cpp. This code shows how the library can be used to control the epos4 motor driver. There, however, no interrupt functionality was implemented but only the PPM mode was used (see epos4::moveToPosition). For the cyclic sync modes, see pos_controller.cpp to understand how interrupts were used for the timing of the sync. +The Simulink subsystem was compiled in C using the Simulink coder. It is also possible to compile in C++, but then Simulink uses classes and the sample code must be adapted accordingly. +In general, please note that logging for code generation must be switched off (MAT file logging). The STM32 cannot write to files by default. +When Simulink generates C code, be sure to set the configuration `CONFIG_CPLUSPLUS=y` in the [prj.conf](epos4_zephyr/epos_conrtoller/prj.conf) and to include the libary as follows to avoid the include c++ mangle: +```c++ +#ifdef __cplusplus +extern "C" +{ +#endif +#include "Atomic.h" +#ifdef __cplusplus +} +#endif +``` -2. **epos_controller_mcp2515** Provides the same functionality. However, instead of the onboard CAN devices of the STM32F407G, it uses the Arduino Shield MCP2515 which is controlled via SPI. +The CAN interface of the STM32 was managed by the [stm32f4_disco.overlay](epos4_zephyr/epos_conrtoller/stm32f4_disco.overlay) devicetree extension. -3. **epos_controller_model** only shows an integration of a Simulink subsystem in C. - -**epos_controller** is described in more detail below: -Zephyr is an open source real-time operating system developed by the Linux Foundation for the IoT domain. -More information and detailed documentation can be found at https://docs.zephyrproject.org/latest/. -For an easy start into the development, I recommend reprogramming an introductory tutorial from the docs. - -Since Zephyr uses cmake, the compiling information is given in the [CMakeLists.txt](epos4_zephyr/epos_conrtoller/CMakeLists.txt). Among other things, the EPOS4 library and all C-generated files from Simulink are made known to the compiler there. -Simulink generates the files depending on the name of the respective subsystem. If the CMakeLists are not to be edited, make sure that the corresponding subsystem is named the same in Simulink. - -The CAN interface of the STM32 was managed via the [stm32f4_disco.overlay](epos4_zephyr/epos_conrtoller/stm32f4_disco.overlay) Devicetree extension. - -Simulink libarys needed to run the simulink code generation are not available here. - -# collection of important commands -## compile and flash +# Collection of important commands +## Compile and flash First, `west` and `zephyr` must be installed. Read about this at `https://docs.zephyrproject.org/latest/getting_started/index.html`. west build -b @@ -53,14 +57,16 @@ First, `west` and `zephyr` must be installed. Read about this at `https://docs.z for certain changes, the >build< folder must be deleted before the build. You can read more about this in the zephyr docs. So far the board `stm32f4_disco` was used in the project -## Plotter with virtual environment -The plotter can be used to plot data that is sent from the controller to the pc via uart. +## Plotter +The plotter makes it possible to display and evaluate the data sent via CAN to the microcontroller via uart on the PC. The data can be displayed graphically or written to files. This allows e.g. a parameter identification. + +### Virtual environment If necessary, the virtual environment must be started first. source venv/bin/activate then the plotter can be started with: - python3 pythonploter2.py + python3 plotter.py ## Device trees Information about the board and its hardware can be changed and learned via the Zephyr device trees. @@ -75,5 +81,5 @@ Also the interrupt frequency for sending the sync frame must be adjusted to the # Note If you have any questions, criticism, suggestions or ideas for improvement, please feel free to contact us. A more detailed code documentation will also be written to simplify the use. -The code was developed as part of a project at RWTH Aachen University. Some content cannot be presented here for legal reasons. For more information, please contact jakob.gebler@rwth-aachen.de. -The use is on own guarantee, I take over no responsibility with the use of the Libary. +The code was developed as part of a project at Medit - RWTH Aachen University. Some content cannot be presented here for legal reasons. For more information, please contact jakob.gebler@rwth-aachen.de. +The use is on own guarantee, I take over no responsibility with the use of the Libary. \ No newline at end of file diff --git a/arduino/.vscode/arduino.json b/arduino/.vscode/arduino.json deleted file mode 100644 index 681e2d7..0000000 --- a/arduino/.vscode/arduino.json +++ /dev/null @@ -1,8 +0,0 @@ -{ - "board": "arduino:avr:mega", - "programmer": "AVR ISP", - "sketch": "examples/example/example.ino", - "port": "/dev/ttyUSB0", - "prebuild": "sh prebuild.sh", - "configuration": "cpu=atmega2560" -} \ No newline at end of file diff --git a/arduino/.vscode/c_cpp_properties.json b/arduino/.vscode/c_cpp_properties.json deleted file mode 100644 index 310aeb5..0000000 --- a/arduino/.vscode/c_cpp_properties.json +++ /dev/null @@ -1,565 +0,0 @@ -{ - "version": 4, - "configurations": [ - { - "name": "Linux", - "compilerPath": "/usr/bin/gcc", - "compilerArgs": [], - "intelliSenseMode": "linux-gcc-x64", - "includePath": [ - "/home/gebler/Downloads/arduino-1.8.13-linux64/arduino-1.8.13/libraries/Esplora/src", - "/home/gebler/Downloads/arduino-1.8.13-linux64/arduino-1.8.13/tools/**", - "/home/gebler/Arduino/libraries/**", - "/home/gebler/Downloads/arduino-1.8.13-linux64/arduino-1.8.13/libraries/**", - "/home/gebler/Downloads/arduino-1.8.13-linux64/arduino-1.8.13/hardware/tools/**", - "/home/gebler/Downloads/arduino-1.8.13-linux64/arduino-1.8.13/hardware/arduino/avr/**", - "/home/gebler/Arduino/epos4-arduino-seeed/src/epos4/**", - "/home/gebler/Arduino/epos4-arduino-seeed/src/mcp/**" - ], - "forcedInclude": [ - "/home/gebler/Downloads/arduino-1.8.13-linux64/arduino-1.8.13/hardware/arduino/avr/cores/arduino/Arduino.h" - ], - "cStandard": "gnu11", - "cppStandard": "gnu++14", - "defines": [ - "USBCON" - ] - }, - { - "name": "Arduino", - "compilerPath": "/home/gebler/Downloads/arduino-1.8.13-linux64/arduino-1.8.13/hardware/tools/avr/bin/avr-g++", - "compilerArgs": [ - "-Wall", - "-Wextra", - "-std=gnu++11", - "-fpermissive", - "-fno-exceptions", - "-ffunction-sections", - "-fdata-sections", - "-fno-threadsafe-statics", - "-Wno-error=narrowing" - ], - "intelliSenseMode": "gcc-x64", - "includePath": [ - "/home/gebler/Downloads/arduino-1.8.13-linux64/arduino-1.8.13/hardware/arduino/avr/cores/arduino", - "/home/gebler/Downloads/arduino-1.8.13-linux64/arduino-1.8.13/hardware/arduino/avr/variants/mega", - "/home/gebler/Arduino/libraries/epos4_seeed", - "/home/gebler/Downloads/arduino-1.8.13-linux64/arduino-1.8.13/hardware/arduino/avr/libraries/SPI/src", - "/home/gebler/Downloads/arduino-1.8.13-linux64/arduino-1.8.13/hardware/arduino/avr/libraries/SoftwareSerial/src", - "/home/gebler/Downloads/arduino-1.8.13-linux64/arduino-1.8.13/hardware/tools/avr/lib/gcc/avr/7.3.0/include", - "/home/gebler/Downloads/arduino-1.8.13-linux64/arduino-1.8.13/hardware/tools/avr/lib/gcc/avr/7.3.0/include-fixed", - "/home/gebler/Downloads/arduino-1.8.13-linux64/arduino-1.8.13/hardware/tools/avr/avr/include" - ], - "forcedInclude": [ - "/home/gebler/Downloads/arduino-1.8.13-linux64/arduino-1.8.13/hardware/arduino/avr/cores/arduino/Arduino.h" - ], - "cStandard": "c11", - "cppStandard": "c++11", - "defines": [ - "F_CPU=16000000L", - "ARDUINO=10813", - "ARDUINO_AVR_MEGA2560", - "ARDUINO_ARCH_AVR", - "__DBL_MIN_EXP__=(-125)", - "__HQ_FBIT__=15", - "__cpp_attributes=200809", - "__UINT_LEAST16_MAX__=0xffffU", - "__ATOMIC_ACQUIRE=2", - "__SFRACT_IBIT__=0", - "__FLT_MIN__=1.17549435e-38F", - "__GCC_IEC_559_COMPLEX=0", - "__BUILTIN_AVR_SLEEP=1", - "__BUILTIN_AVR_COUNTLSULLK=1", - "__cpp_aggregate_nsdmi=201304", - "__BUILTIN_AVR_COUNTLSULLR=1", - "__UFRACT_MAX__=0XFFFFP-16UR", - "__UINT_LEAST8_TYPE__=unsigned char", - "__DQ_FBIT__=63", - "__INTMAX_C(c)=c ## LL", - "__ULFRACT_FBIT__=32", - "__SACCUM_EPSILON__=0x1P-7HK", - "__CHAR_BIT__=8", - "__USQ_IBIT__=0", - "__UINT8_MAX__=0xff", - "__ACCUM_FBIT__=15", - "__WINT_MAX__=0x7fff", - "__FLT32_MIN_EXP__=(-125)", - "__cpp_static_assert=200410", - "__USFRACT_FBIT__=8", - "__ORDER_LITTLE_ENDIAN__=1234", - "__SIZE_MAX__=0xffffU", - "__WCHAR_MAX__=0x7fff", - "__LACCUM_IBIT__=32", - "__DBL_DENORM_MIN__=double(1.40129846e-45L)", - "__GCC_ATOMIC_CHAR_LOCK_FREE=1", - "__GCC_IEC_559=0", - "__FLT_EVAL_METHOD__=0", - "__BUILTIN_AVR_LLKBITS=1", - "__cpp_binary_literals=201304", - "__LLACCUM_MAX__=0X7FFFFFFFFFFFFFFFP-47LLK", - "__GCC_ATOMIC_CHAR32_T_LOCK_FREE=1", - "__BUILTIN_AVR_HKBITS=1", - "__BUILTIN_AVR_BITSLLK=1", - "__FRACT_FBIT__=15", - "__BUILTIN_AVR_BITSLLR=1", - "__cpp_variadic_templates=200704", - "__UINT_FAST64_MAX__=0xffffffffffffffffULL", - "__SIG_ATOMIC_TYPE__=char", - "__BUILTIN_AVR_UHKBITS=1", - "__UACCUM_FBIT__=16", - "__DBL_MIN_10_EXP__=(-37)", - "__FINITE_MATH_ONLY__=0", - "__cpp_variable_templates=201304", - "__LFRACT_IBIT__=0", - "__GNUC_PATCHLEVEL__=0", - "__FLT32_HAS_DENORM__=1", - "__LFRACT_MAX__=0X7FFFFFFFP-31LR", - "__UINT_FAST8_MAX__=0xff", - "__has_include(STR)=__has_include__(STR)", - "__DEC64_MAX_EXP__=385", - "__INT8_C(c)=c", - "__INT_LEAST8_WIDTH__=8", - "__UINT_LEAST64_MAX__=0xffffffffffffffffULL", - "__SA_FBIT__=15", - "__SHRT_MAX__=0x7fff", - "__LDBL_MAX__=3.40282347e+38L", - "__FRACT_MAX__=0X7FFFP-15R", - "__UFRACT_FBIT__=16", - "__UFRACT_MIN__=0.0UR", - "__UINT_LEAST8_MAX__=0xff", - "__GCC_ATOMIC_BOOL_LOCK_FREE=1", - "__UINTMAX_TYPE__=long long unsigned int", - "__LLFRACT_EPSILON__=0x1P-63LLR", - "__BUILTIN_AVR_DELAY_CYCLES=1", - "__DEC32_EPSILON__=1E-6DF", - "__FLT_EVAL_METHOD_TS_18661_3__=0", - "__UINT32_MAX__=0xffffffffUL", - "__GXX_EXPERIMENTAL_CXX0X__=1", - "__ULFRACT_MAX__=0XFFFFFFFFP-32ULR", - "__TA_IBIT__=16", - "__LDBL_MAX_EXP__=128", - "__WINT_MIN__=(-__WINT_MAX__ - 1)", - "__INT_LEAST16_WIDTH__=16", - "__ULLFRACT_MIN__=0.0ULLR", - "__SCHAR_MAX__=0x7f", - "__WCHAR_MIN__=(-__WCHAR_MAX__ - 1)", - "__INT64_C(c)=c ## LL", - "__DBL_DIG__=6", - "__GCC_ATOMIC_POINTER_LOCK_FREE=1", - "__AVR_HAVE_SPH__=1", - "__LLACCUM_MIN__=(-0X1P15LLK-0X1P15LLK)", - "__BUILTIN_AVR_KBITS=1", - "__BUILTIN_AVR_ABSK=1", - "__BUILTIN_AVR_ABSR=1", - "__SIZEOF_INT__=2", - "__SIZEOF_POINTER__=2", - "__GCC_ATOMIC_CHAR16_T_LOCK_FREE=1", - "__USACCUM_IBIT__=8", - "__USER_LABEL_PREFIX__", - "__STDC_HOSTED__=1", - "__LDBL_HAS_INFINITY__=1", - "__LFRACT_MIN__=(-0.5LR-0.5LR)", - "__HA_IBIT__=8", - "__FLT32_DIG__=6", - "__TQ_IBIT__=0", - "__FLT_EPSILON__=1.19209290e-7F", - "__GXX_WEAK__=1", - "__SHRT_WIDTH__=16", - "__USFRACT_IBIT__=0", - "__LDBL_MIN__=1.17549435e-38L", - "__FRACT_MIN__=(-0.5R-0.5R)", - "__AVR_SFR_OFFSET__=0x20", - "__DEC32_MAX__=9.999999E96DF", - "__cpp_threadsafe_static_init=200806", - "__DA_IBIT__=32", - "__INT32_MAX__=0x7fffffffL", - "__UQQ_FBIT__=8", - "__INT_WIDTH__=16", - "__SIZEOF_LONG__=4", - "__UACCUM_MAX__=0XFFFFFFFFP-16UK", - "__UINT16_C(c)=c ## U", - "__PTRDIFF_WIDTH__=16", - "__DECIMAL_DIG__=9", - "__LFRACT_EPSILON__=0x1P-31LR", - "__AVR_2_BYTE_PC__=1", - "__ULFRACT_MIN__=0.0ULR", - "__INTMAX_WIDTH__=64", - "__has_include_next(STR)=__has_include_next__(STR)", - "__BUILTIN_AVR_ULLRBITS=1", - "__LDBL_HAS_QUIET_NAN__=1", - "__ULACCUM_IBIT__=32", - "__UACCUM_EPSILON__=0x1P-16UK", - "__BUILTIN_AVR_SEI=1", - "__GNUC__=7", - "__ULLACCUM_MAX__=0XFFFFFFFFFFFFFFFFP-48ULLK", - "__cpp_delegating_constructors=200604", - "__HQ_IBIT__=0", - "__BUILTIN_AVR_SWAP=1", - "__FLT_HAS_DENORM__=1", - "__SIZEOF_LONG_DOUBLE__=4", - "__BIGGEST_ALIGNMENT__=1", - "__STDC_UTF_16__=1", - "__UINT24_MAX__=16777215UL", - "__BUILTIN_AVR_NOP=1", - "__GNUC_STDC_INLINE__=1", - "__DQ_IBIT__=0", - "__FLT32_HAS_INFINITY__=1", - "__DBL_MAX__=double(3.40282347e+38L)", - "__ULFRACT_IBIT__=0", - "__cpp_raw_strings=200710", - "__INT_FAST32_MAX__=0x7fffffffL", - "__DBL_HAS_INFINITY__=1", - "__INT64_MAX__=0x7fffffffffffffffLL", - "__ACCUM_IBIT__=16", - "__DEC32_MIN_EXP__=(-94)", - "__BUILTIN_AVR_UKBITS=1", - "__INTPTR_WIDTH__=16", - "__BUILTIN_AVR_FMULSU=1", - "__LACCUM_MAX__=0X7FFFFFFFFFFFFFFFP-31LK", - "__INT_FAST16_TYPE__=int", - "__LDBL_HAS_DENORM__=1", - "__BUILTIN_AVR_BITSK=1", - "__BUILTIN_AVR_BITSR=1", - "__cplusplus=201402L", - "__cpp_ref_qualifiers=200710", - "__DEC128_MAX__=9.999999999999999999999999999999999E6144DL", - "__INT_LEAST32_MAX__=0x7fffffffL", - "__USING_SJLJ_EXCEPTIONS__=1", - "__DEC32_MIN__=1E-95DF", - "__ACCUM_MAX__=0X7FFFFFFFP-15K", - "__DEPRECATED=1", - "__cpp_rvalue_references=200610", - "__DBL_MAX_EXP__=128", - "__USACCUM_EPSILON__=0x1P-8UHK", - "__WCHAR_WIDTH__=16", - "__FLT32_MAX__=3.40282347e+38F32", - "__DEC128_EPSILON__=1E-33DL", - "__SFRACT_MAX__=0X7FP-7HR", - "__FRACT_IBIT__=0", - "__PTRDIFF_MAX__=0x7fff", - "__UACCUM_MIN__=0.0UK", - "__UACCUM_IBIT__=16", - "__BUILTIN_AVR_NOPS=1", - "__BUILTIN_AVR_WDR=1", - "__FLT32_HAS_QUIET_NAN__=1", - "__GNUG__=7", - "__LONG_LONG_MAX__=0x7fffffffffffffffLL", - "__SIZEOF_SIZE_T__=2", - "__ULACCUM_MAX__=0XFFFFFFFFFFFFFFFFP-32ULK", - "__cpp_rvalue_reference=200610", - "__cpp_nsdmi=200809", - "__SIZEOF_WINT_T__=2", - "__LONG_LONG_WIDTH__=64", - "__cpp_initializer_lists=200806", - "__FLT32_MAX_EXP__=128", - "__SA_IBIT__=16", - "__ULLACCUM_MIN__=0.0ULLK", - "__BUILTIN_AVR_ROUNDUHK=1", - "__BUILTIN_AVR_ROUNDUHR=1", - "__cpp_hex_float=201603", - "__GXX_ABI_VERSION=1011", - "__INT24_MAX__=8388607L", - "__UTA_FBIT__=48", - "__FLT_MIN_EXP__=(-125)", - "__USFRACT_MAX__=0XFFP-8UHR", - "__UFRACT_IBIT__=0", - "__BUILTIN_AVR_ROUNDFX=1", - "__BUILTIN_AVR_ROUNDULK=1", - "__BUILTIN_AVR_ROUNDULR=1", - "__cpp_lambdas=200907", - "__BUILTIN_AVR_COUNTLSLLK=1", - "__BUILTIN_AVR_COUNTLSLLR=1", - "__BUILTIN_AVR_ROUNDHK=1", - "__INT_FAST64_TYPE__=long long int", - "__BUILTIN_AVR_ROUNDHR=1", - "__DBL_MIN__=double(1.17549435e-38L)", - "__BUILTIN_AVR_COUNTLSK=1", - "__BUILTIN_AVR_ROUNDLK=1", - "__BUILTIN_AVR_COUNTLSR=1", - "__BUILTIN_AVR_ROUNDLR=1", - "__LACCUM_MIN__=(-0X1P31LK-0X1P31LK)", - "__ULLACCUM_FBIT__=48", - "__BUILTIN_AVR_LKBITS=1", - "__ULLFRACT_EPSILON__=0x1P-64ULLR", - "__DEC128_MIN__=1E-6143DL", - "__REGISTER_PREFIX__", - "__UINT16_MAX__=0xffffU", - "__DBL_HAS_DENORM__=1", - "__BUILTIN_AVR_ULKBITS=1", - "__ACCUM_MIN__=(-0X1P15K-0X1P15K)", - "__AVR_ARCH__=2", - "__SQ_IBIT__=0", - "__FLT32_MIN__=1.17549435e-38F32", - "__UINT8_TYPE__=unsigned char", - "__BUILTIN_AVR_ROUNDUK=1", - "__BUILTIN_AVR_ROUNDUR=1", - "__UHA_FBIT__=8", - "__NO_INLINE__=1", - "__SFRACT_MIN__=(-0.5HR-0.5HR)", - "__UTQ_FBIT__=128", - "__FLT_MANT_DIG__=24", - "__LDBL_DECIMAL_DIG__=9", - "__VERSION__=\"7.3.0\"", - "__UINT64_C(c)=c ## ULL", - "__ULLFRACT_FBIT__=64", - "__cpp_unicode_characters=200704", - "__FRACT_EPSILON__=0x1P-15R", - "__ULACCUM_MIN__=0.0ULK", - "__UDA_FBIT__=32", - "__cpp_decltype_auto=201304", - "__LLACCUM_EPSILON__=0x1P-47LLK", - "__GCC_ATOMIC_INT_LOCK_FREE=1", - "__FLT32_MANT_DIG__=24", - "__BUILTIN_AVR_BITSUHK=1", - "__BUILTIN_AVR_BITSUHR=1", - "__FLOAT_WORD_ORDER__=__ORDER_LITTLE_ENDIAN__", - "__USFRACT_MIN__=0.0UHR", - "__BUILTIN_AVR_BITSULK=1", - "__ULLACCUM_IBIT__=16", - "__BUILTIN_AVR_BITSULR=1", - "__UQQ_IBIT__=0", - "__BUILTIN_AVR_LLRBITS=1", - "__SCHAR_WIDTH__=8", - "__BUILTIN_AVR_BITSULLK=1", - "__BUILTIN_AVR_BITSULLR=1", - "__INT32_C(c)=c ## L", - "__DEC64_EPSILON__=1E-15DD", - "__ORDER_PDP_ENDIAN__=3412", - "__DEC128_MIN_EXP__=(-6142)", - "__UHQ_FBIT__=16", - "__LLACCUM_FBIT__=47", - "__FLT32_MAX_10_EXP__=38", - "__BUILTIN_AVR_ROUNDULLK=1", - "__BUILTIN_AVR_ROUNDULLR=1", - "__INT_FAST32_TYPE__=long int", - "__BUILTIN_AVR_HRBITS=1", - "__UINT_LEAST16_TYPE__=unsigned int", - "__BUILTIN_AVR_UHRBITS=1", - "__INT16_MAX__=0x7fff", - "__SIZE_TYPE__=unsigned int", - "__UINT64_MAX__=0xffffffffffffffffULL", - "__UDQ_FBIT__=64", - "__INT8_TYPE__=signed char", - "__cpp_digit_separators=201309", - "__ELF__=1", - "__ULFRACT_EPSILON__=0x1P-32ULR", - "__LLFRACT_FBIT__=63", - "__FLT_RADIX__=2", - "__INT_LEAST16_TYPE__=int", - "__BUILTIN_AVR_ABSFX=1", - "__LDBL_EPSILON__=1.19209290e-7L", - "__UINTMAX_C(c)=c ## ULL", - "__INT24_MIN__=(-__INT24_MAX__-1)", - "__SACCUM_MAX__=0X7FFFP-7HK", - "__BUILTIN_AVR_ABSHR=1", - "__SIG_ATOMIC_MAX__=0x7f", - "__GCC_ATOMIC_WCHAR_T_LOCK_FREE=1", - "__cpp_sized_deallocation=201309", - "__SIZEOF_PTRDIFF_T__=2", - "__AVR=1", - "__BUILTIN_AVR_ABSLK=1", - "__BUILTIN_AVR_ABSLR=1", - "__LACCUM_EPSILON__=0x1P-31LK", - "__DEC32_SUBNORMAL_MIN__=0.000001E-95DF", - "__INT_FAST16_MAX__=0x7fff", - "__UINT_FAST32_MAX__=0xffffffffUL", - "__UINT_LEAST64_TYPE__=long long unsigned int", - "__USACCUM_MAX__=0XFFFFP-8UHK", - "__SFRACT_EPSILON__=0x1P-7HR", - "__FLT_HAS_QUIET_NAN__=1", - "__FLT_MAX_10_EXP__=38", - "__LONG_MAX__=0x7fffffffL", - "__DEC128_SUBNORMAL_MIN__=0.000000000000000000000000000000001E-6143DL", - "__FLT_HAS_INFINITY__=1", - "__cpp_unicode_literals=200710", - "__USA_FBIT__=16", - "__UINT_FAST16_TYPE__=unsigned int", - "__DEC64_MAX__=9.999999999999999E384DD", - "__INT_FAST32_WIDTH__=32", - "__BUILTIN_AVR_RBITS=1", - "__CHAR16_TYPE__=unsigned int", - "__PRAGMA_REDEFINE_EXTNAME=1", - "__SIZE_WIDTH__=16", - "__INT_LEAST16_MAX__=0x7fff", - "__DEC64_MANT_DIG__=16", - "__UINT_LEAST32_MAX__=0xffffffffUL", - "__SACCUM_FBIT__=7", - "__FLT32_DENORM_MIN__=1.40129846e-45F32", - "__GCC_ATOMIC_LONG_LOCK_FREE=1", - "__SIG_ATOMIC_WIDTH__=8", - "__INT_LEAST64_TYPE__=long long int", - "__INT16_TYPE__=int", - "__INT_LEAST8_TYPE__=signed char", - "__SQ_FBIT__=31", - "__DEC32_MAX_EXP__=97", - "__INT_FAST8_MAX__=0x7f", - "__INTPTR_MAX__=0x7fff", - "__QQ_FBIT__=7", - "__cpp_range_based_for=200907", - "__UTA_IBIT__=16", - "__AVR_ERRATA_SKIP__=1", - "__FLT32_MIN_10_EXP__=(-37)", - "__LDBL_MANT_DIG__=24", - "__SFRACT_FBIT__=7", - "__SACCUM_MIN__=(-0X1P7HK-0X1P7HK)", - "__DBL_HAS_QUIET_NAN__=1", - "__SIG_ATOMIC_MIN__=(-__SIG_ATOMIC_MAX__ - 1)", - "AVR=1", - "__BUILTIN_AVR_FMULS=1", - "__cpp_return_type_deduction=201304", - "__INTPTR_TYPE__=int", - "__UINT16_TYPE__=unsigned int", - "__WCHAR_TYPE__=int", - "__SIZEOF_FLOAT__=4", - "__AVR__=1", - "__BUILTIN_AVR_INSERT_BITS=1", - "__USQ_FBIT__=32", - "__UINTPTR_MAX__=0xffffU", - "__INT_FAST64_WIDTH__=64", - "__DEC64_MIN_EXP__=(-382)", - "__cpp_decltype=200707", - "__FLT32_DECIMAL_DIG__=9", - "__INT_FAST64_MAX__=0x7fffffffffffffffLL", - "__GCC_ATOMIC_TEST_AND_SET_TRUEVAL=1", - "__FLT_DIG__=6", - "__UINT_FAST64_TYPE__=long long unsigned int", - "__BUILTIN_AVR_BITSHK=1", - "__BUILTIN_AVR_BITSHR=1", - "__INT_MAX__=0x7fff", - "__LACCUM_FBIT__=31", - "__USACCUM_MIN__=0.0UHK", - "__UHA_IBIT__=8", - "__INT64_TYPE__=long long int", - "__BUILTIN_AVR_BITSLK=1", - "__BUILTIN_AVR_BITSLR=1", - "__FLT_MAX_EXP__=128", - "__UTQ_IBIT__=0", - "__DBL_MANT_DIG__=24", - "__cpp_inheriting_constructors=201511", - "__BUILTIN_AVR_ULLKBITS=1", - "__INT_LEAST64_MAX__=0x7fffffffffffffffLL", - "__DEC64_MIN__=1E-383DD", - "__WINT_TYPE__=int", - "__UINT_LEAST32_TYPE__=long unsigned int", - "__SIZEOF_SHORT__=2", - "__ULLFRACT_IBIT__=0", - "__LDBL_MIN_EXP__=(-125)", - "__UDA_IBIT__=32", - "__WINT_WIDTH__=16", - "__INT_LEAST8_MAX__=0x7f", - "__LFRACT_FBIT__=31", - "__LDBL_MAX_10_EXP__=38", - "__ATOMIC_RELAXED=0", - "__DBL_EPSILON__=double(1.19209290e-7L)", - "__BUILTIN_AVR_BITSUK=1", - "__BUILTIN_AVR_BITSUR=1", - "__UINT8_C(c)=c", - "__INT_LEAST32_TYPE__=long int", - "__BUILTIN_AVR_URBITS=1", - "__SIZEOF_WCHAR_T__=2", - "__LLFRACT_MAX__=0X7FFFFFFFFFFFFFFFP-63LLR", - "__TQ_FBIT__=127", - "__INT_FAST8_TYPE__=signed char", - "__ULLACCUM_EPSILON__=0x1P-48ULLK", - "__BUILTIN_AVR_ROUNDK=1", - "__BUILTIN_AVR_ROUNDR=1", - "__UHQ_IBIT__=0", - "__LLACCUM_IBIT__=16", - "__FLT32_EPSILON__=1.19209290e-7F32", - "__DBL_DECIMAL_DIG__=9", - "__STDC_UTF_32__=1", - "__INT_FAST8_WIDTH__=8", - "__DEC_EVAL_METHOD__=2", - "__TA_FBIT__=47", - "__UDQ_IBIT__=0", - "__ORDER_BIG_ENDIAN__=4321", - "__cpp_runtime_arrays=198712", - "__WITH_AVRLIBC__=1", - "__UINT64_TYPE__=long long unsigned int", - "__ACCUM_EPSILON__=0x1P-15K", - "__UINT32_C(c)=c ## UL", - "__BUILTIN_AVR_COUNTLSUHK=1", - "__INTMAX_MAX__=0x7fffffffffffffffLL", - "__cpp_alias_templates=200704", - "__BUILTIN_AVR_COUNTLSUHR=1", - "__BYTE_ORDER__=__ORDER_LITTLE_ENDIAN__", - "__FLT_DENORM_MIN__=1.40129846e-45F", - "__LLFRACT_IBIT__=0", - "__INT8_MAX__=0x7f", - "__LONG_WIDTH__=32", - "__UINT_FAST32_TYPE__=long unsigned int", - "__CHAR32_TYPE__=long unsigned int", - "__BUILTIN_AVR_COUNTLSULK=1", - "__BUILTIN_AVR_COUNTLSULR=1", - "__FLT_MAX__=3.40282347e+38F", - "__cpp_constexpr=201304", - "__USACCUM_FBIT__=8", - "__BUILTIN_AVR_COUNTLSFX=1", - "__INT32_TYPE__=long int", - "__SIZEOF_DOUBLE__=4", - "__FLT_MIN_10_EXP__=(-37)", - "__UFRACT_EPSILON__=0x1P-16UR", - "__INT_LEAST32_WIDTH__=32", - "__BUILTIN_AVR_COUNTLSHK=1", - "__BUILTIN_AVR_COUNTLSHR=1", - "__INTMAX_TYPE__=long long int", - "__BUILTIN_AVR_ABSLLK=1", - "__BUILTIN_AVR_ABSLLR=1", - "__DEC128_MAX_EXP__=6145", - "__AVR_HAVE_16BIT_SP__=1", - "__ATOMIC_CONSUME=1", - "__GNUC_MINOR__=3", - "__INT_FAST16_WIDTH__=16", - "__UINTMAX_MAX__=0xffffffffffffffffULL", - "__DEC32_MANT_DIG__=7", - "__HA_FBIT__=7", - "__BUILTIN_AVR_COUNTLSLK=1", - "__BUILTIN_AVR_COUNTLSLR=1", - "__BUILTIN_AVR_CLI=1", - "__DBL_MAX_10_EXP__=38", - "__LDBL_DENORM_MIN__=1.40129846e-45L", - "__INT16_C(c)=c", - "__cpp_generic_lambdas=201304", - "__STDC__=1", - "__PTRDIFF_TYPE__=int", - "__LLFRACT_MIN__=(-0.5LLR-0.5LLR)", - "__BUILTIN_AVR_LRBITS=1", - "__ATOMIC_SEQ_CST=5", - "__DA_FBIT__=31", - "__UINT32_TYPE__=long unsigned int", - "__BUILTIN_AVR_ROUNDLLK=1", - "__UINTPTR_TYPE__=unsigned int", - "__BUILTIN_AVR_ROUNDLLR=1", - "__USA_IBIT__=16", - "__BUILTIN_AVR_ULRBITS=1", - "__DEC64_SUBNORMAL_MIN__=0.000000000000001E-383DD", - "__DEC128_MANT_DIG__=34", - "__LDBL_MIN_10_EXP__=(-37)", - "__BUILTIN_AVR_COUNTLSUK=1", - "__BUILTIN_AVR_COUNTLSUR=1", - "__SIZEOF_LONG_LONG__=8", - "__ULACCUM_EPSILON__=0x1P-32ULK", - "__cpp_user_defined_literals=200809", - "__SACCUM_IBIT__=8", - "__GCC_ATOMIC_LLONG_LOCK_FREE=1", - "__LDBL_DIG__=6", - "__FLT_DECIMAL_DIG__=9", - "__UINT_FAST16_MAX__=0xffffU", - "__GCC_ATOMIC_SHORT_LOCK_FREE=1", - "__BUILTIN_AVR_ABSHK=1", - "__BUILTIN_AVR_FLASH_SEGMENT=1", - "__INT_LEAST64_WIDTH__=64", - "__ULLFRACT_MAX__=0XFFFFFFFFFFFFFFFFP-64ULLR", - "__UINT_FAST8_TYPE__=unsigned char", - "__USFRACT_EPSILON__=0x1P-8UHR", - "__ULACCUM_FBIT__=32", - "__QQ_IBIT__=0", - "__cpp_init_captures=201304", - "__ATOMIC_ACQ_REL=4", - "__ATOMIC_RELEASE=3", - "__BUILTIN_AVR_FMUL=1", - "USBCON" - ] - } - ] -} \ No newline at end of file diff --git a/arduino/examples/distrb.csv b/arduino/examples/distrb.csv deleted file mode 100644 index 2f93ee0..0000000 --- a/arduino/examples/distrb.csv +++ /dev/null @@ -1,2837 +0,0 @@ -0.00 0 -7 0 -0.01 0 -7 0 -0.02 0 -8 0 -0.03 0 -8 0 -0.04 0 -8 0 -0.05 0 -8 0 -0.06 0 -8 0 -0.07 0 -8 0 -0.08 0 -8 0 -0.09 0 -8 0 -0.10 0 -8 0 -0.11 0 -8 0 -0.12 0 -8 0 -0.13 0 -8 0 -0.14 0 -8 0 -0.15 0 -8 0 -0.16 0 -8 0 -0.17 0 -8 0 -0.18 0 -8 0 -0.19 0 -8 0 -0.20 0 -8 0 -0.21 0 -8 0 -0.22 0 -8 0 -0.23 0 -8 0 -0.24 0 -8 0 -0.25 0 -8 0 -0.26 0 -8 0 -0.27 0 -8 0 -0.28 0 -8 0 -0.29 0 -8 0 -0.30 0 -8 0 -0.31 0 -8 0 -0.32 0 -8 0 -0.33 0 -8 0 -0.34 0 -8 0 -0.35 0 -8 0 -0.36 0 -8 0 -0.37 0 -8 0 -0.38 0 -8 0 -0.39 0 -8 0 -0.40 0 -8 0 -0.41 0 -8 0 -0.42 0 -8 0 -0.43 0 -8 0 -0.44 0 -8 0 -0.45 0 -8 0 -0.46 0 -8 0 -0.47 0 -8 0 -0.48 0 -8 0 -0.49 0 -8 0 -0.50 0 -10 -5720 -0.51 0 -8 0 -0.52 0 -8 0 -0.53 0 -8 0 -0.54 0 -8 0 -0.55 0 -8 0 -0.56 0 -8 0 -0.57 0 -8 0 -0.58 0 -8 0 -0.59 0 -8 0 -0.60 0 -8 0 -0.61 0 -8 0 -0.62 0 -8 0 -0.63 0 -8 0 -0.64 0 -8 0 -0.65 0 -8 0 -0.66 0 -8 0 -0.67 0 -8 0 -0.68 0 -8 0 -0.69 0 -8 0 -0.70 0 -8 0 -0.71 0 -8 0 -0.72 0 -8 0 -0.73 0 -8 0 -0.74 0 -8 0 -0.75 0 -8 0 -0.76 0 -8 0 -0.77 0 -8 0 -0.78 0 -8 0 -0.79 0 -8 0 -0.80 0 -8 0 -0.81 0 -8 0 -0.82 0 -8 0 -0.83 0 -8 0 -0.84 0 -8 0 -0.85 0 -8 0 -0.86 0 -8 0 -0.87 0 -8 0 -0.88 0 -8 0 -0.89 0 -8 0 -0.90 0 -8 0 -0.91 0 -8 0 -0.92 0 -8 0 -0.93 0 -8 0 -0.94 0 -8 0 -0.95 0 -8 0 -0.96 0 -8 0 -0.97 0 -8 0 -0.98 0 -8 0 -0.99 0 -8 0 -1.00 0 -8 0 -1.01 0 -8 0 -1.02 0 -8 0 -1.03 0 -8 0 -1.04 0 -8 0 -1.05 0 -8 0 -1.06 0 -8 0 -1.07 0 -8 0 -1.08 0 -8 0 -1.09 0 -8 0 -1.10 0 -8 0 -1.11 0 -8 0 -1.12 0 -8 0 -1.13 0 -8 0 -1.14 0 -8 0 -1.15 0 -8 0 -1.16 0 -8 0 -1.17 0 -8 0 -1.18 0 -8 0 -1.19 0 -8 0 -1.20 0 -8 0 -1.21 0 -8 0 -1.22 0 -8 0 -1.23 0 -8 0 -1.24 0 -8 0 -1.25 0 -8 0 -1.26 0 -8 0 -1.27 0 -8 0 -1.28 0 -8 0 -1.29 0 -8 0 -1.30 0 -8 0 -1.31 0 -8 0 -1.32 0 -8 0 -1.33 0 -8 0 -1.34 0 -8 0 -1.35 0 -8 0 -1.36 0 -8 0 -1.37 0 -8 0 -1.38 0 -8 0 -1.39 0 -8 0 -1.40 0 -8 0 -1.41 0 -8 0 -1.42 0 -8 0 -1.43 0 -8 0 -1.44 0 -8 0 -1.45 0 -8 0 -1.46 0 -8 0 -1.47 0 -8 0 -1.48 0 -8 0 -1.49 0 -8 0 -1.50 0 -8 0 -1.51 0 -8 0 -1.52 0 -8 0 -1.53 0 -8 0 -1.54 0 -8 0 -1.55 0 -8 0 -1.56 0 -8 0 -1.57 0 -8 0 -1.58 0 -8 0 -1.59 0 -8 0 -1.60 0 -8 0 -1.61 0 -8 0 -1.62 0 -8 0 -1.63 0 -8 0 -1.64 0 -8 0 -1.65 0 -8 0 -1.66 0 -8 0 -1.67 0 -8 0 -1.68 0 -8 0 -1.69 0 -8 0 -1.70 0 -8 0 -1.71 0 -8 0 -1.72 0 -8 0 -1.73 0 -8 0 -1.74 0 -8 0 -1.75 0 -8 0 -1.76 0 -8 0 -1.77 0 -8 0 -1.78 0 -8 0 -1.79 0 -8 0 -1.80 0 -8 0 -1.81 0 -8 0 -1.82 0 -8 0 -1.83 0 -8 0 -1.84 0 -8 0 -1.85 0 -8 0 -1.86 0 -8 0 -1.87 0 -8 0 -1.88 0 -8 0 -1.89 0 -8 0 -1.90 0 -8 0 -1.91 0 -8 0 -1.92 0 -8 0 -1.93 0 -8 0 -1.94 0 -8 0 -1.95 0 -8 0 -1.96 0 -8 0 -1.97 0 -8 0 -1.98 0 -8 0 -1.99 0 -8 0 -2.00 0 -8 0 -2.01 0 -8 0 -2.02 0 -8 0 -2.03 0 -8 0 -2.04 0 -8 0 -2.05 0 -8 0 -2.06 0 -8 0 -2.07 0 -8 0 -2.08 0 -8 0 -2.09 0 -8 0 -2.10 0 -8 0 -2.11 0 -8 0 -2.12 0 -8 0 -2.13 0 -8 0 -2.14 0 -8 0 -2.15 0 -8 0 -2.16 0 -8 0 -2.17 0 -8 0 -2.18 0 -8 0 -2.19 0 -8 0 -2.20 0 -8 0 -2.21 0 -8 0 -2.22 0 -8 0 -2.23 0 -8 0 -2.24 0 -8 0 -2.25 0 -8 0 -2.26 0 -8 0 -2.27 0 -8 0 -2.28 0 -8 0 -2.29 0 -8 0 -2.30 0 -8 0 -2.31 0 -8 0 -2.32 0 -8 0 -2.33 0 -8 0 -2.34 0 -8 0 -2.35 0 -8 0 -2.36 0 -8 0 -2.37 0 -8 0 -2.38 0 -8 0 -2.39 0 -8 0 -2.40 0 -8 0 -2.41 0 -8 0 -2.42 0 -8 0 -2.43 0 -8 0 -2.44 0 -8 0 -2.45 0 -8 0 -2.46 0 -8 0 -2.47 0 -8 0 -2.48 0 -8 0 -2.49 0 -8 0 -2.50 0 -8 0 -2.51 0 -8 0 -2.52 0 -8 0 -2.53 0 -8 0 -2.54 0 -8 0 -2.55 0 -8 0 -2.56 0 -8 0 -2.57 0 -8 0 -2.58 0 -8 0 -2.59 0 -8 0 -2.60 0 -8 0 -2.61 0 -8 0 -2.62 0 -8 0 -2.63 0 -8 0 -2.64 0 -8 0 -2.65 0 -8 0 -2.66 0 -8 0 -2.67 0 -8 0 -2.68 0 -8 0 -2.69 0 -8 0 -2.70 0 -8 0 -2.71 0 -8 0 -2.72 0 -8 0 -2.73 0 -8 0 -2.74 0 -8 0 -2.75 0 -8 0 -2.76 0 -8 0 -2.77 0 -8 0 -2.78 0 -8 0 -2.79 0 -8 0 -2.80 0 -8 0 -2.81 0 -8 0 -2.82 0 -8 0 -2.83 0 -8 0 -2.84 0 -8 0 -2.85 0 -8 0 -2.86 0 -8 0 -2.87 0 -8 0 -2.88 0 -8 0 -2.89 0 -8 0 -2.90 0 -8 0 -2.91 0 -8 0 -2.92 0 -8 0 -2.93 0 -8 0 -2.94 0 -8 0 -2.95 0 -8 0 -2.96 0 -8 0 -2.97 0 -8 0 -2.98 0 -8 0 -2.99 0 -8 0 -3.00 0 -8 0 -3.01 0 -8 0 -3.02 0 -8 0 -3.03 0 -8 0 -3.04 0 -8 0 -3.05 0 -8 0 -3.06 0 -8 0 -3.07 0 -8 0 -3.08 0 -8 0 -3.09 0 -8 0 -3.10 0 -8 0 -3.11 0 -8 0 -3.12 0 -8 0 -3.13 0 -8 0 -3.14 0 -8 0 -3.15 0 -8 0 -3.16 0 -8 0 -3.17 0 -8 0 -3.18 0 -8 0 -3.19 0 -8 0 -3.20 0 -8 0 -3.21 0 -8 0 -3.22 0 -8 0 -3.23 0 -8 0 -3.24 0 -8 0 -3.25 0 -8 0 -3.26 0 -8 0 -3.27 0 -8 0 -3.28 0 -8 0 -3.29 0 -8 0 -3.30 0 -8 0 -3.31 0 -8 0 -3.32 0 -8 0 -3.33 0 -8 0 -3.34 0 -8 0 -3.35 0 -8 0 -3.36 0 -8 0 -3.37 0 -8 0 -3.38 0 -8 0 -3.39 0 -8 0 -3.40 0 -8 0 -3.41 0 -8 0 -3.42 0 -8 0 -3.43 0 -8 5720 -3.44 0 -8 0 -3.45 0 -8 0 -3.46 0 -8 0 -3.47 0 -8 0 -3.48 0 -8 0 -3.49 0 -8 0 -3.50 0 -8 0 -3.51 0 -8 0 -3.52 0 -8 0 -3.53 0 -8 0 -3.54 0 -8 0 -3.55 0 -8 0 -3.56 0 -8 0 -3.57 0 -8 0 -3.58 0 -8 0 -3.59 0 -8 0 -3.60 0 -8 0 -3.61 0 -8 0 -3.62 0 -8 0 -3.63 0 -8 0 -3.64 0 -8 0 -3.65 0 -8 0 -3.66 0 -8 0 -3.67 0 -8 0 -3.68 0 -8 0 -3.69 0 -8 0 -3.70 0 -8 0 -3.71 0 -8 0 -3.72 0 -8 0 -3.73 0 -8 0 -3.74 0 -8 0 -3.75 0 -8 0 -3.76 0 -8 0 -3.77 0 -8 0 -3.78 0 -8 0 -3.79 0 -8 0 -3.80 0 -8 0 -3.81 0 -8 0 -3.82 0 -8 0 -3.83 0 -8 0 -3.84 0 -8 0 -3.85 0 -8 0 -3.86 0 -8 0 -3.87 0 -8 0 -3.88 0 -8 0 -3.89 0 -8 0 -3.90 0 -8 0 -3.91 0 -8 0 -3.92 0 -8 0 -3.93 0 -8 0 -3.94 0 -8 0 -3.95 0 -8 0 -3.96 0 -8 0 -3.97 0 -8 0 -3.98 0 -8 0 -3.99 0 -8 0 -4.00 0 -8 0 -4.01 0 -8 0 -4.02 0 -8 0 -4.03 0 -8 0 -4.04 0 -8 0 -4.05 0 -8 0 -4.06 0 -8 0 -4.07 0 -8 0 -4.08 0 -8 0 -4.09 0 -8 0 -4.10 0 -8 0 -4.11 0 -8 0 -4.12 0 -8 0 -4.13 0 -8 0 -4.14 0 -8 0 -4.15 0 -8 0 -4.16 0 -8 0 -4.17 0 -8 0 -4.18 0 -8 0 -4.19 0 -8 0 -4.20 0 -8 0 -4.21 0 -8 0 -4.22 0 -8 0 -4.23 0 -8 0 -4.24 0 -8 0 -4.25 0 -8 0 -4.26 0 -8 0 -4.27 0 -8 0 -4.28 0 -8 0 -4.29 0 -8 0 -4.30 0 -8 0 -4.31 0 -8 0 -4.32 0 -8 0 -4.33 0 -8 0 -4.34 0 -8 0 -4.35 0 -8 0 -4.36 0 -8 0 -4.37 0 -8 0 -4.38 0 -8 0 -4.39 0 -8 0 -4.40 0 -8 0 -4.41 0 -8 0 -4.42 0 -8 0 -4.43 0 -8 0 -4.44 0 -8 0 -4.45 0 -8 0 -4.46 0 -8 0 -4.47 0 -8 0 -4.48 0 -8 0 -4.49 0 -8 0 -4.50 0 -8 0 -4.51 0 -8 0 -4.52 0 -8 0 -4.53 0 -8 0 -4.54 0 -8 0 -4.55 0 -8 0 -4.56 0 -8 0 -4.57 0 -8 0 -4.58 0 -8 0 -4.59 0 -8 0 -4.60 0 -8 0 -4.61 0 -8 0 -4.62 0 -8 0 -4.63 0 -8 0 -4.64 0 -8 0 -4.65 0 -8 0 -4.66 0 -8 0 -4.67 0 -8 0 -4.68 0 -8 0 -4.69 0 -8 0 -4.70 0 -8 0 -4.71 0 -8 0 -4.72 0 -8 0 -4.73 0 -8 0 -4.74 0 -8 0 -4.75 0 -8 0 -4.76 0 -8 0 -4.77 0 -8 0 -4.78 0 -8 0 -4.79 0 -8 0 -4.80 0 -8 0 -4.81 0 -8 0 -4.82 0 -8 0 -4.83 0 -8 0 -4.84 0 -8 0 -4.85 0 -8 0 -4.86 0 -8 0 -4.87 0 -8 0 -4.88 0 -8 0 -4.89 0 -8 0 -4.90 0 -8 0 -4.91 0 -8 0 -4.92 0 -8 0 -4.93 0 -8 0 -4.94 0 -8 0 -4.95 0 -8 0 -4.96 0 -8 0 -4.97 0 -8 0 -4.98 0 -8 0 -4.99 0 -8 0 -5.00 0 -8 0 -5.01 0 -8 0 -5.02 0 -8 0 -5.03 0 -8 0 -5.04 0 -8 0 -5.05 0 -8 0 -5.06 0 -8 0 -5.07 0 -8 0 -5.08 0 -8 0 -5.09 0 -9 0 -5.10 0 -8 0 -5.11 0 -8 0 -5.12 0 -8 0 -5.13 0 -8 0 -5.14 0 -8 0 -5.15 0 -8 0 -5.16 0 -8 0 -5.17 0 -8 0 -5.18 0 -8 0 -5.19 0 -8 0 -5.20 0 -8 0 -5.21 0 -8 0 -5.22 0 -8 0 -5.23 0 -8 0 -5.24 0 -8 0 -5.25 0 -8 0 -5.26 0 -8 0 -5.27 0 -8 0 -5.28 0 -8 0 -5.29 0 -8 0 -5.30 0 -8 0 -5.31 0 -8 0 -5.32 0 -8 0 -5.33 0 -8 0 -5.34 0 -8 0 -5.35 0 -8 0 -5.36 0 -8 0 -5.37 0 -8 0 -5.38 0 -8 0 -5.39 0 -8 0 -5.40 0 -8 0 -5.41 0 -8 0 -5.42 0 -8 0 -5.43 0 -8 0 -5.44 0 -8 0 -5.45 0 -8 0 -5.46 0 -8 0 -5.47 0 -8 0 -5.48 0 -8 0 -5.49 0 -8 0 -5.50 0 -8 0 -5.51 0 -8 0 -5.52 0 -8 0 -5.53 0 -8 0 -5.54 0 -8 0 -5.55 0 -8 0 -5.56 0 -8 0 -5.57 0 -8 0 -5.58 0 -8 0 -5.59 0 -8 0 -5.60 0 -8 0 -5.61 0 -8 0 -5.62 0 -8 0 -5.63 0 -8 0 -5.64 0 -8 0 -5.65 0 -8 0 -5.66 0 -8 0 -5.67 0 -8 0 -5.68 0 -8 0 -5.69 0 -8 0 -5.70 0 -8 0 -5.71 0 -8 0 -5.72 0 -8 0 -5.73 0 -8 0 -5.74 0 -8 0 -5.75 0 -8 0 -5.76 0 -8 0 -5.77 0 -8 0 -5.78 0 -8 0 -5.79 0 -8 0 -5.80 0 -8 0 -5.81 0 -8 0 -5.82 0 -8 0 -5.83 0 -8 0 -5.84 0 -8 0 -5.85 0 -8 0 -5.86 0 -8 0 -5.87 0 -8 0 -5.88 0 -8 0 -5.89 0 -8 0 -5.90 0 -8 0 -5.91 0 -8 0 -5.92 0 -8 0 -5.93 0 -8 0 -5.94 0 -8 0 -5.95 0 -8 0 -5.96 0 -8 0 -5.97 0 -8 0 -5.98 0 -8 0 -5.99 0 -8 0 -6.00 0 -8 0 -6.01 0 -8 0 -6.02 0 -8 0 -6.03 0 -8 0 -6.04 0 -8 0 -6.05 0 -8 0 -6.06 0 -8 0 -6.07 0 -8 0 -6.08 0 -8 0 -6.09 0 -8 0 -6.10 0 -8 0 -6.11 0 -8 0 -6.12 0 -8 0 -6.13 0 -8 0 -6.14 0 -8 0 -6.15 0 -8 0 -6.16 0 -8 0 -6.17 0 -8 0 -6.18 0 -8 0 -6.19 0 -8 0 -6.20 0 -8 0 -6.21 0 -8 0 -6.22 0 -8 0 -6.23 0 -8 0 -6.24 0 -8 0 -6.25 0 -8 0 -6.26 0 -8 0 -6.27 0 -8 0 -6.28 0 -8 0 -6.29 0 -10 -5720 -6.30 0 -8 0 -6.31 0 -8 0 -6.32 0 -8 0 -6.33 0 -8 0 -6.34 0 -8 0 -6.35 0 -8 0 -6.36 0 -8 0 -6.37 0 -8 0 -6.38 0 -8 0 -6.39 0 -8 0 -6.40 0 -8 0 -6.41 0 -8 0 -6.42 0 -8 0 -6.43 0 -8 0 -6.44 0 -8 0 -6.45 0 -8 0 -6.46 0 -8 0 -6.47 0 -8 0 -6.48 0 -8 0 -6.49 0 -8 0 -6.50 0 -8 0 -6.51 0 -8 0 -6.52 0 -8 0 -6.53 0 -8 0 -6.54 0 -8 0 -6.55 0 -8 0 -6.56 0 -8 0 -6.57 0 -8 0 -6.58 0 -8 0 -6.59 0 -8 0 -6.60 0 -8 0 -6.61 0 -8 0 -6.62 0 -8 0 -6.63 0 -8 0 -6.64 0 -8 0 -6.65 0 -8 0 -6.66 0 -8 0 -6.67 0 -8 0 -6.68 0 -8 0 -6.69 0 -8 0 -6.70 0 -8 0 -6.71 0 -8 0 -6.72 0 -8 0 -6.73 0 -8 0 -6.74 0 -8 0 -6.75 0 -8 0 -6.76 0 -8 0 -6.77 0 -8 0 -6.78 0 -8 0 -6.79 0 -8 0 -6.80 0 -8 0 -6.81 0 -8 0 -6.82 0 -8 0 -6.83 0 -8 0 -6.84 0 -8 0 -6.85 0 -8 0 -6.86 0 -8 0 -6.87 0 -8 0 -6.88 0 -8 0 -6.89 0 -8 0 -6.90 0 -8 0 -6.91 0 -8 0 -6.92 0 -8 0 -6.93 0 -9 0 -6.94 0 -8 0 -6.95 0 -8 0 -6.96 0 -8 0 -6.97 0 -8 0 -6.98 0 -8 0 -6.99 0 -8 0 -7.00 0 -8 0 -7.01 0 -8 0 -7.02 0 -8 0 -7.03 0 -8 0 -7.04 0 -8 0 -7.05 0 -8 0 -7.06 0 -8 0 -7.07 0 -8 0 -7.08 0 -8 0 -7.09 0 -10 -5720 -7.10 0 -8 0 -7.11 0 -8 0 -7.12 0 -8 0 -7.13 0 -8 0 -7.14 0 -8 0 -7.15 0 -8 0 -7.16 0 -8 0 -7.17 0 -8 0 -7.18 0 -8 0 -7.19 0 -8 0 -7.20 0 -8 0 -7.21 0 -8 0 -7.22 0 -8 0 -7.23 0 -8 0 -7.24 0 -8 0 -7.25 0 -8 0 -7.26 0 -8 0 -7.27 0 -8 0 -7.28 0 -8 0 -7.29 0 -8 0 -7.30 0 -8 0 -7.31 0 -8 0 -7.32 0 -8 0 -7.33 0 -8 0 -7.34 0 -8 0 -7.35 0 -8 0 -7.36 0 -8 0 -7.37 0 -8 0 -7.38 0 -8 0 -7.39 0 -8 0 -7.40 0 -8 0 -7.41 0 -8 0 -7.42 0 -8 0 -7.43 0 -8 0 -7.44 0 -8 0 -7.45 0 -8 0 -7.46 0 -8 0 -7.47 0 -8 0 -7.48 0 -8 0 -7.49 0 -8 0 -7.50 0 -8 0 -7.51 0 -8 0 -7.52 0 -8 0 -7.53 0 -8 0 -7.54 0 -8 0 -7.55 0 -8 0 -7.56 0 -8 0 -7.57 0 -8 0 -7.58 0 -8 0 -7.59 0 -8 0 -7.60 0 -8 0 -7.61 0 -8 0 -7.62 0 -8 0 -7.63 0 -6 0 -7.64 0 -2 0 -7.65 0 0 0 -7.66 0 0 -5720 -7.67 0 4 0 -7.68 0 9 0 -7.69 0 14 0 -7.70 0 15 0 -7.71 0 17 0 -7.72 0 19 0 -7.73 0 23 0 -7.74 0 37 5720 -7.75 0 47 5720 -7.76 0 64 5720 -7.77 0 106 11440 -7.78 0 134 0 -7.79 0 144 0 -7.80 0 157 5720 -7.81 0 170 0 -7.82 0 180 0 -7.83 0 186 0 -7.84 0 189 0 -7.85 0 191 0 -7.86 0 192 0 -7.87 0 194 0 -7.88 0 195 0 -7.89 0 197 0 -7.90 0 199 5720 -7.91 0 201 0 -7.92 0 203 0 -7.93 0 206 0 -7.94 0 210 0 -7.95 0 216 5720 -7.96 0 222 0 -7.97 0 231 5720 -7.98 0 239 0 -7.99 0 249 0 -8.00 0 261 0 -8.01 0 275 5720 -8.02 0 292 5720 -8.03 0 310 5720 -8.04 0 330 5720 -8.05 0 352 5720 -8.06 0 376 5720 -8.07 0 402 5720 -8.08 0 430 5720 -8.09 0 461 5720 -8.10 0 492 5720 -8.11 0 527 11440 -8.12 0 562 5720 -8.13 0 599 5720 -8.14 0 635 11440 -8.15 0 672 11440 -8.16 0 709 5720 -8.17 0 748 11440 -8.18 0 793 11440 -8.19 0 838 11440 -8.20 0 886 11440 -8.21 0 936 11440 -8.22 0 985 11440 -8.23 0 1036 11440 -8.24 0 1091 11440 -8.25 0 1147 11440 -8.26 0 1205 11440 -8.27 0 1266 17170 -8.28 0 1327 17170 -8.29 0 1391 11440 -8.30 0 1455 11440 -8.31 0 1522 11440 -8.32 0 1590 11440 -8.33 0 1659 11440 -8.34 0 1730 17170 -8.35 0 1801 17170 -8.36 0 1873 17170 -8.37 0 1945 17170 -8.38 0 2017 17170 -8.39 0 2083 17170 -8.40 0 2160 17170 -8.41 0 2238 17170 -8.42 0 2316 17170 -8.43 0 2389 17170 -8.44 0 2464 17170 -8.45 0 2538 17170 -8.46 0 2614 17170 -8.47 0 2691 22890 -8.48 0 2759 17170 -8.49 0 2846 22890 -8.50 0 2923 17170 -8.51 0 3001 22890 -8.52 0 3077 17170 -8.53 0 3156 17170 -8.54 0 3246 17170 -8.55 0 3328 17170 -8.56 0 3411 17170 -8.57 0 3487 17170 -8.58 0 3583 22890 -8.59 0 3669 22890 -8.60 0 3756 17170 -8.61 0 3854 22890 -8.62 0 3940 22890 -8.63 0 4028 22890 -8.64 0 4117 22890 -8.65 0 4207 22890 -8.66 0 4299 22890 -8.67 0 4402 22890 -8.68 0 4495 22890 -8.69 0 4588 22890 -8.70 0 4681 22890 -8.71 0 4775 22890 -8.72 0 4881 22890 -8.73 0 4977 22890 -8.74 0 5071 22890 -8.75 0 5167 22890 -8.76 0 5265 22890 -8.77 0 5365 28610 -8.78 0 5467 28610 -8.79 0 5582 28610 -8.80 0 5687 28610 -8.81 0 5791 22890 -8.82 0 5896 28610 -8.83 0 6010 22890 -8.84 0 6114 22890 -8.85 0 6219 28610 -8.86 0 6323 22890 -8.87 0 6444 28610 -8.88 0 6554 28610 -8.89 0 6667 28610 -8.90 0 6779 28610 -8.91 0 6890 28610 -8.92 0 7015 34330 -8.93 0 7127 28610 -8.94 0 7241 28610 -8.95 0 7357 28610 -8.96 0 7487 34330 -8.97 0 7606 28610 -8.98 0 7726 28610 -8.99 0 7847 28610 -9.00 0 7980 28610 -9.01 0 8100 28610 -9.02 0 8219 28610 -9.03 0 8343 28610 -9.04 0 8467 28610 -9.05 0 8594 34330 -9.06 0 8722 28610 -9.07 0 8837 34330 -9.08 0 8979 34330 -9.09 0 9108 34330 - -9.10 0 9235 34330 -9.11 0 9383 34330 -9.12 0 9521 34330 -9.13 0 9660 34330 -9.14 0 9801 34330 -9.15 0 9945 40050 -9.16 0 10085 34330 -9.17 0 10226 34330 -9.18 0 10371 34330 -9.19 0 10537 40050 -9.20 0 10703 34330 -9.21 0 10875 34330 -9.22 0 11047 40050 -9.23 0 11218 40050 -9.24 0 11391 34330 -9.25 0 11570 40050 -9.26 0 11732 40050 -9.27 0 11915 40050 -9.28 0 12097 40050 -9.29 0 12260 40050 -9.30 0 12447 45780 -9.31 0 12636 40050 -9.32 0 12828 40050 -9.33 0 13019 40050 -9.34 0 13209 40050 -9.35 0 13398 40050 -9.36 0 13595 45780 -9.37 0 13797 45780 -9.38 0 13999 45780 -9.39 0 14197 40050 -9.40 0 14394 45780 -9.41 0 14597 45780 -9.42 0 14801 45780 -9.43 0 15007 45780 -9.44 0 15212 45780 -9.45 0 15413 40050 -9.46 0 15624 45780 -9.47 0 15837 45780 -9.48 0 16049 45780 -9.49 0 16260 45780 -9.50 0 16470 45780 -9.51 0 16688 51500 -9.52 0 16907 51500 -9.53 0 17125 51500 -9.54 0 17341 45780 -9.55 0 17559 51500 -9.56 0 17781 45780 -9.57 0 18010 51500 -9.58 0 18233 51500 -9.59 0 18454 51500 -9.60 0 18679 51500 -9.61 0 18909 51500 -9.62 0 19138 51500 -9.63 0 19365 51500 -9.64 0 19590 51500 -9.65 0 19822 57220 -9.66 0 20056 51500 -9.67 0 20289 57220 -9.68 0 20516 51500 -9.69 0 20750 57220 -9.70 0 20987 51500 -9.71 0 21223 51500 -9.72 0 21456 51500 -9.73 0 21692 51500 -9.74 0 21932 51500 -9.75 0 22172 51500 -9.76 0 22409 51500 -9.77 0 22643 57220 -9.78 0 22886 57220 -9.79 0 23133 57220 -9.80 0 23377 57220 -9.81 0 23616 57220 -9.82 0 23858 51500 -9.83 0 24103 57220 -9.84 0 24350 57220 -9.85 0 24592 57220 -9.86 0 24839 57220 -9.87 0 25087 57220 -9.88 0 25335 51500 -9.89 0 25576 51500 -9.90 0 25825 57220 -9.91 0 26077 57220 -9.92 0 26325 51500 -9.93 0 26569 51500 -9.94 0 26812 51500 -9.95 0 27063 57220 -9.96 0 27314 57220 -9.97 0 27564 57220 -9.98 0 27810 57220 -9.99 0 28060 57220 -10.00 0 28310 57220 -10.01 0 28552 51500 -10.02 0 28792 51500 -10.03 0 29038 57220 -10.04 0 29286 57220 -10.05 0 29530 57220 -10.06 0 29767 57220 -10.07 0 30007 51500 -10.08 0 30251 51500 -10.09 0 30491 51500 -10.10 0 30724 51500 -10.11 0 30959 57220 -10.12 0 31193 51500 -10.13 0 31425 51500 -10.14 0 31652 51500 -10.15 0 31874 45780 -10.16 0 32099 51500 -10.17 0 32321 51500 -10.18 0 32539 45780 -10.19 0 32752 45780 -10.20 0 32966 45780 -10.21 0 33180 45780 -10.22 0 33394 51500 -10.23 0 33598 45780 -10.24 0 33797 45780 -10.25 0 34001 45780 -10.26 0 34206 45780 -10.27 0 34406 40050 -10.28 0 34602 45780 -10.29 0 34791 40050 -10.30 0 34981 45780 -10.31 0 35169 45780 -10.32 0 35357 40050 -10.33 0 35542 40050 -10.34 0 35723 40050 -10.35 0 35898 40050 -10.36 0 36074 34330 -10.37 0 36253 40050 -10.38 0 36428 34330 -10.39 0 36598 34330 -10.40 0 36765 34330 -10.41 0 36929 34330 -10.42 0 37096 40050 -10.43 0 37262 34330 -10.44 0 37424 34330 -10.45 0 37582 34330 -10.46 0 37737 34330 -10.47 0 37885 34330 -10.48 0 38032 28610 -10.49 0 38182 34330 -10.50 0 38331 34330 -10.51 0 38477 28610 -10.52 0 38622 28610 -10.53 0 38763 28610 -10.54 0 38900 28610 -10.55 0 39036 34330 -10.56 0 39171 28610 -10.57 0 39305 28610 -10.58 0 39439 28610 -10.59 0 39570 28610 -10.60 0 39698 28610 -10.61 0 39824 28610 -10.62 0 39945 22890 -10.63 0 40068 28610 -10.64 0 40191 28610 -10.65 0 40313 28610 -10.66 0 40435 28610 -10.67 0 40552 22890 -10.68 0 40669 22890 -10.69 0 40783 22890 -10.70 0 40896 28610 -10.71 0 41004 22890 -10.72 0 41114 22890 -10.73 0 41226 28610 -10.74 0 41337 22890 -10.75 0 41449 28610 -10.76 0 41559 22890 -10.77 0 41669 22890 -10.78 0 41778 22890 -10.79 0 41888 28610 -10.80 0 41992 22890 -10.81 0 42099 22890 -10.82 0 42209 22890 -10.83 0 42321 28610 -10.84 0 42431 22890 -10.85 0 42539 22890 -10.86 0 42651 22890 -10.87 0 42762 28610 -10.88 0 42872 22890 -10.89 0 42981 22890 -10.90 0 43092 22890 -10.91 0 43205 28610 -10.92 0 43319 22890 -10.93 0 43433 22890 -10.94 0 43547 22890 -10.95 0 43662 22890 -10.96 0 43778 28610 -10.97 0 43891 22890 -10.98 0 44005 22890 -10.99 0 44121 28610 -11.00 0 44236 22890 -11.01 0 44354 22890 -11.02 0 44476 28610 -11.03 0 44598 28610 -11.04 0 44719 28610 -11.05 0 44839 22890 -11.06 0 44959 22890 -11.07 0 45076 28610 -11.08 0 45195 28610 -11.09 0 45315 28610 -11.10 0 45437 28610 -11.11 0 45557 28610 -11.12 0 45678 28610 -11.13 0 45798 28610 -11.14 0 45916 28610 -11.15 0 46031 22890 -11.16 0 46147 28610 -11.17 0 46263 28610 -11.18 0 46378 22890 -11.19 0 46494 28610 -11.20 0 46606 22890 -11.21 0 46717 28610 -11.22 0 46824 22890 -11.23 0 46927 22890 -11.24 0 47026 22890 -11.25 0 47124 22890 -11.26 0 47223 22890 -11.27 0 47319 22890 -11.28 0 47412 22890 -11.29 0 47501 22890 -11.30 0 47588 17170 -11.31 0 47667 17170 -11.32 0 47741 17170 -11.33 0 47786 5720 -11.34 0 47811 11440 -11.35 0 47876 11440 -11.36 0 47946 17170 -11.37 0 48014 17170 -11.38 0 48084 17170 -11.39 0 48148 11440 -11.40 0 48205 11440 -11.41 0 48255 11440 -11.42 0 48298 11440 -11.43 0 48338 5720 -11.44 0 48376 11440 -11.45 0 48409 11440 -11.46 0 48441 5720 -11.47 0 48469 5720 -11.48 0 48492 5720 -11.49 0 48514 5720 -11.50 0 48534 0 -11.51 0 48552 5720 -11.52 0 48566 5720 -11.53 0 48576 0 -11.54 0 48586 0 -11.55 0 48594 0 -11.56 0 48601 0 -11.57 0 48606 0 -11.58 0 48610 0 -11.59 0 48612 0 -11.60 0 48613 0 -11.61 0 48613 0 -11.62 0 48611 -5720 -11.63 0 48612 0 -11.64 0 48610 0 -11.65 0 48607 0 -11.66 0 48606 5720 -11.67 0 48602 0 -11.68 0 48601 0 -11.69 0 48599 -5720 -11.70 0 48599 0 -11.71 0 48598 0 -11.72 0 48598 0 -11.73 0 48597 0 -11.74 0 48598 5720 -11.75 0 48595 0 -11.76 0 48594 0 -11.77 0 48592 0 -11.78 0 48589 0 -11.79 0 48582 0 -11.80 0 48571 -5720 -11.81 0 48566 0 -11.82 0 48564 0 -11.83 0 48563 0 -11.84 0 48561 0 -11.85 0 48560 0 -11.86 0 48558 -5720 -11.87 0 48557 0 -11.88 0 48556 0 -11.89 0 48554 0 -11.90 0 48551 0 -11.91 0 48547 0 -11.92 0 48544 0 -11.93 0 48541 0 -11.94 0 48537 0 -11.95 0 48533 0 -11.96 0 48529 0 -11.97 0 48526 0 -11.98 0 48523 0 -11.99 0 48520 0 -12.00 0 48516 0 -12.01 0 48513 0 -12.02 0 48511 0 -12.03 0 48509 0 -12.04 0 48506 0 -12.05 0 48502 -5720 -12.06 0 48501 0 -12.07 0 48498 0 -12.08 0 48495 0 -12.09 0 48492 0 -12.10 0 48487 -5720 -12.11 0 48485 0 -12.12 0 48480 -5720 -12.13 0 48477 0 -12.14 0 48473 -5720 -12.15 0 48470 0 -12.16 0 48467 0 -12.17 0 48464 0 -12.18 0 48460 0 -12.19 0 48455 -5720 -12.20 0 48453 0 -12.21 0 48449 0 -12.22 0 48444 0 -12.23 0 48439 0 -12.24 0 48433 0 -12.25 0 48426 -5720 -12.26 0 48418 0 -12.27 0 48408 -5720 -12.28 0 48398 0 -12.29 0 48386 -5720 -12.30 0 48372 -5720 -12.31 0 48358 -5720 -12.32 0 48344 0 -12.33 0 48327 -5720 -12.34 0 48314 0 -12.35 0 48299 -5720 -12.36 0 48282 -5720 -12.37 0 48265 -5720 -12.38 0 48246 -5720 -12.39 0 48227 -5720 -12.40 0 48205 -5720 -12.41 0 48183 -5720 -12.42 0 48162 -5720 -12.43 0 48140 -5720 -12.44 0 48118 -5720 -12.45 0 48095 -5720 -12.46 0 48072 -5720 -12.47 0 48048 -5720 -12.48 0 48024 -5720 -12.49 0 48000 -5720 -12.50 0 47975 -5720 -12.51 0 47949 -5720 -12.52 0 47924 -5720 -12.53 0 47897 -5720 -12.54 0 47871 -5720 -12.55 0 47845 0 -12.56 0 47817 -5720 -12.57 0 47791 -5720 -12.58 0 47767 -5720 -12.59 0 47742 -5720 -12.60 0 47717 -5720 -12.61 0 47691 0 -12.62 0 47663 -5720 -12.63 0 47637 -5720 -12.64 0 47613 -5720 -12.65 0 47589 -5720 -12.66 0 47562 -5720 -12.67 0 47536 -5720 -12.68 0 47512 -5720 -12.69 0 47486 -5720 -12.70 0 47461 -5720 -12.71 0 47436 -5720 -12.72 0 47412 -5720 -12.73 0 47390 -5720 -12.74 0 47368 -5720 -12.75 0 47346 -5720 -12.76 0 47326 -5720 -12.77 0 47305 0 -12.78 0 47282 -5720 -12.79 0 47262 0 -12.80 0 47243 -5720 -12.81 0 47227 0 -12.82 0 47209 -5720 -12.83 0 47192 -5720 -12.84 0 47175 -5720 -12.85 0 47158 -5720 -12.86 0 47141 -5720 -12.87 0 47124 -5720 -12.88 0 47105 -5720 -12.89 0 47087 -5720 -12.90 0 47070 -5720 -12.91 0 47053 -5720 -12.92 0 47036 0 -12.93 0 47016 -5720 -12.94 0 46995 -5720 -12.95 0 46976 -5720 -12.96 0 46959 0 -12.97 0 46937 -5720 -12.98 0 46916 -5720 -12.99 0 46898 0 -13.00 0 46877 -5720 -13.01 0 46853 -5720 -13.02 0 46832 -5720 -13.03 0 46810 -5720 -13.04 0 46788 0 -13.05 0 46762 -5720 -13.06 0 46736 -5720 -13.07 0 46712 -5720 -13.08 0 46689 -11440 -13.09 0 46659 -11440 -13.10 0 46630 -5720 -13.11 0 46600 -5720 -13.12 0 46569 -5720 -13.13 0 46536 -5720 -13.14 0 46500 -11440 -13.15 0 46466 -5720 -13.16 0 46430 -5720 -13.17 0 46392 -11440 -13.18 0 46354 -11440 -13.19 0 46315 -5720 -13.20 0 46273 -11440 -13.21 0 46231 -11440 -13.22 0 46187 -11440 -13.23 0 46143 -11440 -13.24 0 46097 -11440 -13.25 0 46050 -11440 -13.26 0 46002 -11440 -13.27 0 45952 -11440 -13.28 0 45900 -11440 -13.29 0 45850 -11440 -13.30 0 45796 -11440 -13.31 0 45739 -11440 -13.32 0 45679 -17170 -13.33 0 45619 -11440 -13.34 0 45557 -11440 -13.35 0 45493 -11440 -13.36 0 45426 -17170 -13.37 0 45359 -17170 -13.38 0 45290 -17170 -13.39 0 45219 -17170 -13.40 0 45148 -11440 -13.41 0 45071 -17170 -13.42 0 44996 -17170 -13.43 0 44916 -17170 -13.44 0 44831 -22890 -13.45 0 44744 -22890 -13.46 0 44656 -17170 -13.47 0 44562 -22890 -13.48 0 44465 -22890 -13.49 0 44367 -22890 -13.50 0 44275 -22890 -13.51 0 44171 -22890 -13.52 0 44066 -22890 -13.53 0 43960 -28610 -13.54 0 43851 -22890 -13.55 0 43739 -22890 -13.56 0 43622 -28610 -13.57 0 43502 -22890 -13.58 0 43380 -28610 -13.59 0 43256 -28610 -13.60 0 43130 -28610 -13.61 0 43004 -22890 -13.62 0 42875 -28610 -13.63 0 42740 -34330 -13.64 0 42603 -28610 -13.65 0 42460 -34330 -13.66 0 42317 -34330 -13.67 0 42171 -34330 -13.68 0 42040 -34330 -13.69 0 41907 -34330 -13.70 0 41772 -34330 -13.71 0 41632 -40050 -13.72 0 41476 -34330 -13.73 0 41315 -34330 -13.74 0 41155 -34330 -13.75 0 40992 -40050 -13.76 0 40829 -40050 -13.77 0 40663 -34330 -13.78 0 40487 -40050 -13.79 0 40309 -40050 -13.80 0 40131 -34330 -13.81 0 39947 -40050 -13.82 0 39765 -40050 -13.83 0 39575 -45780 -13.84 0 39384 -40050 -13.85 0 39183 -45780 -13.86 0 38982 -45780 -13.87 0 38781 -45780 -13.88 0 38572 -51500 -13.89 0 38357 -51500 -13.90 0 38137 -45780 -13.91 0 37919 -45780 -13.92 0 37721 -51500 -13.93 0 37493 -51500 -13.94 0 37255 -51500 -13.95 0 37017 -51500 -13.96 0 36781 -51500 -13.97 0 36540 -51500 -13.98 0 36290 -57220 -13.99 0 36040 -51500 -14.00 0 35790 -57220 -14.01 0 35538 -57220 -14.02 0 35278 -57220 -14.03 0 35015 -57220 -14.04 0 34753 -57220 -14.05 0 34486 -62940 -14.06 0 34212 -57220 -14.07 0 33934 -57220 -14.08 0 33661 -62940 -14.09 0 33383 -62940 -14.10 0 33094 -62940 -14.11 0 32807 -62940 -14.12 0 32521 -62940 -14.13 0 32252 -62940 -14.14 0 31950 -68660 -14.15 0 31655 -62940 -14.16 0 31351 -68660 -14.17 0 31041 -68660 -14.18 0 30732 -68660 -14.19 0 30426 -68660 -14.20 0 30106 -74390 -14.21 0 29791 -74390 -14.22 0 29479 -68660 -14.23 0 29157 -74390 -14.24 0 28834 -74390 -14.25 0 28513 -74390 -14.26 0 28183 -74390 -14.27 0 27854 -74390 -14.28 0 27531 -74390 -14.29 0 27199 -74390 -14.30 0 26860 -74390 -14.31 0 26527 -74390 -14.32 0 26193 -74390 -14.33 0 25853 -68660 -14.34 0 25518 -80110 -14.35 0 25184 -80110 -14.36 0 24842 -74390 -14.37 0 24511 -68660 -14.38 0 24174 -74390 -14.39 0 23833 -74390 -14.40 0 23502 -74390 -14.41 0 23167 -74390 -14.42 0 22829 -74390 -14.43 0 22498 -74390 -14.44 0 22166 -80110 -14.45 0 21827 -68660 -14.46 0 21494 -74390 -14.47 0 21163 -74390 -14.48 0 20826 -74390 -14.49 0 20494 -74390 -14.50 0 20198 -74390 -14.51 0 19895 -74390 -14.52 0 19595 -74390 -14.53 0 19301 -74390 -14.54 0 18971 -74390 -14.55 0 18673 -74390 -14.56 0 18349 -74390 -14.57 0 18025 -68660 -14.58 0 17698 -68660 -14.59 0 17377 -68660 -14.60 0 17056 -74390 -14.61 0 16732 -68660 -14.62 0 16411 -68660 -14.63 0 16094 -74390 -14.64 0 15770 -74390 -14.65 0 15449 -68660 -14.66 0 15130 -74390 -14.67 0 14811 -68660 -14.68 0 14488 -74390 -14.69 0 14173 -74390 -14.70 0 13849 -80110 -14.71 0 13526 -74390 -14.72 0 13215 -68660 -14.73 0 12897 -74390 -14.74 0 12574 -74390 -14.75 0 12255 -74390 -14.76 0 11971 -74390 -14.77 0 11650 -68660 -14.78 0 11333 -68660 -14.79 0 11022 -68660 -14.80 0 10704 -68660 -14.81 0 10388 -68660 -14.82 0 10080 -68660 -14.83 0 9767 -62940 -14.84 0 9450 -74390 -14.85 0 9146 -62940 -14.86 0 8837 -68660 -14.87 0 8524 -68660 -14.88 0 8213 -74390 -14.89 0 7909 -68660 -14.90 0 7597 -68660 -14.91 0 7289 -68660 -14.92 0 6988 -68660 -14.93 0 6677 -74390 -14.94 0 6367 -68660 -14.95 0 6065 -68660 -14.96 0 5758 -68660 -14.97 0 5449 -62940 -14.98 0 5141 -68660 -14.99 0 4841 -68660 -15.00 0 4534 -62940 -15.01 0 4228 -68660 -15.02 0 3930 -68660 -15.03 0 3626 -68660 -15.04 0 3318 -74390 -15.05 0 3021 -68660 -15.06 0 2720 -74390 -15.07 0 2415 -68660 -15.08 0 2114 -62940 -15.09 0 1816 -68660 -15.10 0 1515 -68660 -15.11 0 1215 -62940 -15.12 0 923 -68660 -15.13 0 626 -62940 -15.14 0 325 -62940 -15.15 0 28 -62940 -15.16 0 -264 -62940 -15.17 0 -561 -62940 -15.18 0 -857 -62940 -15.19 0 -1145 -62940 -15.20 0 -1437 -68660 -15.21 0 -1734 -68660 -15.22 0 -2024 -62940 -15.23 0 -2309 -62940 -15.24 0 -2601 -62940 -15.25 0 -2890 -57220 -15.26 0 -3173 -68660 -15.27 0 -3456 -62940 -15.28 0 -3747 -68660 -15.29 0 -4033 -62940 -15.30 0 -4313 -68660 -15.31 0 -4596 -62940 -15.32 0 -4880 -62940 -15.33 0 -5156 -62940 -15.34 0 -5429 -62940 -15.35 0 -5710 -62940 -15.36 0 -5987 -57220 -15.37 0 -6259 -57220 -15.38 0 -6535 -62940 -15.39 0 -6810 -57220 -15.40 0 -7083 -57220 -15.41 0 -7348 -57220 -15.42 0 -7622 -62940 -15.43 0 -7895 -62940 -15.44 0 -8166 -57220 -15.45 0 -8431 -57220 -15.46 0 -8702 -62940 -15.47 0 -8971 -57220 -15.48 0 -9235 -57220 -15.49 0 -9495 -57220 -15.50 0 -9762 -62940 -15.51 0 -10028 -62940 -15.52 0 -10287 -57220 -15.53 0 -10548 -57220 -15.54 0 -10813 -57220 -15.55 0 -11074 -57220 -15.56 0 -11327 -57220 -15.57 0 -11579 -57220 -15.58 0 -11836 -57220 -15.59 0 -12088 -57220 -15.60 0 -12339 -57220 -15.61 0 -12585 -57220 -15.62 0 -12835 -57220 -15.63 0 -13085 -57220 -15.64 0 -13332 -51500 -15.65 0 -13551 -51500 -15.66 0 -13771 -51500 -15.67 0 -13994 -51500 -15.68 0 -14239 -51500 -15.69 0 -14477 -51500 -15.70 0 -14717 -51500 -15.71 0 -14958 -51500 -15.72 0 -15198 -51500 -15.73 0 -15430 -51500 -15.74 0 -15663 -51500 -15.75 0 -15898 -51500 -15.76 0 -16134 -51500 -15.77 0 -16366 -51500 -15.78 0 -16591 -51500 -15.79 0 -16822 -51500 -15.80 0 -17054 -51500 -15.81 0 -17279 -45780 -15.82 0 -17503 -51500 -15.83 0 -17726 -51500 -15.84 0 -17952 -45780 -15.85 0 -18177 -45780 -15.86 0 -18398 -45780 -15.87 0 -18613 -51500 -15.88 0 -18810 -45780 -15.89 0 -19009 -51500 -15.90 0 -19203 -45780 -15.91 0 -19398 -51500 -15.92 0 -19609 -51500 -15.93 0 -19824 -51500 -15.94 0 -20035 -45780 -15.95 0 -20247 -45780 -15.96 0 -20457 -45780 -15.97 0 -20659 -45780 -15.98 0 -20867 -45780 -15.99 0 -21076 -45780 -16.00 0 -21285 -45780 -16.01 0 -21491 -45780 -16.02 0 -21689 -45780 -16.03 0 -21893 -45780 -16.04 0 -22098 -45780 -16.05 0 -22302 -45780 -16.06 0 -22501 -40050 -16.07 0 -22698 -51500 -16.08 0 -22897 -45780 -16.09 0 -23099 -45780 -16.10 0 -23299 -45780 -16.11 0 -23495 -45780 -16.12 0 -23667 -45780 -16.13 0 -23845 -45780 -16.14 0 -24021 -45780 -16.15 0 -24198 -40050 -16.16 0 -24394 -40050 -16.17 0 -24589 -45780 -16.18 0 -24778 -45780 -16.19 0 -24972 -45780 -16.20 0 -25167 -45780 -16.21 0 -25359 -40050 -16.22 0 -25547 -40050 -16.23 0 -25734 -45780 -16.24 0 -25920 -45780 -16.25 0 -26110 -45780 -16.26 0 -26299 -40050 -16.27 0 -26489 -40050 -16.28 0 -26672 -40050 -16.29 0 -26856 -40050 -16.30 0 -27041 -40050 -16.31 0 -27213 -45780 -16.32 0 -27396 -34330 -16.33 0 -27581 -45780 -16.34 0 -27759 -40050 -16.35 0 -27925 -45780 -16.36 0 -28092 -40050 -16.37 0 -28261 -40050 -16.38 0 -28429 -40050 -16.39 0 -28612 -40050 -16.40 0 -28792 -40050 -16.41 0 -28974 -40050 -16.42 0 -29158 -40050 -16.43 0 -29344 -40050 -16.44 0 -29530 -45780 -16.45 0 -29714 -45780 -16.46 0 -29896 -40050 -16.47 0 -30083 -40050 -16.48 0 -30273 -45780 -16.49 0 -30461 -40050 -16.50 0 -30649 -45780 -16.51 0 -30831 -40050 -16.52 0 -31019 -40050 -16.53 0 -31210 -45780 -16.54 0 -31399 -40050 -16.55 0 -31590 -40050 -16.56 0 -31776 -40050 -16.57 0 -31962 -40050 -16.58 0 -32135 -45780 -16.59 0 -32308 -45780 -16.60 0 -32482 -40050 -16.61 0 -32672 -40050 -16.62 0 -32857 -40050 -16.63 0 -33049 -40050 -16.64 0 -33244 -45780 -16.65 0 -33420 -45780 -16.66 0 -33611 -40050 -16.67 0 -33799 -40050 -16.68 0 -33987 -40050 -16.69 0 -34179 -40050 -16.70 0 -34371 -40050 -16.71 0 -34568 -45780 -16.72 0 -34763 -45780 -16.73 0 -34950 -45780 -16.74 0 -35138 -40050 -16.75 0 -35333 -45780 -16.76 0 -35528 -45780 -16.77 0 -35722 -45780 -16.78 0 -35912 -45780 -16.79 0 -36085 -40050 -16.80 0 -36264 -45780 -16.81 0 -36443 -40050 -16.82 0 -36607 -45780 -16.83 0 -36805 -45780 -16.84 0 -36999 -40050 -16.85 0 -37199 -45780 -16.86 0 -37401 -40050 -16.87 0 -37605 -45780 -16.88 0 -37809 -51500 -16.89 0 -38005 -40050 -16.90 0 -38208 -45780 -16.91 0 -38412 -45780 -16.92 0 -38618 -45780 -16.93 0 -38821 -40050 -16.94 0 -39020 -45780 -16.95 0 -39224 -45780 -16.96 0 -39428 -40050 -16.97 0 -39636 -45780 -16.98 0 -39843 -45780 -16.99 0 -40025 -45780 -17.00 0 -40210 -51500 -17.01 0 -40397 -45780 -17.02 0 -40586 -45780 -17.03 0 -40795 -45780 -17.04 0 -41000 -45780 -17.05 0 -41205 -45780 -17.06 0 -41416 -51500 -17.07 0 -41625 -45780 -17.08 0 -41831 -51500 -17.09 0 -42036 -45780 -17.10 0 -42243 -45780 -17.11 0 -42450 -45780 -17.12 0 -42661 -45780 -17.13 0 -42870 -51500 -17.14 0 -43073 -45780 -17.15 0 -43279 -51500 -17.16 0 -43491 -45780 -17.17 0 -43702 -45780 -17.18 0 -43911 -45780 -17.19 0 -44117 -45780 -17.20 0 -44326 -51500 -17.21 0 -44538 -51500 -17.22 0 -44749 -45780 -17.23 0 -44960 -45780 -17.24 0 -45128 -45780 -17.25 0 -45318 -45780 -17.26 0 -45511 -45780 -17.27 0 -45725 -45780 -17.28 0 -45940 -45780 -17.29 0 -46150 -45780 -17.30 0 -46363 -45780 -17.31 0 -46583 -45780 -17.32 0 -46805 -51500 -17.33 0 -47023 -45780 -17.34 0 -47238 -45780 -17.35 0 -47457 -45780 -17.36 0 -47679 -51500 -17.37 0 -47902 -51500 -17.38 0 -48124 -45780 -17.39 0 -48342 -45780 -17.40 0 -48566 -51500 -17.41 0 -48792 -51500 -17.42 0 -49020 -51500 -17.43 0 -49239 -45780 -17.44 0 -49470 -51500 -17.45 0 -49701 -51500 -17.46 0 -49933 -51500 -17.47 0 -50140 -51500 -17.48 0 -50346 -51500 -17.49 0 -50556 -51500 -17.50 0 -50791 -51500 -17.51 0 -51027 -57220 -17.52 0 -51261 -51500 -17.53 0 -51493 -51500 -17.54 0 -51729 -51500 -17.55 0 -51965 -51500 -17.56 0 -52199 -51500 -17.57 0 -52431 -51500 -17.58 0 -52666 -51500 -17.59 0 -52905 -51500 -17.60 0 -53144 -51500 -17.61 0 -53378 -51500 -17.62 0 -53616 -51500 -17.63 0 -53857 -51500 -17.64 0 -54101 -57220 -17.65 0 -54338 -51500 -17.66 0 -54578 -57220 -17.67 0 -54823 -57220 -17.68 0 -55067 -51500 -17.69 0 -55305 -51500 -17.70 0 -55522 -51500 -17.71 0 -55743 -51500 -17.72 0 -55963 -57220 -17.73 0 -56183 -57220 -17.74 0 -56422 -51500 -17.75 0 -56667 -57220 -17.76 0 -56915 -57220 -17.77 0 -57163 -57220 -17.78 0 -57404 -57220 -17.79 0 -57647 -51500 -17.80 0 -57896 -57220 -17.81 0 -58144 -57220 -17.82 0 -58383 -51500 -17.83 0 -58623 -57220 -17.84 0 -58866 -57220 -17.85 0 -59108 -57220 -17.86 0 -59349 -51500 -17.87 0 -59585 -51500 -17.88 0 -59828 -51500 -17.89 0 -60070 -51500 -17.90 0 -60310 -51500 -17.91 0 -60543 -51500 -17.92 0 -60756 -51500 -17.93 0 -60973 -57220 -17.94 0 -61191 -57220 -17.95 0 -61402 -51500 -17.96 0 -61610 -45780 -17.97 0 -61850 -57220 -17.98 0 -62087 -51500 -17.99 0 -62322 -45780 -18.00 0 -62553 -51500 -18.01 0 -62787 -51500 -18.02 0 -63028 -57220 -18.03 0 -63267 -51500 -18.04 0 -63495 -51500 -18.05 0 -63724 -51500 -18.06 0 -63958 -51500 -18.07 0 -64194 -51500 -18.08 0 -64427 -45780 -18.09 0 -64655 -51500 -18.10 0 -64884 -51500 -18.11 0 -65114 -51500 -18.12 0 -65342 -51500 -18.13 0 -65566 -45780 -18.14 0 -65770 -51500 -18.15 0 -65975 -51500 -18.16 0 -66184 -51500 -18.17 0 -66410 -45780 -18.18 0 -66630 -51500 -18.19 0 -66852 -45780 -18.20 0 -67077 -51500 -18.21 0 -67300 -51500 -18.22 0 -67520 -51500 -18.23 0 -67734 -45780 -18.24 0 -67948 -40050 -18.25 0 -68164 -45780 -18.26 0 -68375 -45780 -18.27 0 -68582 -45780 -18.28 0 -68782 -45780 -18.29 0 -68984 -45780 -18.30 0 -69181 -45780 -18.31 0 -69375 -45780 -18.32 0 -69555 -40050 -18.33 0 -69728 -40050 -18.34 0 -69910 -40050 -18.35 0 -70094 -40050 -18.36 0 -70257 -40050 -18.37 0 -70417 -40050 -18.38 0 -70571 -34330 -18.39 0 -70717 -34330 -18.40 0 -70874 -34330 -18.41 0 -71032 -34330 -18.42 0 -71182 -34330 -18.43 0 -71334 -34330 -18.44 0 -71477 -28610 -18.45 0 -71620 -34330 -18.46 0 -71752 -28610 -18.47 0 -71883 -28610 -18.48 0 -72011 -28610 -18.49 0 -72137 -28610 -18.50 0 -72261 -28610 -18.51 0 -72383 -22890 -18.52 0 -72507 -28610 -18.53 0 -72627 -28610 -18.54 0 -72741 -22890 -18.55 0 -72841 -22890 -18.56 0 -72948 -22890 -18.57 0 -73053 -22890 -18.58 0 -73147 -22890 -18.59 0 -73239 -22890 -18.60 0 -73324 -17170 -18.61 0 -73409 -22890 -18.62 0 -73500 -17170 -18.63 0 -73587 -17170 -18.64 0 -73671 -22890 -18.65 0 -73749 -17170 -18.66 0 -73821 -11440 -18.67 0 -73895 -17170 -18.68 0 -73966 -17170 -18.69 0 -74032 -17170 -18.70 0 -74096 -17170 -18.71 0 -74156 -11440 -18.72 0 -74209 -11440 -18.73 0 -74264 -11440 -18.74 0 -74317 -11440 -18.75 0 -74365 -11440 -18.76 0 -74412 -11440 -18.77 0 -74454 -11440 -18.78 0 -74493 -5720 -18.79 0 -74527 -11440 -18.80 0 -74558 -11440 -18.81 0 -74588 -11440 -18.82 0 -74614 -5720 -18.83 0 -74640 0 -18.84 0 -74665 -5720 -18.85 0 -74685 -5720 -18.86 0 -74703 -5720 -18.87 0 -74717 0 -18.88 0 -74731 0 -18.89 0 -74744 0 -18.90 0 -74753 0 -18.91 0 -74759 0 -18.92 0 -74762 0 -18.93 0 -74763 0 -18.94 0 -74762 0 -18.95 0 -74759 0 -18.96 0 -74756 0 -18.97 0 -74751 0 -18.98 0 -74741 0 -18.99 0 -74718 5720 -19.00 0 -74696 5720 -19.01 0 -74691 0 -19.02 0 -74687 0 -19.03 0 -74686 0 -19.04 0 -74686 0 -19.05 0 -74686 0 -19.06 0 -74685 0 -19.07 0 -74685 0 -19.08 0 -74683 0 -19.09 0 -74681 0 -19.10 0 -74678 0 -19.11 0 -74672 0 -19.12 0 -74661 0 -19.13 0 -74652 0 -19.14 0 -74642 5720 -19.15 0 -74630 5720 -19.16 0 -74620 5720 -19.17 0 -74615 0 -19.18 0 -74611 0 -19.19 0 -74610 0 -19.20 0 -74609 0 -19.21 0 -74608 0 -19.22 0 -74608 0 -19.23 0 -74606 0 -19.24 0 -74604 0 -19.25 0 -74601 0 -19.26 0 -74597 0 -19.27 0 -74592 0 -19.28 0 -74589 0 -19.29 0 -74586 0 -19.30 0 -74583 0 -19.31 0 -74580 0 -19.32 0 -74577 0 -19.33 0 -74574 0 -19.34 0 -74572 0 -19.35 0 -74569 0 -19.36 0 -74566 0 -19.37 0 -74562 0 -19.38 0 -74557 5720 -19.39 0 -74553 0 -19.40 0 -74547 5720 -19.41 0 -74542 0 -19.42 0 -74537 0 -19.43 0 -74533 0 -19.44 0 -74529 0 -19.45 0 -74526 0 -19.46 0 -74523 0 -19.47 0 -74519 0 -19.48 0 -74515 0 -19.49 0 -74511 0 -19.50 0 -74507 0 -19.51 0 -74503 0 -19.52 0 -74498 0 -19.53 0 -74492 0 -19.54 0 -74486 0 -19.55 0 -74479 0 -19.56 0 -74470 5720 -19.57 0 -74460 5720 -19.58 0 -74449 5720 -19.59 0 -74435 5720 -19.60 0 -74421 0 -19.61 0 -74403 5720 -19.62 0 -74383 5720 -19.63 0 -74360 5720 -19.64 0 -74334 5720 -19.65 0 -74306 11440 -19.66 0 -74278 5720 -19.67 0 -74247 5720 -19.68 0 -74214 5720 -19.69 0 -74176 11440 -19.70 0 -74138 11440 -19.71 0 -74099 5720 -19.72 0 -74056 11440 -19.73 0 -74012 11440 -19.74 0 -73967 11440 -19.75 0 -73918 11440 -19.76 0 -73869 11440 -19.77 0 -73816 11440 -19.78 0 -73764 11440 -19.79 0 -73708 11440 -19.80 0 -73649 11440 -19.81 0 -73586 17170 -19.82 0 -73523 11440 -19.83 0 -73456 17170 -19.84 0 -73386 17170 -19.85 0 -73314 17170 -19.86 0 -73241 17170 -19.87 0 -73164 17170 -19.88 0 -73085 17170 -19.89 0 -73002 17170 -19.90 0 -72918 17170 -19.91 0 -72832 17170 -19.92 0 -72746 17170 -19.93 0 -72657 22890 -19.94 0 -72563 17170 -19.95 0 -72465 22890 -19.96 0 -72365 22890 -19.97 0 -72261 22890 -19.98 0 -72157 22890 -19.99 0 -72049 22890 -20.00 0 -71941 22890 -20.01 0 -71833 22890 -20.02 0 -71724 22890 -20.03 0 -71615 22890 -20.04 0 -71500 28610 -20.05 0 -71383 28610 -20.06 0 -71266 22890 -20.07 0 -71144 28610 -20.08 0 -71021 22890 -20.09 0 -70908 22890 -20.10 0 -70793 28610 -20.11 0 -70679 28610 -20.12 0 -70576 28610 -20.13 0 -70443 34330 -20.14 0 -70308 28610 -20.15 0 -70169 34330 -20.16 0 -70030 34330 -20.17 0 -69892 28610 -20.18 0 -69754 28610 -20.19 0 -69617 28610 -20.20 0 -69476 28610 -20.21 0 -69329 34330 -20.22 0 -69182 34330 -20.23 0 -69035 28610 -20.24 0 -68886 34330 -20.25 0 -68739 34330 -20.26 0 -68594 34330 -20.27 0 -68443 34330 -20.28 0 -68290 34330 -20.29 0 -68133 34330 -20.30 0 -67974 34330 -20.31 0 -67815 34330 -20.32 0 -67657 34330 -20.33 0 -67516 34330 -20.34 0 -67357 34330 -20.35 0 -67196 34330 -20.36 0 -67032 40050 -20.37 0 -66869 34330 -20.38 0 -66703 40050 -20.39 0 -66539 34330 -20.40 0 -66365 40050 -20.41 0 -66191 40050 -20.42 0 -66015 40050 -20.43 0 -65840 40050 -20.44 0 -65669 34330 -20.45 0 -65498 40050 -20.46 0 -65323 34330 -20.47 0 -65143 40050 -20.48 0 -64961 40050 -20.49 0 -64780 40050 -20.50 0 -64600 40050 -20.51 0 -64423 40050 -20.52 0 -64239 45780 -20.53 0 -64051 45780 -20.54 0 -63859 45780 -20.55 0 -63670 40050 -20.56 0 -63484 40050 -20.57 0 -63293 40050 -20.58 0 -63099 45780 -20.59 0 -62905 45780 -20.60 0 -62711 45780 -20.61 0 -62522 40050 -20.62 0 -62328 40050 -20.63 0 -62127 45780 -20.64 0 -61922 45780 -20.65 0 -61718 45780 -20.66 0 -61518 45780 -20.67 0 -61316 45780 -20.68 0 -61113 45780 -20.69 0 -60905 45780 -20.70 0 -60699 45780 -20.71 0 -60491 45780 -20.72 0 -60285 51500 -20.73 0 -60074 51500 -20.74 0 -59860 51500 -20.75 0 -59646 45780 -20.76 0 -59434 45780 -20.77 0 -59221 51500 -20.78 0 -59005 51500 -20.79 0 -58788 45780 -20.80 0 -58568 51500 -20.81 0 -58355 51500 -20.82 0 -58133 51500 -20.83 0 -57908 51500 -20.84 0 -57684 51500 -20.85 0 -57461 45780 -20.86 0 -57239 51500 -20.87 0 -57032 51500 -20.88 0 -56824 51500 -20.89 0 -56615 51500 -20.90 0 -56411 51500 -20.91 0 -56185 51500 -20.92 0 -55951 45780 -20.93 0 -55712 57220 -20.94 0 -55480 51500 -20.95 0 -55248 57220 -20.96 0 -55010 51500 -20.97 0 -54773 51500 -20.98 0 -54531 57220 -20.99 0 -54295 51500 -21.00 0 -54081 51500 -21.01 0 -53838 57220 -21.02 0 -53592 51500 -21.03 0 -53348 51500 -21.04 0 -53105 51500 -21.05 0 -52856 57220 -21.06 0 -52606 57220 -21.07 0 -52360 57220 -21.08 0 -52114 51500 -21.09 0 -51861 57220 -21.10 0 -51606 57220 -21.11 0 -51353 57220 -21.12 0 -51102 51500 -21.13 0 -50843 62940 -21.14 0 -50581 57220 -21.15 0 -50322 57220 -21.16 0 -50063 57220 -21.17 0 -49799 62940 -21.18 0 -49533 57220 -21.19 0 -49267 62940 -21.20 0 -49001 57220 -21.21 0 -48755 62940 -21.22 0 -48483 62940 -21.23 0 -48217 57220 -21.24 0 -47950 57220 -21.25 0 -47671 62940 -21.26 0 -47394 62940 -21.27 0 -47122 62940 -21.28 0 -46847 57220 -21.29 0 -46566 62940 -21.30 0 -46286 62940 -21.31 0 -46006 57220 -21.32 0 -45721 62940 -21.33 0 -45436 62940 -21.34 0 -45153 57220 -21.35 0 -44868 62940 -21.36 0 -44574 62940 -21.37 0 -44283 68660 -21.38 0 -43997 62940 -21.39 0 -43703 68660 -21.40 0 -43407 62940 -21.41 0 -43112 62940 -21.42 0 -42819 62940 -21.43 0 -42521 62940 -21.44 0 -42219 68660 -21.45 0 -41925 62940 -21.46 0 -41618 68660 -21.47 0 -41311 68660 -21.48 0 -41014 62940 -21.49 0 -40710 68660 -21.50 0 -40403 62940 -21.51 0 -40091 74390 -21.52 0 -39787 68660 -21.53 0 -39479 62940 -21.54 0 -39170 62940 -21.55 0 -38864 68660 -21.56 0 -38551 68660 -21.57 0 -38237 68660 -21.58 0 -37931 68660 -21.59 0 -37620 74390 -21.60 0 -37304 68660 -21.61 0 -36992 68660 -21.62 0 -36683 68660 -21.63 0 -36369 68660 -21.64 0 -36058 74390 -21.65 0 -35756 68660 -21.66 0 -35446 68660 -21.67 0 -35130 68660 -21.68 0 -34830 68660 -21.69 0 -34529 62940 -21.70 0 -34231 68660 -21.71 0 -33937 62940 -21.72 0 -33649 62940 -21.73 0 -33373 62940 -21.74 0 -33094 62940 -21.75 0 -32829 57220 -21.76 0 -32559 62940 -21.77 0 -32289 57220 -21.78 0 -32027 51500 -21.79 0 -31776 57220 -21.80 0 -31523 51500 -21.81 0 -31265 57220 -21.82 0 -31014 57220 -21.83 0 -30772 51500 -21.84 0 -30533 51500 -21.85 0 -30289 57220 -21.86 0 -30054 45780 -21.87 0 -29824 51500 -21.88 0 -29622 51500 -21.89 0 -29418 51500 -21.90 0 -29216 51500 -21.91 0 -29017 45780 -21.92 0 -28807 45780 -21.93 0 -28602 45780 -21.94 0 -28398 45780 -21.95 0 -28196 45780 -21.96 0 -28000 40050 -21.97 0 -27809 40050 -21.98 0 -27623 45780 -21.99 0 -27438 40050 -22.00 0 -27254 40050 -22.01 0 -27074 40050 -22.02 0 -26899 40050 -22.03 0 -26729 40050 -22.04 0 -26560 40050 -22.05 0 -26394 40050 -22.06 0 -26225 40050 -22.07 0 -26038 40050 -22.08 0 -25870 34330 -22.09 0 -25711 34330 -22.10 0 -25559 34330 -22.11 0 -25412 28610 -22.12 0 -25263 34330 -22.13 0 -25131 34330 -22.14 0 -24987 34330 -22.15 0 -24845 28610 -22.16 0 -24702 34330 -22.17 0 -24563 34330 -22.18 0 -24423 28610 -22.19 0 -24280 34330 -22.20 0 -24139 34330 -22.21 0 -23997 34330 -22.22 0 -23856 34330 -22.23 0 -23715 28610 -22.24 0 -23577 34330 -22.25 0 -23436 34330 -22.26 0 -23290 34330 -22.27 0 -23143 34330 -22.28 0 -22993 34330 -22.29 0 -22843 34330 -22.30 0 -22693 34330 -22.31 0 -22544 34330 -22.32 0 -22393 34330 -22.33 0 -22238 34330 -22.34 0 -22096 34330 -22.35 0 -21936 34330 -22.36 0 -21775 40050 -22.37 0 -21613 40050 -22.38 0 -21454 40050 -22.39 0 -21288 40050 -22.40 0 -21120 34330 -22.41 0 -20950 40050 -22.42 0 -20778 40050 -22.43 0 -20606 40050 -22.44 0 -20435 40050 -22.45 0 -20258 40050 -22.46 0 -20078 40050 -22.47 0 -19897 40050 -22.48 0 -19717 40050 -22.49 0 -19536 40050 -22.50 0 -19354 40050 -22.51 0 -19166 45780 -22.52 0 -18974 40050 -22.53 0 -18780 40050 -22.54 0 -18586 40050 -22.55 0 -18410 45780 -22.56 0 -18234 40050 -22.57 0 -18053 45780 -22.58 0 -17871 45780 -22.59 0 -17688 45780 -22.60 0 -17486 45780 -22.61 0 -17282 45780 -22.62 0 -17070 45780 -22.63 0 -16859 45780 -22.64 0 -16650 45780 -22.65 0 -16443 45780 -22.66 0 -16233 45780 -22.67 0 -16019 40050 -22.68 0 -15802 45780 -22.69 0 -15585 45780 -22.70 0 -15372 45780 -22.71 0 -15158 45780 -22.72 0 -14962 51500 -22.73 0 -14743 51500 -22.74 0 -14528 45780 -22.75 0 -14316 45780 -22.76 0 -14104 45780 -22.77 0 -13888 45780 -22.78 0 -13673 45780 -22.79 0 -13463 45780 -22.80 0 -13257 45780 -22.81 0 -13047 45780 -22.82 0 -12836 45780 -22.83 0 -12625 45780 -22.84 0 -12418 45780 -22.85 0 -12215 45780 -22.86 0 -12009 45780 -22.87 0 -11806 45780 -22.88 0 -11606 40050 -22.89 0 -11412 45780 -22.90 0 -11226 40050 -22.91 0 -11037 45780 -22.92 0 -10846 40050 -22.93 0 -10656 40050 -22.94 0 -10468 45780 -22.95 0 -10288 34330 -22.96 0 -10111 40050 -22.97 0 -9933 34330 -22.98 0 -9758 34330 -22.99 0 -9586 40050 -23.00 0 -9424 34330 -23.01 0 -9272 34330 -23.02 0 -9131 28610 -23.03 0 -8999 28610 -23.04 0 -8854 34330 -23.05 0 -8703 34330 -23.06 0 -8558 34330 -23.07 0 -8414 34330 -23.08 0 -8272 28610 -23.09 0 -8134 34330 -23.10 0 -7995 34330 -23.11 0 -7858 34330 -23.12 0 -7723 34330 -23.13 0 -7591 28610 -23.14 0 -7463 28610 -23.15 0 -7340 28610 -23.16 0 -7223 28610 -23.17 0 -7112 22890 -23.18 0 -6998 22890 -23.19 0 -6888 22890 -23.20 0 -6779 22890 -23.21 0 -6674 22890 -23.22 0 -6572 22890 -23.23 0 -6474 22890 -23.24 0 -6380 17170 -23.25 0 -6288 22890 -23.26 0 -6204 17170 -23.27 0 -6124 17170 -23.28 0 -6044 17170 -23.29 0 -5964 17170 -23.30 0 -5888 17170 -23.31 0 -5814 11440 -23.32 0 -5742 17170 -23.33 0 -5672 17170 -23.34 0 -5607 11440 -23.35 0 -5544 11440 -23.36 0 -5486 11440 -23.37 0 -5432 11440 -23.38 0 -5382 11440 -23.39 0 -5336 11440 -23.40 0 -5291 5720 -23.41 0 -5247 11440 -23.42 0 -5209 5720 -23.43 0 -5172 11440 -23.44 0 -5141 5720 -23.45 0 -5111 5720 -23.46 0 -5083 5720 -23.47 0 -5058 5720 -23.48 0 -5037 5720 -23.49 0 -5018 5720 -23.50 0 -5002 0 -23.51 0 -4988 0 -23.52 0 -4977 0 -23.53 0 -4967 0 -23.54 0 -4959 0 -23.55 0 -4952 0 -23.56 0 -4947 5720 -23.57 0 -4946 0 -23.58 0 -4946 0 -23.59 0 -4947 0 -23.60 0 -4947 0 -23.61 0 -4947 0 -23.62 0 -4947 0 -23.63 0 -4947 0 -23.64 0 -4947 0 -23.65 0 -4947 0 -23.66 0 -4947 0 -23.67 0 -4947 0 -23.68 0 -4947 0 -23.69 0 -4947 0 -23.70 0 -4947 0 -23.71 0 -4947 0 -23.72 0 -4947 0 -23.73 0 -4947 0 -23.74 0 -4947 0 -23.75 0 -4947 0 -23.76 0 -4947 0 -23.77 0 -4947 0 -23.78 0 -4947 0 -23.79 0 -4947 0 -23.80 0 -4947 0 -23.81 0 -4947 0 -23.82 0 -4947 0 -23.83 0 -4947 0 -23.84 0 -4947 0 -23.85 0 -4947 0 -23.86 0 -4947 0 -23.87 0 -4947 0 -23.88 0 -4947 0 -23.89 0 -4947 0 -23.90 0 -4947 0 -23.91 0 -4947 0 -23.92 0 -4947 0 -23.93 0 -4947 0 -23.94 0 -4947 0 -23.95 0 -4947 0 -23.96 0 -4947 0 -23.97 0 -4947 0 -23.98 0 -4947 0 -23.99 0 -4947 0 -24.00 0 -4947 0 -24.01 0 -4947 0 -24.02 0 -4947 0 -24.03 0 -4947 0 -24.04 0 -4947 0 -24.05 0 -4947 0 -24.06 0 -4947 0 -24.07 0 -4947 0 -24.08 0 -4947 0 -24.09 0 -4947 0 -24.10 0 -4947 0 -24.11 0 -4947 0 -24.12 0 -4947 0 -24.13 0 -4947 0 -24.14 0 -4947 0 -24.15 0 -4947 0 -24.16 0 -4947 0 -24.17 0 -4947 0 -24.18 0 -4947 0 -24.19 0 -4947 0 -24.20 0 -4947 0 -24.21 0 -4947 0 -24.22 0 -4947 0 -24.23 0 -4947 0 -24.24 0 -4947 0 -24.25 0 -4947 0 -24.26 0 -4947 0 -24.27 0 -4947 0 -24.28 0 -4947 0 -24.29 0 -4947 0 -24.30 0 -4947 0 -24.31 0 -4947 0 -24.32 0 -4947 0 -24.33 0 -4947 0 -24.34 0 -4947 0 -24.35 0 -4947 0 -24.36 0 -4947 0 -24.37 0 -4947 0 -24.38 0 -4947 0 -24.39 0 -4947 0 -24.40 0 -4947 0 -24.41 0 -4947 0 -24.42 0 -4947 0 -24.43 0 -4947 0 -24.44 0 -4947 0 -24.45 0 -4947 0 -24.46 0 -4947 0 -24.47 0 -4947 0 -24.48 0 -4947 0 -24.49 0 -4947 0 -24.50 0 -4947 0 -24.51 0 -4947 0 -24.52 0 -4947 0 -24.53 0 -4947 0 -24.54 0 -4947 0 -24.55 0 -4947 0 -24.56 0 -4947 0 -24.57 0 -4947 0 -24.58 0 -4947 0 -24.59 0 -4947 0 -24.60 0 -4947 0 -24.61 0 -4947 0 -24.62 0 -4947 0 -24.63 0 -4947 0 -24.64 0 -4947 0 -24.65 0 -4947 0 -24.66 0 -4947 0 -24.67 0 -4947 0 -24.68 0 -4947 0 -24.69 0 -4947 0 -24.70 0 -4947 0 -24.71 0 -4947 0 -24.72 0 -4947 0 -24.73 0 -4947 0 -24.74 0 -4947 0 -24.75 0 -4947 0 -24.76 0 -4947 0 -24.77 0 -4947 0 -24.78 0 -4947 0 -24.79 0 -4947 0 -24.80 0 -4947 0 -24.81 0 -4947 0 -24.82 0 -4947 0 -24.83 0 -4947 0 -24.84 0 -4947 0 -24.85 0 -4947 0 -24.86 0 -4947 0 -24.87 0 -4947 0 -24.88 0 -4947 0 -24.89 0 -4947 0 -24.90 0 -4945 5720 -24.91 0 -4947 0 -24.92 0 -4947 0 -24.93 0 -4947 0 -24.94 0 -4947 0 -24.95 0 -4947 0 -24.96 0 -4947 0 -24.97 0 -4947 0 -24.98 0 -4947 0 -24.99 0 -4947 0 -25.00 0 -4947 0 -25.01 0 -4947 0 -25.02 0 -4947 0 -25.03 0 -4947 0 -25.04 0 -4947 0 -25.05 0 -4947 0 -25.06 0 -4947 0 -25.07 0 -4947 0 -25.08 0 -4947 0 -25.09 0 -4947 0 -25.10 0 -4947 0 -25.11 0 -4947 0 -25.12 0 -4947 0 -25.13 0 -4947 0 -25.14 0 -4947 0 -25.15 0 -4947 0 -25.16 0 -4947 0 -25.17 0 -4947 0 -25.18 0 -4947 0 -25.19 0 -4947 0 -25.20 0 -4947 0 -25.21 0 -4947 0 -25.22 0 -4947 0 -25.23 0 -4947 0 -25.24 0 -4947 0 -25.25 0 -4947 0 -25.26 0 -4947 0 -25.27 0 -4947 0 -25.28 0 -4948 -5720 -25.29 0 -4947 0 -25.30 0 -4947 0 -25.31 0 -4947 0 -25.32 0 -4947 0 -25.33 0 -4947 0 -25.34 0 -4947 0 -25.35 0 -4947 0 -25.36 0 -4947 0 -25.37 0 -4947 0 -25.38 0 -4947 0 -25.39 0 -4947 0 -25.40 0 -4947 0 -25.41 0 -4947 0 -25.42 0 -4947 0 -25.43 0 -4947 -5720 -25.44 0 -4947 0 -25.45 0 -4947 0 -25.46 0 -4947 0 -25.47 0 -4947 0 -25.48 0 -4947 0 -25.49 0 -4947 0 -25.50 0 -4947 0 -25.51 0 -4946 5720 -25.52 0 -4947 0 -25.53 0 -4947 0 -25.54 0 -4947 0 -25.55 0 -4947 0 -25.56 0 -4947 0 -25.57 0 -4947 0 -25.58 0 -4947 0 -25.59 0 -4947 0 -25.60 0 -4947 0 -25.61 0 -4947 0 -25.62 0 -4947 0 -25.63 0 -4947 0 -25.64 0 -4947 0 -25.65 0 -4947 0 -25.66 0 -4947 0 -25.67 0 -4947 0 -25.68 0 -4947 0 -25.69 0 -4947 0 -25.70 0 -4947 0 -25.71 0 -4947 0 -25.72 0 -4947 0 -25.73 0 -4947 0 -25.74 0 -4947 0 -25.75 0 -4947 0 -25.76 0 -4947 0 -25.77 0 -4947 0 -25.78 0 -4947 0 -25.79 0 -4947 0 -25.80 0 -4947 0 -25.81 0 -4947 0 -25.82 0 -4947 0 -25.83 0 -4947 0 -25.84 0 -4947 0 -25.85 0 -4947 0 -25.86 0 -4947 0 -25.87 0 -4947 0 -25.88 0 -4947 0 -25.89 0 -4947 0 -25.90 0 -4947 0 -25.91 0 -4947 0 -25.92 0 -4947 0 -25.93 0 -4947 0 -25.94 0 -4947 0 -25.95 0 -4947 0 -25.96 0 -4947 0 -25.97 0 -4947 0 -25.98 0 -4947 0 -25.99 0 -4947 0 -26.00 0 -4947 0 -26.01 0 -4947 0 -26.02 0 -4947 0 -26.03 0 -4947 0 -26.04 0 -4947 0 -26.05 0 -4947 0 -26.06 0 -4947 0 -26.07 0 -4947 0 -26.08 0 -4947 0 -26.09 0 -4947 0 -26.10 0 -4947 0 -26.11 0 -4947 0 -26.12 0 -4947 0 -26.13 0 -4947 0 -26.14 0 -4947 0 -26.15 0 -4947 0 -26.16 0 -4947 0 -26.17 0 -4947 0 -26.18 0 -4947 0 -26.19 0 -4947 0 -26.20 0 -4947 0 -26.21 0 -4947 0 -26.22 0 -4947 0 -26.23 0 -4947 0 -26.24 0 -4947 0 -26.25 0 -4947 0 -26.26 0 -4947 0 -26.27 0 -4947 0 -26.28 0 -4947 0 -26.29 0 -4947 0 -26.30 0 -4947 0 -26.31 0 -4947 0 -26.32 0 -4947 0 -26.33 0 -4947 0 -26.34 0 -4947 0 -26.35 0 -4947 0 -26.36 0 -4947 0 -26.37 0 -4947 0 -26.38 0 -4947 0 -26.39 0 -4947 0 -26.40 0 -4947 0 -26.41 0 -4947 0 -26.42 0 -4947 0 -26.43 0 -4947 0 -26.44 0 -4947 0 -26.45 0 -4947 0 -26.46 0 -4947 0 -26.47 0 -4947 0 -26.48 0 -4947 0 -26.49 0 -4947 0 -26.50 0 -4947 0 -26.51 0 -4947 0 -26.52 0 -4947 0 -26.53 0 -4947 0 -26.54 0 -4947 0 -26.55 0 -4947 0 -26.56 0 -4947 0 -26.57 0 -4947 0 -26.58 0 -4947 0 -26.59 0 -4947 0 -26.60 0 -4947 0 -26.61 0 -4947 0 -26.62 0 -4947 0 -26.63 0 -4947 0 -26.64 0 -4947 0 -26.65 0 -4947 0 -26.66 0 -4947 0 -26.67 0 -4947 0 -26.68 0 -4947 0 -26.69 0 -4947 0 -26.70 0 -4947 0 -26.71 0 -4947 0 -26.72 0 -4947 0 -26.73 0 -4947 0 -26.74 0 -4947 0 -26.75 0 -4947 0 -26.76 0 -4947 0 -26.77 0 -4947 0 -26.78 0 -4947 0 -26.79 0 -4947 0 -26.80 0 -4947 0 -26.81 0 -4947 0 -26.82 0 -4947 0 -26.83 0 -4947 0 -26.84 0 -4947 0 -26.85 0 -4947 0 -26.86 0 -4947 0 -26.87 0 -4947 0 -26.88 0 -4947 0 -26.89 0 -4947 0 -26.90 0 -4947 0 -26.91 0 -4947 0 -26.92 0 -4947 0 -26.93 0 -4947 0 -26.94 0 -4947 0 -26.95 0 -4947 0 -26.96 0 -4947 0 -26.97 0 -4947 0 -26.98 0 -4947 0 -26.99 0 -4947 0 -27.00 0 -4947 0 -27.01 0 -4947 0 -27.02 0 -4947 0 -27.03 0 -4947 0 -27.04 0 -4947 0 -27.05 0 -4947 0 -27.06 0 -4947 0 -27.07 0 -4947 0 -27.08 0 -4947 0 -27.09 0 -4947 0 -27.10 0 -4947 0 -27.11 0 -4947 0 -27.12 0 -4947 0 -27.13 0 -4947 0 -27.14 0 -4947 0 -27.15 0 -4947 0 -27.16 0 -4947 0 -27.17 0 -4947 0 -27.18 0 -4947 0 -27.19 0 -4947 0 -27.20 0 -4947 0 -27.21 0 -4947 0 -27.22 0 -4947 0 -27.23 0 -4947 0 -27.24 0 -4947 0 -27.25 0 -4947 0 -27.26 0 -4947 0 -27.27 0 -4947 0 -27.28 0 -4947 0 -27.29 0 -4947 0 -27.30 0 -4947 0 -27.31 0 -4947 0 -27.32 0 -4947 0 -27.33 0 -4947 0 -27.34 0 -4947 0 -27.35 0 -4947 0 -27.36 0 -4947 0 -27.37 0 -4947 0 -27.38 0 -4947 0 -27.39 0 -4947 0 -27.40 0 -4947 0 -27.41 0 -4947 0 -27.42 0 -4947 0 -27.43 0 -4947 0 -27.44 0 -4947 0 -27.45 0 -4947 0 -27.46 0 -4947 0 -27.47 0 -4947 0 -27.48 0 -4947 0 -27.49 0 -4947 0 -27.50 0 -4947 0 -27.51 0 -4947 0 -27.52 0 -4947 0 -27.53 0 -4947 0 -27.54 0 -4947 0 -27.55 0 -4947 0 -27.56 0 -4947 0 -27.57 0 -4947 0 -27.58 0 -4947 0 -27.59 0 -4947 0 -27.60 0 -4947 0 -27.61 0 -4947 0 -27.62 0 -4947 0 -27.63 0 -4947 0 -27.64 0 -4947 0 -27.65 0 -4947 0 -27.66 0 -4947 0 -27.67 0 -4947 0 -27.68 0 -4947 0 -27.69 0 -4947 0 -27.70 0 -4947 0 -27.71 0 -4947 0 -27.72 0 -4947 0 -27.73 0 -4947 0 -27.74 0 -4947 0 -27.75 0 -4947 0 -27.76 0 -4947 0 -27.77 0 -4947 0 -27.78 0 -4947 0 -27.79 0 -4947 0 -27.80 0 -4947 0 -27.81 0 -4947 0 -27.82 0 -4947 0 -27.83 0 -4947 0 -27.84 0 -4947 0 -27.85 0 -4947 0 -27.86 0 -4947 0 -27.87 0 -4947 0 -27.88 0 -4947 0 -27.89 0 -4947 0 -27.90 0 -4947 0 -27.91 0 -4947 0 -27.92 0 -4947 0 -27.93 0 -4947 0 -27.94 0 -4947 0 -27.95 0 -4947 0 -27.96 0 -4947 0 -27.97 0 -4947 0 -27.98 0 -4947 0 -27.99 0 -4947 0 -28.00 0 -4947 0 -28.01 0 -4947 0 -28.02 0 -4947 0 -28.03 0 -4947 0 -28.04 0 -4947 0 -28.05 0 -4947 0 -28.06 0 -4947 0 -28.07 0 -4947 0 -28.08 0 -4947 0 -28.09 0 -4947 0 -28.10 0 -4947 0 -28.11 0 -4947 0 -28.12 0 -4947 0 -28.13 0 -4947 0 -28.14 0 -4947 0 -28.15 0 -4947 0 -28.16 0 -4947 0 -28.17 0 -4947 0 -28.18 0 -4947 0 -28.19 0 -4947 0 -28.20 0 -4947 0 -28.21 0 -4947 0 -28.22 0 -4947 0 -28.23 0 -4947 0 -28.24 0 -4947 0 -28.25 0 -4947 0 -28.26 0 -4947 0 -28.27 0 -4947 0 -28.28 0 -4947 0 -28.29 0 -4947 0 -28.30 0 -4947 0 -28.31 0 -4947 0 -28.32 0 -4947 0 -28.33 0 -4947 0 -28.34 0 -4947 0 -28.35 0 -4947 0 \ No newline at end of file diff --git a/arduino/examples/example/example.ino b/arduino/examples/example/example.ino deleted file mode 100644 index d4590be..0000000 --- a/arduino/examples/example/example.ino +++ /dev/null @@ -1,189 +0,0 @@ -#include "Arduino.h" - -#include "epos4.h" - -#define MAX_DATA_SIZE 64 -#define SPI_CS_PIN 9 -#define CAN_INT_PIN 2 -#define DT 0.01 -#define KP 5.2 -#define KI 7.0 - -mcp2515_can CAN_INTERFACE(SPI_CS_PIN); -epos4 epos4_1(0x1,0x601, &CAN_INTERFACE); - -volatile boolean gchecker = false; -volatile boolean toor = false; -volatile int dt = 0; - -// Time | input | output -volatile unsigned long daten_time[400]; -volatile uint32_t daten_input[400]; -volatile int16_t daten_input_print[400]; -volatile uint32_t daten_output[400]; - -// need to think about this later -unsigned long startTime; -unsigned long endTime; -unsigned char value[2] = {0}; - -void setup() -{ - int ccount = 0; - for(float i = 0.0; i < 4.0; i+=0.01) - { - daten_time[ccount] = 0.0; - daten_output[ccount] = 0.0; - - uint32_t inValue; - - if( i >= 1.0 && i <= 1.5) inValue = (uint32_t)(300); - //else if( i >=1.0 && i <= 1.5 ) inValue = (uint32_t)(-100); - //else if( i >=1.9 && i <= 2.4 ) inValue = (uint32_t)(150); - //else if( i >=2.4 && i <= 3.0 ) inValue = (uint32_t)(-100); - else inValue = (uint32_t)(0); - - daten_input[ccount] = ((inValue>>24)&0xff) | ((inValue<<8)&0xff0000) | ((inValue>>8)&0xff00) | ((inValue<<24)&0xff000000); - - ccount += 1; - } - - // Interupt stuff - cli(); - - TCCR1A = 0;// set entire TCCR1A register to 0 - TCCR1B = 0;// same for TCCR1B - TCNT1 = 0;//initialize counter value to 0 - // set compare match register for 1hz increments - OCR1A = 2499;// = (16*10^6) / (1*64) - 1 (must be <65536) - - TCCR1B |= (1 << WGM12);//for timer1 - TCCR1B |= (1 << CS10); - TCCR1B |= (1 << CS11); - - // enable timer compare interrupt - TIMSK1 |= (1 << OCIE1A); - - sei(); - - Serial.begin(115200); - - while (CAN_OK != CAN_INTERFACE.begin(CAN_500KBPS)) { - Serial.println("CAN Interface init failed ... try again"); - delay(100); - } - Serial.println("CAN Interface init success!"); - delay(500); - - epos4_1.init(); - - uint32_t posl[1] = {0}; - epos4_1.moveToPosition(posl, 1); - delay(5000); - - epos4_1.initCST(); - gchecker = true; - toor = true; -} - -void csp_test() -{ - while(1) - { - startTime = micros(); - - - uint32_t amp = (uint32_t)(50000 * cos(dt)); - // uint32_t amp = 50000; - - uint32_t swapped = ((amp>>24)&0xff) | ((amp<<8)&0xff0000) | ((amp>>8)&0xff00) | ((amp<<24)&0xff000000); - uint8_t *n2 = (uint8_t *) &swapped; - - unsigned char value[4] = {n2[3],n2[2],n2[1],n2[0]}; - - epos4_1._can_interface->sendMsgBuf(0x201, 0, 4, value); - - // send sync - Serial.print("Data==="); - Serial.print(String(dt)); - epos4_1.sync(); - - dt += 0.01; - - - endTime = micros() - startTime; - delay(10-endTime); - } -} -void csv_test() -{ - while(1) - { - startTime = millis(); - - - uint32_t amp = (uint32_t)(-5000 * sin(dt)); - //uint32_t amp = 50000; - - uint32_t swapped = ((amp>>24)&0xff) | ((amp<<8)&0xff0000) | ((amp>>8)&0xff00) | ((amp<<24)&0xff000000); - uint8_t *n2 = (uint8_t *) &swapped; - - unsigned char value[4] = {n2[3],n2[2],n2[1],n2[0]}; - - epos4_1._can_interface->sendMsgBuf(0x301, 0, 4, value); - - // send sync - epos4_1.sync(); - - dt += 0.01; - - - endTime = millis() - startTime; - delay(10-endTime); - } -} -void cst_test() -{ - if(dt<400 && gchecker == true) - { - uint8_t *n2 = (uint8_t *)(daten_input + dt); - - value[0] = n2[3]; - value[1] = n2[2]; - - epos4_1.sync(); - - daten_time[dt] = micros(); - daten_input_print[dt] = (int16_t)epos4_1.torque; - daten_output[dt] = (int32_t)epos4_1.position; - - dt += 1; - }else if(dt >= 400 && gchecker == true){ - - for(int i=0; i < 400; i+=1) - { - Serial.print(String(i) + ","); - Serial.print(String(daten_time[i]) + ","); - Serial.print(String((int16_t)(daten_input_print[i])) + ","); - Serial.println(String((int32_t)(daten_output[i]))); - } - - gchecker = false; - } -} - -//timer1 interrupt 100Hz -ISR(TIMER1_COMPA_vect) -{ - if(toor) - { - toor = false; - epos4_1._can_interface->sendMsgBuf(0x401, 0, 2, value); - cst_test(); - toor = true; - } -} - -void loop() -{ -} diff --git a/arduino/examples/subsystem/Subsystem.c b/arduino/examples/subsystem/Subsystem.c deleted file mode 100644 index aca2185..0000000 --- a/arduino/examples/subsystem/Subsystem.c +++ /dev/null @@ -1,263 +0,0 @@ -/* - * Subsystem.c - * - * Academic License - for use in teaching, academic research, and meeting - * course requirements at degree granting institutions only. Not for - * government, commercial, or other organizational use. - * - * Code generation for model "Subsystem". - * - * Model version : 1.11 - * Simulink Coder version : 9.3 (R2020a) 18-Nov-2019 - * C source code generated on : Wed Mar 24 19:21:59 2021 - * - * Target selection: grt.tlc - * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Atmel->AVR (8-bit) - * Code generation objective: Execution efficiency - * Validation result: Not run - */ - -#include "Subsystem.h" -#include "Subsystem_private.h" - -/* Block signals (default storage) */ -B_Subsystem_T Subsystem_B; - -/* Continuous states */ -X_Subsystem_T Subsystem_X; - -/* External inputs (root inport signals with default storage) */ -ExtU_Subsystem_T Subsystem_U; - -/* External outputs (root outports fed by signals with default storage) */ -ExtY_Subsystem_T Subsystem_Y; - -/* Real-time model */ -RT_MODEL_Subsystem_T Subsystem_M_; -RT_MODEL_Subsystem_T *const Subsystem_M = &Subsystem_M_; - -/* - * This function updates continuous states using the ODE4 fixed-step - * solver algorithm - */ -static void rt_ertODEUpdateContinuousStates(RTWSolverInfo *si ) -{ - time_T t = rtsiGetT(si); - time_T tnew = rtsiGetSolverStopTime(si); - time_T h = rtsiGetStepSize(si); - real_T *x = rtsiGetContStates(si); - ODE4_IntgData *id = (ODE4_IntgData *)rtsiGetSolverData(si); - real_T *y = id->y; - real_T *f0 = id->f[0]; - real_T *f1 = id->f[1]; - real_T *f2 = id->f[2]; - real_T *f3 = id->f[3]; - real_T temp; - int_T i; - int_T nXc = 2; - rtsiSetSimTimeStep(si,MINOR_TIME_STEP); - - /* Save the state values at time t in y, we'll use x as ynew. */ - (void) memcpy(y, x, - (uint_T)nXc*sizeof(real_T)); - - /* Assumes that rtsiSetT and ModelOutputs are up-to-date */ - /* f0 = f(t,y) */ - rtsiSetdX(si, f0); - Subsystem_derivatives(); - - /* f1 = f(t + (h/2), y + (h/2)*f0) */ - temp = 0.5 * h; - for (i = 0; i < nXc; i++) { - x[i] = y[i] + (temp*f0[i]); - } - - rtsiSetT(si, t + temp); - rtsiSetdX(si, f1); - Subsystem_step(); - Subsystem_derivatives(); - - /* f2 = f(t + (h/2), y + (h/2)*f1) */ - for (i = 0; i < nXc; i++) { - x[i] = y[i] + (temp*f1[i]); - } - - rtsiSetdX(si, f2); - Subsystem_step(); - Subsystem_derivatives(); - - /* f3 = f(t + h, y + h*f2) */ - for (i = 0; i < nXc; i++) { - x[i] = y[i] + (h*f2[i]); - } - - rtsiSetT(si, tnew); - rtsiSetdX(si, f3); - Subsystem_step(); - Subsystem_derivatives(); - - /* tnew = t + h - ynew = y + (h/6)*(f0 + 2*f1 + 2*f2 + 2*f3) */ - temp = h / 6.0; - for (i = 0; i < nXc; i++) { - x[i] = y[i] + temp*(f0[i] + 2.0*f1[i] + 2.0*f2[i] + f3[i]); - } - - rtsiSetSimTimeStep(si,MAJOR_TIME_STEP); -} - -/* Model step function */ -void Subsystem_step(void) -{ - real_T rtb_Sum7; - if (rtmIsMajorTimeStep(Subsystem_M)) { - /* set solver stop time */ - rtsiSetSolverStopTime(&Subsystem_M->solverInfo, - ((Subsystem_M->Timing.clockTick0+1)* - Subsystem_M->Timing.stepSize0)); - } /* end MajorTimeStep */ - - /* Update absolute time of base rate at minor time step */ - if (rtmIsMinorTimeStep(Subsystem_M)) { - Subsystem_M->Timing.t[0] = rtsiGetT(&Subsystem_M->solverInfo); - } - - /* Sum: '/Sum7' incorporates: - * Inport: '/phi_L' - * Integrator: '/Integrator1' - */ - rtb_Sum7 = Subsystem_U.phi_L - Subsystem_X.Integrator1_CSTATE; - - /* Outport: '/Out1' */ - Subsystem_Y.Out1 = rtb_Sum7; - - /* Integrator: '/Integrator' */ - Subsystem_B.dphi_m = Subsystem_X.Integrator_CSTATE; - if (rtmIsMajorTimeStep(Subsystem_M)) { - /* Gain: '/Gain3' incorporates: - * Inport: '/phi_L' - */ - Subsystem_B.Gain3 = 61.050649350649351 * Subsystem_U.phi_L; - } - - /* Sum: '/Sum' incorporates: - * Gain: '/Gain1' - * Gain: '/Gain2' - * Gain: '/Gain4' - * Gain: '/Gain5' - * Integrator: '/Integrator1' - * Sum: '/Sum1' - * Sum: '/Sum2' - */ - Subsystem_B.d2phi_m = ((-61.050649350649351 * Subsystem_X.Integrator1_CSTATE + - Subsystem_B.Gain3) + -9.9766233766233761 * Subsystem_B.dphi_m) + -470.09 * - rtb_Sum7 * -12.987012987012987; - if (rtmIsMajorTimeStep(Subsystem_M)) { - rt_ertODEUpdateContinuousStates(&Subsystem_M->solverInfo); - - /* Update absolute time for base rate */ - /* The "clockTick0" counts the number of times the code of this task has - * been executed. The absolute time is the multiplication of "clockTick0" - * and "Timing.stepSize0". Size of "clockTick0" ensures timer will not - * overflow during the application lifespan selected. - */ - ++Subsystem_M->Timing.clockTick0; - Subsystem_M->Timing.t[0] = rtsiGetSolverStopTime(&Subsystem_M->solverInfo); - - { - /* Update absolute timer for sample time: [0.01s, 0.0s] */ - /* The "clockTick1" counts the number of times the code of this task has - * been executed. The resolution of this integer timer is 0.01, which is the step size - * of the task. Size of "clockTick1" ensures timer will not overflow during the - * application lifespan selected. - */ - Subsystem_M->Timing.clockTick1++; - } - } /* end MajorTimeStep */ -} - -/* Derivatives for root system: '' */ -void Subsystem_derivatives(void) -{ - XDot_Subsystem_T *_rtXdot; - _rtXdot = ((XDot_Subsystem_T *) Subsystem_M->derivs); - - /* Derivatives for Integrator: '/Integrator1' */ - _rtXdot->Integrator1_CSTATE = Subsystem_B.dphi_m; - - /* Derivatives for Integrator: '/Integrator' */ - _rtXdot->Integrator_CSTATE = Subsystem_B.d2phi_m; -} - -/* Model initialize function */ -void Subsystem_initialize(void) -{ - /* Registration code */ - - /* initialize real-time model */ - (void) memset((void *)Subsystem_M, 0, - sizeof(RT_MODEL_Subsystem_T)); - - { - /* Setup solver object */ - rtsiSetSimTimeStepPtr(&Subsystem_M->solverInfo, - &Subsystem_M->Timing.simTimeStep); - rtsiSetTPtr(&Subsystem_M->solverInfo, &rtmGetTPtr(Subsystem_M)); - rtsiSetStepSizePtr(&Subsystem_M->solverInfo, &Subsystem_M->Timing.stepSize0); - rtsiSetdXPtr(&Subsystem_M->solverInfo, &Subsystem_M->derivs); - rtsiSetContStatesPtr(&Subsystem_M->solverInfo, (real_T **) - &Subsystem_M->contStates); - rtsiSetNumContStatesPtr(&Subsystem_M->solverInfo, - &Subsystem_M->Sizes.numContStates); - rtsiSetNumPeriodicContStatesPtr(&Subsystem_M->solverInfo, - &Subsystem_M->Sizes.numPeriodicContStates); - rtsiSetPeriodicContStateIndicesPtr(&Subsystem_M->solverInfo, - &Subsystem_M->periodicContStateIndices); - rtsiSetPeriodicContStateRangesPtr(&Subsystem_M->solverInfo, - &Subsystem_M->periodicContStateRanges); - rtsiSetErrorStatusPtr(&Subsystem_M->solverInfo, (&rtmGetErrorStatus - (Subsystem_M))); - rtsiSetRTModelPtr(&Subsystem_M->solverInfo, Subsystem_M); - } - - rtsiSetSimTimeStep(&Subsystem_M->solverInfo, MAJOR_TIME_STEP); - Subsystem_M->intgData.y = Subsystem_M->odeY; - Subsystem_M->intgData.f[0] = Subsystem_M->odeF[0]; - Subsystem_M->intgData.f[1] = Subsystem_M->odeF[1]; - Subsystem_M->intgData.f[2] = Subsystem_M->odeF[2]; - Subsystem_M->intgData.f[3] = Subsystem_M->odeF[3]; - Subsystem_M->contStates = ((X_Subsystem_T *) &Subsystem_X); - rtsiSetSolverData(&Subsystem_M->solverInfo, (void *)&Subsystem_M->intgData); - rtsiSetSolverName(&Subsystem_M->solverInfo,"ode4"); - rtmSetTPtr(Subsystem_M, &Subsystem_M->Timing.tArray[0]); - Subsystem_M->Timing.stepSize0 = 0.01; - - /* block I/O */ - (void) memset(((void *) &Subsystem_B), 0, - sizeof(B_Subsystem_T)); - - /* states (continuous) */ - { - (void) memset((void *)&Subsystem_X, 0, - sizeof(X_Subsystem_T)); - } - - /* external inputs */ - Subsystem_U.phi_L = 0.0; - - /* external outputs */ - Subsystem_Y.Out1 = 0.0; - - /* InitializeConditions for Integrator: '/Integrator1' */ - Subsystem_X.Integrator1_CSTATE = 0.0; - - /* InitializeConditions for Integrator: '/Integrator' */ - Subsystem_X.Integrator_CSTATE = 0.0; -} - -/* Model terminate function */ -void Subsystem_terminate(void) -{ - /* (no terminate code required) */ -} diff --git a/arduino/examples/subsystem/Subsystem.h b/arduino/examples/subsystem/Subsystem.h deleted file mode 100644 index d240cfa..0000000 --- a/arduino/examples/subsystem/Subsystem.h +++ /dev/null @@ -1,283 +0,0 @@ -/* - * Subsystem.h - * - * Academic License - for use in teaching, academic research, and meeting - * course requirements at degree granting institutions only. Not for - * government, commercial, or other organizational use. - * - * Code generation for model "Subsystem". - * - * Model version : 1.11 - * Simulink Coder version : 9.3 (R2020a) 18-Nov-2019 - * C source code generated on : Wed Mar 24 19:21:59 2021 - * - * Target selection: grt.tlc - * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Atmel->AVR (8-bit) - * Code generation objective: Execution efficiency - * Validation result: Not run - */ - -#ifndef RTW_HEADER_Subsystem_h_ -#define RTW_HEADER_Subsystem_h_ -#include -#ifndef Subsystem_COMMON_INCLUDES_ -# define Subsystem_COMMON_INCLUDES_ -#include "rtwtypes.h" -#include "rtw_continuous.h" -#include "rtw_solver.h" -#endif /* Subsystem_COMMON_INCLUDES_ */ - -#include "Subsystem_types.h" - -/* Shared type includes */ -#include "multiword_types.h" - -/* Macros for accessing real-time model data structure */ -#ifndef rtmGetContStateDisabled -# define rtmGetContStateDisabled(rtm) ((rtm)->contStateDisabled) -#endif - -#ifndef rtmSetContStateDisabled -# define rtmSetContStateDisabled(rtm, val) ((rtm)->contStateDisabled = (val)) -#endif - -#ifndef rtmGetContStates -# define rtmGetContStates(rtm) ((rtm)->contStates) -#endif - -#ifndef rtmSetContStates -# define rtmSetContStates(rtm, val) ((rtm)->contStates = (val)) -#endif - -#ifndef rtmGetContTimeOutputInconsistentWithStateAtMajorStepFlag -# define rtmGetContTimeOutputInconsistentWithStateAtMajorStepFlag(rtm) ((rtm)->CTOutputIncnstWithState) -#endif - -#ifndef rtmSetContTimeOutputInconsistentWithStateAtMajorStepFlag -# define rtmSetContTimeOutputInconsistentWithStateAtMajorStepFlag(rtm, val) ((rtm)->CTOutputIncnstWithState = (val)) -#endif - -#ifndef rtmGetDerivCacheNeedsReset -# define rtmGetDerivCacheNeedsReset(rtm) ((rtm)->derivCacheNeedsReset) -#endif - -#ifndef rtmSetDerivCacheNeedsReset -# define rtmSetDerivCacheNeedsReset(rtm, val) ((rtm)->derivCacheNeedsReset = (val)) -#endif - -#ifndef rtmGetIntgData -# define rtmGetIntgData(rtm) ((rtm)->intgData) -#endif - -#ifndef rtmSetIntgData -# define rtmSetIntgData(rtm, val) ((rtm)->intgData = (val)) -#endif - -#ifndef rtmGetOdeF -# define rtmGetOdeF(rtm) ((rtm)->odeF) -#endif - -#ifndef rtmSetOdeF -# define rtmSetOdeF(rtm, val) ((rtm)->odeF = (val)) -#endif - -#ifndef rtmGetOdeY -# define rtmGetOdeY(rtm) ((rtm)->odeY) -#endif - -#ifndef rtmSetOdeY -# define rtmSetOdeY(rtm, val) ((rtm)->odeY = (val)) -#endif - -#ifndef rtmGetPeriodicContStateIndices -# define rtmGetPeriodicContStateIndices(rtm) ((rtm)->periodicContStateIndices) -#endif - -#ifndef rtmSetPeriodicContStateIndices -# define rtmSetPeriodicContStateIndices(rtm, val) ((rtm)->periodicContStateIndices = (val)) -#endif - -#ifndef rtmGetPeriodicContStateRanges -# define rtmGetPeriodicContStateRanges(rtm) ((rtm)->periodicContStateRanges) -#endif - -#ifndef rtmSetPeriodicContStateRanges -# define rtmSetPeriodicContStateRanges(rtm, val) ((rtm)->periodicContStateRanges = (val)) -#endif - -#ifndef rtmGetZCCacheNeedsReset -# define rtmGetZCCacheNeedsReset(rtm) ((rtm)->zCCacheNeedsReset) -#endif - -#ifndef rtmSetZCCacheNeedsReset -# define rtmSetZCCacheNeedsReset(rtm, val) ((rtm)->zCCacheNeedsReset = (val)) -#endif - -#ifndef rtmGetdX -# define rtmGetdX(rtm) ((rtm)->derivs) -#endif - -#ifndef rtmSetdX -# define rtmSetdX(rtm, val) ((rtm)->derivs = (val)) -#endif - -#ifndef rtmGetErrorStatus -# define rtmGetErrorStatus(rtm) ((rtm)->errorStatus) -#endif - -#ifndef rtmSetErrorStatus -# define rtmSetErrorStatus(rtm, val) ((rtm)->errorStatus = (val)) -#endif - -#ifndef rtmGetStopRequested -# define rtmGetStopRequested(rtm) ((rtm)->Timing.stopRequestedFlag) -#endif - -#ifndef rtmSetStopRequested -# define rtmSetStopRequested(rtm, val) ((rtm)->Timing.stopRequestedFlag = (val)) -#endif - -#ifndef rtmGetStopRequestedPtr -# define rtmGetStopRequestedPtr(rtm) (&((rtm)->Timing.stopRequestedFlag)) -#endif - -#ifndef rtmGetT -# define rtmGetT(rtm) (rtmGetTPtr((rtm))[0]) -#endif - -#ifndef rtmGetTPtr -# define rtmGetTPtr(rtm) ((rtm)->Timing.t) -#endif - -/* Block signals (default storage) */ -typedef struct { - real_T dphi_m; /* '/Integrator' */ - real_T Gain3; /* '/Gain3' */ - real_T d2phi_m; /* '/Sum' */ -} B_Subsystem_T; - -/* Continuous states (default storage) */ -typedef struct { - real_T Integrator1_CSTATE; /* '/Integrator1' */ - real_T Integrator_CSTATE; /* '/Integrator' */ -} X_Subsystem_T; - -/* State derivatives (default storage) */ -typedef struct { - real_T Integrator1_CSTATE; /* '/Integrator1' */ - real_T Integrator_CSTATE; /* '/Integrator' */ -} XDot_Subsystem_T; - -/* State disabled */ -typedef struct { - boolean_T Integrator1_CSTATE; /* '/Integrator1' */ - boolean_T Integrator_CSTATE; /* '/Integrator' */ -} XDis_Subsystem_T; - -#ifndef ODE4_INTG -#define ODE4_INTG - -/* ODE4 Integration Data */ -typedef struct { - real_T *y; /* output */ - real_T *f[4]; /* derivatives */ -} ODE4_IntgData; - -#endif - -/* External inputs (root inport signals with default storage) */ -typedef struct { - real_T phi_L; /* '/phi_L' */ -} ExtU_Subsystem_T; - -/* External outputs (root outports fed by signals with default storage) */ -typedef struct { - real_T Out1; /* '/Out1' */ -} ExtY_Subsystem_T; - -/* Real-time Model Data Structure */ -struct tag_RTM_Subsystem_T { - const char_T *errorStatus; - RTWSolverInfo solverInfo; - X_Subsystem_T *contStates; - int_T *periodicContStateIndices; - real_T *periodicContStateRanges; - real_T *derivs; - boolean_T *contStateDisabled; - boolean_T zCCacheNeedsReset; - boolean_T derivCacheNeedsReset; - boolean_T CTOutputIncnstWithState; - real_T odeY[2]; - real_T odeF[4][2]; - ODE4_IntgData intgData; - - /* - * Sizes: - * The following substructure contains sizes information - * for many of the model attributes such as inputs, outputs, - * dwork, sample times, etc. - */ - struct { - int_T numContStates; - int_T numPeriodicContStates; - int_T numSampTimes; - } Sizes; - - /* - * Timing: - * The following substructure contains information regarding - * the timing information for the model. - */ - struct { - uint32_T clockTick0; - time_T stepSize0; - uint32_T clockTick1; - SimTimeStep simTimeStep; - boolean_T stopRequestedFlag; - time_T *t; - time_T tArray[2]; - } Timing; -}; - -/* Block signals (default storage) */ -extern B_Subsystem_T Subsystem_B; - -/* Continuous states (default storage) */ -extern X_Subsystem_T Subsystem_X; - -/* External inputs (root inport signals with default storage) */ -extern ExtU_Subsystem_T Subsystem_U; - -/* External outputs (root outports fed by signals with default storage) */ -extern ExtY_Subsystem_T Subsystem_Y; - -/* Model entry point functions */ -extern void Subsystem_initialize(void); -extern void Subsystem_step(void); -extern void Subsystem_terminate(void); - -/* Real-time Model object */ -extern RT_MODEL_Subsystem_T *const Subsystem_M; - -/*- - * The generated code includes comments that allow you to trace directly - * back to the appropriate location in the model. The basic format - * is /block_name, where system is the system number (uniquely - * assigned by Simulink) and block_name is the name of the block. - * - * Note that this particular code originates from a subsystem build, - * and has its own system numbers different from the parent model. - * Refer to the system hierarchy for this subsystem below, and use the - * MATLAB hilite_system command to trace the generated code back - * to the parent model. For example, - * - * hilite_system('untitled/Subsystem') - opens subsystem untitled/Subsystem - * hilite_system('untitled/Subsystem/Kp') - opens and selects block Kp - * - * Here is the system hierarchy for this model - * - * '' : 'untitled' - * '' : 'untitled/Subsystem' - */ -#endif /* RTW_HEADER_Subsystem_h_ */ diff --git a/arduino/examples/subsystem/Subsystem_types.h b/arduino/examples/subsystem/Subsystem_types.h deleted file mode 100644 index bb97ee2..0000000 --- a/arduino/examples/subsystem/Subsystem_types.h +++ /dev/null @@ -1,29 +0,0 @@ -/* - * Subsystem_types.h - * - * Academic License - for use in teaching, academic research, and meeting - * course requirements at degree granting institutions only. Not for - * government, commercial, or other organizational use. - * - * Code generation for model "Subsystem". - * - * Model version : 1.11 - * Simulink Coder version : 9.3 (R2020a) 18-Nov-2019 - * C source code generated on : Wed Mar 24 19:21:59 2021 - * - * Target selection: grt.tlc - * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Atmel->AVR (8-bit) - * Code generation objective: Execution efficiency - * Validation result: Not run - */ - -#ifndef RTW_HEADER_Subsystem_types_h_ -#define RTW_HEADER_Subsystem_types_h_ - -/* Model Code Variants */ - -/* Forward declaration for rtModel */ -typedef struct tag_RTM_Subsystem_T RT_MODEL_Subsystem_T; - -#endif /* RTW_HEADER_Subsystem_types_h_ */ diff --git a/arduino/examples/subsystem/test_code_gen.ino b/arduino/examples/subsystem/test_code_gen.ino deleted file mode 100644 index 8ecd316..0000000 --- a/arduino/examples/subsystem/test_code_gen.ino +++ /dev/null @@ -1,40 +0,0 @@ -#include "Arduino.h" - - -void setup() -{ - Serial.begin(115200); -} - -double f(double z) -{ - double z; -} -double g(double z, double y, double phi_l,double M_M ) -{ - return ( M_M/0.0770 - 0.7682*z - 4.7009*y - 4.7009*phi_l ); -} -double step(double h, double z, double y, double phi_l, double M_M) -{ - double k_0 = h*f(z); - double l_0 = h*g(z,y,phi_l,M_M); - - double k_1 = h*f(z+0.5*l_0); - double l_1 = h*g(z+0.5*l_0,y+0.5*k_0,phi_l,M_M); - - double k_2 = h*f(z+0.5*l_1); - double l_2 = h*g(z+0.5*l_1,y+0.5*k_1,phi_l,M_M); - - double k_3 = h*f(z+l_2); - double l_3 = h*g(z+l_2,y+k_2,phi_l,M_M); - - return ( y + (k_0 + 2*k_1 + 2*k_2 + k_3)/6 ); -} - -void loop() -{ - double M_M = - Subsystem_initialize(); - printf("coderRand=%g\n", Subsystem()); - Subsystem_terminate(); -} diff --git a/arduino/prebuild.sh b/arduino/prebuild.sh deleted file mode 100644 index d9c58ed..0000000 --- a/arduino/prebuild.sh +++ /dev/null @@ -1,3 +0,0 @@ -mkdir -p /home/.../Arduino/libraries/epos4_seeed -yes | cp -rf src/epos4/* /home/.../Arduino/libraries/epos4_seeed/ -yes | cp -rf src/mcp/* /home/.../Arduino/libraries/epos4_seeed/ diff --git a/arduino/src/epos4/epos4.cpp b/arduino/src/epos4/epos4.cpp deleted file mode 100644 index 58717a4..0000000 --- a/arduino/src/epos4/epos4.cpp +++ /dev/null @@ -1,524 +0,0 @@ -#include "epos4.h" - -#define MAX_DATA_SIZE 64 - -unsigned char tmp_data[MAX_DATA_SIZE] = {0}; -int32_t tmpper = 0; -uint8_t tmp_len; -uint32_t tmp_id; -uint8_t tmp_type; - -int32_t velo_inti = 0x00; - -epos4::epos4(int canid_epos, int canid_self, mcp2515_can *CAN_INTERFACE) -{ - _canid_epos = canid_epos; - _canid_self = canid_self; - _softwareVersion = 0; - _hardwareVersion = 0; - _can_interface = CAN_INTERFACE; -} - -void epos4::init() -{ - // get state of drive - Serial.println("hellooooo"); - epos4::readStatusword(); - - switch( epos4::_state_of_drive ) - { - case epos4::Switch_on_disabled: - epos4::writeControlword(0x00, epos4::dcc_shutdown); - delay(10); - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - delay(10); - break; - - case epos4::Ready_to_switch_on: - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - delay(10); - break; - - case epos4::Switched_on: - epos4::writeControlword(0x00, epos4::dcc_enableoperation); - delay(10); - break; - - case epos4::Quick_stop_active: - epos4::writeControlword(0x00, epos4::dcc_enableoperation); - delay(10); - break; - - case epos4::Fault: - epos4::writeControlword(0x00, epos4::dcc_faultreset); - delay(10); - epos4::writeControlword(0x00, epos4::dcc_shutdown); - delay(10); - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - delay(10); - break; - - case epos4::Operation_enabled: - Serial.println("Drive function is enabled and power is applied to the motor. "); - break; - - default: - Serial.println("State of drive not found in enum ... may some error occured"); - } - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - Serial.print("Start SI config ... "); - epos4::initSI(); - Serial.println("done!"); - - Serial.println("Start TPDO config ... "); - epos4::configPDO(); - Serial.println("done!"); - - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - Serial.println("EPOS enabled"); -} - -void epos4::initSI() -{ - epos4::writeControlword(0x00, epos4::dcc_shutdown); - delay(10); - - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - - char velocity_si[8] = {0x22, 0xA9, 0x60, 0x00, 0x00, 0x47, 0xB4, 0xFD}; // FD is maximum - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, velocity_si); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - delay(10); -} - -void epos4::initPPM() -{ - Serial.println("Set Operationmode"); - unsigned char data0[8] = {0x22, 0x60, 0x60, 0x00, 0x01, 0x00, 0x00, 0x00}; - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, data0); - delay(10); - - // Set all Profile Position Mode Parametersa here ... - - - // -------------------------------------------------------- - - Serial.println("Switch on and enable ..."); - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - delay(10); -} - -void epos4::initCSP() -{ - Serial.println("Set Operationmode to CSP"); - unsigned char data0[8] = {0x22, 0x60, 0x60, 0x00, 0x08, 0x00, 0x00, 0x00}; - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, data0); - delay(10); - - // Interpolation time period value - unsigned char data01[8] = {0x22, 0xC2, 0x60, 0x01, 0x0A, 0x00, 0x00, 0x00}; - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, data01); - delay(10); - - - Serial.println("Switch on and enable ..."); - epos4::writeControlword(0x00, epos4::dcc_shutdown); - delay(10); - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - delay(10); - -} - -void epos4::initCSV() -{ - Serial.println("Set Operationmode to CSV"); - unsigned char data0[8] = {0x22, 0x60, 0x60, 0x00, 0x09, 0x00, 0x00, 0x00}; - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, data0); - delay(10); - - // Interpolation time period value - unsigned char data01[8] = {0x22, 0xC2, 0x60, 0x01, 0x0A, 0x00, 0x00, 0x00}; - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, data01); - delay(10); - - - Serial.println("Switch on and enable ..."); - epos4::writeControlword(0x00, epos4::dcc_shutdown); - delay(10); - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - delay(10); -} - -void epos4::initCST() -{ - Serial.println("Set Operationmode to CST"); - unsigned char data0[8] = {0x22, 0x60, 0x60, 0x00, 0x0A, 0x00, 0x00, 0x00}; - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, data0); - delay(10); - - // Interpolation time period value - unsigned char data01[8] = {0x22, 0xC2, 0x60, 0x01, 0x0A, 0x00, 0x00, 0x00}; - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, data01); - delay(10); - - - Serial.println("Switch on and enable ..."); - epos4::writeControlword(0x00, epos4::dcc_shutdown); - delay(10); - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - delay(10); -} - -void epos4::sync() -{ - epos4::_can_interface->sendMsgBuf(0x80, 0, 1, 0x00); - - bool checker = false; - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type, &checker); - - if( checker == true ) - { - if(tmp_id == 0x181) - { - int32_t *pos = (int32_t *)tmp_data; - int16_t *tor = (int16_t *)(tmp_data+4); - - epos4::position = *pos; - epos4::torque = *tor; - - } - - } -} - -/** - * @brief Send a controlword with SDO communication - * - * @details The first byte is the command specifier. For controlword its fixed with 0x2B because we want expedited transfer with const size of 2 Byte - * For more details look in >EPOS4 Firmware Specification< chapter 6.2.85 - Controlword and >EPOS4 Application Notes< chapter 5.4 - SDO Communication - * - * @param highByte - * @param lowByte - */ -void epos4::writeControlword(unsigned char highByte, unsigned char lowByte) -{ - unsigned char data[8] = {0x2B, 0x40, 0x60, 0x00, lowByte, highByte, 0x00, 0x00}; - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, data); -} -void epos4::readStatusword() -{ - unsigned char data[8] = {0x40, 0x41, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00}; - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, data); - - Serial.println("asddd1"); - - tmp_data[1] = 0x00; - while(tmp_data[1] != 0x41 || tmp_data[2] != 0x60){ - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - } - - Serial.print("State of Drive: "); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - uint16_t statusword = ( tmp_data[5] << 8 ) | ( tmp_data[4] ); - - epos4::_target_reached = statusword & 0b0000010000000000; - epos4::_state_of_drive = statusword & 0b01101111; -} - -void epos4::moveToPosition(uint8_t *position) -{ - // position is an 32 bit integer. Wen give the uint8 here because we can interate on the bytes from the uint32 - Serial.print("Starte move to position ... "); - - unsigned char data[8] = {0x22, 0x7A, 0x60, 0x00, position[3], position[2], position[1], position[0]}; - //unsigned char data[8] = {0x22, 0x7A, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00}; - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, data); - delay(10); - - unsigned char data1[8] = {0x22, 0x40, 0x60, 0x00, 0x1F, 0x00, 0x00, 0x00}; - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, data1); - delay(10); - - - Serial.println("done!"); - -} - -void epos4::moveToPosition(uint32_t *posList, uint8_t len) -{ - epos4::initPPM(); - - uint32_t reversedPos; - uint32_t printPos; - uint8_t *n2; - n2 = (uint8_t *) &reversedPos; - - for( uint8_t i = 0; i < len; i+= 1 ) - { - n2[3] = (posList[i]); - n2[2] = (posList[i]) >> 8; - n2[1] = (posList[i]) >> 16; - n2[0] = (posList[i]) >> 24; - - moveToPosition(n2); - delay(1); - - // Serial.println("Toggle new poisition ..."); - epos4::writeControlword(0x00, 0x0F); - delay(1); - } -} - -void epos4::configPDO() { - - // State Maschinbe of MNT Service to Pre Operational to checnge PDOs - epos4::_can_interface->sendMsgBuf(0x00, 0, 2, epos4::enter_preoperational); - delay(10); - - // Config of TxPDO 1 - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_transmissiontype_TxPDO1); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_inhibit_time_TxPDO1); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_number_of_mapped_objects_null_TxPDO1); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_first_mapped_obj_position_TxPDO1); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_first_mapped_obj_velocity_TxPDO1); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_number_of_mapped_objects_TxPDO1); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - - // Config of TxPDO 2 - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_transmissiontype_TxPDO2); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_inhibit_time_TxPDO2); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_number_of_mapped_objects_null_TxPDO2); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_first_mapped_obj_torque_TxPDO2); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_number_of_mapped_objects_TxPDO2); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - - - - // Config of RxPDO 1 - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_transmissiontype_RxPDO1); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_number_of_mapped_objects_null_RxPDO1); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_first_mapped_obj_position_RxPDO1); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_number_of_mapped_objects_RxPDO1); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - - // Config of RxPDO 2 - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_transmissiontype_RxPDO2); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_number_of_mapped_objects_null_RxPDO2); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_first_mapped_obj_position_RxPDO2); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_number_of_mapped_objects_RxPDO2); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - - // Config of RxPDO 3 - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_transmissiontype_RxPDO3); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_number_of_mapped_objects_null_RxPDO3); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_first_mapped_obj_position_RxPDO3); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, epos4::pdo_number_of_mapped_objects_RxPDO3); - delay(10); - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - - // Set Statemaschine of NMT service back to Operational - epos4::_can_interface->sendMsgBuf(0x00, 0, 2, epos4::start_remotenode); - delay(100); - - epos4::checkReceivedData(tmp_data, &tmp_len, &tmp_id, &tmp_type); - epos4::printCANframe(tmp_data, &tmp_len, &tmp_id, &tmp_type); - - - Serial.println("TPDO Configured!"); -} - -void epos4::getVersions(uint16_t* hardware_version, uint16_t* application_number, uint16_t* software_version, uint16_t* application_version) -{ - epos4::getProductCode(hardware_version,application_number); - epos4::getRevisionNumber(software_version,application_version); -} -void epos4::getProductCode(uint16_t* hardware_version, uint16_t* application_number) -{ - unsigned char getHardwareVersion[8] = {0x40, 0x18, 0x10, 0x02, 0x00, 0x00, 0x00, 0x00}; - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, getHardwareVersion); - - unsigned char data[MAX_DATA_SIZE] = {0}; - uint8_t len; - uint32_t id; - uint8_t type; - - epos4::checkReceivedData(data, &len, &id, &type); - epos4::printCANframe(data, &len, &id, &type); - - if( id == epos4::_canid_epos ) - { - if( data[0] == 0x43 && data[1] == 0x18 && data[2] == 0x10 && data[3] == 0x02 ) - { - (*hardware_version) = (data[7]<<8) | data[6]; - (*application_number) = (data[5]<<8) | data[4]; - epos4::_hardwareVersion = (*hardware_version); - } - } -} -void epos4::getRevisionNumber(uint16_t* software_version, uint16_t* application_version) -{ - byte getSoftwareVersion[8] = {0x40, 0x18, 0x10, 0x03, 0x00, 0x00, 0x00, 0x00}; - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, getSoftwareVersion); - - unsigned char data[MAX_DATA_SIZE] = {0}; - uint8_t len; - uint32_t id; - uint8_t type; - - epos4::checkReceivedData(data, &len, &id, &type); - epos4::printCANframe(data, &len, &id, &type); - - if( id == epos4::_canid_epos ) - { - if( data[0] == 0x43 && data[1] == 0x18 && data[2] == 0x10 && data[3] == 0x03 ) - { - (*software_version) = (data[7]<<8) | data[6]; - (*application_version) = (data[5]<<8) | data[4]; - epos4::_softwareVersion = (*software_version); - } - } -} - -void epos4::checkReceivedData(unsigned char *data, uint8_t *len, uint32_t *id, uint8_t *type, bool *check) -{ - if (CAN_MSGAVAIL == epos4::_can_interface->checkReceive()) - { - epos4::_can_interface->readMsgBuf(len, data); - *id = epos4::_can_interface->getCanId(); - *type = (epos4::_can_interface->isExtendedFrame() << 0) | - (epos4::_can_interface->isRemoteRequest() << 1); - if(check) *check = true; - - }else{ - if(check) *check = false; - *id = 0x0; - } -} - -void epos4::printCANframe(unsigned char *data, uint8_t *len, uint32_t *id, uint8_t *type) -{ - Serial.print(*id, HEX); - Serial.print(" | "); - - char buffer[2] = {0}; - - for( uint8_t i = 0; i < *len; i += 1 ) - { - // Serial.print(data[i],HEX); - sprintf(buffer, "%02x", data[i]); - Serial.print(buffer); - Serial.print(" "); - } - Serial.println(""); -} diff --git a/arduino/src/epos4/epos4.h b/arduino/src/epos4/epos4.h deleted file mode 100644 index 6fddfa0..0000000 --- a/arduino/src/epos4/epos4.h +++ /dev/null @@ -1,146 +0,0 @@ -#ifndef epos4_h -#define epos4_h - -#include "Arduino.h" -#include -#include -#include - -class epos4 -{ -public: - epos4(int canid_epos, int canid_self, mcp2515_can *CAN_INTERFACE); - - void init(); - void initSI(); - void initPPM(); - void initCSP(); - void initCSV(); - void initCST(); - void sync(); - - void moveToPosition(uint32_t *posList, uint8_t len); - void getVersions(uint16_t *hardware_version, uint16_t *application_number, uint16_t *software_version, uint16_t *application_version); - - void writeControlword(unsigned char highByte, unsigned char lowByte); - void readStatusword(); - - void checkReceivedData(unsigned char *data, uint8_t *len, uint32_t *id, uint8_t *type,bool *check=NULL); - void printCANframe(unsigned char *data, uint8_t *len, uint32_t *id, uint8_t *type); - - - mcp2515_can *_can_interface; - - int32_t position = 0x00; - int32_t velocity = 0x00; - int16_t torque = 0x00; - - - int _softwareVersion; - int _hardwareVersion; - - uint8_t _state_of_drive = 0; - bool _target_reached = false; - - // Statemaschine enum - enum - { - Not_ready_to_switch_on = 0b00000000, - Switch_on_disabled = 0b01000000, - Ready_to_switch_on = 0b00100001, - Switched_on = 0b00100011, - Operation_enabled = 0b00100111, - Quick_stop_active = 0b00000111, - Fault_reaction_active = 0b00001111, - Fault = 0b00001000 - }; - - /** - * @addtogroup DeviceControlCommands - * @brief Device Control Commands - * @details For more details look in the EPOS4 Firmware Specification - 2.2 Device Control - * @{ - */ - enum - { - dcc_shutdown = 0x06, /**< will end in axis state >ready to switch on< */ - dcc_switchon = 0x07, /**< will end in axis state >switched on< */ - dcc_switchon_and_enable = 0x0F, /**< will end in axis state >switch on< then auto transition to >operation enabled< */ - dcc_disablevoltage = 0x00, /**< will end in axis state >switch on disabled< */ - dcc_quickstop = 0x02, /**< will end in axis state >quick stop active< */ - dcc_disableoperation = 0x07, /**< will end in axis state >switched on< */ - dcc_enableoperation = 0x0F, /**< will end in axis state >operation enabled< */ - dcc_faultreset = 0x80 /**< will end in axis state >Fault< and/or >switch on disabled< */ - }; - /** @} */ - - /** - * @addtogroup StatemaschineVariables - * @brief Statemaschine for NMT - * @details For more details look in the EPOS4 Communication Guide - 3.3.3.5 NMT Services - * @{ - */ - unsigned char enter_preoperational[2] = {0x80, 0x00}; /**< All CANopen nodes will enter NMT state >Pre-operational< */ - unsigned char reset_communication[2] = {0x82, 0x00}; /**< All CANopen nodes will first enter NMT state >Initialization< and then switch automatically >Pre-operational< */ - unsigned char reset_node[2] = {0x81, 0x00}; /**< All CANopen nodes will first enter NMT state >Initialization< and then switch automatically >Pre-operational< */ - unsigned char start_remotenode[2] = {0x01, 0x00}; /**< All CANopen nodes will enter NMT state >Operational< */ - unsigned char stop_remotenode[2] = {0x02, 0x00}; /**< All CANopen nodes will enter NMT state >Stopped< */ - /** @} */ - - - /** - * @addtogroup TxPDO config - * @brief set config for transmition pdos - * @details For more details look in the EPOS4 Communication Firmaware Specification - 6.2.21 Transmit PDO 1 parameter - * @{ - */ - // TxPDO 1 - unsigned char pdo_transmissiontype_TxPDO1[8] = {0x22, 0x00, 0x18, 0x02, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_inhibit_time_TxPDO1[8] = {0x22, 0x00, 0x18, 0x03, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_TxPDO1[8] = {0x22, 0x00, 0x1A, 0x00, 0x02, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_null_TxPDO1[8] = {0x22, 0x00, 0x1A, 0x00, 0x00, 0x00, 0x00, 0x00}; - unsigned char pdo_first_mapped_obj_position_TxPDO1[8] = {0x23, 0x00, 0x1A, 0x01, 0x20, 0x00, 0x64, 0x60}; // 104 Grad = 120000 inc - //unsigned char pdo_first_mapped_obj_velocity_TxPDO1[8] = {0x23, 0x00, 0x1A, 0x02, 0x20, 0x00, 0x6C, 0x60}; // e-10 rpm - unsigned char pdo_first_mapped_obj_velocity_TxPDO1[8] = {0x22, 0x00, 0x1A, 0x02, 0x10, 0x00, 0x77, 0x60}; // e-10 rpm - - // TxPDO 2 - unsigned char pdo_transmissiontype_TxPDO2[8] = {0x22, 0x01, 0x18, 0x02, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_inhibit_time_TxPDO2[8] = {0x22, 0x01, 0x18, 0x03, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_TxPDO2[8] = {0x22, 0x01, 0x1A, 0x00, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_null_TxPDO2[8] = {0x22, 0x01, 0x1A, 0x00, 0x00, 0x00, 0x00, 0x00}; - unsigned char pdo_first_mapped_obj_torque_TxPDO2[8] = {0x22, 0x01, 0x1A, 0x01, 0x10, 0x00, 0x77, 0x60}; - /** @} */ - - // RxPDO 1 - unsigned char pdo_transmissiontype_RxPDO1[8] = {0x22, 0x00, 0x14, 0x02, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_RxPDO1[8] = {0x22, 0x00, 0x16, 0x00, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_null_RxPDO1[8] = {0x22, 0x00, 0x16, 0x00, 0x00, 0x00, 0x00, 0x00}; - unsigned char pdo_first_mapped_obj_position_RxPDO1[8] = {0x23, 0x00, 0x16, 0x01, 0x20, 0x00, 0x7A, 0x60}; - - // RxPDO 2 - unsigned char pdo_transmissiontype_RxPDO2[8] = {0x22, 0x01, 0x14, 0x02, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_RxPDO2[8] = {0x22, 0x01, 0x16, 0x00, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_null_RxPDO2[8] = {0x22, 0x01, 0x16, 0x00, 0x00, 0x00, 0x00, 0x00}; - unsigned char pdo_first_mapped_obj_position_RxPDO2[8] = {0x23, 0x01, 0x16, 0x01, 0x20, 0x00, 0xFF, 0x60}; - - // RxPDO 3 - unsigned char pdo_transmissiontype_RxPDO3[8] = {0x22, 0x02, 0x14, 0x02, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_RxPDO3[8] = {0x22, 0x02, 0x16, 0x00, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_null_RxPDO3[8] = {0x22, 0x02, 0x16, 0x00, 0x00, 0x00, 0x00, 0x00}; - unsigned char pdo_first_mapped_obj_position_RxPDO3[8] = {0x23, 0x02, 0x16, 0x01, 0x10, 0x00, 0x71, 0x60}; - -private: - void getProductCode(uint16_t *hardware_version, uint16_t *application_number); - void getRevisionNumber(uint16_t *software_version, uint16_t *application_version); - void configPDO(); - void moveToPosition(uint8_t *position); - - int _canid_epos; - int _canid_self; - int _spi_cs_pin; - int _can_int_pin; - int _state; - -}; - -#endif diff --git a/arduino/src/mcp/can-serial.cpp b/arduino/src/mcp/can-serial.cpp deleted file mode 100644 index 9bd01df..0000000 --- a/arduino/src/mcp/can-serial.cpp +++ /dev/null @@ -1,575 +0,0 @@ -/***************************************************************************************** -* This is implementation of CAN BUS ASCII protocol based on LAWICEL v1.3 serial protocol -* of CAN232/CANUSB device (http://www.can232.com/docs/can232_v3.pdf) -* -* Made for Arduino with Seeduino/ElecFreaks CAN BUS Shield based on MCP2515 -* -* Copyright (C) 2015 Anton Viktorov -* https://github.com/latonita/can-ascii -* -* This library is free software. You may use/redistribute it under The MIT License terms. -* -*****************************************************************************************/ - -#include -#include "mcp_can.h" -#include "can-serial.h" - -// #define LOGGING_ENABLED - -#ifdef LOGGING_ENABLED -#define dbg_begin(x) debug.begin(x) -#define dbg0(x) debug.print(x) -#define dbg1(x) debug.println(x) -#define dbg2(x,y) debug.print(x); debug.println(y) -#define dbgH(x) debug.print(x,HEX) -#define DEBUG_RX_PIN 8 -#define DEBUG_TX_PIN 9 -#else -#define dbg_begin(x) -#define dbg0(x) -#define dbg1(x) -#define dbg2(x,y) -#define dbgH(x) -#endif - -#ifdef LOGGING_ENABLED - // software serial #2: TX = digital pin 8, RX = digital pin 9 - // on the Mega, use other pins instead, since 8 and 9 don't work on the Mega - SoftwareSerial debug(DEBUG_RX_PIN, DEBUG_TX_PIN); - - //#define debug Serial -#endif - -Can232* Can232::_instance = 0; - -Can232* Can232::instance() { - if (_instance == 0) - _instance = new Can232(); - return _instance; -} - -void Can232::init(INT8U defaultCanSpeed, const INT8U clock) { - dbg_begin(LW232_DEFAULT_BAUD_RATE); // logging through software serial - dbg1("CAN ASCII. Welcome to debug"); - - instance()->lw232CanSpeedSelection = defaultCanSpeed; - instance()->lw232McpModuleClock = clock; - instance()->initFunc(); -} - - -MCP_CAN* Can232::MCP_OBJECT = NULL; - -void Can232::attach(MCP_CAN *CAN) { - MCP_OBJECT = CAN; - #define lw232CAN MCP_OBJECT -} - -void Can232::setFilter(INT8U (*userFunc)(INT32U)) { - instance()->setFilterFunc(userFunc); -} - -void Can232::loop() { - instance()->loopFunc(); -} - -void Can232::serialEvent() { - instance()->serialEventFunc(); -} - -void Can232::initFunc() { - if (!inputString.reserve(LW232_INPUT_STRING_BUFFER_SIZE)) { - dbg0("inputString.reserve failed in initFunc. less optimal String work is expected"); - } - // lw232AutoStart = true; //todo: read from eeprom - // lw232AutoPoll = false; //todo: read from eeprom - // lw232TimeStamp = //read from eeprom - // lw232Message[0] = 'Z'; lw232Message[1] = '1'; exec(); - //if (lw232AutoStart) { - inputString = "O\x0D"; - stringComplete = true; - loopFunc(); - //} -} - -void Can232::setFilterFunc(INT8U (*userFunc)(INT32U)) { - instance()->userAddressFilterFunc = userFunc; -} - -void Can232::loopFunc() { - if (stringComplete) { - unsigned len = inputString.length(); - if (len > 0 && len < LW232_FRAME_MAX_SIZE) { - // maybe not single commands - int cr_pos; - for (; (cr_pos = inputString.indexOf(LW232_CR)) >= 0;) { - strncpy((char*)lw232Message, inputString.c_str(), cr_pos + 1); - lw232Message[cr_pos] = '\0'; - exec(); - inputString = inputString.substring(cr_pos + 1); - } - } - // clear the string: - stringComplete = false; - } - if (lw232CanChannelMode != LW232_STATUS_CAN_CLOSED) { - int recv = 0; - while (CAN_MSGAVAIL == checkReceive() && recv++<5) { - dbg0('+'); - if (CAN_OK == receiveSingleFrame()) { - Serial.write(LW232_CR); - } - } - Serial.flush(); - } -} - -void Can232::serialEventFunc() { - while (Serial.available()) { - char inChar = (char)Serial.read(); - inputString += inChar; - if (inChar == LW232_CR) { - stringComplete = true; - } - } -} - -INT8U Can232::exec() { - lw232LastErr = parseAndRunCommand(); - switch (lw232LastErr) { - case LW232_OK: - Serial.write(LW232_RET_ASCII_OK); - break; - case LW232_OK_SMALL: - Serial.write(LW232_RET_ASCII_OK_SMALL); - Serial.write(LW232_RET_ASCII_OK); - break; - case LW232_OK_BIG: - Serial.write(LW232_RET_ASCII_OK_BIG); - Serial.write(LW232_RET_ASCII_OK); - break; - case LW232_ERR_NOT_IMPLEMENTED: - // Choose behavior: will it fail or not when not implemented command comes in. Some can monitors might be affected by this selection. - Serial.write(LW232_RET_ASCII_ERROR); - //Serial.write(LW232_RET_ASCII_OK); - break; - default: - Serial.write(LW232_RET_ASCII_ERROR); - } - return 0; -} - -INT8U Can232::parseAndRunCommand() { - INT8U ret = LW232_OK; - INT8U idx = 0; - INT8U err = 0; - - lw232LastErr = LW232_OK; - - // __debug_buf("RX:", (char*)lw232Message, strlen((char*)lw232Message)); - - switch (lw232Message[0]) { - case LW232_CMD_SETUP: - // Sn[CR] Setup with standard CAN bit-rates where n is 0-9. - if (lw232CanChannelMode == LW232_STATUS_CAN_CLOSED) { - idx = HexHelper::parseNibbleWithLimit(lw232Message[1], LW232_CAN_BAUD_NUM); - lw232CanSpeedSelection = lw232CanBaudRates[idx]; - } - else { - ret = LW232_ERR; - } - break; - case LW232_CMD_SETUP_BTR: - // sxxyy[CR] Setup with BTR0/BTR1 CAN bit-rates where xx and yy is a hex value. - ret = LW232_ERR; break; - case LW232_CMD_OPEN: - // O[CR] Open the CAN channel in normal mode (sending & receiving). - if (lw232CanChannelMode == LW232_STATUS_CAN_CLOSED) { - ret = openCanBus(); - if (ret == LW232_OK) { - lw232CanChannelMode = LW232_STATUS_CAN_OPEN_NORMAL; - } - } - else { - ret = LW232_ERR; - } - break; - case LW232_CMD_LISTEN: - // L[CR] Open the CAN channel in listen only mode (receiving). - if (lw232CanChannelMode == LW232_STATUS_CAN_CLOSED) { - ret = openCanBus(); - if (ret == LW232_OK) { - lw232CanChannelMode = LW232_STATUS_CAN_OPEN_LISTEN; - } - } - else { - ret = LW232_ERR; - } - break; - case LW232_CMD_CLOSE: - // C[CR] Close the CAN channel. - if (lw232CanChannelMode != LW232_STATUS_CAN_CLOSED) { - lw232CanChannelMode = LW232_STATUS_CAN_CLOSED; - } - else { - ret = LW232_ERR; - } - break; - case LW232_CMD_TX11: - // tiiildd...[CR] Transmit a standard (11bit) CAN frame. - if (lw232CanChannelMode == LW232_STATUS_CAN_OPEN_NORMAL) { - parseCanStdId(); - lw232PacketLen = HexHelper::parseNibbleWithLimit(lw232Message[LW232_OFFSET_STD_PKT_LEN], LW232_FRAME_MAX_LENGTH + 1); - for (; idx < lw232PacketLen; idx++) { - lw232Buffer[idx] = HexHelper::parseFullByte(lw232Message[LW232_OFFSET_STD_PKT_DATA + idx * 2], lw232Message[LW232_OFFSET_STD_PKT_DATA + idx * 2 + 1]); - } - INT8U mcpErr = sendMsgBuf(lw232CanId, 0, 0, lw232PacketLen, lw232Buffer); - if (mcpErr != CAN_OK) { - ret = LW232_ERR; - } else if (lw232AutoPoll) { - ret = LW232_OK_SMALL; - } - } - else { - ret = LW232_ERR; - } - break; - case LW232_CMD_TX29: - // Tiiiiiiiildd...[CR] Transmit an extended (29bit) CAN frame - if (lw232CanChannelMode == LW232_STATUS_CAN_OPEN_NORMAL) { - parseCanExtId(); - lw232PacketLen = HexHelper::parseNibbleWithLimit(lw232Message[LW232_OFFSET_EXT_PKT_LEN], LW232_FRAME_MAX_LENGTH + 1); - for (; idx < lw232PacketLen; idx++) { - lw232Buffer[idx] = HexHelper::parseFullByte(lw232Message[LW232_OFFSET_EXT_PKT_DATA + idx * 2], lw232Message[LW232_OFFSET_EXT_PKT_DATA + idx * 2 + 1]); - } - if (CAN_OK != sendMsgBuf(lw232CanId, 1, 0, lw232PacketLen, lw232Buffer)) { - ret = LW232_ERR; - } else if (lw232AutoPoll) { - ret = LW232_OK_BIG; - } else { - ret = LW232_OK; - } - } - break; - case LW232_CMD_RTR11: - // riiil[CR] Transmit an standard RTR (11bit) CAN frame. - if (lw232CanChannelMode == LW232_STATUS_CAN_OPEN_NORMAL) { - parseCanStdId(); - lw232PacketLen = HexHelper::parseNibbleWithLimit(lw232Message[LW232_OFFSET_STD_PKT_LEN], LW232_FRAME_MAX_LENGTH + 1); - if (CAN_OK != sendMsgBuf(lw232CanId, 0, 1, lw232PacketLen, lw232Buffer)) { - ret = LW232_ERR; - } - else if (lw232AutoPoll) { - ret = LW232_OK_SMALL; - } - } - else { - ret = LW232_ERR; - } - break; - case LW232_CMD_RTR29: - // Riiiiiiiil[CR] Transmit an extended RTR (29bit) CAN frame. - if (lw232CanChannelMode == LW232_STATUS_CAN_OPEN_NORMAL) { - parseCanExtId(); - lw232PacketLen = HexHelper::parseNibbleWithLimit(lw232Message[LW232_OFFSET_EXT_PKT_LEN], LW232_FRAME_MAX_LENGTH + 1); - if (CAN_OK != sendMsgBuf(lw232CanId, 1, 1, lw232PacketLen, lw232Buffer)) { - ret = LW232_ERR; - } - else if (lw232AutoPoll) { - ret = LW232_OK_SMALL; // not a typo. strangely can232_v3.pdf tells to return "z[CR]", not "Z[CR]" as in 29bit. todo: check if it is error in pdf??? - } - } else { - ret = LW232_ERR; - } - break; - case LW232_CMD_POLL_ONE: - // P[CR] Poll incomming FIFO for CAN frames (single poll) - if (lw232CanChannelMode != LW232_STATUS_CAN_CLOSED && lw232AutoPoll == LW232_AUTOPOLL_OFF) { - if (CAN_MSGAVAIL == checkReceive()) { - ret = receiveSingleFrame(); - } - } else { - ret = LW232_ERR; - } - break; - case LW232_CMD_POLL_MANY: - // A[CR] Polls incomming FIFO for CAN frames (all pending frames) - if (lw232CanChannelMode != LW232_STATUS_CAN_CLOSED && lw232AutoPoll == LW232_AUTOPOLL_OFF) { - while (CAN_MSGAVAIL == checkReceive()) { - ret = ret ^ receiveSingleFrame(); - if (ret != CAN_OK) - break; - Serial.write(LW232_CR); - } - if (ret == CAN_OK) - Serial.print(LW232_ALL); - } else { - ret = LW232_ERR; - } - break; - case LW232_CMD_FLAGS: - // F[CR] Read Status Flags. - // LAWICEL CAN232 and CANUSB have some specific errors which differ from MCP2515/MCP2551 errors. We just return MCP2515 error. - Serial.print(LW232_FLAG); - if (lw232CAN && lw232CAN->checkError(&err) == CAN_OK) - err = 0; - HexHelper::printFullByte(err /*& MCP_EFLG_ERRORMASK*/); - break; - case LW232_CMD_AUTOPOLL: - // Xn[CR] Sets Auto Poll/Send ON/OFF for received frames. - if (lw232CanChannelMode == LW232_STATUS_CAN_CLOSED) { - lw232AutoPoll = (lw232Message[1] == LW232_ON_ONE) ? LW232_AUTOPOLL_ON : LW232_AUTOPOLL_OFF; - //todo: save to eeprom - } else { - ret = LW232_ERR; - } - break; - case LW232_CMD_FILTER: - // Wn[CR] Filter mode setting. By default CAN232 works in dual filter mode (0) and is backwards compatible with previous CAN232 versions. - ret = LW232_ERR_NOT_IMPLEMENTED; break; - case LW232_CMD_ACC_CODE: - // Mxxxxxxxx[CR] Sets Acceptance Code Register (ACn Register of SJA1000). // we use MCP2515, - ret = LW232_ERR_NOT_IMPLEMENTED; break; - case LW232_CMD_ACC_MASK: - // mxxxxxxxx[CR] Sets Acceptance Mask Register (AMn Register of SJA1000). - ret = LW232_ERR_NOT_IMPLEMENTED; break; - case LW232_CMD_UART: - // Un[CR] Setup UART with a new baud rate where n is 0-6. - idx = HexHelper::parseNibbleWithLimit(lw232Message[1], LW232_UART_BAUD_NUM); - Serial.begin(lw232SerialBaudRates[idx]); - break; - case LW232_CMD_VERSION1: - case LW232_CMD_VERSION2: - // V[CR] Get Version number of both CAN232 hardware and software - Serial.print(LW232_LAWICEL_VERSION_STR); - break; - case LW232_CMD_SERIAL: - // N[CR] Get Serial number of the CAN232. - Serial.print(LW232_LAWICEL_SERIAL_NUM); - break; - case LW232_CMD_TIMESTAMP: - // Zn[CR] Sets Time Stamp ON/OFF for received frames only. Z0 - OFF, Z1 - Lawicel's timestamp 2 bytes, Z2 - arduino timestamp 4 bytes. - if (lw232CanChannelMode == LW232_STATUS_CAN_CLOSED) { - // lw232TimeStamp = (lw232Message[1] == LW232_ON_ONE); - if (lw232Message[1] == LW232_ON_ONE) { - lw232TimeStamp = LW232_TIMESTAMP_ON_NORMAL; - } - else if (lw232Message[1] == LW232_ON_TWO) { - lw232TimeStamp = LW232_TIMESTAMP_ON_EXTENDED; - } - else { - lw232TimeStamp = LW232_TIMESTAMP_OFF; - } - } - else { - ret = LW232_ERR; - } - break; - case LW232_CMD_AUTOSTART: - // Qn[CR] Auto Startup feature (from power on). - if (lw232CanChannelMode != LW232_STATUS_CAN_CLOSED) { - if (lw232Message[1] == LW232_ON_ONE) { - lw232AutoStart = LW232_AUTOSTART_ON_NORMAL; - } - else if (lw232Message[1] == LW232_ON_TWO) { - lw232AutoStart = LW232_AUTOSTART_ON_LISTEN; - } - else { - lw232AutoStart = LW232_AUTOSTART_OFF; - } - //todo: save to eeprom - } - else { - ret = LW232_ERR; - } - break; - default: - ret = LW232_ERR_UNKNOWN_CMD; - } - - return ret; -} - -INT8U Can232::checkReceive() { -#ifndef _MCP_FAKE_MODE_ - return lw232CAN? lw232CAN->checkReceive(): CAN_NOMSG; -#else - return CAN_MSGAVAIL; -#endif -} - -INT8U Can232::readMsgBufID(INT32U *ID, INT8U *len, INT8U buf[]) { -#ifndef _MCP_FAKE_MODE_ - return lw232CAN? lw232CAN->readMsgBufID(ID, len, buf): CAN_NOMSG; -#else - *ID = random(0x100, 0x110); - *len = 4; - buf[0] = random(0x01, 0x10); - buf[1] = random(0xa1, 0xf0); - buf[2] = 0x00; - buf[3] = 0x00; - return CAN_OK; -#endif -} - -INT8U Can232::receiveSingleFrame() { - INT8U ret = LW232_OK; - INT8U idx = 0; - if (CAN_OK == readMsgBufID(&lw232CanId, &lw232PacketLen, lw232Buffer)) { - if (lw232CanId > 0x1FFFFFFF) { - ret = LW232_ERR; // address if totally wrong - } - else if (checkPassFilter(lw232CanId)) {// do we want to skip some addresses? - if (isExtendedFrame()) { - Serial.print(LW232_TR29); - HexHelper::printFullByte(HIGH_BYTE(HIGH_WORD(lw232CanId))); - HexHelper::printFullByte(LOW_BYTE(HIGH_WORD(lw232CanId))); - HexHelper::printFullByte(HIGH_BYTE(LOW_WORD(lw232CanId))); - HexHelper::printFullByte(LOW_BYTE(LOW_WORD(lw232CanId))); - } - else { - Serial.print(LW232_TR11); - HexHelper::printNibble(HIGH_BYTE(LOW_WORD(lw232CanId))); - HexHelper::printFullByte(LOW_BYTE(LOW_WORD(lw232CanId))); - } - //write data len - HexHelper::printNibble(lw232PacketLen); - //write data - for (idx = 0; idx < lw232PacketLen; idx++) { - HexHelper::printFullByte(lw232Buffer[idx]); - } - //write timestamp if needed - if (lw232TimeStamp != LW232_TIMESTAMP_OFF) { - INT32U time = millis(); - if (lw232TimeStamp == LW232_TIMESTAMP_ON_NORMAL) { - // standard LAWICEL protocol. two bytes. - time %= 60000; - } else { - // non standard protocol - 4 bytes timestamp - HexHelper::printFullByte(HIGH_BYTE(HIGH_WORD(time))); - HexHelper::printFullByte(LOW_BYTE(HIGH_WORD(time))); - } - HexHelper::printFullByte(HIGH_BYTE(LOW_WORD(time))); - HexHelper::printFullByte(LOW_BYTE(LOW_WORD(time))); - } - } - } - else { - ret = LW232_ERR; - } - return ret; -} - - -INT8U Can232::isExtendedFrame() { -#ifndef _MCP_FAKE_MODE_ - return lw232CAN? lw232CAN->isExtendedFrame(): 0; -#else - return lw232CanId > 0x7FF ? 1 : 0; //simple hack for fake mode -#endif -} - - -INT8U Can232::checkPassFilter(INT32U addr) { - if (userAddressFilterFunc == 0) - return LW232_FILTER_PROCESS; - - return (*userAddressFilterFunc)(addr); -} - -INT8U Can232::openCanBus() { - INT8U ret = LW232_OK; -#ifndef _MCP_FAKE_MODE_ - if (!lw232CAN) { - return CAN_FAILINIT; - } - if (CAN_OK != lw232CAN->begin(lw232CanSpeedSelection, lw232McpModuleClock)) - ret = LW232_ERR; -#endif - return ret; -} - - -INT8U Can232::sendMsgBuf(INT32U id, INT8U ext, INT8U rtr, INT8U len, INT8U *buf) { -#ifndef _MCP_FAKE_MODE_ - if (!lw232CAN) { - return CAN_FAILTX; - } - return lw232CAN->sendMsgBuf(id, ext, rtr, len, buf); -#else - Serial.print("= '0' && hex <= '9') { - ret = hex - '0'; - } else if (hex >= 'a' && hex <= 'f') { - ret = hex - 'a' + 10; - } else if (hex >= 'A' && hex <= 'F') { - ret = hex - 'A' + 10; - } // else error, return 0 - return ret; -} - -INT8U HexHelper::parseFullByte(INT8U H, INT8U L) { - return (parseNibble(H) << 4) + parseNibble(L); -} - -INT8U HexHelper::parseNibbleWithLimit(INT8U hex, INT8U limit) { - INT8U ret = parseNibble(hex); - if (ret < limit) - return ret; - else - return 0; -} diff --git a/arduino/src/mcp/can-serial.h b/arduino/src/mcp/can-serial.h deleted file mode 100644 index a45756e..0000000 --- a/arduino/src/mcp/can-serial.h +++ /dev/null @@ -1,235 +0,0 @@ -/***************************************************************************************** -* This is implementation of CAN BUS ASCII protocol based on LAWICEL v1.3 serial protocol -* of CAN232/CANUSB device (http://www.can232.com/docs/can232_v3.pdf) -* -* Made for Arduino with Seeduino/ElecFreaks CAN BUS Shield based on MCP2515 -* -* Copyright (C) 2015 Anton Viktorov -* https://github.com/latonita/can-ascii -* -* This library is free software. You may use/redistribute it under The MIT License terms. -* -*****************************************************************************************/ - - -#ifndef _CAN_SERIAL_H_ -#define _CAN_SERIAL_H_ - -//#if defined(ARDUINO) && ARDUINO >= 100 -// #include "arduino.h" -//#else -// #include "WProgram.h" -//#endif - -#include "mcp_can.h" -#include "SoftwareSerial.h" - - -#define LW232_LAWICEL_VERSION_STR "V1013" -#define LW232_LAWICEL_SERIAL_NUM "NA123" -#define LW232_CAN_BUS_SHIELD_CS_PIN 10 - - -////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -// -// Commands not supported/not implemented: -// s, W, M, m, U -// -// Commands modified: -// S - supports not declared 83.3 rate straight away (S9) -// refer to https://github.com/latonita/CAN_BUS_Shield fork with 83.3 support, easy to add. -// F - returns MCP2515 error flags -// Z - extra Z2 option enables 4 byte timestamp vs standard 2 byte (60000ms max) -// -////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -// -// CODE SUPPORTED SYNTAX DESCRIPTION -// -#define LW232_CMD_SETUP 'S' // YES+ Sn[CR] Setup with standard CAN bit-rates where n is 0-8. - // S0 10Kbit S4 125Kbit S8 1Mbit - // S1 20Kbit S5 250Kbit S9 83.3Kbit - // S2 50Kbit S6 500Kbit - // S3 100Kbit S7 800Kbit -#define LW232_CMD_SETUP_BTR 's' // - sxxyy[CR] Setup with BTR0/BTR1 CAN bit-rates where xx and yy is a hex value. -#define LW232_CMD_OPEN 'O' // YES O[CR] Open the CAN channel in normal mode (sending & receiving). -#define LW232_CMD_LISTEN 'L' // YES L[CR] Open the CAN channel in listen only mode (receiving). -#define LW232_CMD_CLOSE 'C' // YES C[CR] Close the CAN channel. -#define LW232_CMD_TX11 't' // YES tiiildd...[CR] Transmit a standard (11bit) CAN frame. -#define LW232_CMD_TX29 'T' // YES Tiiiiiiiildd...[CR] Transmit an extended (29bit) CAN frame -#define LW232_CMD_RTR11 'r' // YES riiil[CR] Transmit an standard RTR (11bit) CAN frame. -#define LW232_CMD_RTR29 'R' // YES Riiiiiiiil[CR] Transmit an extended RTR (29bit) CAN frame. -#define LW232_CMD_POLL_ONE 'P' // YES P[CR] Poll incomming FIFO for CAN frames (single poll) -#define LW232_CMD_POLL_MANY 'A' // YES A[CR] Polls incomming FIFO for CAN frames (all pending frames) -#define LW232_CMD_FLAGS 'F' // YES+ F[CR] Read Status Flags. -#define LW232_CMD_AUTOPOLL 'X' // YES Xn[CR] Sets Auto Poll/Send ON/OFF for received frames. -#define LW232_CMD_FILTER 'W' // - Wn[CR] Filter mode setting. By default CAN232 works in dual filter mode (0) and is backwards compatible with previous CAN232 versions. -#define LW232_CMD_ACC_CODE 'M' // - Mxxxxxxxx[CR] Sets Acceptance Code Register (ACn Register of SJA1000). // we use MCP2515, not supported -#define LW232_CMD_ACC_MASK 'm' // - mxxxxxxxx[CR] Sets Acceptance Mask Register (AMn Register of SJA1000). // we use MCP2515, not supported -#define LW232_CMD_UART 'U' // YES Un[CR] Setup UART with a new baud rate where n is 0-6. -#define LW232_CMD_VERSION1 'V' // YES v[CR] Get Version number of both CAN232 hardware and software -#define LW232_CMD_VERSION2 'v' // YES V[CR] Get Version number of both CAN232 hardware and software -#define LW232_CMD_SERIAL 'N' // YES N[CR] Get Serial number of the CAN232. -#define LW232_CMD_TIMESTAMP 'Z' // YES+ Zn[CR] Sets Time Stamp ON/OFF for received frames only. EXTENSION to LAWICEL: Z2 - millis() timestamp w/o standard 60000ms cycle -#define LW232_CMD_AUTOSTART 'Q' // YES todo Qn[CR] Auto Startup feature (from power on). - -#define LOW_BYTE(x) ((unsigned char)((x)&0xFF)) -#define HIGH_BYTE(x) ((unsigned char)(((x)>>8)&0xFF)) -#define LOW_WORD(x) ((unsigned short)((x)&0xFFFF)) -#define HIGH_WORD(x) ((unsigned short)(((x)>>16)&0xFFFF)) - -#ifndef INT32U -#define INT32U unsigned long -#endif - -#ifndef INT16U -#define INT16U word -#endif - -#ifndef INT8U -#define INT8U byte -#endif - -#define LW232_OK 0x00 -#define LW232_OK_SMALL 0x01 -#define LW232_OK_BIG 0x02 -#define LW232_ERR 0x03 -#define LW232_ERR_NOT_IMPLEMENTED 0x04 -#define LW232_ERR_UNKNOWN_CMD 0x05 - -#define LW232_FILTER_SKIP 0x00 -#define LW232_FILTER_PROCESS 0x01 - -//#define LW232_IS_OK(x) ((x)==LW232_OK ||(x)==LW232_OK_NEW ? TRUE : FALSE) - -#define LW232_CR '\r' -#define LW232_ALL 'A' -#define LW232_FLAG 'F' -#define LW232_TR11 't' -#define LW232_TR29 'T' - -#define LW232_RET_ASCII_OK 0x0D -#define LW232_RET_ASCII_ERROR 0x07 -#define LW232_RET_ASCII_OK_SMALL 'z' -#define LW232_RET_ASCII_OK_BIG 'Z' - -#define LW232_STATUS_CAN_CLOSED 0x00 -#define LW232_STATUS_CAN_OPEN_NORMAL 0x01 -#define LW232_STATUS_CAN_OPEN_LISTEN 0x01 - -#define LW232_FRAME_MAX_LENGTH 0x08 -#define LW232_FRAME_MAX_SIZE (sizeof("Tiiiiiiiildddddddddddddddd\r")+1) - -#define LW232_INPUT_STRING_BUFFER_SIZE 200 - -#define LW232_OFF '0' -#define LW232_ON_ONE '1' -#define LW232_ON_TWO '2' - -#define LW232_AUTOPOLL_OFF 0x00 -#define LW232_AUTOPOLL_ON 0x01 - -#define LW232_AUTOSTART_OFF 0x00 -#define LW232_AUTOSTART_ON_NORMAL 0x01 -#define LW232_AUTOSTART_ON_LISTEN 0x02 - -#define LW232_TIMESTAMP_OFF 0x00 -#define LW232_TIMESTAMP_ON_NORMAL 0x01 -#define LW232_TIMESTAMP_ON_EXTENDED 0x02 - -#define LW232_OFFSET_STD_PKT_LEN 0x04 -#define LW232_OFFSET_STD_PKT_DATA 0x05 -#define LW232_OFFSET_EXT_PKT_LEN 0x09 -#define LW232_OFFSET_EXT_PKT_DATA 0x0A - - -#define LW232_DEFAULT_BAUD_RATE 115200 -#define LW232_DEFAULT_CAN_RATE CAN_500KBPS -#define LW232_DEFAULT_CLOCK_FREQ MCP_16MHz - -#define LW232_CAN_BAUD_NUM 0x0a -#define LW232_UART_BAUD_NUM 0x07 - - - -const INT32U lw232SerialBaudRates[] //PROGMEM -= { 230400, 115200, 57600, 38400, 19200, 9600, 2400 }; - -const INT32U lw232CanBaudRates[] //PROGMEM - = { CAN_10KBPS, CAN_20KBPS, CAN_50KBPS, CAN_100KBPS, CAN_125KBPS, CAN_250KBPS, CAN_500KBPS, CAN_800KBPS, CAN_1000KBPS, CAN_83K3BPS }; - -class Can232 -{ -public: - static void init(INT8U defaultCanSpeed = LW232_DEFAULT_CAN_RATE, const INT8U clock = LW232_DEFAULT_CLOCK_FREQ); - static void attach(MCP_CAN *can); - static void setFilter(INT8U (*userFunc)(INT32U)); - static void loop(); - static void serialEvent(); - -private: - static MCP_CAN *MCP_OBJECT; - static Can232* _instance; - static Can232* instance(); - - void initFunc(); - void setFilterFunc(INT8U (*userFunc)(INT32U)); - void loopFunc(); - void serialEventFunc(); - - INT8U (*userAddressFilterFunc)(INT32U addr) = 0; - - /* - MCP_CAN lw232CAN = MCP_CAN(LW232_CAN_BUS_SHIELD_CS_PIN); - */ - - INT8U lw232CanSpeedSelection = CAN_83K3BPS; - INT8U lw232McpModuleClock = MCP_16MHz; - INT8U lw232CanChannelMode = LW232_STATUS_CAN_CLOSED; - INT8U lw232LastErr = LW232_OK; - - INT8U lw232AutoStart = LW232_AUTOSTART_OFF; - INT8U lw232AutoPoll = LW232_AUTOPOLL_OFF; - INT8U lw232TimeStamp = LW232_TIMESTAMP_OFF; - - INT32U lw232CanId = 0; - - INT8U lw232Buffer[8]; - INT8U lw232PacketLen = 0; - - INT8U lw232Message[LW232_FRAME_MAX_SIZE]; - - String inputString = ""; // a string to hold incoming data - boolean stringComplete = false; // whether the string is complete - - INT8U parseAndRunCommand(); - INT8U exec(); - - INT8U checkReceive(); - INT8U readMsgBufID(INT32U *ID, INT8U *len, INT8U buf[]); - INT8U receiveSingleFrame(); - INT8U isExtendedFrame(); - INT8U checkPassFilter(INT32U addr); - INT8U openCanBus(); - - INT8U sendMsgBuf(INT32U id, INT8U ext, INT8U rtr, INT8U len, INT8U *buf); - - void parseCanStdId(); - void parseCanExtId(); -}; - -class HexHelper { -public: - static void printFullByte(INT8U b); - static void printNibble(INT8U b); - - static INT8U parseNibble(INT8U hex); - static INT8U parseFullByte(INT8U H, INT8U L); - static INT8U parseNibbleWithLimit(INT8U hex, INT8U limit); -}; - -class Can232Fake : Can232 { - -}; - - -#endif diff --git a/arduino/src/mcp/mcp2515_can.cpp b/arduino/src/mcp/mcp2515_can.cpp deleted file mode 100644 index 93b9a3d..0000000 --- a/arduino/src/mcp/mcp2515_can.cpp +++ /dev/null @@ -1,1546 +0,0 @@ -/* - mcp_can.cpp - 2012 Copyright (c) Seeed Technology Inc. All right reserved. - - Author:Loovee (loovee@seeed.cc) - 2014-1-16 - - Contributor: - - Cory J. Fowler - Latonita - Woodward1 - Mehtajaghvi - BykeBlast - TheRo0T - Tsipizic - ralfEdmund - Nathancheek - BlueAndi - Adlerweb - Btetz - Hurvajs - xboxpro1 - ttlappalainen - - The MIT License (MIT) - - Copyright (c) 2013 Seeed Technology Inc. - - 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. -*/ -#define DEBUG_EN 0 -#include "mcp2515_can.h" - -#define spi_readwrite pSPI->transfer -#define spi_read() spi_readwrite(0x00) -#define spi_write(spi_val) spi_readwrite(spi_val) -#define SPI_BEGIN() pSPI->beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE0)) -#define SPI_END() pSPI->endTransaction() - -/********************************************************************************************************* -** Function name: txCtrlReg -** Descriptions: return tx ctrl reg according to tx buffer index. -** According to my tests this is faster and saves memory compared using vector -*********************************************************************************************************/ -byte txCtrlReg(byte i) { - switch (i) { - case 0: return MCP_TXB0CTRL; - case 1: return MCP_TXB1CTRL; - case 2: return MCP_TXB2CTRL; - } - return MCP_TXB2CTRL; -} - -/********************************************************************************************************* -** Function name: statusToBuffer -** Descriptions: converts CANINTF status to tx buffer index -*********************************************************************************************************/ -byte statusToTxBuffer(byte status) { - switch (status) { - case MCP_TX0IF : return 0; - case MCP_TX1IF : return 1; - case MCP_TX2IF : return 2; - } - - return 0xff; -} - -/********************************************************************************************************* -** Function name: statusToBuffer -** Descriptions: converts CANINTF status to tx buffer sidh -*********************************************************************************************************/ -byte statusToTxSidh(byte status) { - switch (status) { - case MCP_TX0IF : return MCP_TXB0SIDH; - case MCP_TX1IF : return MCP_TXB1SIDH; - case MCP_TX2IF : return MCP_TXB2SIDH; - } - - return 0; -} - -/********************************************************************************************************* -** Function name: txSidhToTxLoad -** Descriptions: return tx load command according to tx buffer sidh register -*********************************************************************************************************/ -byte txSidhToRTS(byte sidh) { - switch (sidh) { - case MCP_TXB0SIDH: return MCP_RTS_TX0; - case MCP_TXB1SIDH: return MCP_RTS_TX1; - case MCP_TXB2SIDH: return MCP_RTS_TX2; - } - return 0; -} - -/********************************************************************************************************* -** Function name: txSidhToTxLoad -** Descriptions: return tx load command according to tx buffer sidh register -*********************************************************************************************************/ -byte txSidhToTxLoad(byte sidh) { - switch (sidh) { - case MCP_TXB0SIDH: return MCP_LOAD_TX0; - case MCP_TXB1SIDH: return MCP_LOAD_TX1; - case MCP_TXB2SIDH: return MCP_LOAD_TX2; - } - return 0; -} - -/********************************************************************************************************* -** Function name: txIfFlag -** Descriptions: return tx interrupt flag -*********************************************************************************************************/ -byte txIfFlag(byte i) { - switch (i) { - case 0: return MCP_TX0IF; - case 1: return MCP_TX1IF; - case 2: return MCP_TX2IF; - } - return 0; -} - -/********************************************************************************************************* -** Function name: txStatusPendingFlag -** Descriptions: return buffer tx pending flag on status -*********************************************************************************************************/ -byte txStatusPendingFlag(byte i) { - switch (i) { - case 0: return MCP_STAT_TX0_PENDING; - case 1: return MCP_STAT_TX1_PENDING; - case 2: return MCP_STAT_TX2_PENDING; - } - return 0xff; -} - -/********************************************************************************************************* -** Function name: mcp2515_reset -** Descriptions: reset the device -*********************************************************************************************************/ -void mcp2515_can::mcp2515_reset(void) { - #ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); - #endif - MCP2515_SELECT(); - spi_readwrite(MCP_RESET); - MCP2515_UNSELECT(); - #ifdef SPI_HAS_TRANSACTION - SPI_END(); - #endif - delay(10); -} - -/********************************************************************************************************* -** Function name: mcp2515_readRegister -** Descriptions: read register -*********************************************************************************************************/ -byte mcp2515_can::mcp2515_readRegister(const byte address) { - byte ret; - - #ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); - #endif - MCP2515_SELECT(); - spi_readwrite(MCP_READ); - spi_readwrite(address); - ret = spi_read(); - MCP2515_UNSELECT(); - #ifdef SPI_HAS_TRANSACTION - SPI_END(); - #endif - - return ret; -} - -/********************************************************************************************************* -** Function name: mcp2515_readRegisterS -** Descriptions: read registerS -*********************************************************************************************************/ -void mcp2515_can::mcp2515_readRegisterS(const byte address, byte values[], const byte n) { - byte i; - #ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); - #endif - MCP2515_SELECT(); - spi_readwrite(MCP_READ); - spi_readwrite(address); - // mcp2515 has auto-increment of address-pointer - for (i = 0; i < n && i < CAN_MAX_CHAR_IN_MESSAGE; i++) { - values[i] = spi_read(); - } - MCP2515_UNSELECT(); - #ifdef SPI_HAS_TRANSACTION - SPI_END(); - #endif -} - -/********************************************************************************************************* -** Function name: mcp2515_setRegister -** Descriptions: set register -*********************************************************************************************************/ -void mcp2515_can::mcp2515_setRegister(const byte address, const byte value) { - #ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); - #endif - MCP2515_SELECT(); - spi_readwrite(MCP_WRITE); - spi_readwrite(address); - spi_readwrite(value); - MCP2515_UNSELECT(); - #ifdef SPI_HAS_TRANSACTION - SPI_END(); - #endif -} - -/********************************************************************************************************* -** Function name: mcp2515_setRegisterS -** Descriptions: set registerS -*********************************************************************************************************/ -void mcp2515_can::mcp2515_setRegisterS(const byte address, const byte values[], const byte n) { - byte i; - #ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); - #endif - MCP2515_SELECT(); - spi_readwrite(MCP_WRITE); - spi_readwrite(address); - - for (i = 0; i < n; i++) { - spi_readwrite(values[i]); - } - MCP2515_UNSELECT(); - #ifdef SPI_HAS_TRANSACTION - SPI_END(); - #endif -} - -/********************************************************************************************************* -** Function name: mcp2515_modifyRegister -** Descriptions: set bit of one register -*********************************************************************************************************/ -void mcp2515_can::mcp2515_modifyRegister(const byte address, const byte mask, const byte data) { - #ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); - #endif - MCP2515_SELECT(); - spi_readwrite(MCP_BITMOD); - spi_readwrite(address); - spi_readwrite(mask); - spi_readwrite(data); - MCP2515_UNSELECT(); - #ifdef SPI_HAS_TRANSACTION - SPI_END(); - #endif -} - -/********************************************************************************************************* -** Function name: mcp2515_readStatus -** Descriptions: read mcp2515's Status -*********************************************************************************************************/ -byte mcp2515_can::mcp2515_readStatus(void) { - byte i; - #ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); - #endif - MCP2515_SELECT(); - spi_readwrite(MCP_READ_STATUS); - i = spi_read(); - MCP2515_UNSELECT(); - #ifdef SPI_HAS_TRANSACTION - SPI_END(); - #endif - - return i; -} - -/********************************************************************************************************* -** Function name: setSleepWakeup -** Descriptions: Enable or disable the wake up interrupt (If disabled the MCP2515 will not be woken up by CAN bus activity) -*********************************************************************************************************/ -void mcp2515_can::setSleepWakeup(const byte enable) { - mcp2515_modifyRegister(MCP_CANINTE, MCP_WAKIF, enable ? MCP_WAKIF : 0); -} - -/********************************************************************************************************* -** Function name: sleep -** Descriptions: Put mcp2515 in sleep mode to save power -*********************************************************************************************************/ -byte mcp2515_can::sleep() { - if (getMode() != MODE_SLEEP) { - return mcp2515_setCANCTRL_Mode(MODE_SLEEP); - } else { - return CAN_OK; - } -} - -/********************************************************************************************************* -** Function name: wake -** Descriptions: wake MCP2515 manually from sleep. It will come back in the mode it was before sleeping. -*********************************************************************************************************/ -byte mcp2515_can::wake() { - byte currMode = getMode(); - if (currMode != mcpMode) { - return mcp2515_setCANCTRL_Mode(mcpMode); - } else { - return CAN_OK; - } -} - -/********************************************************************************************************* -** Function name: setMode -** Descriptions: Sets control mode -*********************************************************************************************************/ -byte mcp2515_can::setMode(const byte opMode) { - if (opMode != - MODE_SLEEP) { // if going to sleep, the value stored in opMode is not changed so that we can return to it later - mcpMode = opMode; - } - return mcp2515_setCANCTRL_Mode(opMode); -} - -/********************************************************************************************************* -** Function name: getMode -** Descriptions: Returns current control mode -*********************************************************************************************************/ -byte mcp2515_can::getMode() { - return mcp2515_readRegister(MCP_CANSTAT) & MODE_MASK; -} - -/********************************************************************************************************* -** Function name: mcp2515_setCANCTRL_Mode -** Descriptions: set control mode -*********************************************************************************************************/ -byte mcp2515_can::mcp2515_setCANCTRL_Mode(const byte newmode) { - // If the chip is asleep and we want to change mode then a manual wake needs to be done - // This is done by setting the wake up interrupt flag - // This undocumented trick was found at https://github.com/mkleemann/can/blob/master/can_sleep_mcp2515.c - if ((getMode()) == MODE_SLEEP && newmode != MODE_SLEEP) { - // Make sure wake interrupt is enabled - byte wakeIntEnabled = (mcp2515_readRegister(MCP_CANINTE) & MCP_WAKIF); - if (!wakeIntEnabled) { - mcp2515_modifyRegister(MCP_CANINTE, MCP_WAKIF, MCP_WAKIF); - } - - // Set wake flag (this does the actual waking up) - mcp2515_modifyRegister(MCP_CANINTF, MCP_WAKIF, MCP_WAKIF); - - // Wait for the chip to exit SLEEP and enter LISTENONLY mode. - - // If the chip is not connected to a CAN bus (or the bus has no other powered nodes) it will sometimes trigger the wake interrupt as soon - // as it's put to sleep, but it will stay in SLEEP mode instead of automatically switching to LISTENONLY mode. - // In this situation the mode needs to be manually set to LISTENONLY. - - if (mcp2515_requestNewMode(MODE_LISTENONLY) != MCP2515_OK) { - return MCP2515_FAIL; - } - - // Turn wake interrupt back off if it was originally off - if (!wakeIntEnabled) { - mcp2515_modifyRegister(MCP_CANINTE, MCP_WAKIF, 0); - } - } - - // Clear wake flag - mcp2515_modifyRegister(MCP_CANINTF, MCP_WAKIF, 0); - - return mcp2515_requestNewMode(newmode); -} - -/********************************************************************************************************* -** Function name: mcp2515_requestNewMode -** Descriptions: Set control mode -*********************************************************************************************************/ -byte mcp2515_can::mcp2515_requestNewMode(const byte newmode) { - unsigned long startTime = millis(); - - // Spam new mode request and wait for the operation to complete - while (1) { - // Request new mode - // This is inside the loop as sometimes requesting the new mode once doesn't work (usually when attempting to sleep) - mcp2515_modifyRegister(MCP_CANCTRL, MODE_MASK, newmode); - - byte statReg = mcp2515_readRegister(MCP_CANSTAT); - if ((statReg & MODE_MASK) == newmode) { // We're now in the new mode - return MCP2515_OK; - } else if ((millis() - startTime) > 200) { // Wait no more than 200ms for the operation to complete - return MCP2515_FAIL; - } - } -} - -/********************************************************************************************************* -** Function name: mcp2515_configRate -** Descriptions: set baudrate -*********************************************************************************************************/ -byte mcp2515_can::mcp2515_configRate(const byte canSpeed, const byte clock) { - byte set, cfg1, cfg2, cfg3; - set = 1; - switch (clock) { - case (MCP_16MHz) : - switch (canSpeed) { - case (CAN_5KBPS): - cfg1 = MCP_16MHz_5kBPS_CFG1; - cfg2 = MCP_16MHz_5kBPS_CFG2; - cfg3 = MCP_16MHz_5kBPS_CFG3; - break; - - case (CAN_10KBPS): - cfg1 = MCP_16MHz_10kBPS_CFG1; - cfg2 = MCP_16MHz_10kBPS_CFG2; - cfg3 = MCP_16MHz_10kBPS_CFG3; - break; - - case (CAN_20KBPS): - cfg1 = MCP_16MHz_20kBPS_CFG1; - cfg2 = MCP_16MHz_20kBPS_CFG2; - cfg3 = MCP_16MHz_20kBPS_CFG3; - break; - - case (CAN_25KBPS): - cfg1 = MCP_16MHz_25kBPS_CFG1; - cfg2 = MCP_16MHz_25kBPS_CFG2; - cfg3 = MCP_16MHz_25kBPS_CFG3; - break; - - case (CAN_31K25BPS): - cfg1 = MCP_16MHz_31k25BPS_CFG1; - cfg2 = MCP_16MHz_31k25BPS_CFG2; - cfg3 = MCP_16MHz_31k25BPS_CFG3; - break; - - case (CAN_33KBPS): - cfg1 = MCP_16MHz_33kBPS_CFG1; - cfg2 = MCP_16MHz_33kBPS_CFG2; - cfg3 = MCP_16MHz_33kBPS_CFG3; - break; - - case (CAN_40KBPS): - cfg1 = MCP_16MHz_40kBPS_CFG1; - cfg2 = MCP_16MHz_40kBPS_CFG2; - cfg3 = MCP_16MHz_40kBPS_CFG3; - break; - - case (CAN_50KBPS): - cfg1 = MCP_16MHz_50kBPS_CFG1; - cfg2 = MCP_16MHz_50kBPS_CFG2; - cfg3 = MCP_16MHz_50kBPS_CFG3; - break; - - case (CAN_80KBPS): - cfg1 = MCP_16MHz_80kBPS_CFG1; - cfg2 = MCP_16MHz_80kBPS_CFG2; - cfg3 = MCP_16MHz_80kBPS_CFG3; - break; - - case (CAN_83K3BPS): - cfg1 = MCP_16MHz_83k3BPS_CFG1; - cfg2 = MCP_16MHz_83k3BPS_CFG2; - cfg3 = MCP_16MHz_83k3BPS_CFG3; - break; - - case (CAN_95KBPS): - cfg1 = MCP_16MHz_95kBPS_CFG1; - cfg2 = MCP_16MHz_95kBPS_CFG2; - cfg3 = MCP_16MHz_95kBPS_CFG3; - break; - - case (CAN_100KBPS): - cfg1 = MCP_16MHz_100kBPS_CFG1; - cfg2 = MCP_16MHz_100kBPS_CFG2; - cfg3 = MCP_16MHz_100kBPS_CFG3; - break; - - case (CAN_125KBPS): - cfg1 = MCP_16MHz_125kBPS_CFG1; - cfg2 = MCP_16MHz_125kBPS_CFG2; - cfg3 = MCP_16MHz_125kBPS_CFG3; - break; - - case (CAN_200KBPS): - cfg1 = MCP_16MHz_200kBPS_CFG1; - cfg2 = MCP_16MHz_200kBPS_CFG2; - cfg3 = MCP_16MHz_200kBPS_CFG3; - break; - - case (CAN_250KBPS): - cfg1 = MCP_16MHz_250kBPS_CFG1; - cfg2 = MCP_16MHz_250kBPS_CFG2; - cfg3 = MCP_16MHz_250kBPS_CFG3; - break; - - case (CAN_500KBPS): - cfg1 = MCP_16MHz_500kBPS_CFG1; - cfg2 = MCP_16MHz_500kBPS_CFG2; - cfg3 = MCP_16MHz_500kBPS_CFG3; - break; - - case (CAN_666KBPS): - cfg1 = MCP_16MHz_666kBPS_CFG1; - cfg2 = MCP_16MHz_666kBPS_CFG2; - cfg3 = MCP_16MHz_666kBPS_CFG3; - break; - - case (CAN_800KBPS) : - cfg1 = MCP_16MHz_800kBPS_CFG1; - cfg2 = MCP_16MHz_800kBPS_CFG2; - cfg3 = MCP_16MHz_800kBPS_CFG3; - break; - - case (CAN_1000KBPS): - cfg1 = MCP_16MHz_1000kBPS_CFG1; - cfg2 = MCP_16MHz_1000kBPS_CFG2; - cfg3 = MCP_16MHz_1000kBPS_CFG3; - break; - - default: - set = 0; - break; - } - break; - - case (MCP_8MHz) : - switch (canSpeed) { - case (CAN_5KBPS) : - cfg1 = MCP_8MHz_5kBPS_CFG1; - cfg2 = MCP_8MHz_5kBPS_CFG2; - cfg3 = MCP_8MHz_5kBPS_CFG3; - break; - - case (CAN_10KBPS) : - cfg1 = MCP_8MHz_10kBPS_CFG1; - cfg2 = MCP_8MHz_10kBPS_CFG2; - cfg3 = MCP_8MHz_10kBPS_CFG3; - break; - - case (CAN_20KBPS) : - cfg1 = MCP_8MHz_20kBPS_CFG1; - cfg2 = MCP_8MHz_20kBPS_CFG2; - cfg3 = MCP_8MHz_20kBPS_CFG3; - break; - - case (CAN_31K25BPS) : - cfg1 = MCP_8MHz_31k25BPS_CFG1; - cfg2 = MCP_8MHz_31k25BPS_CFG2; - cfg3 = MCP_8MHz_31k25BPS_CFG3; - break; - - case (CAN_40KBPS) : - cfg1 = MCP_8MHz_40kBPS_CFG1; - cfg2 = MCP_8MHz_40kBPS_CFG2; - cfg3 = MCP_8MHz_40kBPS_CFG3; - break; - - case (CAN_50KBPS) : - cfg1 = MCP_8MHz_50kBPS_CFG1; - cfg2 = MCP_8MHz_50kBPS_CFG2; - cfg3 = MCP_8MHz_50kBPS_CFG3; - break; - - case (CAN_80KBPS) : - cfg1 = MCP_8MHz_80kBPS_CFG1; - cfg2 = MCP_8MHz_80kBPS_CFG2; - cfg3 = MCP_8MHz_80kBPS_CFG3; - break; - - case (CAN_100KBPS) : - cfg1 = MCP_8MHz_100kBPS_CFG1; - cfg2 = MCP_8MHz_100kBPS_CFG2; - cfg3 = MCP_8MHz_100kBPS_CFG3; - break; - - case (CAN_125KBPS) : - cfg1 = MCP_8MHz_125kBPS_CFG1; - cfg2 = MCP_8MHz_125kBPS_CFG2; - cfg3 = MCP_8MHz_125kBPS_CFG3; - break; - - case (CAN_200KBPS) : - cfg1 = MCP_8MHz_200kBPS_CFG1; - cfg2 = MCP_8MHz_200kBPS_CFG2; - cfg3 = MCP_8MHz_200kBPS_CFG3; - break; - - case (CAN_250KBPS) : - cfg1 = MCP_8MHz_250kBPS_CFG1; - cfg2 = MCP_8MHz_250kBPS_CFG2; - cfg3 = MCP_8MHz_250kBPS_CFG3; - break; - - case (CAN_500KBPS) : - cfg1 = MCP_8MHz_500kBPS_CFG1; - cfg2 = MCP_8MHz_500kBPS_CFG2; - cfg3 = MCP_8MHz_500kBPS_CFG3; - break; - - case (CAN_800KBPS) : - cfg1 = MCP_8MHz_800kBPS_CFG1; - cfg2 = MCP_8MHz_800kBPS_CFG2; - cfg3 = MCP_8MHz_800kBPS_CFG3; - break; - - case (CAN_1000KBPS) : - cfg1 = MCP_8MHz_1000kBPS_CFG1; - cfg2 = MCP_8MHz_1000kBPS_CFG2; - cfg3 = MCP_8MHz_1000kBPS_CFG3; - break; - - default: - set = 0; - break; - } - break; - - default: - set = 0; - break; - } - - if (set) { - mcp2515_setRegister(MCP_CNF1, cfg1); - mcp2515_setRegister(MCP_CNF2, cfg2); - mcp2515_setRegister(MCP_CNF3, cfg3); - return MCP2515_OK; - } else { - return MCP2515_FAIL; - } -} - -/********************************************************************************************************* -** Function name: mcp2515_initCANBuffers -** Descriptions: init canbuffers -*********************************************************************************************************/ -void mcp2515_can::mcp2515_initCANBuffers(void) { - byte i, a1, a2, a3; - - a1 = MCP_TXB0CTRL; - a2 = MCP_TXB1CTRL; - a3 = MCP_TXB2CTRL; - for (i = 0; i < 14; i++) { // in-buffer loop - mcp2515_setRegister(a1, 0); - mcp2515_setRegister(a2, 0); - mcp2515_setRegister(a3, 0); - a1++; - a2++; - a3++; - } - mcp2515_setRegister(MCP_RXB0CTRL, 0); - mcp2515_setRegister(MCP_RXB1CTRL, 0); -} - -/********************************************************************************************************* -** Function name: mcp2515_init -** Descriptions: init the device -*********************************************************************************************************/ -byte mcp2515_can::mcp2515_init(const byte canSpeed, const byte clock) { - - byte res; - - mcp2515_reset(); - - res = mcp2515_setCANCTRL_Mode(MODE_CONFIG); - if (res > 0) { - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Enter setting mode fail")); - #else - delay(10); - #endif - return res; - } - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Enter setting mode success ")); - #else - delay(10); - #endif - - // set boadrate - if (mcp2515_configRate(canSpeed, clock)) { - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("set rate fall!!")); - #else - delay(10); - #endif - return res; - } - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("set rate success!!")); - #else - delay(10); - #endif - - if (res == MCP2515_OK) { - - // init canbuffers - mcp2515_initCANBuffers(); - - // interrupt mode - mcp2515_setRegister(MCP_CANINTE, MCP_RX0IF | MCP_RX1IF); - - #if (DEBUG_RXANY==1) - // enable both receive-buffers to receive any message and enable rollover - mcp2515_modifyRegister(MCP_RXB0CTRL, - MCP_RXB_RX_MASK | MCP_RXB_BUKT_MASK, - MCP_RXB_RX_ANY | MCP_RXB_BUKT_MASK); - mcp2515_modifyRegister(MCP_RXB1CTRL, MCP_RXB_RX_MASK, - MCP_RXB_RX_ANY); - #else - // enable both receive-buffers to receive messages with std. and ext. identifiers and enable rollover - mcp2515_modifyRegister(MCP_RXB0CTRL, - MCP_RXB_RX_MASK | MCP_RXB_BUKT_MASK, - MCP_RXB_RX_STDEXT | MCP_RXB_BUKT_MASK); - mcp2515_modifyRegister(MCP_RXB1CTRL, MCP_RXB_RX_MASK, - MCP_RXB_RX_STDEXT); - #endif - // enter normal mode - res = setMode(MODE_NORMAL); - if (res) { - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Enter Normal Mode Fail!!")); - #else - delay(10); - #endif - return res; - } - - - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Enter Normal Mode Success!!")); - #else - delay(10); - #endif - - } - return res; - -} - -/********************************************************************************************************* -** Function name: mcp2515_id_to_buf -** Descriptions: configure tbufdata[4] from id and ext -*********************************************************************************************************/ -void mcp2515_id_to_buf(const byte ext, const unsigned long id, byte* tbufdata) { - uint16_t canid; - - canid = (uint16_t)(id & 0x0FFFF); - - if (ext == 1) { - tbufdata[MCP_EID0] = (byte)(canid & 0xFF); - tbufdata[MCP_EID8] = (byte)(canid >> 8); - canid = (uint16_t)(id >> 16); - tbufdata[MCP_SIDL] = (byte)(canid & 0x03); - tbufdata[MCP_SIDL] += (byte)((canid & 0x1C) << 3); - tbufdata[MCP_SIDL] |= MCP_TXB_EXIDE_M; - tbufdata[MCP_SIDH] = (byte)(canid >> 5); - } else { - tbufdata[MCP_SIDH] = (byte)(canid >> 3); - tbufdata[MCP_SIDL] = (byte)((canid & 0x07) << 5); - tbufdata[MCP_EID0] = 0; - tbufdata[MCP_EID8] = 0; - } -} - -/********************************************************************************************************* -** Function name: mcp2515_write_id -** Descriptions: write can id -*********************************************************************************************************/ -void mcp2515_can::mcp2515_write_id(const byte mcp_addr, const byte ext, const unsigned long id) { - byte tbufdata[4]; - - mcp2515_id_to_buf(ext, id, tbufdata); - mcp2515_setRegisterS(mcp_addr, tbufdata, 4); -} - -/********************************************************************************************************* -** Function name: mcp2515_read_id -** Descriptions: read can id -*********************************************************************************************************/ -void mcp2515_can::mcp2515_read_id(const byte mcp_addr, byte* ext, unsigned long* id) { - byte tbufdata[4]; - - *ext = 0; - *id = 0; - - mcp2515_readRegisterS(mcp_addr, tbufdata, 4); - - *id = (tbufdata[MCP_SIDH] << 3) + (tbufdata[MCP_SIDL] >> 5); - - if ((tbufdata[MCP_SIDL] & MCP_TXB_EXIDE_M) == MCP_TXB_EXIDE_M) { - // extended id - *id = (*id << 2) + (tbufdata[MCP_SIDL] & 0x03); - *id = (*id << 8) + tbufdata[MCP_EID8]; - *id = (*id << 8) + tbufdata[MCP_EID0]; - *ext = 1; - } -} - -/********************************************************************************************************* -** Function name: mcp2515_write_canMsg -** Descriptions: write msg -** Note! There is no check for right address! -*********************************************************************************************************/ -void mcp2515_can::mcp2515_write_canMsg(const byte buffer_sidh_addr, unsigned long id, byte ext, byte rtrBit, byte len, - volatile const byte* buf) { - byte load_addr = txSidhToTxLoad(buffer_sidh_addr); - - byte tbufdata[4]; - byte dlc = len | (rtrBit ? MCP_RTR_MASK : 0) ; - byte i; - - mcp2515_id_to_buf(ext, id, tbufdata); - - #ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); - #endif - MCP2515_SELECT(); - spi_readwrite(load_addr); - for (i = 0; i < 4; i++) { - spi_write(tbufdata[i]); - } - spi_write(dlc); - for (i = 0; i < len && i < CAN_MAX_CHAR_IN_MESSAGE; i++) { - spi_write(buf[i]); - } - - MCP2515_UNSELECT(); - #ifdef SPI_HAS_TRANSACTION - SPI_END(); - #endif - - mcp2515_start_transmit(buffer_sidh_addr); - -} - -/********************************************************************************************************* -** Function name: mcp2515_read_canMsg -** Descriptions: read message -*********************************************************************************************************/ -void mcp2515_can::mcp2515_read_canMsg(const byte buffer_load_addr, volatile unsigned long* id, volatile byte* ext, - volatile byte* rtrBit, volatile byte* len, volatile byte* buf) { /* read can msg */ - byte tbufdata[4]; - byte i; - - MCP2515_SELECT(); - spi_readwrite(buffer_load_addr); - // mcp2515 has auto-increment of address-pointer - for (i = 0; i < 4; i++) { - tbufdata[i] = spi_read(); - } - - *id = (tbufdata[MCP_SIDH] << 3) + (tbufdata[MCP_SIDL] >> 5); - *ext = 0; - if ((tbufdata[MCP_SIDL] & MCP_TXB_EXIDE_M) == MCP_TXB_EXIDE_M) { - /* extended id */ - *id = (*id << 2) + (tbufdata[MCP_SIDL] & 0x03); - *id = (*id << 8) + tbufdata[MCP_EID8]; - *id = (*id << 8) + tbufdata[MCP_EID0]; - *ext = 1; - } - - byte pMsgSize = spi_read(); - *len = pMsgSize & MCP_DLC_MASK; - *rtrBit = (pMsgSize & MCP_RTR_MASK) ? 1 : 0; - for (i = 0; i < *len && i < CAN_MAX_CHAR_IN_MESSAGE; i++) { - buf[i] = spi_read(); - } - - MCP2515_UNSELECT(); -} - -/********************************************************************************************************* -** Function name: mcp2515_start_transmit -** Descriptions: Start message transmit on mcp2515 -*********************************************************************************************************/ -void mcp2515_can::mcp2515_start_transmit(const byte mcp_addr) { // start transmit - #ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); - #endif - MCP2515_SELECT(); - spi_readwrite(txSidhToRTS(mcp_addr)); - MCP2515_UNSELECT(); - #ifdef SPI_HAS_TRANSACTION - SPI_END(); - #endif -} - -/********************************************************************************************************* -** Function name: mcp2515_isTXBufFree -** Descriptions: Test is tx buffer free for transmitting -*********************************************************************************************************/ -byte mcp2515_can::mcp2515_isTXBufFree(byte* txbuf_n, byte iBuf) { /* get Next free txbuf */ - *txbuf_n = 0x00; - - if (iBuf >= MCP_N_TXBUFFERS || - (mcp2515_readStatus() & txStatusPendingFlag(iBuf)) != 0) { - return MCP_ALLTXBUSY; - } - - *txbuf_n = txCtrlReg(iBuf) + 1; /* return SIDH-address of Buffer */ - mcp2515_modifyRegister(MCP_CANINTF, txIfFlag(iBuf), 0); - - return MCP2515_OK; -} - -/********************************************************************************************************* -** Function name: mcp2515_getNextFreeTXBuf -** Descriptions: finds next free tx buffer for sending. Return MCP_ALLTXBUSY, if there is none. -*********************************************************************************************************/ -byte mcp2515_can::mcp2515_getNextFreeTXBuf(byte* txbuf_n) { // get Next free txbuf - byte status = mcp2515_readStatus() & MCP_STAT_TX_PENDING_MASK; - byte i; - - *txbuf_n = 0x00; - - if (status == MCP_STAT_TX_PENDING_MASK) { - return MCP_ALLTXBUSY; // All buffers are pending - } - - // check all 3 TX-Buffers except reserved - for (i = 0; i < MCP_N_TXBUFFERS - nReservedTx; i++) { - if ((status & txStatusPendingFlag(i)) == 0) { - *txbuf_n = txCtrlReg(i) + 1; // return SIDH-address of Buffer - mcp2515_modifyRegister(MCP_CANINTF, txIfFlag(i), 0); - return MCP2515_OK; // ! function exit - } - } - - return MCP_ALLTXBUSY; -} -/********************************************************************************************************* -** Function name: begin -** Descriptions: init can and set speed -*********************************************************************************************************/ -byte mcp2515_can::begin(uint32_t speedset, const byte clockset) { - pSPI->begin(); - byte res = mcp2515_init((byte)speedset, clockset); - - return ((res == MCP2515_OK) ? CAN_OK : CAN_FAILINIT); -} - -/********************************************************************************************************* -** Function name: enableTxInterrupt -** Descriptions: enable interrupt for all tx buffers -*********************************************************************************************************/ -void mcp2515_can::enableTxInterrupt(bool enable) { - byte interruptStatus = mcp2515_readRegister(MCP_CANINTE); - - if (enable) { - interruptStatus |= MCP_TX_INT; - } else { - interruptStatus &= ~MCP_TX_INT; - } - - mcp2515_setRegister(MCP_CANINTE, interruptStatus); -} - -/********************************************************************************************************* -** Function name: init_Mask -** Descriptions: init canid Masks -*********************************************************************************************************/ -byte mcp2515_can::init_Mask(byte num, byte ext, unsigned long ulData) { - byte res = MCP2515_OK; - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Begin to set Mask!!")); - #else - delay(10); - #endif - res = mcp2515_setCANCTRL_Mode(MODE_CONFIG); - if (res > 0) { - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Enter setting mode fall")); - #else - delay(10); - #endif - return res; - } - - if (num == 0) { - mcp2515_write_id(MCP_RXM0SIDH, ext, ulData); - - } else if (num == 1) { - mcp2515_write_id(MCP_RXM1SIDH, ext, ulData); - } else { - res = MCP2515_FAIL; - } - - res = mcp2515_setCANCTRL_Mode(mcpMode); - if (res > 0) { - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Enter normal mode fall")); - #else - delay(10); - #endif - return res; - } - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("set Mask success!!")); - #else - delay(10); - #endif - return res; -} - -/********************************************************************************************************* -** Function name: init_Filt -** Descriptions: init canid filters -*********************************************************************************************************/ -byte mcp2515_can::init_Filt(byte num, byte ext, unsigned long ulData) { - byte res = MCP2515_OK; - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Begin to set Filter!!")); - #else - delay(10); - #endif - res = mcp2515_setCANCTRL_Mode(MODE_CONFIG); - if (res > 0) { - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Enter setting mode fall")); - #else - delay(10); - #endif - return res; - } - - switch (num) { - case 0: - mcp2515_write_id(MCP_RXF0SIDH, ext, ulData); - break; - - case 1: - mcp2515_write_id(MCP_RXF1SIDH, ext, ulData); - break; - - case 2: - mcp2515_write_id(MCP_RXF2SIDH, ext, ulData); - break; - - case 3: - mcp2515_write_id(MCP_RXF3SIDH, ext, ulData); - break; - - case 4: - mcp2515_write_id(MCP_RXF4SIDH, ext, ulData); - break; - - case 5: - mcp2515_write_id(MCP_RXF5SIDH, ext, ulData); - break; - - default: - res = MCP2515_FAIL; - } - - res = mcp2515_setCANCTRL_Mode(mcpMode); - if (res > 0) { - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Enter normal mode fall\r\nSet filter fail!!")); - #else - delay(10); - #endif - return res; - } - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("set Filter success!!")); - #else - delay(10); - #endif - - return res; -} - -/********************************************************************************************************* -** Function name: sendMsgBuf -** Descriptions: Send message by using buffer read as free from CANINTF status -** Status has to be read with readRxTxStatus and filtered with checkClearTxStatus -*********************************************************************************************************/ -byte mcp2515_can::sendMsgBuf(byte status, unsigned long id, byte ext, byte rtrBit, byte len, volatile const byte* buf) { - byte txbuf_n = statusToTxSidh(status); - - if (txbuf_n == 0) { - return CAN_FAILTX; // Invalid status - } - - mcp2515_modifyRegister(MCP_CANINTF, status, 0); // Clear interrupt flag - mcp2515_write_canMsg(txbuf_n, id, ext, rtrBit, len, buf); - - return CAN_OK; -} - -/********************************************************************************************************* -** Function name: trySendMsgBuf -** Descriptions: Try to send message. There is no delays for waiting free buffer. -*********************************************************************************************************/ -byte mcp2515_can::trySendMsgBuf(unsigned long id, byte ext, byte rtrBit, byte len, const byte* buf, byte iTxBuf) { - byte txbuf_n; - - if (iTxBuf < MCP_N_TXBUFFERS) { // Use specified buffer - if (mcp2515_isTXBufFree(&txbuf_n, iTxBuf) != MCP2515_OK) { - return CAN_FAILTX; - } - } else { - if (mcp2515_getNextFreeTXBuf(&txbuf_n) != MCP2515_OK) { - return CAN_FAILTX; - } - } - - mcp2515_write_canMsg(txbuf_n, id, ext, rtrBit, len, buf); - - return CAN_OK; -} - -/********************************************************************************************************* -** Function name: sendMsg -** Descriptions: send message -*********************************************************************************************************/ -byte mcp2515_can::sendMsg(unsigned long id, byte ext, byte rtrBit, byte len, const byte* buf, bool wait_sent) { - byte res, res1, txbuf_n; - uint16_t uiTimeOut = 0; - - can_id = id; - ext_flg = ext; - rtr = rtrBit; - - do { - if (uiTimeOut > 0) { - delayMicroseconds(10); - } - res = mcp2515_getNextFreeTXBuf(&txbuf_n); // info = addr. - uiTimeOut++; - } while (res == MCP_ALLTXBUSY && (uiTimeOut < TIMEOUTVALUE)); - - if (uiTimeOut == TIMEOUTVALUE) { - return CAN_GETTXBFTIMEOUT; // get tx buff time out - } - mcp2515_write_canMsg(txbuf_n, id, ext, rtrBit, len, buf); - - if (wait_sent) { - uiTimeOut = 0; - do { - if (uiTimeOut > 0) { - delayMicroseconds(10); - } - uiTimeOut++; - res1 = mcp2515_readRegister(txbuf_n - 1); // read send buff ctrl reg - res1 = res1 & 0x08; - } while (res1 && (uiTimeOut < TIMEOUTVALUE)); - - if (uiTimeOut == TIMEOUTVALUE) { // send msg timeout - return CAN_SENDMSGTIMEOUT; - } - } - - return CAN_OK; - -} - -/********************************************************************************************************* -** Function name: sendMsgBuf -** Descriptions: send buf -*********************************************************************************************************/ -byte mcp2515_can::sendMsgBuf(unsigned long id, byte ext, byte rtrBit, byte len, const byte* buf, bool wait_sent) { - return sendMsg(id, ext, rtrBit, len, buf, wait_sent); -} - -/********************************************************************************************************* -** Function name: readMsgBufID -** Descriptions: Read message buf and can bus source ID according to status. -** Status has to be read with readRxTxStatus. -*********************************************************************************************************/ -byte mcp2515_can::readMsgBufID(byte status, volatile unsigned long* id, volatile byte* ext, volatile byte* rtrBit, - volatile byte* len, volatile byte* buf) { - byte rc = CAN_NOMSG; - - if (status & MCP_RX0IF) { // Msg in Buffer 0 - mcp2515_read_canMsg(MCP_READ_RX0, id, ext, rtrBit, len, buf); - rc = CAN_OK; - } else if (status & MCP_RX1IF) { // Msg in Buffer 1 - mcp2515_read_canMsg(MCP_READ_RX1, id, ext, rtrBit, len, buf); - rc = CAN_OK; - } - - if (rc == CAN_OK) { - rtr = *rtrBit; - // dta_len=*len; // not used on any interface function - ext_flg = *ext; - can_id = *id; - } else { - *len = 0; - } - - return rc; -} - -/********************************************************************************************************* -** Function name: readRxTxStatus -** Descriptions: Read RX and TX interrupt bits. Function uses status reading, but translates. -** result to MCP_CANINTF. With this you can check status e.g. on interrupt sr -** with one single call to save SPI calls. Then use checkClearRxStatus and -** checkClearTxStatus for testing. -*********************************************************************************************************/ -byte mcp2515_can::readRxTxStatus(void) { - byte ret = (mcp2515_readStatus() & (MCP_STAT_TXIF_MASK | MCP_STAT_RXIF_MASK)); - ret = (ret & MCP_STAT_TX0IF ? MCP_TX0IF : 0) | - (ret & MCP_STAT_TX1IF ? MCP_TX1IF : 0) | - (ret & MCP_STAT_TX2IF ? MCP_TX2IF : 0) | - (ret & MCP_STAT_RXIF_MASK); // Rx bits happend to be same on status and MCP_CANINTF - return ret; -} - -/********************************************************************************************************* -** Function name: checkClearRxStatus -** Descriptions: Return first found rx CANINTF status and clears it from parameter. -** Note that this does not affect to chip CANINTF at all. You can use this -** with one single readRxTxStatus call. -*********************************************************************************************************/ -byte mcp2515_can::checkClearRxStatus(byte* status) { - byte ret; - - ret = *status & MCP_RX0IF; *status &= ~MCP_RX0IF; - - if (ret == 0) { - ret = *status & MCP_RX1IF; - *status &= ~MCP_RX1IF; - } - - return ret; -} - -/********************************************************************************************************* -** Function name: checkClearTxStatus -** Descriptions: Return specified buffer of first found tx CANINTF status and clears it from parameter. -** Note that this does not affect to chip CANINTF at all. You can use this -** with one single readRxTxStatus call. -*********************************************************************************************************/ -byte mcp2515_can::checkClearTxStatus(byte* status, byte iTxBuf) { - byte ret; - - if (iTxBuf < MCP_N_TXBUFFERS) { // Clear specific buffer flag - ret = *status & txIfFlag(iTxBuf); *status &= ~txIfFlag(iTxBuf); - } else { - ret = 0; - for (byte i = 0; i < MCP_N_TXBUFFERS - nReservedTx; i++) { - ret = *status & txIfFlag(i); - if (ret != 0) { - *status &= ~txIfFlag(i); - return ret; - } - }; - } - - return ret; -} - -/********************************************************************************************************* -** Function name: clearBufferTransmitIfFlags -** Descriptions: Clear transmit interrupt flags for specific buffer or for all unreserved buffers. -** If interrupt will be used, it is important to clear all flags, when there is no -** more data to be sent. Otherwise IRQ will newer change state. -*********************************************************************************************************/ -void mcp2515_can::clearBufferTransmitIfFlags(byte flags) { - flags &= MCP_TX_INT; - if (flags == 0) { - return; - } - mcp2515_modifyRegister(MCP_CANINTF, flags, 0); -} - -/********************************************************************************************************* -** Function name: checkReceive -** Descriptions: check if got something -*********************************************************************************************************/ -byte mcp2515_can::checkReceive(void) { - byte res; - res = mcp2515_readStatus(); // RXnIF in Bit 1 and 0 - return ((res & MCP_STAT_RXIF_MASK) ? CAN_MSGAVAIL : CAN_NOMSG); -} - -/********************************************************************************************************* -** Function name: checkError -** Descriptions: if something error -*********************************************************************************************************/ -byte mcp2515_can::checkError(uint8_t* err_ptr) { - byte eflg = mcp2515_readRegister(MCP_EFLG); - if (err_ptr) { - *err_ptr = eflg; - } - return ((eflg & MCP_EFLG_ERRORMASK) ? CAN_CTRLERROR : CAN_OK); -} - -/********************************************************************************************************* -** Function name: mcpPinMode -** Descriptions: switch supported pins between HiZ, interrupt, output or input -*********************************************************************************************************/ -bool mcp2515_can::mcpPinMode(const byte pin, const byte mode) { - byte res; - bool ret = true; - - switch (pin) { - case MCP_RX0BF: - switch (mode) { - case MCP_PIN_HIZ: - mcp2515_modifyRegister(MCP_BFPCTRL, B0BFE, 0); - break; - case MCP_PIN_INT: - mcp2515_modifyRegister(MCP_BFPCTRL, B0BFM | B0BFE, B0BFM | B0BFE); - break; - case MCP_PIN_OUT: - mcp2515_modifyRegister(MCP_BFPCTRL, B0BFM | B0BFE, B0BFE); - break; - default: - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Invalid pin mode request")); - #endif - return false; - } - return true; - break; - case MCP_RX1BF: - switch (mode) { - case MCP_PIN_HIZ: - mcp2515_modifyRegister(MCP_BFPCTRL, B1BFE, 0); - break; - case MCP_PIN_INT: - mcp2515_modifyRegister(MCP_BFPCTRL, B1BFM | B1BFE, B1BFM | B1BFE); - break; - case MCP_PIN_OUT: - mcp2515_modifyRegister(MCP_BFPCTRL, B1BFM | B1BFE, B1BFE); - break; - default: - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Invalid pin mode request")); - #endif - return false; - } - return true; - break; - case MCP_TX0RTS: - res = mcp2515_setCANCTRL_Mode(MODE_CONFIG); - if (res > 0) { - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Entering Configuration Mode Failure...")); - #else - delay(10); - #endif - return false; - } - switch (mode) { - case MCP_PIN_INT: - mcp2515_modifyRegister(MCP_TXRTSCTRL, B0RTSM, B0RTSM); - break; - case MCP_PIN_IN: - mcp2515_modifyRegister(MCP_TXRTSCTRL, B0RTSM, 0); - break; - default: - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Invalid pin mode request")); - #endif - ret = false; - } - res = mcp2515_setCANCTRL_Mode(mcpMode); - if (res) { - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("`Setting ID Mode Failure...")); - #else - delay(10); - #endif - return false; - } - return ret; - break; - case MCP_TX1RTS: - res = mcp2515_setCANCTRL_Mode(MODE_CONFIG); - if (res > 0) { - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Entering Configuration Mode Failure...")); - #else - delay(10); - #endif - return false; - } - switch (mode) { - case MCP_PIN_INT: - mcp2515_modifyRegister(MCP_TXRTSCTRL, B1RTSM, B1RTSM); - break; - case MCP_PIN_IN: - mcp2515_modifyRegister(MCP_TXRTSCTRL, B1RTSM, 0); - break; - default: - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Invalid pin mode request")); - #endif - ret = false; - } - res = mcp2515_setCANCTRL_Mode(mcpMode); - if (res) { - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("`Setting ID Mode Failure...")); - #else - delay(10); - #endif - return false; - } - return ret; - break; - case MCP_TX2RTS: - res = mcp2515_setCANCTRL_Mode(MODE_CONFIG); - if (res > 0) { - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Entering Configuration Mode Failure...")); - #else - delay(10); - #endif - return false; - } - switch (mode) { - case MCP_PIN_INT: - mcp2515_modifyRegister(MCP_TXRTSCTRL, B2RTSM, B2RTSM); - break; - case MCP_PIN_IN: - mcp2515_modifyRegister(MCP_TXRTSCTRL, B2RTSM, 0); - break; - default: - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Invalid pin mode request")); - #endif - ret = false; - } - res = mcp2515_setCANCTRL_Mode(mcpMode); - if (res) { - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("`Setting ID Mode Failure...")); - #else - delay(10); - #endif - return false; - } - return ret; - break; - default: - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Invalid pin for mode request")); - #endif - return false; - } -} - -/********************************************************************************************************* -** Function name: mcpDigitalWrite -** Descriptions: write HIGH or LOW to RX0BF/RX1BF -*********************************************************************************************************/ -bool mcp2515_can::mcpDigitalWrite(const byte pin, const byte mode) { - switch (pin) { - case MCP_RX0BF: - switch (mode) { - case HIGH: - mcp2515_modifyRegister(MCP_BFPCTRL, B0BFS, B0BFS); - return true; - break; - default: - mcp2515_modifyRegister(MCP_BFPCTRL, B0BFS, 0); - return true; - } - break; - case MCP_RX1BF: - switch (mode) { - case HIGH: - mcp2515_modifyRegister(MCP_BFPCTRL, B1BFS, B1BFS); - return true; - break; - default: - mcp2515_modifyRegister(MCP_BFPCTRL, B1BFS, 0); - return true; - } - break; - default: - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Invalid pin for mcpDigitalWrite")); - #endif - return false; - } -} - -/********************************************************************************************************* -** Function name: mcpDigitalRead -** Descriptions: read HIGH or LOW from supported pins -*********************************************************************************************************/ -byte mcp2515_can::mcpDigitalRead(const byte pin) { - switch (pin) { - case MCP_RX0BF: - if ((mcp2515_readRegister(MCP_BFPCTRL) & B0BFS) > 0) { - return HIGH; - } else { - return LOW; - } - break; - case MCP_RX1BF: - if ((mcp2515_readRegister(MCP_BFPCTRL) & B1BFS) > 0) { - return HIGH; - } else { - return LOW; - } - break; - case MCP_TX0RTS: - if ((mcp2515_readRegister(MCP_TXRTSCTRL) & B0RTS) > 0) { - return HIGH; - } else { - return LOW; - } - break; - case MCP_TX1RTS: - if ((mcp2515_readRegister(MCP_TXRTSCTRL) & B1RTS) > 0) { - return HIGH; - } else { - return LOW; - } - break; - case MCP_TX2RTS: - if ((mcp2515_readRegister(MCP_TXRTSCTRL) & B2RTS) > 0) { - return HIGH; - } else { - return LOW; - } - break; - default: - #if DEBUG_EN - SERIAL_PORT_MONITOR.println(F("Invalid pin for mcpDigitalRead")); - #endif - return LOW; - } -} - -/********************************************************************************************************* - END FILE -*********************************************************************************************************/ diff --git a/arduino/src/mcp/mcp2515_can.h b/arduino/src/mcp/mcp2515_can.h deleted file mode 100644 index dc593bf..0000000 --- a/arduino/src/mcp/mcp2515_can.h +++ /dev/null @@ -1,163 +0,0 @@ -/* - mcp_can.h - 2012 Copyright (c) Seeed Technology Inc. All right reserved. - - Author:Loovee (loovee@seeed.cc) - 2014-1-16 - - Contributor: - - Cory J. Fowler - Latonita - Woodward1 - Mehtajaghvi - BykeBlast - TheRo0T - Tsipizic - ralfEdmund - Nathancheek - BlueAndi - Adlerweb - Btetz - Hurvajs - ttlappalainen - - The MIT License (MIT) - - Copyright (c) 2013 Seeed Technology Inc. - - 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 _MCP2515_H_ -#define _MCP2515_H_ - -#include "mcp_can.h" -#include "mcp2515_can_dfs.h" - -#define MAX_CHAR_IN_MESSAGE 8 - -class mcp2515_can : public MCP_CAN -{ -public: - mcp2515_can(byte _CS) : MCP_CAN(_CS), nReservedTx(0){}; - /* - mcp2515 driver function - */ -public: - virtual void enableTxInterrupt(bool enable = true); // enable transmit interrupt - virtual void reserveTxBuffers(byte nTxBuf = 0) - { - nReservedTx = (nTxBuf < MCP_N_TXBUFFERS ? nTxBuf : MCP_N_TXBUFFERS - 1); - } - virtual byte getLastTxBuffer() - { - return MCP_N_TXBUFFERS - 1; // read index of last tx buffer - } - virtual byte begin(uint32_t speedset, const byte clockset = MCP_16MHz); // init can - virtual byte init_Mask(byte num, byte ext, unsigned long ulData); // init Masks - virtual byte init_Filt(byte num, byte ext, unsigned long ulData); // init filters - virtual void setSleepWakeup(byte enable); // Enable or disable the wake up interrupt (If disabled the MCP2515 will not be woken up by CAN bus activity, making it send only) - virtual byte sleep(); // Put the MCP2515 in sleep mode - virtual byte wake(); // Wake MCP2515 manually from sleep - virtual byte setMode(byte opMode); // Set operational mode - virtual byte getMode(); // Get operational mode - virtual byte checkError(uint8_t* err_ptr = NULL); // if something error - - virtual byte checkReceive(void); // if something received - virtual byte readMsgBufID(byte status, volatile unsigned long *id, volatile byte *ext, volatile byte *rtr, volatile byte *len, volatile byte *buf); // read buf with object ID - /* wrapper */ - byte readMsgBufID(unsigned long *ID, byte *len, byte *buf) { - return readMsgBufID(readRxTxStatus(), ID, &ext_flg, &rtr, len, buf); - } - byte readMsgBuf(byte *len, byte *buf) { - return readMsgBufID(readRxTxStatus(), &can_id, &ext_flg, &rtr, len, buf); - } - - virtual byte trySendMsgBuf(unsigned long id, byte ext, byte rtrBit, byte len, const byte *buf, byte iTxBuf = 0xff); // as sendMsgBuf, but does not have any wait for free buffer - virtual byte sendMsgBuf(byte status, unsigned long id, byte ext, byte rtrBit, byte len, volatile const byte *buf); // send message buf by using parsed buffer status - virtual byte sendMsgBuf(unsigned long id, byte ext, byte rtrBit, byte len, const byte *buf, bool wait_sent = true); // send buf - /* wrapper */ - inline byte sendMsgBuf(unsigned long id, byte ext, byte len, const byte *buf) { - return sendMsgBuf(id, ext, 0, len, buf, true); - } - - virtual void clearBufferTransmitIfFlags(byte flags = 0); // Clear transmit flags according to status - virtual byte readRxTxStatus(void); // read has something send or received - virtual byte checkClearRxStatus(byte *status); // read and clear and return first found rx status bit - virtual byte checkClearTxStatus(byte *status, byte iTxBuf = 0xff); // read and clear and return first found or buffer specified tx status bit - virtual bool mcpPinMode(const byte pin, const byte mode); // switch supported pins between HiZ, interrupt, output or input - virtual bool mcpDigitalWrite(const byte pin, const byte mode); // write HIGH or LOW to RX0BF/RX1BF - virtual byte mcpDigitalRead(const byte pin); - -private: - void mcp2515_reset(void); // reset mcp2515 - - byte mcp2515_readRegister(const byte address); // read mcp2515's register - - void mcp2515_readRegisterS(const byte address, - byte values[], - const byte n); - void mcp2515_setRegister(const byte address, // set mcp2515's register - const byte value); - - void mcp2515_setRegisterS(const byte address, // set mcp2515's registers - const byte values[], - const byte n); - - void mcp2515_initCANBuffers(void); - - void mcp2515_modifyRegister(const byte address, // set bit of one register - const byte mask, - const byte data); - - byte mcp2515_readStatus(void); // read mcp2515's Status - byte mcp2515_setCANCTRL_Mode(const byte newmode); // set mode - byte mcp2515_requestNewMode(const byte newmode); // Set mode - byte mcp2515_configRate(const byte canSpeed, const byte clock); // set baudrate - byte mcp2515_init(const byte canSpeed, const byte clock); // mcp2515init - - void mcp2515_write_id(const byte mcp_addr, // write can id - const byte ext, - const unsigned long id); - - void mcp2515_read_id(const byte mcp_addr, // read can id - byte *ext, - unsigned long *id); - - void mcp2515_write_canMsg(const byte buffer_sidh_addr, unsigned long id, byte ext, byte rtr, byte len, - volatile const byte *buf); // read can msg - void mcp2515_read_canMsg(const byte buffer_load_addr, volatile unsigned long *id, volatile byte *ext, - volatile byte *rtr, volatile byte *len, volatile byte *buf); // write can msg - void mcp2515_start_transmit(const byte mcp_addr); // start transmit - byte mcp2515_getNextFreeTXBuf(byte *txbuf_n); // get Next free txbuf - byte mcp2515_isTXBufFree(byte *txbuf_n, byte iBuf); // is buffer by index free - - /* - can operator function - */ - - byte sendMsg(unsigned long id, byte ext, byte rtrBit, byte len, const byte *buf, bool wait_sent = true); // send message -private: - byte nReservedTx; // Count of tx buffers for reserved send -}; - -#endif -/********************************************************************************************************* - END FILE -*********************************************************************************************************/ diff --git a/arduino/src/mcp/mcp2515_can_dfs.h b/arduino/src/mcp/mcp2515_can_dfs.h deleted file mode 100644 index 025a44f..0000000 --- a/arduino/src/mcp/mcp2515_can_dfs.h +++ /dev/null @@ -1,462 +0,0 @@ -/* - mcp_can_dfs.h - 2012 Copyright (c) Seeed Technology Inc. All right reserved. - - Author:Loovee (loovee@seeed.cc) - 2014-1-16 - - Contributor: - - Cory J. Fowler - Latonita - Woodward1 - Mehtajaghvi - BykeBlast - TheRo0T - Tsipizic - ralfEdmund - Nathancheek - BlueAndi - Adlerweb - Btetz - Hurvajs - xboxpro1 - ttlappalainen - - The MIT License (MIT) - - Copyright (c) 2013 Seeed Technology Inc. - - 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 _MCP2515DFS_H_ -#define _MCP2515DFS_H_ - -#include -#include -#include - - -// if print debug information -#ifndef DEBUG_EN - #define DEBUG_EN 1 -#endif - -// Begin mt - -#define TIMEOUTVALUE 50 -#define MCP_SIDH 0 -#define MCP_SIDL 1 -#define MCP_EID8 2 -#define MCP_EID0 3 - -#define MCP_TXB_EXIDE_M 0x08 // In TXBnSIDL -#define MCP_DLC_MASK 0x0F // 4 LSBits -#define MCP_RTR_MASK 0x40 // (1<<6) Bit 6 - -#define MCP_RXB_RX_ANY 0x60 -#define MCP_RXB_RX_EXT 0x40 -#define MCP_RXB_RX_STD 0x20 -#define MCP_RXB_RX_STDEXT 0x00 -#define MCP_RXB_RX_MASK 0x60 -#define MCP_RXB_BUKT_MASK (1<<2) - - -// Bits in the TXBnCTRL registers. - -#define MCP_TXB_TXBUFE_M 0x80 -#define MCP_TXB_ABTF_M 0x40 -#define MCP_TXB_MLOA_M 0x20 -#define MCP_TXB_TXERR_M 0x10 -#define MCP_TXB_TXREQ_M 0x08 -#define MCP_TXB_TXIE_M 0x04 -#define MCP_TXB_TXP10_M 0x03 - -#define MCP_TXB_RTR_M 0x40 // In TXBnDLC -#define MCP_RXB_IDE_M 0x08 // In RXBnSIDL -#define MCP_RXB_RTR_M 0x40 // In RXBnDLC - -#define MCP_STAT_TX_PENDING_MASK (0x54) -#define MCP_STAT_TX0_PENDING (0x04) -#define MCP_STAT_TX1_PENDING (0x10) -#define MCP_STAT_TX2_PENDING (0x40) -#define MCP_STAT_TXIF_MASK (0xA8) -#define MCP_STAT_TX0IF (0x08) -#define MCP_STAT_TX1IF (0x20) -#define MCP_STAT_TX2IF (0x80) -#define MCP_STAT_RXIF_MASK (0x03) -#define MCP_STAT_RX0IF (1<<0) -#define MCP_STAT_RX1IF (1<<1) - -#define MCP_EFLG_RX1OVR (1<<7) -#define MCP_EFLG_RX0OVR (1<<6) -#define MCP_EFLG_TXBO (1<<5) -#define MCP_EFLG_TXEP (1<<4) -#define MCP_EFLG_RXEP (1<<3) -#define MCP_EFLG_TXWAR (1<<2) -#define MCP_EFLG_RXWAR (1<<1) -#define MCP_EFLG_EWARN (1<<0) -#define MCP_EFLG_ERRORMASK (0xF8) // 5 MS-Bits - -// Define MCP2515 register addresses - -#define MCP_RXF0SIDH 0x00 -#define MCP_RXF0SIDL 0x01 -#define MCP_RXF0EID8 0x02 -#define MCP_RXF0EID0 0x03 -#define MCP_RXF1SIDH 0x04 -#define MCP_RXF1SIDL 0x05 -#define MCP_RXF1EID8 0x06 -#define MCP_RXF1EID0 0x07 -#define MCP_RXF2SIDH 0x08 -#define MCP_RXF2SIDL 0x09 -#define MCP_RXF2EID8 0x0A -#define MCP_RXF2EID0 0x0B -#define MCP_BFPCTRL 0x0C -#define MCP_TXRTSCTRL 0x0D -#define MCP_CANSTAT 0x0E -#define MCP_CANCTRL 0x0F -#define MCP_RXF3SIDH 0x10 -#define MCP_RXF3SIDL 0x11 -#define MCP_RXF3EID8 0x12 -#define MCP_RXF3EID0 0x13 -#define MCP_RXF4SIDH 0x14 -#define MCP_RXF4SIDL 0x15 -#define MCP_RXF4EID8 0x16 -#define MCP_RXF4EID0 0x17 -#define MCP_RXF5SIDH 0x18 -#define MCP_RXF5SIDL 0x19 -#define MCP_RXF5EID8 0x1A -#define MCP_RXF5EID0 0x1B -#define MCP_TEC 0x1C -#define MCP_REC 0x1D -#define MCP_RXM0SIDH 0x20 -#define MCP_RXM0SIDL 0x21 -#define MCP_RXM0EID8 0x22 -#define MCP_RXM0EID0 0x23 -#define MCP_RXM1SIDH 0x24 -#define MCP_RXM1SIDL 0x25 -#define MCP_RXM1EID8 0x26 -#define MCP_RXM1EID0 0x27 -#define MCP_CNF3 0x28 -#define MCP_CNF2 0x29 -#define MCP_CNF1 0x2A -#define MCP_CANINTE 0x2B -#define MCP_CANINTF 0x2C -#define MCP_EFLG 0x2D -#define MCP_TXB0CTRL 0x30 -#define MCP_TXB0SIDH 0x31 -#define MCP_TXB1CTRL 0x40 -#define MCP_TXB1SIDH 0x41 -#define MCP_TXB2CTRL 0x50 -#define MCP_TXB2SIDH 0x51 -#define MCP_RXB0CTRL 0x60 -#define MCP_RXB0SIDH 0x61 -#define MCP_RXB1CTRL 0x70 -#define MCP_RXB1SIDH 0x71 - -#define MCP_TX_INT 0x1C // Enable all transmit interrup ts -#define MCP_TX01_INT 0x0C // Enable TXB0 and TXB1 interru pts -#define MCP_RX_INT 0x03 // Enable receive interrupts -#define MCP_NO_INT 0x00 // Disable all interrupts - -#define MCP_TX01_MASK 0x14 -#define MCP_TX_MASK 0x54 - - -// Define SPI Instruction Set - -#define MCP_WRITE 0x02 -#define MCP_READ 0x03 -#define MCP_BITMOD 0x05 -#define MCP_LOAD_TX0 0x40 -#define MCP_LOAD_TX1 0x42 -#define MCP_LOAD_TX2 0x44 - -#define MCP_RTS_TX0 0x81 -#define MCP_RTS_TX1 0x82 -#define MCP_RTS_TX2 0x84 -#define MCP_RTS_ALL 0x87 -#define MCP_READ_RX0 0x90 -#define MCP_READ_RX1 0x94 -#define MCP_READ_STATUS 0xA0 -#define MCP_RX_STATUS 0xB0 -#define MCP_RESET 0xC0 - - -// CANCTRL Register Values - -#define MODE_NORMAL 0x00 -#define MODE_SLEEP 0x20 -#define MODE_LOOPBACK 0x40 -#define MODE_LISTENONLY 0x60 -#define MODE_CONFIG 0x80 -#define MODE_POWERUP 0xE0 -#define MODE_MASK 0xE0 -#define ABORT_TX 0x10 -#define MODE_ONESHOT 0x08 -#define CLKOUT_ENABLE 0x04 -#define CLKOUT_DISABLE 0x00 -#define CLKOUT_PS1 0x00 -#define CLKOUT_PS2 0x01 -#define CLKOUT_PS4 0x02 -#define CLKOUT_PS8 0x03 - - -// CNF1 Register Values - -#define SJW1 0x00 -#define SJW2 0x40 -#define SJW3 0x80 -#define SJW4 0xC0 - - -// CNF2 Register Values - -#define BTLMODE 0x80 -#define SAMPLE_1X 0x00 -#define SAMPLE_3X 0x40 - - -// CNF3 Register Values - -#define SOF_ENABLE 0x80 -#define SOF_DISABLE 0x00 -#define WAKFIL_ENABLE 0x40 -#define WAKFIL_DISABLE 0x00 - - -// CANINTF Register Bits - -#define MCP_RX0IF 0x01 -#define MCP_RX1IF 0x02 -#define MCP_TX0IF 0x04 -#define MCP_TX1IF 0x08 -#define MCP_TX2IF 0x10 -#define MCP_ERRIF 0x20 -#define MCP_WAKIF 0x40 -#define MCP_MERRF 0x80 - -// BFPCTRL Register Bits - -#define B1BFS 0x20 -#define B0BFS 0x10 -#define B1BFE 0x08 -#define B0BFE 0x04 -#define B1BFM 0x02 -#define B0BFM 0x01 - -// TXRTCTRL Register Bits - -#define B2RTS 0x20 -#define B1RTS 0x10 -#define B0RTS 0x08 -#define B2RTSM 0x04 -#define B1RTSM 0x02 -#define B0RTSM 0x01 - -// speed 16M - -#define MCP_16MHz_1000kBPS_CFG1 (0x00) -#define MCP_16MHz_1000kBPS_CFG2 (0xD0) -#define MCP_16MHz_1000kBPS_CFG3 (0x82) - -#define MCP_16MHz_800kBPS_CFG1 (0x40) -#define MCP_16MHz_800kBPS_CFG2 (0x92) -#define MCP_16MHz_800kBPS_CFG3 (0x02) - -#define MCP_16MHz_666kBPS_CFG1 (0x00) -#define MCP_16MHz_666kBPS_CFG2 (0xA0) -#define MCP_16MHz_666kBPS_CFG3 (0x04) - -#define MCP_16MHz_500kBPS_CFG1 (0x00) -#define MCP_16MHz_500kBPS_CFG2 (0xF0) -#define MCP_16MHz_500kBPS_CFG3 (0x86) - -#define MCP_16MHz_250kBPS_CFG1 (0x41) -#define MCP_16MHz_250kBPS_CFG2 (0xF1) -#define MCP_16MHz_250kBPS_CFG3 (0x85) - -#define MCP_16MHz_200kBPS_CFG1 (0x01) -#define MCP_16MHz_200kBPS_CFG2 (0xFA) -#define MCP_16MHz_200kBPS_CFG3 (0x87) - -#define MCP_16MHz_125kBPS_CFG1 (0x03) -#define MCP_16MHz_125kBPS_CFG2 (0xF0) -#define MCP_16MHz_125kBPS_CFG3 (0x86) - -#define MCP_16MHz_100kBPS_CFG1 (0x03) -#define MCP_16MHz_100kBPS_CFG2 (0xFA) -#define MCP_16MHz_100kBPS_CFG3 (0x87) - -#define MCP_16MHz_95kBPS_CFG1 (0x03) -#define MCP_16MHz_95kBPS_CFG2 (0xAD) -#define MCP_16MHz_95kBPS_CFG3 (0x07) - -#define MCP_16MHz_83k3BPS_CFG1 (0x03) -#define MCP_16MHz_83k3BPS_CFG2 (0xBE) -#define MCP_16MHz_83k3BPS_CFG3 (0x07) - -#define MCP_16MHz_80kBPS_CFG1 (0x03) -#define MCP_16MHz_80kBPS_CFG2 (0xFF) -#define MCP_16MHz_80kBPS_CFG3 (0x87) - -#define MCP_16MHz_50kBPS_CFG1 (0x07) -#define MCP_16MHz_50kBPS_CFG2 (0xFA) -#define MCP_16MHz_50kBPS_CFG3 (0x87) - -#define MCP_16MHz_40kBPS_CFG1 (0x07) -#define MCP_16MHz_40kBPS_CFG2 (0xFF) -#define MCP_16MHz_40kBPS_CFG3 (0x87) - -#define MCP_16MHz_33kBPS_CFG1 (0x09) -#define MCP_16MHz_33kBPS_CFG2 (0xBE) -#define MCP_16MHz_33kBPS_CFG3 (0x07) - -#define MCP_16MHz_31k25BPS_CFG1 (0x0F) -#define MCP_16MHz_31k25BPS_CFG2 (0xF1) -#define MCP_16MHz_31k25BPS_CFG3 (0x85) - -#define MCP_16MHz_25kBPS_CFG1 (0X0F) -#define MCP_16MHz_25kBPS_CFG2 (0XBA) -#define MCP_16MHz_25kBPS_CFG3 (0X07) - -#define MCP_16MHz_20kBPS_CFG1 (0x0F) -#define MCP_16MHz_20kBPS_CFG2 (0xFF) -#define MCP_16MHz_20kBPS_CFG3 (0x87) - -#define MCP_16MHz_10kBPS_CFG1 (0x1F) -#define MCP_16MHz_10kBPS_CFG2 (0xFF) -#define MCP_16MHz_10kBPS_CFG3 (0x87) - -#define MCP_16MHz_5kBPS_CFG1 (0x3F) -#define MCP_16MHz_5kBPS_CFG2 (0xFF) -#define MCP_16MHz_5kBPS_CFG3 (0x87) - - - -// speed 8M - -#define MCP_8MHz_1000kBPS_CFG1 (0x00) -#define MCP_8MHz_1000kBPS_CFG2 (0x80) -#define MCP_8MHz_1000kBPS_CFG3 (0x00) - -#define MCP_8MHz_800kBPS_CFG1 (0x00) -#define MCP_8MHz_800kBPS_CFG2 (0x80) -#define MCP_8MHz_800kBPS_CFG3 (0x01) - -#define MCP_8MHz_500kBPS_CFG1 (0x00) -#define MCP_8MHz_500kBPS_CFG2 (0x90) -#define MCP_8MHz_500kBPS_CFG3 (0x02) - -#define MCP_8MHz_250kBPS_CFG1 (0x00) -#define MCP_8MHz_250kBPS_CFG2 (0xb1) -#define MCP_8MHz_250kBPS_CFG3 (0x05) - -#define MCP_8MHz_200kBPS_CFG1 (0x00) -#define MCP_8MHz_200kBPS_CFG2 (0xb4) -#define MCP_8MHz_200kBPS_CFG3 (0x06) - -#define MCP_8MHz_125kBPS_CFG1 (0x01) -#define MCP_8MHz_125kBPS_CFG2 (0xb1) -#define MCP_8MHz_125kBPS_CFG3 (0x05) - -#define MCP_8MHz_100kBPS_CFG1 (0x01) -#define MCP_8MHz_100kBPS_CFG2 (0xb4) -#define MCP_8MHz_100kBPS_CFG3 (0x06) - -#define MCP_8MHz_80kBPS_CFG1 (0x01) -#define MCP_8MHz_80kBPS_CFG2 (0xbf) -#define MCP_8MHz_80kBPS_CFG3 (0x07) - -#define MCP_8MHz_50kBPS_CFG1 (0x03) -#define MCP_8MHz_50kBPS_CFG2 (0xb4) -#define MCP_8MHz_50kBPS_CFG3 (0x06) - -#define MCP_8MHz_40kBPS_CFG1 (0x03) -#define MCP_8MHz_40kBPS_CFG2 (0xbf) -#define MCP_8MHz_40kBPS_CFG3 (0x07) - -#define MCP_8MHz_31k25BPS_CFG1 (0x07) -#define MCP_8MHz_31k25BPS_CFG2 (0xa4) -#define MCP_8MHz_31k25BPS_CFG3 (0x04) - -#define MCP_8MHz_20kBPS_CFG1 (0x07) -#define MCP_8MHz_20kBPS_CFG2 (0xbf) -#define MCP_8MHz_20kBPS_CFG3 (0x07) - -#define MCP_8MHz_10kBPS_CFG1 (0x0f) -#define MCP_8MHz_10kBPS_CFG2 (0xbf) -#define MCP_8MHz_10kBPS_CFG3 (0x07) - -#define MCP_8MHz_5kBPS_CFG1 (0x1f) -#define MCP_8MHz_5kBPS_CFG2 (0xbf) -#define MCP_8MHz_5kBPS_CFG3 (0x07) - -#define MCPDEBUG (0) -#define MCPDEBUG_TXBUF (0) -#define MCP_N_TXBUFFERS (3) - -#define MCP_RXBUF_0 (MCP_RXB0SIDH) -#define MCP_RXBUF_1 (MCP_RXB1SIDH) - -#define MCP2515_SELECT() digitalWrite(SPICS, LOW) -#define MCP2515_UNSELECT() digitalWrite(SPICS, HIGH) - -#define MCP2515_OK (0) -#define MCP2515_FAIL (1) -#define MCP_ALLTXBUSY (2) - -#define CANDEBUG 1 - -#define CANUSELOOP 0 - -#define CANSENDTIMEOUT (200) // milliseconds - -#define MCP_PIN_HIZ (0) -#define MCP_PIN_INT (1) -#define MCP_PIN_OUT (2) -#define MCP_PIN_IN (3) - -#define MCP_RX0BF (0) -#define MCP_RX1BF (1) -#define MCP_TX0RTS (2) -#define MCP_TX1RTS (3) -#define MCP_TX2RTS (4) - - -// initial value of gCANAutoProcess - -#define CANAUTOPROCESS (1) -#define CANAUTOON (1) -#define CANAUTOOFF (0) -#define CAN_STDID (0) -#define CAN_EXTID (1) -#define CANDEFAULTIDENT (0x55CC) -#define CANDEFAULTIDENTEXT (CAN_EXTID) - - - - -#define CAN_MAX_CHAR_IN_MESSAGE (8) - -#endif -/********************************************************************************************************* - END FILE -*********************************************************************************************************/ diff --git a/arduino/src/mcp/mcp2518fd_can.cpp b/arduino/src/mcp/mcp2518fd_can.cpp deleted file mode 100644 index 5dda94a..0000000 --- a/arduino/src/mcp/mcp2518fd_can.cpp +++ /dev/null @@ -1,2285 +0,0 @@ -/* Most of this code are derived from Microchip MCP2518FD SDK */ -#include "mcp2518fd_can.h" - -static CAN_CONFIG config; - -// Receive objects -static CAN_RX_FIFO_CONFIG rxConfig; -static REG_CiFLTOBJ fObj; -static REG_CiMASK mObj; -static CAN_RX_FIFO_EVENT rxFlags; -static CAN_RX_MSGOBJ rxObj; -static uint8_t rxd[MAX_DATA_BYTES]; - -// Transmit objects -static CAN_TX_FIFO_CONFIG txConfig; -static CAN_TX_FIFO_EVENT txFlags; -static CAN_TX_MSGOBJ txObj; -static uint8_t txd[MAX_DATA_BYTES]; - -#define MAX_TXQUEUE_ATTEMPTS 50 - -// Transmit Channels -#define APP_TX_FIFO CAN_FIFO_CH2 - -// Receive Channels -#define APP_RX_FIFO CAN_FIFO_CH1 - -// Maximum number of data bytes in message -#define MAX_DATA_BYTES 64 - -// ***************************************************************************** -// ***************************************************************************** -// Section: Variables - -//! SPI Transmit buffer -static uint8_t spiTransmitBuffer[SPI_DEFAULT_BUFFER_LENGTH + 2]; - -//! SPI Receive buffer -static uint8_t spiReceiveBuffer[SPI_DEFAULT_BUFFER_LENGTH]; - -uint16_t DRV_CANFDSPI_CalculateCRC16(uint8_t *data, uint16_t size) { - uint16_t init = CRCBASE; - uint8_t index; - - while (size-- != 0) { - index = ((uint8_t *)&init)[CRCUPPER] ^ *data++; - init = (init << 8) ^ crc16_table[index]; - } - - return init; -} - - -/********************************************************************************************************* -** Function name: begin -** Descriptions: init can and set speed -*********************************************************************************************************/ -byte mcp2518fd::begin(uint32_t speedset, const byte clockset) { - SPI.begin(); - - /* compatible layer translation */ - speedset = bittime_compat_to_mcp2518fd(speedset); - - byte res = mcp2518fd_init(speedset, clockset); - return res; -} - -/********************************************************************************************************* -** Function name: mcp2518fd_reset -** Descriptions: reset the device -*********************************************************************************************************/ -int8_t mcp2518fd::mcp2518fd_reset(void) { - int8_t spiTransferError = 0; - - // Compose command - spiTransmitBuffer[0] = (uint8_t)(cINSTRUCTION_RESET << 4); - spiTransmitBuffer[1] = 0; - -#ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); -#endif - MCP2518fd_SELECT(); - spi_readwrite(spiTransmitBuffer[0]); - spi_readwrite(spiTransmitBuffer[1]); - MCP2518fd_UNSELECT(); -#ifdef SPI_HAS_TRANSACTION - SPI_END(); -#endif - delay(10); - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_ReadByte(uint16_t address, uint8_t *rxd) { - int8_t spiTransferError = 0; - - // Compose command - spiTransmitBuffer[0] = - (uint8_t)((cINSTRUCTION_READ << 4) + ((address >> 8) & 0xF)); - spiTransmitBuffer[1] = (uint8_t)(address & 0xFF); - spiTransmitBuffer[2] = 0; - -#ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); -#endif - MCP2518fd_SELECT(); - spi_readwrite(spiTransmitBuffer[0]); - spi_readwrite(spiTransmitBuffer[1]); - spiReceiveBuffer[2] = spi_readwrite(0x00); - MCP2518fd_UNSELECT(); -#ifdef SPI_HAS_TRANSACTION - SPI_END(); -#endif - // Update data - *rxd = spiReceiveBuffer[2]; - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_WriteByte(uint16_t address, uint8_t txd) { - int8_t spiTransferError = 0; - - // Compose command - spiTransmitBuffer[0] = - (uint8_t)((cINSTRUCTION_WRITE << 4) + ((address >> 8) & 0xF)); - spiTransmitBuffer[1] = (uint8_t)(address & 0xFF); - spiTransmitBuffer[2] = txd; - -#ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); -#endif - MCP2518fd_SELECT(); - spi_readwrite(spiTransmitBuffer[0]); - spi_readwrite(spiTransmitBuffer[1]); - spi_readwrite(spiTransmitBuffer[2]); - MCP2518fd_UNSELECT(); -#ifdef SPI_HAS_TRANSACTION - SPI_END(); -#endif - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_ReadWord(uint16_t address, uint32_t *rxd) { - uint8_t i; - uint32_t x; - int8_t spiTransferError = 0; - - // Compose command - spiTransmitBuffer[0] = - (uint8_t)((cINSTRUCTION_READ << 4) + ((address >> 8) & 0xF)); - spiTransmitBuffer[1] = (uint8_t)(address & 0xFF); - -#ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); -#endif - MCP2518fd_SELECT(); - spi_readwrite(spiTransmitBuffer[0]); - spi_readwrite(spiTransmitBuffer[1]); - for (i = 2; i < 6; i++) { - spiReceiveBuffer[i] = spi_readwrite(0x00); - } - MCP2518fd_UNSELECT(); -#ifdef SPI_HAS_TRANSACTION - SPI_END(); -#endif - - // Update data - *rxd = 0; - for (i = 2; i < 6; i++) { - x = (uint32_t)spiReceiveBuffer[i]; - *rxd += x << ((i - 2) * 8); - } - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_WriteWord(uint16_t address, uint32_t txd) { - uint8_t i; - int8_t spiTransferError = 0; - - // Compose command - spiTransmitBuffer[0] = - (uint8_t)((cINSTRUCTION_WRITE << 4) + ((address >> 8) & 0xF)); - spiTransmitBuffer[1] = (uint8_t)(address & 0xFF); - - // Split word into 4 bytes and add them to buffer - for (i = 0; i < 4; i++) { - spiTransmitBuffer[i + 2] = (uint8_t)((txd >> (i * 8)) & 0xFF); - } - -#ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); -#endif - MCP2518fd_SELECT(); - spi_readwrite(spiTransmitBuffer[0]); - spi_readwrite(spiTransmitBuffer[1]); - spi_readwrite(spiTransmitBuffer[2]); - spi_readwrite(spiTransmitBuffer[3]); - spi_readwrite(spiTransmitBuffer[4]); - spi_readwrite(spiTransmitBuffer[5]); - MCP2518fd_UNSELECT(); -#ifdef SPI_HAS_TRANSACTION - SPI_END(); -#endif - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_ReadHalfWord(uint16_t address, uint16_t *rxd) { - uint8_t i; - uint32_t x; - int8_t spiTransferError = 0; - - // Compose command - spiTransmitBuffer[0] = - (uint8_t)((cINSTRUCTION_READ << 4) + ((address >> 8) & 0xF)); - spiTransmitBuffer[1] = (uint8_t)(address & 0xFF); - -#ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); -#endif - MCP2518fd_SELECT(); - spi_readwrite(spiTransmitBuffer[0]); - spi_readwrite(spiTransmitBuffer[1]); - for (i = 2; i < 4; i++) { - spiReceiveBuffer[i] = spi_readwrite(0x00); - } - MCP2518fd_UNSELECT(); -#ifdef SPI_HAS_TRANSACTION - SPI_END(); -#endif - - // Update data - *rxd = 0; - for (i = 2; i < 4; i++) { - x = (uint32_t)spiReceiveBuffer[i]; - *rxd += x << ((i - 2) * 8); - } - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_WriteHalfWord(uint16_t address, uint16_t txd) { - uint8_t i; - int8_t spiTransferError = 0; - - // Compose command - spiTransmitBuffer[0] = - (uint8_t)((cINSTRUCTION_WRITE << 4) + ((address >> 8) & 0xF)); - spiTransmitBuffer[1] = (uint8_t)(address & 0xFF); - - // Split word into 2 bytes and add them to buffer - for (i = 0; i < 2; i++) { - spiTransmitBuffer[i + 2] = (uint8_t)((txd >> (i * 8)) & 0xFF); - } - -#ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); -#endif - MCP2518fd_SELECT(); - spi_readwrite(spiTransmitBuffer[0]); - spi_readwrite(spiTransmitBuffer[1]); - spi_readwrite(spiTransmitBuffer[2]); - spi_readwrite(spiTransmitBuffer[3]); - MCP2518fd_UNSELECT(); -#ifdef SPI_HAS_TRANSACTION - SPI_END(); -#endif - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_ReadByteArray(uint16_t address, uint8_t *rxd, - uint16_t nBytes) { - uint16_t i; - uint16_t spiTransferSize = nBytes + 2; - int8_t spiTransferError = 0; - - // Compose command - spiTransmitBuffer[0] = - (uint8_t)((cINSTRUCTION_READ << 4) + ((address >> 8) & 0xF)); - spiTransmitBuffer[1] = (uint8_t)(address & 0xFF); - - // Clear data - for (i = 2; i < spiTransferSize; i++) { - spiTransmitBuffer[i] = 0; - } - -#ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); -#endif - MCP2518fd_SELECT(); - spi_readwrite(spiTransmitBuffer[0]); - spi_readwrite(spiTransmitBuffer[1]); - for (i = 0; i < nBytes; i++) { - spiReceiveBuffer[i + 2] = spi_readwrite(0x00); - } - MCP2518fd_UNSELECT(); -#ifdef SPI_HAS_TRANSACTION - SPI_END(); -#endif - - // Update data - for (i = 0; i < nBytes; i++) { - rxd[i] = spiReceiveBuffer[i + 2]; - } - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_WriteByteArray(uint16_t address, uint8_t *txd, - uint16_t nBytes) { - uint16_t i; - uint16_t spiTransferSize = nBytes + 2; - int8_t spiTransferError = 0; - - // Compose command - spiTransmitBuffer[0] = - (uint8_t)((cINSTRUCTION_WRITE << 4) + ((address >> 8) & 0xF)); - spiTransmitBuffer[1] = (uint8_t)(address & 0xFF); - // Add data - for (i = 2; i < spiTransferSize; i++) { - spiTransmitBuffer[i] = txd[i - 2]; - } - -#ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); -#endif - MCP2518fd_SELECT(); - spi_readwrite(spiTransmitBuffer[0]); - spi_readwrite(spiTransmitBuffer[1]); - for (i = 2; i < spiTransferSize; i++) { - spi_readwrite(spiTransmitBuffer[i]); - } - MCP2518fd_UNSELECT(); -#ifdef SPI_HAS_TRANSACTION - SPI_END(); -#endif - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_WriteByteSafe(uint16_t address, uint8_t txd) { - uint16_t crcResult = 0; - int8_t spiTransferError = 0; - - // Compose command - spiTransmitBuffer[0] = - (uint8_t)((cINSTRUCTION_WRITE_SAFE << 4) + ((address >> 8) & 0xF)); - spiTransmitBuffer[1] = (uint8_t)(address & 0xFF); - spiTransmitBuffer[2] = txd; - - // Add CRC - crcResult = DRV_CANFDSPI_CalculateCRC16(spiTransmitBuffer, 3); - spiTransmitBuffer[3] = (crcResult >> 8) & 0xFF; - spiTransmitBuffer[4] = crcResult & 0xFF; - -#ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); -#endif - MCP2518fd_SELECT(); - spi_readwrite(spiTransmitBuffer[0]); - spi_readwrite(spiTransmitBuffer[1]); - spi_readwrite(spiTransmitBuffer[2]); - spi_readwrite(spiTransmitBuffer[3]); - spi_readwrite(spiTransmitBuffer[4]); - MCP2518fd_UNSELECT(); -#ifdef SPI_HAS_TRANSACTION - SPI_END(); -#endif - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_WriteWordSafe(uint16_t address, uint32_t txd) { - uint8_t i; - uint16_t crcResult = 0; - int8_t spiTransferError = 0; - - // Compose command - spiTransmitBuffer[0] = - (uint8_t)((cINSTRUCTION_WRITE_SAFE << 4) + ((address >> 8) & 0xF)); - spiTransmitBuffer[1] = (uint8_t)(address & 0xFF); - - // Split word into 4 bytes and add them to buffer - for (i = 0; i < 4; i++) { - spiTransmitBuffer[i + 2] = (uint8_t)((txd >> (i * 8)) & 0xFF); - } - - // Add CRC - crcResult = DRV_CANFDSPI_CalculateCRC16(spiTransmitBuffer, 6); - spiTransmitBuffer[6] = (crcResult >> 8) & 0xFF; - spiTransmitBuffer[7] = crcResult & 0xFF; - -#ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); -#endif - MCP2518fd_SELECT(); - spi_readwrite(spiTransmitBuffer[0]); - spi_readwrite(spiTransmitBuffer[1]); - spi_readwrite(spiTransmitBuffer[2]); - spi_readwrite(spiTransmitBuffer[3]); - spi_readwrite(spiTransmitBuffer[4]); - spi_readwrite(spiTransmitBuffer[5]); - spi_readwrite(spiTransmitBuffer[6]); - spi_readwrite(spiTransmitBuffer[7]); - MCP2518fd_UNSELECT(); -#ifdef SPI_HAS_TRANSACTION - SPI_END(); -#endif - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_ReadByteArrayWithCRC(uint16_t address, uint8_t *rxd, - uint16_t nBytes, bool fromRam, - bool *crcIsCorrect) { - uint8_t i; - uint16_t crcFromSpiSlave = 0; - uint16_t crcAtController = 0; - uint16_t spiTransferSize = - nBytes + 5; // first two bytes for sending command & address, third for - // size, last two bytes for CRC - int8_t spiTransferError = 0; - - // Compose command - spiTransmitBuffer[0] = - (uint8_t)((cINSTRUCTION_READ_CRC << 4) + ((address >> 8) & 0xF)); - spiTransmitBuffer[1] = (uint8_t)(address & 0xFF); - spiTransmitBuffer[2] = fromRam? (nBytes >> 2): nBytes; - - // Clear data - for (i = 3; i < spiTransferSize; i++) { - spiTransmitBuffer[i] = 0; - } - -#ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); -#endif - MCP2518fd_SELECT(); - spi_readwrite(spiTransmitBuffer[0]); - spi_readwrite(spiTransmitBuffer[1]); - spi_readwrite(spiTransmitBuffer[2]); - for (i = 3; i < spiTransferSize; i++) { - spiReceiveBuffer[i] = spi_readwrite(0x00); - } - MCP2518fd_UNSELECT(); -#ifdef SPI_HAS_TRANSACTION - SPI_END(); -#endif - - // Get CRC from controller - crcFromSpiSlave = (uint16_t)(spiReceiveBuffer[spiTransferSize - 2] << 8) + - (uint16_t)(spiReceiveBuffer[spiTransferSize - 1]); - - // Use the receive buffer to calculate CRC - // First three bytes need to be command - spiReceiveBuffer[0] = spiTransmitBuffer[0]; - spiReceiveBuffer[1] = spiTransmitBuffer[1]; - spiReceiveBuffer[2] = spiTransmitBuffer[2]; - crcAtController = DRV_CANFDSPI_CalculateCRC16(spiReceiveBuffer, nBytes + 3); - - // Compare CRC readings - if (crcFromSpiSlave == crcAtController) { - *crcIsCorrect = true; - } else { - *crcIsCorrect = false; - } - - // Update data - for (i = 0; i < nBytes; i++) { - rxd[i] = spiReceiveBuffer[i + 3]; - } - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_WriteByteArrayWithCRC(uint16_t address, - uint8_t *txd, uint16_t nBytes, - bool fromRam) { - uint16_t i; - uint16_t crcResult = 0; - uint16_t spiTransferSize = nBytes + 5; - int8_t spiTransferError = 0; - - // Compose command - spiTransmitBuffer[0] = - (uint8_t)((cINSTRUCTION_WRITE_CRC << 4) + ((address >> 8) & 0xF)); - spiTransmitBuffer[1] = (uint8_t)(address & 0xFF); - spiTransmitBuffer[2] = fromRam? (nBytes >> 2): nBytes; - - // Add data - for (i = 0; i < nBytes; i++) { - spiTransmitBuffer[i + 3] = txd[i]; - } - - // Add CRC - crcResult = DRV_CANFDSPI_CalculateCRC16(spiTransmitBuffer, spiTransferSize - 2); - spiTransmitBuffer[spiTransferSize - 2] = (uint8_t)((crcResult >> 8) & 0xFF); - spiTransmitBuffer[spiTransferSize - 1] = (uint8_t)(crcResult & 0xFF); - -#ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); -#endif - MCP2518fd_SELECT(); - spi_readwrite(spiTransmitBuffer[0]); - spi_readwrite(spiTransmitBuffer[1]); - spi_readwrite(spiTransmitBuffer[2]); - for (i = 0; i < nBytes; i++) { - spi_readwrite(spiTransmitBuffer[i + 3]); - } - spi_readwrite(spiTransmitBuffer[spiTransferSize - 2]); - spi_readwrite(spiTransmitBuffer[spiTransferSize - 1]); - MCP2518fd_UNSELECT(); -#ifdef SPI_HAS_TRANSACTION - SPI_END(); -#endif - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_ReadWordArray(uint16_t address, uint32_t *rxd, - uint16_t nWords) { - uint16_t i, j, n; - REG_t w; - uint16_t spiTransferSize = nWords * 4 + 2; - int8_t spiTransferError = 0; - - // Compose command - spiTransmitBuffer[0] = (cINSTRUCTION_READ << 4) + ((address >> 8) & 0xF); - spiTransmitBuffer[1] = address & 0xFF; - - // Clear data - for (i = 2; i < spiTransferSize; i++) { - spiTransmitBuffer[i] = 0; - } - -#ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); -#endif - MCP2518fd_SELECT(); - spi_readwrite(spiTransmitBuffer[0]); - spi_readwrite(spiTransmitBuffer[1]); - for (i = 2; i < spiTransferSize; i++) { - // for (i = 2; i < 6; i++) { - spiReceiveBuffer[i] = spi_readwrite(0x00); - } - MCP2518fd_UNSELECT(); -#ifdef SPI_HAS_TRANSACTION - SPI_END(); -#endif - // Convert Byte array to Word array - n = 2; - for (i = 0; i < nWords; i++) { - w.word = 0; - for (j = 0; j < 4; j++, n++) { - w.byte[j] = spiReceiveBuffer[n]; - } - rxd[i] = w.word; - } - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_WriteWordArray(uint16_t address, uint32_t *txd, - uint16_t nWords) { - uint16_t i, j, n; - REG_t w; - uint16_t spiTransferSize = nWords * 4 + 2; - int8_t spiTransferError = 0; - - // Compose command - spiTransmitBuffer[0] = (cINSTRUCTION_WRITE << 4) + ((address >> 8) & 0xF); - spiTransmitBuffer[1] = address & 0xFF; - - // Convert ByteArray to word array - n = 2; - for (i = 0; i < nWords; i++) { - w.word = txd[i]; - for (j = 0; j < 4; j++, n++) { - spiTransmitBuffer[n] = w.byte[j]; - } - } - -#ifdef SPI_HAS_TRANSACTION - SPI_BEGIN(); -#endif - MCP2518fd_SELECT(); - spi_readwrite(spiTransmitBuffer[0]); - spi_readwrite(spiTransmitBuffer[1]); - for (i = 2; i < spiTransferSize; i++) { - spi_readwrite(spiTransmitBuffer[i]); - } - MCP2518fd_UNSELECT(); -#ifdef SPI_HAS_TRANSACTION - SPI_END(); -#endif - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_EccEnable() { - int8_t spiTransferError = 0; - uint8_t d = 0; - - // Read - spiTransferError = mcp2518fd_ReadByte(cREGADDR_ECCCON, &d); - if (spiTransferError) { - return -1; - } - // Modify - d |= 0x01; - - // Write - spiTransferError = mcp2518fd_WriteByte(cREGADDR_ECCCON, d); - if (spiTransferError) { - return -2; - } - - return 0; -} - -int8_t mcp2518fd::mcp2518fd_RamInit(uint8_t d) { - uint8_t txd[SPI_DEFAULT_BUFFER_LENGTH]; - uint32_t k; - int8_t spiTransferError = 0; - - // Prepare data - for (k = 0; k < SPI_DEFAULT_BUFFER_LENGTH; k++) { - txd[k] = d; - } - - uint16_t a = cRAMADDR_START; - - for (k = 0; k < (cRAM_SIZE / SPI_DEFAULT_BUFFER_LENGTH); k++) { - spiTransferError = mcp2518fd_WriteByteArray(a, txd, SPI_DEFAULT_BUFFER_LENGTH); - if (spiTransferError) { - return -1; - } - a += SPI_DEFAULT_BUFFER_LENGTH; - } - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_ConfigureObjectReset(CAN_CONFIG *config) { - REG_CiCON ciCon; - ciCon.word = canControlResetValues[cREGADDR_CiCON / 4]; - - config->DNetFilterCount = ciCon.bF.DNetFilterCount; - config->IsoCrcEnable = ciCon.bF.IsoCrcEnable; - config->ProtocolExpectionEventDisable = ciCon.bF.ProtocolExceptionEventDisable; - config->WakeUpFilterEnable = ciCon.bF.WakeUpFilterEnable; - config->WakeUpFilterTime = ciCon.bF.WakeUpFilterTime; - config->BitRateSwitchDisable = ciCon.bF.BitRateSwitchDisable; - config->RestrictReTxAttempts = ciCon.bF.RestrictReTxAttempts; - config->EsiInGatewayMode = ciCon.bF.EsiInGatewayMode; - config->SystemErrorToListenOnly = ciCon.bF.SystemErrorToListenOnly; - config->StoreInTEF = ciCon.bF.StoreInTEF; - config->TXQEnable = ciCon.bF.TXQEnable; - config->TxBandWidthSharing = ciCon.bF.TxBandWidthSharing; - - return 0; -} - -int8_t mcp2518fd::mcp2518fd_Configure(CAN_CONFIG *config) { - REG_CiCON ciCon; - int8_t spiTransferError = 0; - - ciCon.word = canControlResetValues[cREGADDR_CiCON / 4]; - - ciCon.bF.DNetFilterCount = config->DNetFilterCount; - ciCon.bF.IsoCrcEnable = config->IsoCrcEnable; - ciCon.bF.ProtocolExceptionEventDisable = config->ProtocolExpectionEventDisable; - ciCon.bF.WakeUpFilterEnable = config->WakeUpFilterEnable; - ciCon.bF.WakeUpFilterTime = config->WakeUpFilterTime; - ciCon.bF.BitRateSwitchDisable = config->BitRateSwitchDisable; - ciCon.bF.RestrictReTxAttempts = config->RestrictReTxAttempts; - ciCon.bF.EsiInGatewayMode = config->EsiInGatewayMode; - ciCon.bF.SystemErrorToListenOnly = config->SystemErrorToListenOnly; - ciCon.bF.StoreInTEF = config->StoreInTEF; - ciCon.bF.TXQEnable = config->TXQEnable; - ciCon.bF.TxBandWidthSharing = config->TxBandWidthSharing; - - spiTransferError = mcp2518fd_WriteWord(cREGADDR_CiCON, ciCon.word); - if (spiTransferError) { - return -1; - } - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_TransmitChannelConfigureObjectReset(CAN_TX_FIFO_CONFIG *config) { - REG_CiFIFOCON ciFifoCon; - ciFifoCon.word = canFifoResetValues[0]; // 10010010100101010000 - - config->RTREnable = ciFifoCon.txBF.RTREnable; - config->TxPriority = ciFifoCon.txBF.TxPriority; - config->TxAttempts = ciFifoCon.txBF.TxAttempts; - config->FifoSize = ciFifoCon.txBF.FifoSize; - config->PayLoadSize = ciFifoCon.txBF.PayLoadSize; - - return 0; -} - -int8_t -mcp2518fd::mcp2518fd_TransmitChannelConfigure(CAN_FIFO_CHANNEL channel, - CAN_TX_FIFO_CONFIG *config) { - int8_t spiTransferError = 0; - uint16_t a = 0; - // Setup FIFO - REG_CiFIFOCON ciFifoCon; - ciFifoCon.word = canFifoResetValues[0]; - ciFifoCon.txBF.TxEnable = 1; - ciFifoCon.txBF.FifoSize = config->FifoSize; - ciFifoCon.txBF.PayLoadSize = config->PayLoadSize; - ciFifoCon.txBF.TxAttempts = config->TxAttempts; - ciFifoCon.txBF.TxPriority = config->TxPriority; - ciFifoCon.txBF.RTREnable = config->RTREnable; - - a = cREGADDR_CiFIFOCON + (channel * CiFIFO_OFFSET); - - spiTransferError = mcp2518fd_WriteWord(a, ciFifoCon.word); - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_ReceiveChannelConfigureObjectReset(CAN_RX_FIFO_CONFIG *config) { - REG_CiFIFOCON ciFifoCon; - ciFifoCon.word = canFifoResetValues[0]; - - config->FifoSize = ciFifoCon.rxBF.FifoSize; - config->PayLoadSize = ciFifoCon.rxBF.PayLoadSize; - config->RxTimeStampEnable = ciFifoCon.rxBF.RxTimeStampEnable; - - return 0; -} - -int8_t -mcp2518fd::mcp2518fd_ReceiveChannelConfigure(CAN_FIFO_CHANNEL channel, - CAN_RX_FIFO_CONFIG *config) { - int8_t spiTransferError = 0; - uint16_t a = 0; - - if (channel == CAN_TXQUEUE_CH0) { - return -100; - } - - // Setup FIFO - REG_CiFIFOCON ciFifoCon; - ciFifoCon.word = canFifoResetValues[0]; - - ciFifoCon.rxBF.TxEnable = 0; - ciFifoCon.rxBF.FifoSize = config->FifoSize; - ciFifoCon.rxBF.PayLoadSize = config->PayLoadSize; - ciFifoCon.rxBF.RxTimeStampEnable = config->RxTimeStampEnable; - - a = cREGADDR_CiFIFOCON + (channel * CiFIFO_OFFSET); - - spiTransferError = mcp2518fd_WriteWord(a, ciFifoCon.word); - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_FilterObjectConfigure(CAN_FILTER filter, - CAN_FILTEROBJ_ID *id) { - uint16_t a; - REG_CiFLTOBJ fObj; - int8_t spiTransferError = 0; - - // Setup - fObj.word = 0; - fObj.bF = *id; - a = cREGADDR_CiFLTOBJ + (filter * CiFILTER_OFFSET); - - spiTransferError = mcp2518fd_WriteWord(a, fObj.word); - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_FilterMaskConfigure(CAN_FILTER filter, - CAN_MASKOBJ_ID *mask) { - uint16_t a; - REG_CiMASK mObj; - int8_t spiTransferError = 0; - - // Setup - mObj.word = 0; - mObj.bF = *mask; - a = cREGADDR_CiMASK + (filter * CiFILTER_OFFSET); - - spiTransferError = mcp2518fd_WriteWord(a, mObj.word); - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_FilterToFifoLink(CAN_FILTER filter, - CAN_FIFO_CHANNEL channel, - bool enable) { - uint16_t a; - REG_CiFLTCON_BYTE fCtrl; - int8_t spiTransferError = 0; - - // Enable - fCtrl.bF.Enable = !!enable; - - // Link - fCtrl.bF.BufferPointer = channel; - a = cREGADDR_CiFLTCON + filter; - - spiTransferError = mcp2518fd_WriteByte(a, fCtrl.byte); - - return spiTransferError; -} - - -/* - * bittime calculation code from - * https://github.com/pierremolinaro/acan2517FD - * - */ - -static const uint16_t MAX_BRP = 256 ; -static const uint16_t MAX_ARBITRATION_PHASE_SEGMENT_1 = 256 ; -static const uint8_t MAX_ARBITRATION_PHASE_SEGMENT_2 = 128 ; -static const uint8_t MAX_ARBITRATION_SJW = 128 ; -static const uint16_t MAX_DATA_PHASE_SEGMENT_1 = 32 ; -static const uint8_t MAX_DATA_PHASE_SEGMENT_2 = 16 ; -static const uint8_t MAX_DATA_SJW = 16 ; - -int mcp2518fd::calcBittime(const uint32_t inDesiredArbitrationBitRate, - const uint32_t inTolerancePPM) -{ - if (mDataBitRateFactor <= 1) { // Single bit rate - const uint32_t maxTQCount = MAX_ARBITRATION_PHASE_SEGMENT_1 + MAX_ARBITRATION_PHASE_SEGMENT_2 + 1 ; // Setting for slowest bit rate - uint32_t BRP = MAX_BRP ; - uint32_t smallestError = UINT32_MAX ; - uint32_t bestBRP = 1 ; // Setting for highest bit rate - uint32_t bestTQCount = 4 ; // Setting for highest bit rate - uint32_t TQCount = mSysClock / inDesiredArbitrationBitRate / BRP ; - //--- Loop for finding best BRP and best TQCount - while ((TQCount <= (MAX_ARBITRATION_PHASE_SEGMENT_1 + MAX_ARBITRATION_PHASE_SEGMENT_2 + 1)) && (BRP > 0)) { - //--- Compute error using TQCount - if ((TQCount >= 4) && (TQCount <= maxTQCount)) { - const uint32_t error = mSysClock - inDesiredArbitrationBitRate * TQCount * BRP ; // error is always >= 0 - if (error <= smallestError) { - smallestError = error ; - bestBRP = BRP ; - bestTQCount = TQCount ; - } - } - //--- Compute error using TQCount+1 - if ((TQCount >= 3) && (TQCount < maxTQCount)) { - const uint32_t error = inDesiredArbitrationBitRate * (TQCount + 1) * BRP - mSysClock ; // error is always >= 0 - if (error <= smallestError) { - smallestError = error ; - bestBRP = BRP ; - bestTQCount = TQCount + 1 ; - } - } - //--- Continue with next value of BRP - BRP -- ; - TQCount = (BRP == 0) ? (maxTQCount + 1) : (mSysClock / inDesiredArbitrationBitRate / BRP) ; - } - //--- Compute PS2 (1 <= PS2 <= 128) - uint32_t PS2 = bestTQCount / 5 ; // For sampling point at 80% - if (PS2 == 0) { - PS2 = 1 ; - }else if (PS2 > MAX_ARBITRATION_PHASE_SEGMENT_2) { - PS2 = MAX_ARBITRATION_PHASE_SEGMENT_2 ; - } - //--- Compute PS1 (1 <= PS1 <= 256) - uint32_t PS1 = bestTQCount - PS2 - 1 /* Sync Seg */ ; - if (PS1 > MAX_ARBITRATION_PHASE_SEGMENT_1) { - PS2 += PS1 - MAX_ARBITRATION_PHASE_SEGMENT_1 ; - PS1 = MAX_ARBITRATION_PHASE_SEGMENT_1 ; - } - //--- - mBitRatePrescaler = (uint16_t) bestBRP ; - mArbitrationPhaseSegment1 = (uint16_t) PS1 ; - mArbitrationPhaseSegment2 = (uint8_t) PS2 ; - mArbitrationSJW = mArbitrationPhaseSegment2 ; // Always 1 <= SJW <= 128, and SJW <= mArbitrationPhaseSegment2 - //--- Final check of the nominal configuration - const uint32_t W = bestTQCount * inDesiredArbitrationBitRate * bestBRP ; - const uint64_t diff = (mSysClock > W) ? (mSysClock - W) : (W - mSysClock) ; - const uint64_t ppm = (uint64_t) (1000UL * 1000UL) ; // UL suffix is required for Arduino Uno - mArbitrationBitRateClosedToDesiredRate = (diff * ppm) <= (((uint64_t) W) * inTolerancePPM) ; - }else{ // Dual bit rate, first compute data bit rate - const uint32_t maxDataTQCount = MAX_DATA_PHASE_SEGMENT_1 + MAX_DATA_PHASE_SEGMENT_2 ; // Setting for slowest bit rate - const uint32_t desiredDataBitRate = inDesiredArbitrationBitRate * uint8_t (mDataBitRateFactor) ; - uint32_t smallestError = UINT32_MAX ; - uint32_t bestBRP = MAX_BRP ; // Setting for lowest bit rate - uint32_t bestDataTQCount = maxDataTQCount ; // Setting for lowest bit rate - uint32_t dataTQCount = 4 ; - uint32_t brp = mSysClock / desiredDataBitRate / dataTQCount ; - //--- Loop for finding best BRP and best TQCount - while ((dataTQCount <= maxDataTQCount) && (brp > 0)) { - //--- Compute error using brp - if (brp <= MAX_BRP) { - const uint32_t error = mSysClock - desiredDataBitRate * dataTQCount * brp ; // error is always >= 0 - if (error <= smallestError) { - smallestError = error ; - bestBRP = brp ; - bestDataTQCount = dataTQCount ; - } - } - //--- Compute error using brp+1 - if (brp < MAX_BRP) { - const uint32_t error = desiredDataBitRate * dataTQCount * (brp + 1) - mSysClock ; // error is always >= 0 - if (error <= smallestError) { - smallestError = error ; - bestBRP = brp + 1 ; - bestDataTQCount = dataTQCount ; - } - } - //--- Continue with next value of BRP - dataTQCount += 1 ; - brp = mSysClock / desiredDataBitRate / dataTQCount ; - } - //--- Compute data PS2 (1 <= PS2 <= 16) - uint32_t dataPS2 = bestDataTQCount / 5 ; // For sampling point at 80% - if (dataPS2 == 0) { - dataPS2 = 1 ; - } - //--- Compute data PS1 (1 <= PS1 <= 32) - uint32_t dataPS1 = bestDataTQCount - dataPS2 - 1 /* Sync Seg */ ; - if (dataPS1 > MAX_DATA_PHASE_SEGMENT_1) { - dataPS2 += dataPS1 - MAX_DATA_PHASE_SEGMENT_1 ; - dataPS1 = MAX_DATA_PHASE_SEGMENT_1 ; - } - //--- - const int TDCO = bestBRP * dataPS1 ; // According to DS20005678D, §3.4.8 Page 20 - mTDCO = (TDCO > 63) ? 63 : (int8_t) TDCO ; - mDataPhaseSegment1 = (uint8_t) dataPS1 ; - mDataPhaseSegment2 = (uint8_t) dataPS2 ; - mDataSJW = mDataPhaseSegment2 ; - const uint32_t arbitrationTQCount = bestDataTQCount * uint8_t (mDataBitRateFactor) ; - //--- Compute arbiration PS2 (1 <= PS2 <= 128) - uint32_t arbitrationPS2 = arbitrationTQCount / 5 ; // For sampling point at 80% - if (arbitrationPS2 == 0) { - arbitrationPS2 = 1 ; - } - //--- Compute PS1 (1 <= PS1 <= 256) - uint32_t arbitrationPS1 = arbitrationTQCount - arbitrationPS2 - 1 /* Sync Seg */ ; - if (arbitrationPS1 > MAX_ARBITRATION_PHASE_SEGMENT_1) { - arbitrationPS2 += arbitrationPS1 - MAX_ARBITRATION_PHASE_SEGMENT_1 ; - arbitrationPS1 = MAX_ARBITRATION_PHASE_SEGMENT_1 ; - } - //--- - mBitRatePrescaler = (uint16_t) bestBRP ; - mArbitrationPhaseSegment1 = (uint16_t) arbitrationPS1 ; - mArbitrationPhaseSegment2 = (uint8_t) arbitrationPS2 ; - mArbitrationSJW = mArbitrationPhaseSegment2 ; // Always 1 <= SJW <= 128, and SJW <= mArbitrationPhaseSegment2 - //--- Final check of the nominal configuration - const uint32_t W = arbitrationTQCount * inDesiredArbitrationBitRate * bestBRP ; - const uint64_t diff = (mSysClock > W) ? (mSysClock - W) : (W - mSysClock) ; - const uint64_t ppm = (uint64_t) (1000UL * 1000UL) ; // UL suffix is required for Arduino Uno - mArbitrationBitRateClosedToDesiredRate = (diff * ppm) <= (((uint64_t) W) * inTolerancePPM) ; - } - return mArbitrationBitRateClosedToDesiredRate; -} - -int8_t mcp2518fd::mcp2518fd_BitTimeConfigureNominal() { - int8_t spiTransferError = 0; - REG_CiNBTCFG ciNbtcfg; - - ciNbtcfg.word = canControlResetValues[cREGADDR_CiNBTCFG / 4]; - - // Arbitration Bit rate - ciNbtcfg.bF.BRP = mBitRatePrescaler - 1; - ciNbtcfg.bF.TSEG1 = mArbitrationPhaseSegment1 - 1; - ciNbtcfg.bF.TSEG2 = mArbitrationPhaseSegment2 - 1; - ciNbtcfg.bF.SJW = mArbitrationSJW - 1; - - // Write Bit time registers - spiTransferError = mcp2518fd_WriteWord(cREGADDR_CiNBTCFG, ciNbtcfg.word); - if (spiTransferError) { - return -2; - } - - return spiTransferError; -} - -int8_t -mcp2518fd::mcp2518fd_BitTimeConfigureData(CAN_SSP_MODE sspMode) { - int8_t spiTransferError = 0; - REG_CiDBTCFG ciDbtcfg; - REG_CiTDC ciTdc; - - // Write Bit time registers - ciDbtcfg.word = canControlResetValues[cREGADDR_CiDBTCFG / 4]; - ciDbtcfg.bF.BRP = mBitRatePrescaler - 1; - ciDbtcfg.bF.TSEG1 = mDataPhaseSegment1 - 1; - ciDbtcfg.bF.TSEG2 = mDataPhaseSegment2 - 1; - ciDbtcfg.bF.SJW = mDataSJW - 1; - - spiTransferError = mcp2518fd_WriteWord(cREGADDR_CiDBTCFG, ciDbtcfg.word); - if (spiTransferError) { - return -2; - } - - // Configure Bit time and sample point, SSP - ciTdc.word = canControlResetValues[cREGADDR_CiTDC / 4]; - ciTdc.bF.TDCMode = sspMode; - ciTdc.bF.TDCOffset = mTDCO; - // ciTdc.bF.TDCValue = ?; - - spiTransferError = mcp2518fd_WriteWord(cREGADDR_CiTDC, ciTdc.word); - if (spiTransferError) { - return -3; - } - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_BitTimeConfigure(uint32_t speedset, - CAN_SSP_MODE sspMode, - CAN_SYSCLK_SPEED clk) { - int8_t spiTransferError = 0; - - // Decode bitrate - mDesiredArbitrationBitRate = speedset & 0xFFFFFUL; - mDataBitRateFactor = (speedset >> 24) & 0xFF; - - // Decode clk - switch (clk) { - case CAN_SYSCLK_10M: - mSysClock = 10UL * 1000UL * 1000UL; break; - case CAN_SYSCLK_20M: - mSysClock = 20UL * 1000UL * 1000UL; break; - case CAN_SYSCLK_40M: - default: - mSysClock = 40UL * 1000UL * 1000UL; break; - } - - calcBittime(mDesiredArbitrationBitRate); - mcp2518fd_BitTimeConfigureNominal(); - mcp2518fd_BitTimeConfigureData(sspMode); - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_GpioModeConfigure(GPIO_PIN_MODE gpio0, - GPIO_PIN_MODE gpio1) { - int8_t spiTransferError = 0; - - // Read - uint16_t a = cREGADDR_IOCON + 3; - REG_IOCON iocon; - iocon.word = 0; - - spiTransferError = mcp2518fd_ReadByte(a, &iocon.byte[3]); - if (spiTransferError) { - return -1; - } - - // Modify - iocon.bF.PinMode0 = gpio0; - iocon.bF.PinMode1 = gpio1; - - // Write - spiTransferError = mcp2518fd_WriteByte(a, iocon.byte[3]); - if (spiTransferError) { - return -2; - } - - return spiTransferError; -} - -int8_t -mcp2518fd::mcp2518fd_TransmitChannelEventEnable(CAN_FIFO_CHANNEL channel, - CAN_TX_FIFO_EVENT flags) { - int8_t spiTransferError = 0; - - // Read Interrupt Enables - uint16_t a = cREGADDR_CiFIFOCON + (channel * CiFIFO_OFFSET); - REG_CiFIFOCON ciFifoCon; - ciFifoCon.word = 0; - - spiTransferError = mcp2518fd_ReadByte(a, &ciFifoCon.byte[0]); - if (spiTransferError) { - return -1; - } - - // Modify - ciFifoCon.byte[0] |= (flags & CAN_TX_FIFO_ALL_EVENTS); - - // Write - spiTransferError = mcp2518fd_WriteByte(a, ciFifoCon.byte[0]); - if (spiTransferError) { - return -2; - } - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_ReceiveChannelEventEnable(CAN_FIFO_CHANNEL channel, - CAN_RX_FIFO_EVENT flags) { - int8_t spiTransferError = 0; - uint16_t a = 0; - - if (channel == CAN_TXQUEUE_CH0) - return -100; - - // Read Interrupt Enables - a = cREGADDR_CiFIFOCON + (channel * CiFIFO_OFFSET); - REG_CiFIFOCON ciFifoCon; - ciFifoCon.word = 0; - - spiTransferError = mcp2518fd_ReadByte(a, &ciFifoCon.byte[0]); - if (spiTransferError) { - return -1; - } - - // Modify - ciFifoCon.byte[0] |= (flags & CAN_RX_FIFO_ALL_EVENTS); - - // Write - spiTransferError = mcp2518fd_WriteByte(a, ciFifoCon.byte[0]); - if (spiTransferError) { - return -2; - } - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_ModuleEventEnable(CAN_MODULE_EVENT flags) { - int8_t spiTransferError = 0; - uint16_t a = 0; - - // Read Interrupt Enables - a = cREGADDR_CiINTENABLE; - REG_CiINTENABLE intEnables; - intEnables.word = 0; - - spiTransferError = mcp2518fd_ReadHalfWord(a, &intEnables.word); - if (spiTransferError) { - return -1; - } - - // Modify - intEnables.word |= (flags & CAN_ALL_EVENTS); - - // Write - spiTransferError = mcp2518fd_WriteHalfWord(a, intEnables.word); - if (spiTransferError) { - return -2; - } - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_OperationModeSelect(CAN_OPERATION_MODE opMode) { - uint8_t d = 0; - int8_t spiTransferError = 0; - - // Read - spiTransferError = mcp2518fd_ReadByte(cREGADDR_CiCON + 3, &d); - if (spiTransferError) { - return -1; - } - - // Modify - d &= ~0x07; - d |= opMode; - - // Write - spiTransferError = mcp2518fd_WriteByte(cREGADDR_CiCON + 3, d); - if (spiTransferError) { - return -2; - } - - return spiTransferError; -} - -CAN_OPERATION_MODE mcp2518fd::mcp2518fd_OperationModeGet() { - uint8_t d = 0; - CAN_OPERATION_MODE mode = CAN_INVALID_MODE; - int8_t spiTransferError = 0; - - // Read Opmode - spiTransferError = mcp2518fd_ReadByte(cREGADDR_CiCON + 2, &d); - if (spiTransferError) { - return CAN_INVALID_MODE; - } - - // Get Opmode bits - d = (d >> 5) & 0x7; - - // Decode Opmode - switch (d) { - case CAN_NORMAL_MODE: - mode = CAN_NORMAL_MODE; - break; - case CAN_SLEEP_MODE: - mode = CAN_SLEEP_MODE; - break; - case CAN_INTERNAL_LOOPBACK_MODE: - mode = CAN_INTERNAL_LOOPBACK_MODE; - break; - case CAN_EXTERNAL_LOOPBACK_MODE: - mode = CAN_EXTERNAL_LOOPBACK_MODE; - break; - case CAN_LISTEN_ONLY_MODE: - mode = CAN_LISTEN_ONLY_MODE; - break; - case CAN_CONFIGURATION_MODE: - mode = CAN_CONFIGURATION_MODE; - break; - case CAN_CLASSIC_MODE: - mode = CAN_CLASSIC_MODE; - break; - case CAN_RESTRICTED_MODE: - mode = CAN_RESTRICTED_MODE; - break; - default: - mode = CAN_INVALID_MODE; - break; - } - - return mode; -} - -int8_t mcp2518fd::mcp2518fd_TransmitChannelEventGet(CAN_FIFO_CHANNEL channel, - CAN_TX_FIFO_EVENT *flags) { - int8_t spiTransferError = 0; - uint16_t a = 0; - - // Read Interrupt flags - REG_CiFIFOSTA ciFifoSta; - ciFifoSta.word = 0; - a = cREGADDR_CiFIFOSTA + (channel * CiFIFO_OFFSET); - - spiTransferError = mcp2518fd_ReadByte(a, &ciFifoSta.byte[0]); - if (spiTransferError) { - return -1; - } - - // Update data - *flags = (CAN_TX_FIFO_EVENT)(ciFifoSta.byte[0] & CAN_TX_FIFO_ALL_EVENTS); - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_ErrorCountStateGet(uint8_t *tec, uint8_t *rec, - CAN_ERROR_STATE *flags) { - int8_t spiTransferError = 0; - - // Read Error - uint16_t a = cREGADDR_CiTREC; - REG_CiTREC ciTrec; - ciTrec.word = 0; - - spiTransferError = mcp2518fd_ReadWord(a, &ciTrec.word); - if (spiTransferError) { - return -1; - } - - // Update data - *tec = ciTrec.byte[1]; - *rec = ciTrec.byte[0]; - *flags = (CAN_ERROR_STATE)(ciTrec.byte[2] & CAN_ERROR_ALL); - - return spiTransferError; -} - -// ***************************************************************************** -// ***************************************************************************** -// Section: Miscellaneous -uint32_t DRV_CANFDSPI_DlcToDataBytes(CAN_DLC dlc) { - uint32_t dataBytesInObject = 0; - - if (dlc < CAN_DLC_12) { - dataBytesInObject = dlc; - } else { - switch (dlc) { - case CAN_DLC_12: - dataBytesInObject = 12; - break; - case CAN_DLC_16: - dataBytesInObject = 16; - break; - case CAN_DLC_20: - dataBytesInObject = 20; - break; - case CAN_DLC_24: - dataBytesInObject = 24; - break; - case CAN_DLC_32: - dataBytesInObject = 32; - break; - case CAN_DLC_48: - dataBytesInObject = 48; - break; - case CAN_DLC_64: - dataBytesInObject = 64; - break; - default: - break; - } - } - - return dataBytesInObject; -} - -int8_t mcp2518fd::mcp2518fd_TransmitChannelLoad(CAN_FIFO_CHANNEL channel, - CAN_TX_MSGOBJ *txObj, - uint8_t *txd, - uint32_t txdNumBytes, - bool flush) { - uint16_t a; - uint32_t fifoReg[3]; - uint32_t dataBytesInObject; - REG_CiFIFOCON ciFifoCon; - REG_CiFIFOUA ciFifoUa; - int8_t spiTransferError = 0; - - // Get FIFO registers - a = cREGADDR_CiFIFOCON + (channel * CiFIFO_OFFSET); - - spiTransferError = mcp2518fd_ReadWordArray(a, fifoReg, 3); - if (spiTransferError) { - return -1; - } - - // Check that it is a transmit buffer - ciFifoCon.word = fifoReg[0]; - if (!ciFifoCon.txBF.TxEnable) { - return -2; - } - - // Check that DLC is big enough for data - dataBytesInObject = DRV_CANFDSPI_DlcToDataBytes((CAN_DLC)txObj->bF.ctrl.DLC); - if (dataBytesInObject < txdNumBytes) { - return -3; - } - - // Get address - ciFifoUa.word = fifoReg[2]; -#ifdef USERADDRESS_TIMES_FOUR - a = 4 * ciFifoUa.bF.UserAddress; -#else - a = ciFifoUa.bF.UserAddress; -#endif - a += cRAMADDR_START; - uint8_t txBuffer[MAX_MSG_SIZE]; - - txBuffer[0] = txObj->byte[0]; // not using 'for' to reduce no of instructions - txBuffer[1] = txObj->byte[1]; - txBuffer[2] = txObj->byte[2]; - txBuffer[3] = txObj->byte[3]; - - txBuffer[4] = txObj->byte[4]; - txBuffer[5] = txObj->byte[5]; - txBuffer[6] = txObj->byte[6]; - txBuffer[7] = txObj->byte[7]; - - uint8_t i; - for (i = 0; i < txdNumBytes; i++) { - txBuffer[i + 8] = txd[i]; - } - - // Make sure we write a multiple of 4 bytes to RAM - uint16_t n = 0; - uint8_t j = 0; - - if (txdNumBytes % 4) { - // Need to add bytes - n = 4 - (txdNumBytes % 4); - i = txdNumBytes + 8; - - for (j = 0; j < n; j++) { - txBuffer[i + 8 + j] = 0; - } - } - spiTransferError = mcp2518fd_WriteByteArray(a, txBuffer, txdNumBytes + 8 + n); - if (spiTransferError) { - return -4; - } - - // Set UINC and TXREQ - spiTransferError = mcp2518fd_TransmitChannelUpdate(channel, flush); - if (spiTransferError) { - return -5; - } - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_ReceiveChannelEventGet(CAN_FIFO_CHANNEL channel, - CAN_RX_FIFO_EVENT *flags) { - int8_t spiTransferError = 0; - uint16_t a = 0; - - if (channel == CAN_TXQUEUE_CH0) - return -100; - - // Read Interrupt flags - REG_CiFIFOSTA ciFifoSta; - ciFifoSta.word = 0; - a = cREGADDR_CiFIFOSTA + (channel * CiFIFO_OFFSET); - - spiTransferError = mcp2518fd_ReadByte(a, &ciFifoSta.byte[0]); - if (spiTransferError) { - return -1; - } - - // Update data - *flags = (CAN_RX_FIFO_EVENT)(ciFifoSta.byte[0] & CAN_RX_FIFO_ALL_EVENTS); - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_ReceiveMessageGet(CAN_FIFO_CHANNEL channel, - CAN_RX_MSGOBJ *rxObj, - uint8_t *rxd, uint8_t nBytes) { - uint8_t n = 0; - uint8_t i = 0; - uint16_t a; - uint32_t fifoReg[3]; - REG_CiFIFOCON ciFifoCon; - REG_CiFIFOUA ciFifoUa; - int8_t spiTransferError = 0; - - // Get FIFO registers - a = cREGADDR_CiFIFOCON + (channel * CiFIFO_OFFSET); - - spiTransferError = mcp2518fd_ReadWordArray(a, fifoReg, 3); - if (spiTransferError) { - return -1; - } - - // Check that it is a receive buffer - ciFifoCon.word = fifoReg[0]; - ciFifoCon.txBF.TxEnable = 0; - if (ciFifoCon.txBF.TxEnable) { - return -2; - } - - // Get address - ciFifoUa.word = fifoReg[2]; -#ifdef USERADDRESS_TIMES_FOUR - a = 4 * ciFifoUa.bF.UserAddress; -#else - a = ciFifoUa.bF.UserAddress; -#endif - a += cRAMADDR_START; - - // Number of bytes to read - n = nBytes + 8; // Add 8 header bytes - - if (ciFifoCon.rxBF.RxTimeStampEnable) { - n += 4; // Add 4 time stamp bytes - } - - // Make sure we read a multiple of 4 bytes from RAM - if (n % 4) { - n = n + 4 - (n % 4); - } - - // Read rxObj using one access - uint8_t ba[MAX_MSG_SIZE]; - - if (n > MAX_MSG_SIZE) { - n = MAX_MSG_SIZE; - } - - spiTransferError = mcp2518fd_ReadByteArray(a, ba, n); - if (spiTransferError) { - return -3; - } - - // Assign message header - REG_t myReg; - - myReg.byte[0] = ba[0]; - myReg.byte[1] = ba[1]; - myReg.byte[2] = ba[2]; - myReg.byte[3] = ba[3]; - rxObj->word[0] = myReg.word; - - myReg.byte[0] = ba[4]; - myReg.byte[1] = ba[5]; - myReg.byte[2] = ba[6]; - myReg.byte[3] = ba[7]; - rxObj->word[1] = myReg.word; - - if (ciFifoCon.rxBF.RxTimeStampEnable) { - myReg.byte[0] = ba[8]; - myReg.byte[1] = ba[9]; - myReg.byte[2] = ba[10]; - myReg.byte[3] = ba[11]; - rxObj->word[2] = myReg.word; - - // Assign message data - for (i = 0; i < nBytes; i++) { - rxd[i] = ba[i + 12]; - } - } else { - rxObj->word[2] = 0; - - // Assign message data - for (i = 0; i < nBytes; i++) { - rxd[i] = ba[i + 8]; - } - } - - // UINC channel - spiTransferError = mcp2518fd_ReceiveChannelUpdate(channel); - if (spiTransferError) { - return -4; - } - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_ReceiveChannelUpdate(CAN_FIFO_CHANNEL channel) { - uint16_t a = 0; - REG_CiFIFOCON ciFifoCon; - int8_t spiTransferError = 0; - ciFifoCon.word = 0; - - // Set UINC - a = cREGADDR_CiFIFOCON + (channel * CiFIFO_OFFSET) + - 1; // Byte that contains FRESET - ciFifoCon.rxBF.UINC = 1; - - // Write byte - spiTransferError = mcp2518fd_WriteByte(a, ciFifoCon.byte[1]); - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_TransmitChannelUpdate(CAN_FIFO_CHANNEL channel, - bool flush) { - uint16_t a; - REG_CiFIFOCON ciFifoCon; - int8_t spiTransferError = 0; - - // Set UINC - a = cREGADDR_CiFIFOCON + (channel * CiFIFO_OFFSET) + - 1; // Byte that contains FRESET - ciFifoCon.word = 0; - ciFifoCon.txBF.UINC = 1; - - // Set TXREQ - if (flush) { - ciFifoCon.txBF.TxRequest = 1; - } - - spiTransferError = mcp2518fd_WriteByte(a, ciFifoCon.byte[1]); - if (spiTransferError) { - return -1; - } - - return spiTransferError; -} - -int8_t -mcp2518fd::mcp2518fd_ReceiveChannelStatusGet(CAN_FIFO_CHANNEL channel, - CAN_RX_FIFO_STATUS *status) { - uint16_t a; - REG_CiFIFOSTA ciFifoSta; - int8_t spiTransferError = 0; - - // Read - ciFifoSta.word = 0; - a = cREGADDR_CiFIFOSTA + (channel * CiFIFO_OFFSET); - - spiTransferError = mcp2518fd_ReadByte(a, &ciFifoSta.byte[0]); - if (spiTransferError) { - return -1; - } - - // Update data - *status = (CAN_RX_FIFO_STATUS)(ciFifoSta.byte[0] & 0x0F); - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_ErrorStateGet(CAN_ERROR_STATE *flags) { - int8_t spiTransferError = 0; - - // Read Error state - uint8_t f = 0; - - spiTransferError = mcp2518fd_ReadByte(cREGADDR_CiTREC + 2, &f); - if (spiTransferError) { - return -1; - } - - // Update data - *flags = (CAN_ERROR_STATE)(f & CAN_ERROR_ALL); - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_ModuleEventRxCodeGet(CAN_RXCODE *rxCode) { - int8_t spiTransferError = 0; - uint8_t rxCodeByte = 0; - - spiTransferError = mcp2518fd_ReadByte(cREGADDR_CiVEC + 3, &rxCodeByte); - if (spiTransferError) { - return -1; - } - - // Decode data - // 0x40 = "no interrupt" (CAN_FIFO_CIVEC_NOINTERRUPT) - if ((rxCodeByte < CAN_RXCODE_TOTAL_CHANNELS) || - (rxCodeByte == CAN_RXCODE_NO_INT)) { - *rxCode = (CAN_RXCODE)rxCodeByte; - } else { - *rxCode = CAN_RXCODE_RESERVED; // shouldn't get here - } - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_ModuleEventTxCodeGet(CAN_TXCODE *txCode) { - int8_t spiTransferError = 0; - uint16_t a = 0; - uint8_t txCodeByte = 0; - - // Read - a = cREGADDR_CiVEC + 2; - - spiTransferError = mcp2518fd_ReadByte(a, &txCodeByte); - if (spiTransferError) { - return -1; - } - - // Decode data - // 0x40 = "no interrupt" (CAN_FIFO_CIVEC_NOINTERRUPT) - if ((txCodeByte < CAN_TXCODE_TOTAL_CHANNELS) || - (txCodeByte == CAN_TXCODE_NO_INT)) { - *txCode = (CAN_TXCODE)txCodeByte; - } else { - *txCode = CAN_TXCODE_RESERVED; // shouldn't get here - } - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_TransmitChannelEventAttemptClear(CAN_FIFO_CHANNEL channel) -{ - int8_t spiTransferError = 0; - uint16_t a = 0; - - // Read Interrupt Enables - a = cREGADDR_CiFIFOSTA + (channel * CiFIFO_OFFSET); - REG_CiFIFOSTA ciFifoSta; - ciFifoSta.word = 0; - - spiTransferError = mcp2518fd_ReadByte(a, &ciFifoSta.byte[0]); - if (spiTransferError) { - return -1; - } - - // Modify - ciFifoSta.byte[0] &= ~CAN_TX_FIFO_ATTEMPTS_EXHAUSTED_EVENT; - - // Write - spiTransferError = mcp2518fd_WriteByte(a, ciFifoSta.byte[0]); - if (spiTransferError) { - return -2; - } - - return spiTransferError; -} - - -int8_t mcp2518fd::mcp2518fd_LowPowerModeEnable() { - int8_t spiTransferError = 0; - uint8_t d = 0; - -#ifdef MCP2517FD - // LPM not implemented - spiTransferError = -100; -#else - // Read - spiTransferError = mcp2518fd_ReadByte(cREGADDR_OSC, &d); - if (spiTransferError) { - return -1; - } - - // Modify - d |= 0x08; - - // Write - spiTransferError = mcp2518fd_WriteByte(cREGADDR_OSC, d); - if (spiTransferError) { - return -2; - } -#endif - - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_LowPowerModeDisable() { - int8_t spiTransferError = 0; - uint8_t d = 0; - -#ifdef MCP2517FD - // LPM not implemented - spiTransferError = -100; -#else - // Read - spiTransferError = mcp2518fd_ReadByte(cREGADDR_OSC, &d); - if (spiTransferError) { - return -1; - } - - // Modify - d &= ~0x08; - - // Write - spiTransferError = mcp2518fd_WriteByte(cREGADDR_OSC, d); - if (spiTransferError) { - return -2; - } -#endif - - return spiTransferError; -} - -void mcp2518fd::mcp2518fd_TransmitMessageQueue(void) { - uint8_t attempts = MAX_TXQUEUE_ATTEMPTS; - CAN_ERROR_STATE errorFlags; - uint8_t tec, rec; - - // Check if FIFO is not full - do { - mcp2518fd_TransmitChannelEventGet(APP_TX_FIFO, &txFlags); - if (attempts == 0) { - Nop(); Nop(); - mcp2518fd_ErrorCountStateGet(&tec, &rec, &errorFlags); - return; - } - attempts--; - } while (!(txFlags & CAN_TX_FIFO_NOT_FULL_EVENT)); - - // Load message and transmit - uint8_t n = DRV_CANFDSPI_DlcToDataBytes((CAN_DLC)txObj.bF.ctrl.DLC); - mcp2518fd_TransmitChannelLoad(APP_TX_FIFO, &txObj, txd, n, true); -} - -/********************************************************************************************************* -** Function name: sendMsg -** Descriptions: send message -*********************************************************************************************************/ -byte mcp2518fd::mcp2518fd_sendMsg(const byte *buf, byte len, unsigned long id, - byte ext, byte rtr, bool wait_sent) { - uint8_t n; - int i; - byte spiTransferError = 0; - // Configure message data - txObj.word[0] = 0; - txObj.word[1] = 0; - - txObj.bF.ctrl.RTR = !!rtr; - if (rtr && len > CAN_DLC_8) { - len = CAN_DLC_8; - } - txObj.bF.ctrl.DLC = len; - - txObj.bF.ctrl.IDE = !!ext; - if (ext) { - txObj.bF.id.SID = (id >> 18) & 0x7FF; - txObj.bF.id.EID = id & 0x3FFFF; - } else { - txObj.bF.id.SID = id; - } - - txObj.bF.ctrl.BRS = true; - - txObj.bF.ctrl.FDF = (len > 8); - n = DRV_CANFDSPI_DlcToDataBytes((CAN_DLC)txObj.bF.ctrl.DLC); - // Prepare data - for (i = 0; i < n; i++) { - txd[i] = buf[i]; - } - - mcp2518fd_TransmitMessageQueue(); - return spiTransferError; -} - -int8_t mcp2518fd::mcp2518fd_receiveMsg() { - mcp2518fd_ReceiveChannelEventGet(APP_RX_FIFO, &rxFlags); - - if (rxFlags & CAN_RX_FIFO_NOT_EMPTY_EVENT) { - mcp2518fd_ReceiveMessageGet(APP_RX_FIFO, &rxObj, rxd, 8); - for (int i = 0; i < 8; i++) { - Serial.println(rxd[i]); - Serial.println("\t"); - } - Serial.println(); - } - - return 0; -} - -uint32_t mcp2518fd::bittime_compat_to_mcp2518fd(uint32_t speedset) { - uint32_t r; - - if (speedset > 0x100) { - return speedset; - } - switch (speedset) { - case CAN_5KBPS: r = CANFD::BITRATE( 5000UL, 0); break; - case CAN_10KBPS: r = CANFD::BITRATE( 10000UL, 0); break; - case CAN_20KBPS: r = CANFD::BITRATE( 20000UL, 0); break; - case CAN_25KBPS: r = CANFD::BITRATE( 25000UL, 0); break; - case CAN_31K25BPS:r = CANFD::BITRATE( 31250UL, 0); break; - case CAN_33KBPS: r = CANFD::BITRATE( 33000UL, 0); break; - case CAN_40KBPS: r = CANFD::BITRATE( 40000UL, 0); break; - case CAN_50KBPS: r = CANFD::BITRATE( 50000UL, 0); break; - case CAN_80KBPS: r = CANFD::BITRATE( 80000UL, 0); break; - case CAN_83K3BPS: r = CANFD::BITRATE( 83300UL, 0); break; - case CAN_95KBPS: r = CANFD::BITRATE( 95000UL, 0); break; - case CAN_100KBPS: r = CANFD::BITRATE( 100000UL, 0); break; - case CAN_125KBPS: r = CANFD::BITRATE( 125000UL, 0); break; - case CAN_200KBPS: r = CANFD::BITRATE( 200000UL, 0); break; - case CAN_250KBPS: r = CANFD::BITRATE( 250000UL, 0); break; - default: - case CAN_500KBPS: r = CANFD::BITRATE( 500000UL, 0); break; - case CAN_666KBPS: r = CANFD::BITRATE( 666000UL, 0); break; - case CAN_800KBPS: r = CANFD::BITRATE( 800000UL, 0); break; - case CAN_1000KBPS:r = CANFD::BITRATE(1000000UL, 0); break; - } - return r; -} - -/********************************************************************************************************* -** Function name: mcp2515_init -** Descriptions: init the device -** speedset msb 8 bits = factor (0 or 1 is no bit rate switch) -** lsb 24 bits = arbitration bitrate -*********************************************************************************************************/ -uint8_t mcp2518fd::mcp2518fd_init(uint32_t speedset, const byte clock) { - // Reset device - mcp2518fd_reset(); - - // Enable ECC and initialize RAM - mcp2518fd_EccEnable(); - - mcp2518fd_RamInit(0xff); - - // Configure device - mcp2518fd_ConfigureObjectReset(&config); - config.IsoCrcEnable = 1; - config.StoreInTEF = 0; - mcp2518fd_Configure(&config); - - // Setup TX FIFO - mcp2518fd_TransmitChannelConfigureObjectReset(&txConfig); - txConfig.FifoSize = 7; - txConfig.PayLoadSize = CAN_PLSIZE_64; - txConfig.TxPriority = 1; - mcp2518fd_TransmitChannelConfigure(APP_TX_FIFO, &txConfig); - - // Setup RX FIFO - mcp2518fd_ReceiveChannelConfigureObjectReset(&rxConfig); - rxConfig.FifoSize = 15; - rxConfig.PayLoadSize = CAN_PLSIZE_64; - mcp2518fd_ReceiveChannelConfigure(APP_RX_FIFO, &rxConfig); - - // Setup RX Filter - fObj.word = 0; - mcp2518fd_FilterObjectConfigure(CAN_FILTER0, &fObj.bF); - - // Setup RX Mask - mObj.word = 0; // Only allow standard IDs - mcp2518fd_FilterMaskConfigure(CAN_FILTER0, &mObj.bF); - - // Link FIFO and Filter - mcp2518fd_FilterToFifoLink(CAN_FILTER0, APP_RX_FIFO, true); - - // Setup Bit Time - mcp2518fd_BitTimeConfigure(speedset, CAN_SSP_MODE_AUTO, CAN_SYSCLK_SPEED(clock)); - - // Setup Transmit and Receive Interrupts - mcp2518fd_GpioModeConfigure(GPIO_MODE_INT, GPIO_MODE_INT); -#ifdef APP_USE_TX_INT - mcp2518fd_TransmitChannelEventEnable(APP_TX_FIFO, CAN_TX_FIFO_NOT_FULL_EVENT); -#endif - mcp2518fd_ReceiveChannelEventEnable(APP_RX_FIFO, CAN_RX_FIFO_NOT_EMPTY_EVENT); - mcp2518fd_ModuleEventEnable((CAN_MODULE_EVENT)(CAN_TX_EVENT | CAN_RX_EVENT)); - - // Select Normal Mode - // mcp2518fd_OperationModeSelect(CAN_CLASSIC_MODE); - setMode(mcpMode); - - return 0; -} - -/********************************************************************************************************* -** Function name: enableTxInterrupt -** Descriptions: enable interrupt for all tx buffers -*********************************************************************************************************/ -void mcp2518fd::enableTxInterrupt(bool enable) { - if (enable == true) - { - mcp2518fd_ModuleEventEnable(CAN_TX_EVENT); - } - return; -} - -byte mcp2518fd::init_Mask(byte num, byte ext, unsigned long ulData) { - int8_t err; - - mcp2518fd_OperationModeSelect(CAN_CONFIGURATION_MODE); - - // Setup RX Mask - mObj.word = 0; - mObj.bF.MSID = ulData; - mObj.bF.MIDE = ext; - err = mcp2518fd_FilterMaskConfigure((CAN_FILTER)num, &mObj.bF); - mcp2518fd_OperationModeSelect(mcpMode); - - return err; -} - -/********************************************************************************************************* -** Function name: init_Filt -** Descriptions: init canid filters -*********************************************************************************************************/ -byte mcp2518fd::init_Filt(byte num, byte ext, unsigned long ulData) { - int8_t err; - err = mcp2518fd_OperationModeSelect(CAN_CONFIGURATION_MODE); - - // Setup RX Filter - fObj.word = 0; - if (!ext) { // standard identifier - fObj.bF.SID = ulData; - } else { // extended identifier - fObj.bF.EID = ulData; - } - fObj.bF.EXIDE = !!ext; - mcp2518fd_FilterObjectConfigure((CAN_FILTER)num, &fObj.bF); - mcp2518fd_OperationModeSelect(mcpMode); - return err; -} - -/********************************************************************************************************* -** Function name: setSleepWakeup -** Descriptions: Enable or disable the wake up interrupt (If disabled -*the MCP2515 will not be woken up by CAN bus activity) -*********************************************************************************************************/ -void mcp2518fd::setSleepWakeup(const byte enable) { - if (enable) { - mcp2518fd_LowPowerModeEnable(); - } else { - mcp2518fd_LowPowerModeDisable(); - } -} - -/********************************************************************************************************* -** Function name: sleep -** Descriptions: Put mcp2515 in sleep mode to save power -*********************************************************************************************************/ -byte mcp2518fd::sleep() { - if (getMode() != 0x01) { - return mcp2518fd_OperationModeSelect(CAN_SLEEP_MODE); - } else { - return CAN_OK; - } -} - -/********************************************************************************************************* -** Function name: wake -** Descriptions: wake MCP2515 manually from sleep. It will come back -*in the mode it was before sleeping. -*********************************************************************************************************/ -byte mcp2518fd::wake() { - byte currMode = getMode(); - if (currMode != mcpMode) { - return mcp2518fd_OperationModeSelect(mcpMode); - } else { - return CAN_OK; - } -} - -/********************************************************************************************************* -** Function name: getMode -** Descriptions: Returns current control mode -*********************************************************************************************************/ -byte mcp2518fd::getMode() { - CAN_OPERATION_MODE mode; - mode = mcp2518fd_OperationModeGet(); - return (byte)mode; -} - -/********************************************************************************************************* -** Function name: setMode -** Descriptions: Sets control mode -*********************************************************************************************************/ -byte mcp2518fd::setMode(const byte opMode) { - if ((CAN_OPERATION_MODE)opMode != - CAN_SLEEP_MODE) { // if going to sleep, the value stored in opMode is not - // changed so that we can return to it later - mcpMode = (CAN_OPERATION_MODE)opMode; - } - return mcp2518fd_OperationModeSelect(mcpMode); -} - -/********************************************************************************************************* -** Function name: readMsgBufID -** Descriptions: Read message buf and can bus source ID according to -*status. -** Status has to be read with readRxTxStatus. -*********************************************************************************************************/ -byte mcp2518fd::readMsgBufID(byte status, volatile unsigned long *id, - volatile byte *ext, volatile byte *rtr, - volatile byte *len, volatile byte *buf) { - - byte r = mcp2518fd_readMsgBufID(len, buf); - if (id) - *id = can_id; - if (ext) - *ext = ext_flg; - if (rtr) - *rtr = this->rtr; - return r; -} - -/********************************************************************************************************* -** Function name: checkReceive -** Descriptions: check if got something -*********************************************************************************************************/ -byte mcp2518fd::checkReceive(void) { - CAN_RX_FIFO_STATUS status; - // RXnIF in Bit 1 and 0 return ((res & MCP_STAT_RXIF_MASK)? CAN_MSGAVAIL: CAN_NOMSG); - mcp2518fd_ReceiveChannelStatusGet(APP_RX_FIFO, &status); - - byte res = (byte)(status & CAN_RX_FIFO_NOT_EMPTY_EVENT) + 2; - return res; -} - -/********************************************************************************************************* -** Function name: checkError -** Descriptions: if something error -*********************************************************************************************************/ -byte mcp2518fd::checkError(uint8_t* err_ptr) { - CAN_ERROR_STATE flags; - mcp2518fd_ErrorStateGet(&flags); - if (err_ptr) { - *err_ptr = byte(flags); - } - return (byte)flags; -} - -// /********************************************************************************************************* -// ** Function name: readMsgBufID -// ** Descriptions: Read message buf and can bus source ID according -// to status. -// ** Status has to be read with readRxTxStatus. -// *********************************************************************************************************/ -byte mcp2518fd::mcp2518fd_readMsgBufID(volatile byte *len, volatile byte *buf) { - mcp2518fd_ReceiveMessageGet(APP_RX_FIFO, &rxObj, rxd, MAX_DATA_BYTES); - ext_flg = rxObj.bF.ctrl.IDE; - can_id = ext_flg? (rxObj.bF.id.EID | (rxObj.bF.id.SID << 18)) - : rxObj.bF.id.SID; - rtr = rxObj.bF.ctrl.RTR; - uint8_t n = DRV_CANFDSPI_DlcToDataBytes((CAN_DLC)rxObj.bF.ctrl.DLC); - if (len) { - *len = n; - } - - for (int i = 0; i < n; i++) { - buf[i] = rxd[i]; - } - return 0; -} - -/********************************************************************************************************* -** Function name: trySendMsgBuf -** Descriptions: Try to send message. There is no delays for waiting -*free buffer. -*********************************************************************************************************/ -byte mcp2518fd::trySendMsgBuf(unsigned long id, byte ext, byte rtr, byte len, - const byte *buf, byte iTxBuf) { - (void)iTxBuf; - return mcp2518fd_sendMsg(buf, len, id, ext, rtr, false); -} - -/********************************************************************************************************* -** Function name: clearBufferTransmitIfFlags -** Descriptions: Clear transmit interrupt flags for specific buffer -*or for all unreserved buffers. -** If interrupt will be used, it is important to clear -*all flags, when there is no -** more data to be sent. Otherwise IRQ will newer -*change state. -*********************************************************************************************************/ -void mcp2518fd::clearBufferTransmitIfFlags(byte flags) { - mcp2518fd_TransmitChannelEventAttemptClear(APP_TX_FIFO); - return; -} - -/********************************************************************************************************* -** Function name: sendMsgBuf -** Descriptions: Send message by using buffer read as free from -*CANINTF status -** Status has to be read with readRxTxStatus and -*filtered with checkClearTxStatus -*********************************************************************************************************/ -byte mcp2518fd::sendMsgBuf(byte status, unsigned long id, byte ext, byte rtr, - byte len, volatile const byte *buf) { - return mcp2518fd_sendMsg((const byte *)buf, len, id, ext, rtr, true); -} - -/********************************************************************************************************* -** Function name: sendMsgBuf -** Descriptions: send buf -*********************************************************************************************************/ -byte mcp2518fd::sendMsgBuf(unsigned long id, byte ext, byte rtr, byte len, - const byte *buf, bool wait_sent) { - return mcp2518fd_sendMsg(buf, len, id, ext, rtr, wait_sent); -} - -/********************************************************************************************************* -** Function name: readRxTxStatus -** Descriptions: Read RX and TX interrupt bits. Function uses status -*reading, but translates. -** result to MCP_CANINTF. With this you can check -*status e.g. on interrupt sr -** with one single call to save SPI calls. Then use -*checkClearRxStatus and -** checkClearTxStatus for testing. -*********************************************************************************************************/ -byte mcp2518fd::readRxTxStatus(void) { - byte ret; - mcp2518fd_ReceiveChannelEventGet(APP_RX_FIFO, &rxFlags); - ret = (byte)rxFlags; - return ret; -} - -/********************************************************************************************************* -** Function name: checkClearRxStatus -** Descriptions: Return first found rx CANINTF status and clears it -*from parameter. -** Note that this does not affect to chip CANINTF at -*all. You can use this -** with one single readRxTxStatus call. -*********************************************************************************************************/ -byte mcp2518fd::checkClearRxStatus(byte *status) { - return 1; -} - -/********************************************************************************************************* -** Function name: checkClearTxStatus -** Descriptions: Return specified buffer of first found tx CANINTF -*status and clears it from parameter. -** Note that this does not affect to chip CANINTF at -*all. You can use this -** with one single readRxTxStatus call. -*********************************************************************************************************/ -byte mcp2518fd::checkClearTxStatus(byte *status, byte iTxBuf) { - (void)iTxBuf; - return 1; -} - -/********************************************************************************************************* -** Function name: mcpPinMode -** Descriptions: switch supported pins between HiZ, interrupt, output -*or input -*********************************************************************************************************/ -bool mcp2518fd::mcpPinMode(const byte pin, const byte mode) { - int8_t spiTransferError = 1; - - // Read - uint16_t a = cREGADDR_IOCON + 3; - REG_IOCON iocon; - iocon.word = 0; - - mcp2518fd_ReadByte(a, &iocon.byte[3]); - - if (pin == GPIO_PIN_0) { - // Modify - iocon.bF.PinMode0 = (GPIO_PIN_MODE)mode; - } - if (pin == GPIO_PIN_1) { - // Modify - iocon.bF.PinMode1 = (GPIO_PIN_MODE)mode; - } - // Write - mcp2518fd_WriteByte(a, iocon.byte[3]); - - return spiTransferError; -} - -/********************************************************************************************************* -** Function name: mcpDigitalWrite -** Descriptions: write HIGH or LOW to RX0BF/RX1BF -*********************************************************************************************************/ -bool mcp2518fd::mcpDigitalWrite(const byte pin, const byte mode) { - int8_t spiTransferError = 0; - - // Read - uint16_t a = cREGADDR_IOCON + 1; - REG_IOCON iocon; - iocon.word = 0; - - spiTransferError = mcp2518fd_ReadByte(a, &iocon.byte[1]); - if (spiTransferError) { - return -1; - } - - // Modify - switch (pin) { - case GPIO_PIN_0: - iocon.bF.LAT0 = (GPIO_PIN_STATE)mode; - break; - case GPIO_PIN_1: - iocon.bF.LAT1 = (GPIO_PIN_STATE)mode; - break; - default: - return -1; - break; - } - - // Write - spiTransferError = mcp2518fd_WriteByte(a, iocon.byte[1]); - if (spiTransferError) { - return -2; - } - - return spiTransferError; -} - -/********************************************************************************************************* -** Function name: mcpDigitalRead -** Descriptions: read HIGH or LOW from supported pins -*********************************************************************************************************/ -byte mcp2518fd::mcpDigitalRead(const byte pin) { - GPIO_PIN_STATE state; - - // Read - REG_IOCON iocon; - iocon.word = 0; - - mcp2518fd_ReadByte(cREGADDR_IOCON + 2, &iocon.byte[2]); - - // Update data - switch (pin) { - case GPIO_PIN_0: - state = (GPIO_PIN_STATE)iocon.bF.GPIO0; - break; - case GPIO_PIN_1: - state = (GPIO_PIN_STATE)iocon.bF.GPIO1; - break; - default: - return -1; - break; - } - - return (byte)state;; -} - -/* CANFD Auxiliary helper */ -byte CANFD::dlc2len(byte dlc) { - if (dlc <= CAN_DLC_8) - return dlc; - switch (dlc) { - case CAN_DLC_12: return 12; - case CAN_DLC_16: return 16; - case CAN_DLC_20: return 20; - case CAN_DLC_24: return 24; - case CAN_DLC_32: return 32; - case CAN_DLC_48: return 48; - default: - case CAN_DLC_64: return 64; - } -} - -byte CANFD::len2dlc(byte len) { - if (len <= CAN_DLC_8) - return len; - else if (len <= 12) return CAN_DLC_12; - else if (len <= 16) return CAN_DLC_16; - else if (len <= 20) return CAN_DLC_20; - else if (len <= 24) return CAN_DLC_24; - else if (len <= 32) return CAN_DLC_32; - else if (len <= 48) return CAN_DLC_48; - return CAN_DLC_64; -} - diff --git a/arduino/src/mcp/mcp2518fd_can.h b/arduino/src/mcp/mcp2518fd_can.h deleted file mode 100644 index c811056..0000000 --- a/arduino/src/mcp/mcp2518fd_can.h +++ /dev/null @@ -1,294 +0,0 @@ - - -#ifndef _MCP2518FD_H_ -#define _MCP2518FD_H_ - -#include "mcp2518fd_can_dfs.h" -#include "mcp_can.h" -#include -#include - -// ***************************************************************************** -// ***************************************************************************** -//! Reset DUT - -// Code anchor for break points -#define Nop() asm("nop") - -// Index to SPI channel -// Used when multiple MCP25xxFD are connected to the same SPI interface, but -// with different CS -#define SPI_DEFAULT_BUFFER_LENGTH 96 - -// extern SPIClass* pSPI; -#define spi_readwrite pSPI->transfer -#define spi_read() spi_readwrite(0x00) -#define spi_write(spi_val) spi_readwrite(spi_val) -#define SPI_BEGIN() \ - pSPI->beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE0)) -#define SPI_END() pSPI->endTransaction(); - -// ***************************************************************************** -// ***************************************************************************** -// Section: Defines - -#define CRCBASE 0xFFFF -#define CRCUPPER 1 - -//! Reverse order of bits in byte -const uint8_t BitReverseTable256[256] = { - 0x00, 0x80, 0x40, 0xC0, 0x20, 0xA0, 0x60, 0xE0, 0x10, 0x90, 0x50, 0xD0, - 0x30, 0xB0, 0x70, 0xF0, 0x08, 0x88, 0x48, 0xC8, 0x28, 0xA8, 0x68, 0xE8, - 0x18, 0x98, 0x58, 0xD8, 0x38, 0xB8, 0x78, 0xF8, 0x04, 0x84, 0x44, 0xC4, - 0x24, 0xA4, 0x64, 0xE4, 0x14, 0x94, 0x54, 0xD4, 0x34, 0xB4, 0x74, 0xF4, - 0x0C, 0x8C, 0x4C, 0xCC, 0x2C, 0xAC, 0x6C, 0xEC, 0x1C, 0x9C, 0x5C, 0xDC, - 0x3C, 0xBC, 0x7C, 0xFC, 0x02, 0x82, 0x42, 0xC2, 0x22, 0xA2, 0x62, 0xE2, - 0x12, 0x92, 0x52, 0xD2, 0x32, 0xB2, 0x72, 0xF2, 0x0A, 0x8A, 0x4A, 0xCA, - 0x2A, 0xAA, 0x6A, 0xEA, 0x1A, 0x9A, 0x5A, 0xDA, 0x3A, 0xBA, 0x7A, 0xFA, - 0x06, 0x86, 0x46, 0xC6, 0x26, 0xA6, 0x66, 0xE6, 0x16, 0x96, 0x56, 0xD6, - 0x36, 0xB6, 0x76, 0xF6, 0x0E, 0x8E, 0x4E, 0xCE, 0x2E, 0xAE, 0x6E, 0xEE, - 0x1E, 0x9E, 0x5E, 0xDE, 0x3E, 0xBE, 0x7E, 0xFE, 0x01, 0x81, 0x41, 0xC1, - 0x21, 0xA1, 0x61, 0xE1, 0x11, 0x91, 0x51, 0xD1, 0x31, 0xB1, 0x71, 0xF1, - 0x09, 0x89, 0x49, 0xC9, 0x29, 0xA9, 0x69, 0xE9, 0x19, 0x99, 0x59, 0xD9, - 0x39, 0xB9, 0x79, 0xF9, 0x05, 0x85, 0x45, 0xC5, 0x25, 0xA5, 0x65, 0xE5, - 0x15, 0x95, 0x55, 0xD5, 0x35, 0xB5, 0x75, 0xF5, 0x0D, 0x8D, 0x4D, 0xCD, - 0x2D, 0xAD, 0x6D, 0xED, 0x1D, 0x9D, 0x5D, 0xDD, 0x3D, 0xBD, 0x7D, 0xFD, - 0x03, 0x83, 0x43, 0xC3, 0x23, 0xA3, 0x63, 0xE3, 0x13, 0x93, 0x53, 0xD3, - 0x33, 0xB3, 0x73, 0xF3, 0x0B, 0x8B, 0x4B, 0xCB, 0x2B, 0xAB, 0x6B, 0xEB, - 0x1B, 0x9B, 0x5B, 0xDB, 0x3B, 0xBB, 0x7B, 0xFB, 0x07, 0x87, 0x47, 0xC7, - 0x27, 0xA7, 0x67, 0xE7, 0x17, 0x97, 0x57, 0xD7, 0x37, 0xB7, 0x77, 0xF7, - 0x0F, 0x8F, 0x4F, 0xCF, 0x2F, 0xAF, 0x6F, 0xEF, 0x1F, 0x9F, 0x5F, 0xDF, - 0x3F, 0xBF, 0x7F, 0xFF}; - -//! Look-up table for CRC calculation -const uint16_t crc16_table[256] = { - 0x0000, 0x8005, 0x800F, 0x000A, 0x801B, 0x001E, 0x0014, 0x8011, 0x8033, - 0x0036, 0x003C, 0x8039, 0x0028, 0x802D, 0x8027, 0x0022, 0x8063, 0x0066, - 0x006C, 0x8069, 0x0078, 0x807D, 0x8077, 0x0072, 0x0050, 0x8055, 0x805F, - 0x005A, 0x804B, 0x004E, 0x0044, 0x8041, 0x80C3, 0x00C6, 0x00CC, 0x80C9, - 0x00D8, 0x80DD, 0x80D7, 0x00D2, 0x00F0, 0x80F5, 0x80FF, 0x00FA, 0x80EB, - 0x00EE, 0x00E4, 0x80E1, 0x00A0, 0x80A5, 0x80AF, 0x00AA, 0x80BB, 0x00BE, - 0x00B4, 0x80B1, 0x8093, 0x0096, 0x009C, 0x8099, 0x0088, 0x808D, 0x8087, - 0x0082, 0x8183, 0x0186, 0x018C, 0x8189, 0x0198, 0x819D, 0x8197, 0x0192, - 0x01B0, 0x81B5, 0x81BF, 0x01BA, 0x81AB, 0x01AE, 0x01A4, 0x81A1, 0x01E0, - 0x81E5, 0x81EF, 0x01EA, 0x81FB, 0x01FE, 0x01F4, 0x81F1, 0x81D3, 0x01D6, - 0x01DC, 0x81D9, 0x01C8, 0x81CD, 0x81C7, 0x01C2, 0x0140, 0x8145, 0x814F, - 0x014A, 0x815B, 0x015E, 0x0154, 0x8151, 0x8173, 0x0176, 0x017C, 0x8179, - 0x0168, 0x816D, 0x8167, 0x0162, 0x8123, 0x0126, 0x012C, 0x8129, 0x0138, - 0x813D, 0x8137, 0x0132, 0x0110, 0x8115, 0x811F, 0x011A, 0x810B, 0x010E, - 0x0104, 0x8101, 0x8303, 0x0306, 0x030C, 0x8309, 0x0318, 0x831D, 0x8317, - 0x0312, 0x0330, 0x8335, 0x833F, 0x033A, 0x832B, 0x032E, 0x0324, 0x8321, - 0x0360, 0x8365, 0x836F, 0x036A, 0x837B, 0x037E, 0x0374, 0x8371, 0x8353, - 0x0356, 0x035C, 0x8359, 0x0348, 0x834D, 0x8347, 0x0342, 0x03C0, 0x83C5, - 0x83CF, 0x03CA, 0x83DB, 0x03DE, 0x03D4, 0x83D1, 0x83F3, 0x03F6, 0x03FC, - 0x83F9, 0x03E8, 0x83ED, 0x83E7, 0x03E2, 0x83A3, 0x03A6, 0x03AC, 0x83A9, - 0x03B8, 0x83BD, 0x83B7, 0x03B2, 0x0390, 0x8395, 0x839F, 0x039A, 0x838B, - 0x038E, 0x0384, 0x8381, 0x0280, 0x8285, 0x828F, 0x028A, 0x829B, 0x029E, - 0x0294, 0x8291, 0x82B3, 0x02B6, 0x02BC, 0x82B9, 0x02A8, 0x82AD, 0x82A7, - 0x02A2, 0x82E3, 0x02E6, 0x02EC, 0x82E9, 0x02F8, 0x82FD, 0x82F7, 0x02F2, - 0x02D0, 0x82D5, 0x82DF, 0x02DA, 0x82CB, 0x02CE, 0x02C4, 0x82C1, 0x8243, - 0x0246, 0x024C, 0x8249, 0x0258, 0x825D, 0x8257, 0x0252, 0x0270, 0x8275, - 0x827F, 0x027A, 0x826B, 0x026E, 0x0264, 0x8261, 0x0220, 0x8225, 0x822F, - 0x022A, 0x823B, 0x023E, 0x0234, 0x8231, 0x8213, 0x0216, 0x021C, 0x8219, - 0x0208, 0x820D, 0x8207, 0x0202}; - -class SPIClass; - -class mcp2518fd : public MCP_CAN { -public: - mcp2518fd(byte _CS) : MCP_CAN(_CS), nReservedTx(0){}; - -public: - virtual void - enableTxInterrupt(bool enable = true); // enable transmit interrupt - virtual void reserveTxBuffers(byte nTxBuf = 0) { - nReservedTx = (nTxBuf < 3 ? nTxBuf : 3 - 1); - } - virtual byte getLastTxBuffer() { - return 3 - 1; // read index of last tx buffer - } - /* - * speedset could be in MCP_BITTIME_SETUP, - * or fill by CANFD::BITRATE() - */ - virtual byte begin(uint32_t speedset, - const byte clockset = MCP2518FD_40MHz); // init can - virtual byte init_Mask(byte num, byte ext, unsigned long ulData); - virtual byte init_Filt(byte num, byte ext, - unsigned long ulData); // init filters - virtual void setSleepWakeup(const byte enable); - virtual byte sleep(); - virtual byte wake(); - virtual byte setMode(const byte opMode); - virtual byte getMode(); - virtual byte checkError(uint8_t* err_ptr = NULL); - - /* ---- receiving ---- */ - virtual byte checkReceive(void); - virtual byte readMsgBufID(byte status, volatile unsigned long *id, - volatile byte *ext, volatile byte *rtr, - volatile byte *len, - volatile byte *buf); // read buf with object ID - /* wrapper */ - byte readMsgBufID(unsigned long *ID, byte *len, byte *buf) { - return readMsgBufID(readRxTxStatus(), ID, &ext_flg, &rtr, len, buf); - } - byte readMsgBuf(byte *len, byte *buf) { - return readMsgBufID(readRxTxStatus(), &can_id, &ext_flg, &rtr, len, buf); - } - - /* ---- sending ---- */ - /* dlc = CAN_DLC_0..CAN_DLC_64(0..15) - * CAN_DLC_0..CAN_DLC_8(0..8) = data bytes count, compatible to MCP2515 APIs - * CAN_DLC_12(9) = 12 bytes - * CAN_DLC_16(10) = 16 bytes - * CAN_DLC_20(11) = 20 bytes - * CAN_DLC_24(12) = 24 bytes - * CAN_DLC_32(13) = 32 bytes - * CAN_DLC_48(14) = 48 bytes - * CAN_DLC_64(15) = 64 bytes - */ - virtual byte trySendMsgBuf(unsigned long id, byte ext, byte rtr, byte dlc, - const byte *buf, byte iTxBuf = 0xff); - virtual byte sendMsgBuf(byte status, unsigned long id, byte ext, byte rtr, - byte dlc, volatile const byte *buf); - virtual byte sendMsgBuf(unsigned long id, byte ext, byte rtr, byte dlc, - const byte *buf, bool wait_sent = true); - /* wrapper */ - inline byte sendMsgBuf(unsigned long id, byte ext, byte len, const byte *buf) { - return sendMsgBuf(id, ext, 0, len, buf, true); - } - - virtual void clearBufferTransmitIfFlags(byte flags = 0); - virtual byte readRxTxStatus(void); - virtual byte checkClearRxStatus(byte *status); - virtual byte checkClearTxStatus(byte *status, byte iTxBuf = 0xff); - virtual bool mcpPinMode(const byte pin, const byte mode); - virtual bool mcpDigitalWrite(const byte pin, const byte mode); - virtual byte mcpDigitalRead(const byte pin); - -private: - byte mcp2518fd_readMsgBufID(volatile byte *len, volatile byte *buf); - byte mcp2518fd_sendMsg(const byte *buf, byte len, unsigned long id, byte ext, - byte rtr, bool wait_sent); - int8_t mcp2518fd_receiveMsg(); - -private: - uint8_t mcp2518fd_init(uint32_t speedset, const byte clock); // mcp2518fdinit - int8_t mcp2518fd_reset(void); // reset mcp2518fd - int8_t mcp2518fd_EccEnable(void); // Section: ECC - int8_t mcp2518fd_RamInit(uint8_t d); - int8_t mcp2518fd_ConfigureObjectReset(CAN_CONFIG *config); - int8_t mcp2518fd_Configure(CAN_CONFIG *config); - int8_t - mcp2518fd_TransmitChannelConfigureObjectReset(CAN_TX_FIFO_CONFIG *config); - int8_t mcp2518fd_TransmitChannelConfigure(CAN_FIFO_CHANNEL channel, - CAN_TX_FIFO_CONFIG *config); - int8_t - mcp2518fd_ReceiveChannelConfigureObjectReset(CAN_RX_FIFO_CONFIG *config); - int8_t mcp2518fd_ReceiveChannelConfigure(CAN_FIFO_CHANNEL channel, - CAN_RX_FIFO_CONFIG *config); - int8_t mcp2518fd_FilterObjectConfigure(CAN_FILTER filter, - CAN_FILTEROBJ_ID *id); - int8_t mcp2518fd_FilterMaskConfigure(CAN_FILTER filter, CAN_MASKOBJ_ID *mask); - int8_t mcp2518fd_FilterToFifoLink(CAN_FILTER filter, CAN_FIFO_CHANNEL channel, - bool enable); - int8_t mcp2518fd_BitTimeConfigure(uint32_t speedset, - CAN_SSP_MODE sspMode, CAN_SYSCLK_SPEED clk); - int8_t mcp2518fd_GpioModeConfigure(GPIO_PIN_MODE gpio0, GPIO_PIN_MODE gpio1); - int8_t mcp2518fd_TransmitChannelEventEnable(CAN_FIFO_CHANNEL channel, - CAN_TX_FIFO_EVENT flags); - int8_t mcp2518fd_ReceiveChannelEventEnable(CAN_FIFO_CHANNEL channel, - CAN_RX_FIFO_EVENT flags); - int8_t mcp2518fd_ModuleEventEnable(CAN_MODULE_EVENT flags); - int8_t mcp2518fd_OperationModeSelect(CAN_OPERATION_MODE opMode); - CAN_OPERATION_MODE mcp2518fd_OperationModeGet(); - void mcp2518fd_TransmitMessageQueue(); - int8_t mcp2518fd_TransmitChannelEventGet(CAN_FIFO_CHANNEL channel, - CAN_TX_FIFO_EVENT *flags); - int8_t mcp2518fd_ErrorCountStateGet(uint8_t *tec, uint8_t *rec, - CAN_ERROR_STATE *flags); - int8_t mcp2518fd_TransmitChannelLoad(CAN_FIFO_CHANNEL channel, - CAN_TX_MSGOBJ *txObj, uint8_t *txd, - uint32_t txdNumBytes, bool flush); - int8_t mcp2518fd_ReceiveChannelEventGet(CAN_FIFO_CHANNEL channel, - CAN_RX_FIFO_EVENT *flags); - int8_t mcp2518fd_ReceiveMessageGet(CAN_FIFO_CHANNEL channel, - CAN_RX_MSGOBJ *rxObj, uint8_t *rxd, - uint8_t nBytes); - int8_t mcp2518fd_ReceiveChannelUpdate(CAN_FIFO_CHANNEL channel); - int8_t mcp2518fd_TransmitChannelUpdate(CAN_FIFO_CHANNEL channel, bool flush); - int8_t mcp2518fd_ReceiveChannelStatusGet(CAN_FIFO_CHANNEL channel, - CAN_RX_FIFO_STATUS *status); - int8_t mcp2518fd_ErrorStateGet(CAN_ERROR_STATE *flags); - int8_t mcp2518fd_ModuleEventRxCodeGet(CAN_RXCODE *rxCode); - int8_t mcp2518fd_ModuleEventTxCodeGet(CAN_TXCODE *txCode); - int8_t mcp2518fd_TransmitChannelEventAttemptClear(CAN_FIFO_CHANNEL channel); - - int8_t mcp2518fd_LowPowerModeEnable(); - int8_t mcp2518fd_LowPowerModeDisable(); - - int8_t mcp2518fd_ReadByte(uint16_t address, uint8_t *rxd); - int8_t mcp2518fd_WriteByte(uint16_t address, uint8_t txd); - int8_t mcp2518fd_ReadWord(uint16_t address, uint32_t *rxd); - int8_t mcp2518fd_WriteWord(uint16_t address, uint32_t txd); - int8_t mcp2518fd_ReadHalfWord(uint16_t address, uint16_t *rxd); - int8_t mcp2518fd_WriteHalfWord(uint16_t address, uint16_t txd); - int8_t mcp2518fd_ReadByteArray(uint16_t address, uint8_t *rxd, - uint16_t nBytes); - int8_t mcp2518fd_WriteByteArray(uint16_t address, uint8_t *txd, - uint16_t nBytes); - int8_t mcp2518fd_WriteByteSafe(uint16_t address, uint8_t txd); - int8_t mcp2518fd_WriteWordSafe(uint16_t address, uint32_t txd); - int8_t mcp2518fd_ReadByteArrayWithCRC(uint16_t address, uint8_t *rxd, - uint16_t nBytes, bool fromRam, - bool *crcIsCorrect); - int8_t mcp2518fd_WriteByteArrayWithCRC(uint16_t address, uint8_t *txd, - uint16_t nBytes, bool fromRam); - int8_t mcp2518fd_ReadWordArray(uint16_t address, uint32_t *rxd, - uint16_t nWords); - int8_t mcp2518fd_WriteWordArray(uint16_t address, uint32_t *txd, - uint16_t nWords); - -private: - int8_t - mcp2518fd_BitTimeConfigureNominal(void); - int8_t mcp2518fd_BitTimeConfigureData(CAN_SSP_MODE sspMode); - - byte nReservedTx; // Count of tx buffers for reserved send - CAN_OPERATION_MODE mcpMode = CAN_CLASSIC_MODE; // Current controller mode - - - uint32_t bittime_compat_to_mcp2518fd(uint32_t speedset); - int calcBittime(const uint32_t inDesiredArbitrationBitRate, - const uint32_t inTolerancePPM = 10000/* 1% */); - - uint32_t mSysClock; // PLL disabled, mSysClock = Oscillator Frequency - uint32_t mDesiredArbitrationBitRate; // desired ArbitrationBitRate - uint8_t mDataBitRateFactor; // multiplier between ArbitrationBitRate and DataBitrate - //--- Data bit rate; if mDataBitRateFactor==1, theses properties are not used for configuring the MCP2517FD. - uint8_t mDataPhaseSegment1 = 0 ; // if mDataBitRateFactor > 1: 2...32, else equal to mArbitrationPhaseSegment1 - uint8_t mDataPhaseSegment2 = 0 ; // if mDataBitRateFactor > 1: 1...16, else equal to mArbitrationPhaseSegment2 - uint8_t mDataSJW = 0 ; // if mDataBitRateFactor > 1: 1...16, else equal to mArbitrationSJW - //--- Bit rate prescaler is common to arbitration and data bit rates - uint16_t mBitRatePrescaler = 0 ; // 1...256 - //--- Arbitration bit rate - uint16_t mArbitrationPhaseSegment1 = 0 ; // 2...256 - uint8_t mArbitrationPhaseSegment2 = 0 ; // 1...128 - uint8_t mArbitrationSJW = 0 ; // 1...128 - bool mArbitrationBitRateClosedToDesiredRate = false ; // The above configuration is not correct - //--- Transmitter Delay Compensation Offset - int8_t mTDCO = 0 ; // -64 ... +63 -}; - -/* CANFD Auxiliary helper */ -class CANFD { -public: - static byte dlc2len(byte dlc); - static byte len2dlc(byte len); - static uint32_t BITRATE(uint32_t arbitration, uint8_t factor) { - return ((uint32_t)factor << 24) | (arbitration & 0xFFFFFUL); - } -}; - -#endif \ No newline at end of file diff --git a/arduino/src/mcp/mcp2518fd_can_dfs.h b/arduino/src/mcp/mcp2518fd_can_dfs.h deleted file mode 100644 index fbdd45a..0000000 --- a/arduino/src/mcp/mcp2518fd_can_dfs.h +++ /dev/null @@ -1,1592 +0,0 @@ -/******************************************************************************* - CAN FD SPI Driver: Register Header File - - Company: - Microchip Technology Inc. - - File Name: - drv_canfdspi_register.h - - Summary: - This header file contains SPI instruction defines, register address defines, - register structures, and reset values of registers. - - Description: - This file is used by the API. - *******************************************************************************/ - -// DOM-IGNORE-BEGIN -/******************************************************************************* -Copyright (c) 2018 Microchip Technology Inc. and its subsidiaries. - -Subject to your compliance with these terms, you may use Microchip software and -any derivatives exclusively with Microchip products. It is your responsibility -to comply with third party license terms applicable to your use of third party -software (including open source software) that may accompany Microchip software. - -THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS". NO WARRANTIES, WHETHER EXPRESS, -IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE, INCLUDING ANY IMPLIED WARRANTIES -OF NON-INFRINGEMENT, MERCHANTABILITY, AND FITNESS FOR A PARTICULAR PURPOSE. - -IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE, -INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND WHATSOEVER -RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS BEEN ADVISED OF -THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE. TO THE FULLEST EXTENT ALLOWED -BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL CLAIMS IN ANY WAY RELATED TO -THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF FEES, IF ANY, THAT YOU HAVE PAID -DIRECTLY TO MICROCHIP FOR THIS SOFTWARE. - *******************************************************************************/ -// DOM-IGNORE-END - -#ifndef _DRV_CANFDSPI_REGISTER_H -#define _DRV_CANFDSPI_REGISTER_H - -// ***************************************************************************** -// ***************************************************************************** -// Section: Included Files - -#include -#include -#include "mcp_can.h" - -// DOM-IGNORE-BEGIN -#ifdef __cplusplus // Provide C++ Compatibility -extern "C" { -#endif -// DOM-IGNORE-END - -// ***************************************************************************** -// ***************************************************************************** -/* SPI Instruction Set */ - -#define cINSTRUCTION_RESET 0x00 -#define cINSTRUCTION_READ 0x03 -#define cINSTRUCTION_READ_CRC 0x0B -#define cINSTRUCTION_WRITE 0x02 -#define cINSTRUCTION_WRITE_CRC 0x0A -#define cINSTRUCTION_WRITE_SAFE 0x0C - -// ***************************************************************************** -// ***************************************************************************** -/* Register Addresses */ - -/* CAN FD Controller */ -#define cREGADDR_CiCON 0x000 -#define cREGADDR_CiNBTCFG 0x004 -#define cREGADDR_CiDBTCFG 0x008 -#define cREGADDR_CiTDC 0x00C - -#define cREGADDR_CiTBC 0x010 -#define cREGADDR_CiTSCON 0x014 -#define cREGADDR_CiVEC 0x018 -#define cREGADDR_CiINT 0x01C -#define cREGADDR_CiINTFLAG cREGADDR_CiINT -#define cREGADDR_CiINTENABLE (cREGADDR_CiINT + 2) - -#define cREGADDR_CiRXIF 0x020 -#define cREGADDR_CiTXIF 0x024 -#define cREGADDR_CiRXOVIF 0x028 -#define cREGADDR_CiTXATIF 0x02C - -#define cREGADDR_CiTXREQ 0x030 -#define cREGADDR_CiTREC 0x034 -#define cREGADDR_CiBDIAG0 0x038 -#define cREGADDR_CiBDIAG1 0x03C - -#define cREGADDR_CiTEFCON 0x040 -#define cREGADDR_CiTEFSTA 0x044 -#define cREGADDR_CiTEFUA 0x048 -#define cREGADDR_CiFIFOBA 0x04C - -#define cREGADDR_CiFIFOCON 0x050 -#define cREGADDR_CiFIFOSTA 0x054 -#define cREGADDR_CiFIFOUA 0x058 -#define CiFIFO_OFFSET (3 * 4) - -#define cREGADDR_CiTXQCON 0x050 -#define cREGADDR_CiTXQSTA 0x054 -#define cREGADDR_CiTXQUA 0x058 - -// The filters start right after the FIFO control/status registers -#define cREGADDR_CiFLTCON \ - (cREGADDR_CiFIFOCON + (CiFIFO_OFFSET * CAN_FIFO_TOTAL_CHANNELS)) -#define cREGADDR_CiFLTOBJ (cREGADDR_CiFLTCON + CAN_FIFO_TOTAL_CHANNELS) -#define cREGADDR_CiMASK (cREGADDR_CiFLTOBJ + 4) - -#define CiFILTER_OFFSET (2 * 4) - -/* MCP25xxFD Specific */ -#define cREGADDR_OSC 0xE00 -#define cREGADDR_IOCON 0xE04 -#define cREGADDR_CRC 0xE08 -#define cREGADDR_ECCCON 0xE0C -#define cREGADDR_ECCSTA 0xE10 -#ifndef MCP2517FD -#define cREGADDR_DEVID 0xE14 -#endif - -/* RAM addresses */ -#define cRAM_SIZE 2048 - -#define cRAMADDR_START 0x400 -#define cRAMADDR_END (cRAMADDR_START + cRAM_SIZE) - -/* SPI Chip Select */ -#define MCP2518fd_SELECT() \ - pinMode(SPICS, OUTPUT); \ - digitalWrite(SPICS, LOW) -#define MCP2518fd_UNSELECT() \ - pinMode(SPICS, OUTPUT); \ - digitalWrite(SPICS, HIGH) - -// ***************************************************************************** -// ***************************************************************************** -/* Register Structures */ - -// DOM-IGNORE-END - -// ***************************************************************************** -// ***************************************************************************** -// Section: Implementation - -// Device selection -//#define MCP2517FD -#define MCP2518FD - -// Maximum Size of TX/RX Object -#define MAX_MSG_SIZE 76 - -// Maximum number of data bytes in message -#define MAX_DATA_BYTES 64 - -// ***************************************************************************** -// ***************************************************************************** -// Section: Object definitions - -//! CAN FIFO Channels - -typedef enum { - CAN_FIFO_CH0, // CAN_TXQUEUE_CH0 - CAN_FIFO_CH1, - CAN_FIFO_CH2, - CAN_FIFO_CH3, - CAN_FIFO_CH4, - CAN_FIFO_CH5, - CAN_FIFO_CH6, - CAN_FIFO_CH7, - CAN_FIFO_CH8, - CAN_FIFO_CH9, - CAN_FIFO_CH10, - CAN_FIFO_CH11, - CAN_FIFO_CH12, - CAN_FIFO_CH13, - CAN_FIFO_CH14, - CAN_FIFO_CH15, - CAN_FIFO_CH16, - CAN_FIFO_CH17, - CAN_FIFO_CH18, - CAN_FIFO_CH19, - CAN_FIFO_CH20, - CAN_FIFO_CH21, - CAN_FIFO_CH22, - CAN_FIFO_CH23, - CAN_FIFO_CH24, - CAN_FIFO_CH25, - CAN_FIFO_CH26, - CAN_FIFO_CH27, - CAN_FIFO_CH28, - CAN_FIFO_CH29, - CAN_FIFO_CH30, - CAN_FIFO_CH31, - CAN_FIFO_TOTAL_CHANNELS -} CAN_FIFO_CHANNEL; - -// FIFO0 is a special FIFO, the TX Queue -#define CAN_TXQUEUE_CH0 CAN_FIFO_CH0 - -//! CAN Filter Channels - -typedef enum { - CAN_FILTER0, - CAN_FILTER1, - CAN_FILTER2, - CAN_FILTER3, - CAN_FILTER4, - CAN_FILTER5, - CAN_FILTER6, - CAN_FILTER7, - CAN_FILTER8, - CAN_FILTER9, - CAN_FILTER10, - CAN_FILTER11, - CAN_FILTER12, - CAN_FILTER13, - CAN_FILTER14, - CAN_FILTER15, - CAN_FILTER16, - CAN_FILTER17, - CAN_FILTER18, - CAN_FILTER19, - CAN_FILTER20, - CAN_FILTER21, - CAN_FILTER22, - CAN_FILTER23, - CAN_FILTER24, - CAN_FILTER25, - CAN_FILTER26, - CAN_FILTER27, - CAN_FILTER28, - CAN_FILTER29, - CAN_FILTER30, - CAN_FILTER31, - CAN_FILTER_TOTAL, -} CAN_FILTER; - -//! CAN Operation Modes - -typedef enum { - CAN_NORMAL_MODE = 0x00, - CAN_SLEEP_MODE = 0x01, - CAN_INTERNAL_LOOPBACK_MODE = 0x02, - CAN_LISTEN_ONLY_MODE = 0x03, - CAN_CONFIGURATION_MODE = 0x04, - CAN_EXTERNAL_LOOPBACK_MODE = 0x05, - CAN_CLASSIC_MODE = 0x06, - CAN_RESTRICTED_MODE = 0x07, - CAN_INVALID_MODE = 0xFF -} CAN_OPERATION_MODE; - -//! Transmit Bandwidth Sharing - -typedef enum { - CAN_TXBWS_NO_DELAY, - CAN_TXBWS_2, - CAN_TXBWS_4, - CAN_TXBWS_8, - CAN_TXBWS_16, - CAN_TXBWS_32, - CAN_TXBWS_64, - CAN_TXBWS_128, - CAN_TXBWS_256, - CAN_TXBWS_512, - CAN_TXBWS_1024, - CAN_TXBWS_2048, - CAN_TXBWS_4096 -} CAN_TX_BANDWITH_SHARING; - -//! Wake-up Filter Time - -typedef enum { - CAN_WFT00, - CAN_WFT01, - CAN_WFT10, - CAN_WFT11 -} CAN_WAKEUP_FILTER_TIME; - -//! Data Byte Filter Number - -typedef enum { - CAN_DNET_FILTER_DISABLE = 0, - CAN_DNET_FILTER_SIZE_1_BIT, - CAN_DNET_FILTER_SIZE_2_BIT, - CAN_DNET_FILTER_SIZE_3_BIT, - CAN_DNET_FILTER_SIZE_4_BIT, - CAN_DNET_FILTER_SIZE_5_BIT, - CAN_DNET_FILTER_SIZE_6_BIT, - CAN_DNET_FILTER_SIZE_7_BIT, - CAN_DNET_FILTER_SIZE_8_BIT, - CAN_DNET_FILTER_SIZE_9_BIT, - CAN_DNET_FILTER_SIZE_10_BIT, - CAN_DNET_FILTER_SIZE_11_BIT, - CAN_DNET_FILTER_SIZE_12_BIT, - CAN_DNET_FILTER_SIZE_13_BIT, - CAN_DNET_FILTER_SIZE_14_BIT, - CAN_DNET_FILTER_SIZE_15_BIT, - CAN_DNET_FILTER_SIZE_16_BIT, - CAN_DNET_FILTER_SIZE_17_BIT, - CAN_DNET_FILTER_SIZE_18_BIT -} CAN_DNET_FILTER_SIZE; - -//! FIFO Payload Size - -typedef enum { - CAN_PLSIZE_8, - CAN_PLSIZE_12, - CAN_PLSIZE_16, - CAN_PLSIZE_20, - CAN_PLSIZE_24, - CAN_PLSIZE_32, - CAN_PLSIZE_48, - CAN_PLSIZE_64 -} CAN_FIFO_PLSIZE; - -//! CAN Configure - -typedef struct _CAN_CONFIG { - uint32_t DNetFilterCount : 5; - uint32_t IsoCrcEnable : 1; - uint32_t ProtocolExpectionEventDisable : 1; - uint32_t WakeUpFilterEnable : 1; - uint32_t WakeUpFilterTime : 2; - uint32_t BitRateSwitchDisable : 1; - uint32_t RestrictReTxAttempts : 1; - uint32_t EsiInGatewayMode : 1; - uint32_t SystemErrorToListenOnly : 1; - uint32_t StoreInTEF : 1; - uint32_t TXQEnable : 1; - uint32_t TxBandWidthSharing : 4; -} CAN_CONFIG; - -//! CAN Transmit Channel Configure - -typedef struct _CAN_TX_FIFO_CONFIG { - uint32_t RTREnable : 1; - uint32_t TxPriority : 5; - uint32_t TxAttempts : 2; - uint32_t FifoSize : 5; - uint32_t PayLoadSize : 3; -} CAN_TX_FIFO_CONFIG; - -//! CAN Transmit Queue Configure - -typedef struct _CAN_TX_QUEUE_CONFIG { - uint32_t TxPriority : 5; - uint32_t TxAttempts : 2; - uint32_t FifoSize : 5; - uint32_t PayLoadSize : 3; -} CAN_TX_QUEUE_CONFIG; - -//! CAN Receive Channel Configure - -typedef struct _CAN_RX_FIFO_CONFIG { - uint32_t RxTimeStampEnable : 1; - uint32_t FifoSize : 5; - uint32_t PayLoadSize : 3; -} CAN_RX_FIFO_CONFIG; - -//! CAN Transmit Event FIFO Configure - -typedef struct _CAN_TEF_CONFIG { - uint32_t TimeStampEnable : 1; - uint32_t FifoSize : 5; -} CAN_TEF_CONFIG; - -/* CAN Message Objects */ - -//! CAN Message Object ID - -typedef struct _CAN_MSGOBJ_ID { - uint32_t SID : 11; - uint32_t EID : 18; - uint32_t SID11 : 1; - uint32_t unimplemented1 : 2; -} CAN_MSGOBJ_ID; - -//! CAN Data Length Code - -typedef enum { - CAN_DLC_0, - CAN_DLC_1, - CAN_DLC_2, - CAN_DLC_3, - CAN_DLC_4, - CAN_DLC_5, - CAN_DLC_6, - CAN_DLC_7, - CAN_DLC_8, - CAN_DLC_12, - CAN_DLC_16, - CAN_DLC_20, - CAN_DLC_24, - CAN_DLC_32, - CAN_DLC_48, - CAN_DLC_64 -} CAN_DLC; - -//! CAN TX Message Object Control - -typedef struct _CAN_TX_MSGOBJ_CTRL { - uint32_t DLC : 4; - uint32_t IDE : 1; - uint32_t RTR : 1; - uint32_t BRS : 1; - uint32_t FDF : 1; - uint32_t ESI : 1; -#ifdef MCP2517FD - uint32_t SEQ : 7; - uint32_t unimplemented1 : 16; -#else - uint32_t SEQ : 23; -#endif -} CAN_TX_MSGOBJ_CTRL; - -//! CAN RX Message Object Control - -typedef struct _CAN_RX_MSGOBJ_CTRL { - uint32_t DLC : 4; - uint32_t IDE : 1; - uint32_t RTR : 1; - uint32_t BRS : 1; - uint32_t FDF : 1; - uint32_t ESI : 1; - uint32_t unimplemented1 : 2; - uint32_t FilterHit : 5; - uint32_t unimplemented2 : 16; -} CAN_RX_MSGOBJ_CTRL; - -//! CAN Message Time Stamp -typedef uint32_t CAN_MSG_TIMESTAMP; - -//! CAN TX Message Object - -typedef union _CAN_TX_MSGOBJ { - - struct { - CAN_MSGOBJ_ID id; - CAN_TX_MSGOBJ_CTRL ctrl; - CAN_MSG_TIMESTAMP timeStamp; - } bF; - uint32_t word[3]; - uint8_t byte[12]; -} CAN_TX_MSGOBJ; - -//! CAN RX Message Object - -typedef union _CAN_RX_MSGOBJ { - - struct { - CAN_MSGOBJ_ID id; - CAN_RX_MSGOBJ_CTRL ctrl; - CAN_MSG_TIMESTAMP timeStamp; - } bF; - uint32_t word[3]; - uint8_t byte[12]; -} CAN_RX_MSGOBJ; - -//! CAN TEF Message Object - -typedef union _CAN_TEF_MSGOBJ { - - struct { - CAN_MSGOBJ_ID id; - CAN_TX_MSGOBJ_CTRL ctrl; - CAN_MSG_TIMESTAMP timeStamp; - } bF; - uint32_t word[3]; - uint8_t byte[12]; -} CAN_TEF_MSGOBJ; - -//! CAN Filter Object ID - -typedef struct _CAN_FILTEROBJ_ID { - uint32_t SID : 11; - uint32_t EID : 18; - uint32_t SID11 : 1; - uint32_t EXIDE : 1; - uint32_t unimplemented1 : 1; -} CAN_FILTEROBJ_ID; - -//! CAN Mask Object ID - -typedef struct _CAN_MASKOBJ_ID { - uint32_t MSID : 11; - uint32_t MEID : 18; - uint32_t MSID11 : 1; - uint32_t MIDE : 1; - uint32_t unimplemented1 : 1; -} CAN_MASKOBJ_ID; - -//! CAN RX FIFO Status - -typedef enum { - CAN_RX_FIFO_EMPTY = 0, - CAN_RX_FIFO_STATUS_MASK = 0x0F, - CAN_RX_FIFO_NOT_EMPTY = 0x01, - CAN_RX_FIFO_HALF_FULL = 0x02, - CAN_RX_FIFO_FULL = 0x04, - CAN_RX_FIFO_OVERFLOW = 0x08 -} CAN_RX_FIFO_STATUS; - -//! CAN TX FIFO Status - -typedef enum { - CAN_TX_FIFO_FULL = 0, - CAN_TX_FIFO_STATUS_MASK = 0x1F7, - CAN_TX_FIFO_NOT_FULL = 0x01, - CAN_TX_FIFO_HALF_FULL = 0x02, - CAN_TX_FIFO_EMPTY = 0x04, - CAN_TX_FIFO_ATTEMPTS_EXHAUSTED = 0x10, - CAN_TX_FIFO_ERROR = 0x20, - CAN_TX_FIFO_ARBITRATION_LOST = 0x40, - CAN_TX_FIFO_ABORTED = 0x80, - CAN_TX_FIFO_TRANSMITTING = 0x100 -} CAN_TX_FIFO_STATUS; - -//! CAN TEF FIFO Status - -typedef enum { - CAN_TEF_FIFO_EMPTY = 0, - CAN_TEF_FIFO_STATUS_MASK = 0x0F, - CAN_TEF_FIFO_NOT_EMPTY = 0x01, - CAN_TEF_FIFO_HALF_FULL = 0x02, - CAN_TEF_FIFO_FULL = 0x04, - CAN_TEF_FIFO_OVERFLOW = 0x08 -} CAN_TEF_FIFO_STATUS; - -//! CAN Module Event (Interrupts) - -typedef enum { - CAN_NO_EVENT = 0, - CAN_ALL_EVENTS = 0xFF1F, - CAN_TX_EVENT = 0x0001, - CAN_RX_EVENT = 0x0002, - CAN_TIME_BASE_COUNTER_EVENT = 0x0004, - CAN_OPERATION_MODE_CHANGE_EVENT = 0x0008, - CAN_TEF_EVENT = 0x0010, - - CAN_RAM_ECC_EVENT = 0x0100, - CAN_SPI_CRC_EVENT = 0x0200, - CAN_TX_ATTEMPTS_EVENT = 0x0400, - CAN_RX_OVERFLOW_EVENT = 0x0800, - CAN_SYSTEM_ERROR_EVENT = 0x1000, - CAN_BUS_ERROR_EVENT = 0x2000, - CAN_BUS_WAKEUP_EVENT = 0x4000, - CAN_RX_INVALID_MESSAGE_EVENT = 0x8000 -} CAN_MODULE_EVENT; - -//! CAN TX FIFO Event (Interrupts) - -typedef enum { - CAN_TX_FIFO_NO_EVENT = 0, - CAN_TX_FIFO_ALL_EVENTS = 0x17, - CAN_TX_FIFO_NOT_FULL_EVENT = 0x01, - CAN_TX_FIFO_HALF_FULL_EVENT = 0x02, - CAN_TX_FIFO_EMPTY_EVENT = 0x04, - CAN_TX_FIFO_ATTEMPTS_EXHAUSTED_EVENT = 0x10 -} CAN_TX_FIFO_EVENT; - -//! CAN RX FIFO Event (Interrupts) - -typedef enum { - CAN_RX_FIFO_NO_EVENT = 0, - CAN_RX_FIFO_ALL_EVENTS = 0x0F, - CAN_RX_FIFO_NOT_EMPTY_EVENT = 0x01, - CAN_RX_FIFO_HALF_FULL_EVENT = 0x02, - CAN_RX_FIFO_FULL_EVENT = 0x04, - CAN_RX_FIFO_OVERFLOW_EVENT = 0x08 -} CAN_RX_FIFO_EVENT; - -//! CAN TEF FIFO Event (Interrupts) - -typedef enum { - CAN_TEF_FIFO_NO_EVENT = 0, - CAN_TEF_FIFO_ALL_EVENTS = 0x0F, - CAN_TEF_FIFO_NOT_EMPTY_EVENT = 0x01, - CAN_TEF_FIFO_HALF_FULL_EVENT = 0x02, - CAN_TEF_FIFO_FULL_EVENT = 0x04, - CAN_TEF_FIFO_OVERFLOW_EVENT = 0x08 -} CAN_TEF_FIFO_EVENT; - -//! CAN Bit Time Setup: Arbitration/Data Bit Phase - -/* not apply to AVR platform */ -// typedef enum { -static const uint32_t CAN_125K_500K = ( 4UL << 24) | (125000UL); -static const uint32_t CAN_250K_500K = ( 2UL << 24) | (250000UL); -static const uint32_t CAN_250K_750K = ( 3UL << 24) | (250000UL); -static const uint32_t CAN_250K_1M = ( 4UL << 24) | (250000UL); -static const uint32_t CAN_250K_1M5 = ( 6UL << 24) | (250000UL); -static const uint32_t CAN_250K_2M = ( 8UL << 24) | (250000UL); -static const uint32_t CAN_250K_3M = (12UL << 24) | (250000UL); -static const uint32_t CAN_250K_4M = (16UL << 24) | (250000UL); -static const uint32_t CAN_500K_1M = ( 2UL << 24) | (500000UL); -static const uint32_t CAN_500K_2M = ( 4UL << 24) | (500000UL); -static const uint32_t CAN_500K_3M = ( 6UL << 24) | (500000UL); -static const uint32_t CAN_500K_4M = ( 8UL << 24) | (500000UL); -static const uint32_t CAN_500K_5M = (10UL << 24) | (500000UL); -static const uint32_t CAN_500K_6M5 = (13UL << 24) | (500000UL); -static const uint32_t CAN_500K_8M = (16UL << 24) | (500000UL); -static const uint32_t CAN_500K_10M = (20UL << 24) | (500000UL); -static const uint32_t CAN_1000K_4M = ( 4UL << 24) |(1000000UL); -static const uint32_t CAN_1000K_8M = ( 8UL << 24) |(1000000UL); -//} MCP2518FD_BITTIME_SETUP; - -//! Secondary Sample Point Mode - -typedef enum { - CAN_SSP_MODE_OFF, - CAN_SSP_MODE_MANUAL, - CAN_SSP_MODE_AUTO -} CAN_SSP_MODE; - -//! CAN Error State - -typedef enum { - CAN_ERROR_FREE_STATE = 0, - CAN_ERROR_ALL = 0x3F, - CAN_TX_RX_WARNING_STATE = 0x01, - CAN_RX_WARNING_STATE = 0x02, - CAN_TX_WARNING_STATE = 0x04, - CAN_RX_BUS_PASSIVE_STATE = 0x08, - CAN_TX_BUS_PASSIVE_STATE = 0x10, - CAN_TX_BUS_OFF_STATE = 0x20 -} CAN_ERROR_STATE; - -//! CAN Time Stamp Mode Select - -typedef enum { - CAN_TS_SOF = 0x00, - CAN_TS_EOF = 0x01, - CAN_TS_RES = 0x02 -} CAN_TS_MODE; - -//! CAN ECC EVENT - -typedef enum { - CAN_ECC_NO_EVENT = 0x00, - CAN_ECC_ALL_EVENTS = 0x06, - CAN_ECC_SEC_EVENT = 0x02, - CAN_ECC_DED_EVENT = 0x04 -} CAN_ECC_EVENT; - -//! CAN CRC EVENT - -typedef enum { - CAN_CRC_NO_EVENT = 0x00, - CAN_CRC_ALL_EVENTS = 0x03, - CAN_CRC_CRCERR_EVENT = 0x01, - CAN_CRC_FORMERR_EVENT = 0x02 -} CAN_CRC_EVENT; - -//! GPIO Pin Position - -typedef enum { GPIO_PIN_0, GPIO_PIN_1 } GPIO_PIN_POS; - -//! GPIO Pin Modes - -typedef enum { GPIO_MODE_INT, GPIO_MODE_GPIO } GPIO_PIN_MODE; - -//! GPIO Pin Directions - -typedef enum { GPIO_OUTPUT, GPIO_INPUT } GPIO_PIN_DIRECTION; - -//! GPIO Open Drain Mode - -typedef enum { GPIO_PUSH_PULL, GPIO_OPEN_DRAIN } GPIO_OPEN_DRAIN_MODE; - -//! GPIO Pin State - -typedef enum { GPIO_LOW, GPIO_HIGH } GPIO_PIN_STATE; - -//! Clock Output Mode - -typedef enum { GPIO_CLKO_CLOCK, GPIO_CLKO_SOF } GPIO_CLKO_MODE; - -//! CAN Bus Diagnostic flags - -typedef struct _CAN_BUS_DIAG_FLAGS { - uint32_t NBIT0_ERR : 1; - uint32_t NBIT1_ERR : 1; - uint32_t NACK_ERR : 1; - uint32_t NFORM_ERR : 1; - uint32_t NSTUFF_ERR : 1; - uint32_t NCRC_ERR : 1; - uint32_t unimplemented1 : 1; - uint32_t TXBO_ERR : 1; - uint32_t DBIT0_ERR : 1; - uint32_t DBIT1_ERR : 1; - uint32_t unimplemented2 : 1; - uint32_t DFORM_ERR : 1; - uint32_t DSTUFF_ERR : 1; - uint32_t DCRC_ERR : 1; - uint32_t ESI : 1; - uint32_t DLC_MISMATCH : 1; -} CAN_BUS_DIAG_FLAGS; - -//! CAN Bus Diagnostic Error Counts - -typedef struct _CAN_BUS_ERROR_COUNT { - uint8_t NREC; - uint8_t NTEC; - uint8_t DREC; - uint8_t DTEC; -} CAN_BUS_ERROR_COUNT; - -//! CAN BUS DIAGNOSTICS - -typedef union _CAN_BUS_DIAGNOSTIC { - - struct { - CAN_BUS_ERROR_COUNT errorCount; - uint16_t errorFreeMsgCount; - CAN_BUS_DIAG_FLAGS flag; - } bF; - uint32_t word[3]; - uint8_t byte[12]; -} CAN_BUS_DIAGNOSTIC; - -//! TXREQ Channel Bits -// Multiple channels can be or'ed together - -typedef enum { - CAN_TXREQ_CH0 = 0x00000001, - CAN_TXREQ_CH1 = 0x00000002, - CAN_TXREQ_CH2 = 0x00000004, - CAN_TXREQ_CH3 = 0x00000008, - CAN_TXREQ_CH4 = 0x00000010, - CAN_TXREQ_CH5 = 0x00000020, - CAN_TXREQ_CH6 = 0x00000040, - CAN_TXREQ_CH7 = 0x00000080, - - CAN_TXREQ_CH8 = 0x00000100, - CAN_TXREQ_CH9 = 0x00000200, - CAN_TXREQ_CH10 = 0x00000400, - CAN_TXREQ_CH11 = 0x00000800, - CAN_TXREQ_CH12 = 0x00001000, - CAN_TXREQ_CH13 = 0x00002000, - CAN_TXREQ_CH14 = 0x00004000, - CAN_TXREQ_CH15 = 0x00008000, - - CAN_TXREQ_CH16 = 0x00010000, - CAN_TXREQ_CH17 = 0x00020000, - CAN_TXREQ_CH18 = 0x00040000, - CAN_TXREQ_CH19 = 0x00080000, - CAN_TXREQ_CH20 = 0x00100000, - CAN_TXREQ_CH21 = 0x00200000, - CAN_TXREQ_CH22 = 0x00400000, - CAN_TXREQ_CH23 = 0x00800000, - - CAN_TXREQ_CH24 = 0x01000000, - CAN_TXREQ_CH25 = 0x02000000, - CAN_TXREQ_CH26 = 0x04000000, - CAN_TXREQ_CH27 = 0x08000000, - CAN_TXREQ_CH28 = 0x10000000, - CAN_TXREQ_CH29 = 0x20000000, - CAN_TXREQ_CH30 = 0x40000000, - CAN_TXREQ_CH31 = 0x80000000 -} CAN_TXREQ_CHANNEL; - -//! Oscillator Control - -typedef struct _CAN_OSC_CTRL { - uint32_t PllEnable : 1; - uint32_t OscDisable : 1; - uint32_t SclkDivide : 1; - uint32_t ClkOutDivide : 2; -#ifndef MCP2517FD - uint32_t LowPowerModeEnable : 1; -#endif -} CAN_OSC_CTRL; - -//! Oscillator Status - -typedef struct _CAN_OSC_STATUS { - uint32_t PllReady : 1; - uint32_t OscReady : 1; - uint32_t SclkReady : 1; -} CAN_OSC_STATUS; - -//! ICODE - -typedef enum { - CAN_ICODE_FIFO_CH0, - CAN_ICODE_FIFO_CH1, - CAN_ICODE_FIFO_CH2, - CAN_ICODE_FIFO_CH3, - CAN_ICODE_FIFO_CH4, - CAN_ICODE_FIFO_CH5, - CAN_ICODE_FIFO_CH6, - CAN_ICODE_FIFO_CH7, - CAN_ICODE_FIFO_CH8, - CAN_ICODE_FIFO_CH9, - CAN_ICODE_FIFO_CH10, - CAN_ICODE_FIFO_CH11, - CAN_ICODE_FIFO_CH12, - CAN_ICODE_FIFO_CH13, - CAN_ICODE_FIFO_CH14, - CAN_ICODE_FIFO_CH15, - CAN_ICODE_FIFO_CH16, - CAN_ICODE_FIFO_CH17, - CAN_ICODE_FIFO_CH18, - CAN_ICODE_FIFO_CH19, - CAN_ICODE_FIFO_CH20, - CAN_ICODE_FIFO_CH21, - CAN_ICODE_FIFO_CH22, - CAN_ICODE_FIFO_CH23, - CAN_ICODE_FIFO_CH24, - CAN_ICODE_FIFO_CH25, - CAN_ICODE_FIFO_CH26, - CAN_ICODE_FIFO_CH27, - CAN_ICODE_FIFO_CH28, - CAN_ICODE_FIFO_CH29, - CAN_ICODE_FIFO_CH30, - CAN_ICODE_FIFO_CH31, - CAN_ICODE_TOTAL_CHANNELS, - CAN_ICODE_NO_INT = 0x40, - CAN_ICODE_CERRIF, - CAN_ICODE_WAKIF, - CAN_ICODE_RXOVIF, - CAN_ICODE_ADDRERR_SERRIF, - CAN_ICODE_MABOV_SERRIF, - CAN_ICODE_TBCIF, - CAN_ICODE_MODIF, - CAN_ICODE_IVMIF, - CAN_ICODE_TEFIF, - CAN_ICODE_TXATIF, - CAN_ICODE_RESERVED -} CAN_ICODE; - -//! RXCODE - -typedef enum { - CAN_RXCODE_FIFO_CH1 = 1, - CAN_RXCODE_FIFO_CH2, - CAN_RXCODE_FIFO_CH3, - CAN_RXCODE_FIFO_CH4, - CAN_RXCODE_FIFO_CH5, - CAN_RXCODE_FIFO_CH6, - CAN_RXCODE_FIFO_CH7, - CAN_RXCODE_FIFO_CH8, - CAN_RXCODE_FIFO_CH9, - CAN_RXCODE_FIFO_CH10, - CAN_RXCODE_FIFO_CH11, - CAN_RXCODE_FIFO_CH12, - CAN_RXCODE_FIFO_CH13, - CAN_RXCODE_FIFO_CH14, - CAN_RXCODE_FIFO_CH15, - CAN_RXCODE_FIFO_CH16, - CAN_RXCODE_FIFO_CH17, - CAN_RXCODE_FIFO_CH18, - CAN_RXCODE_FIFO_CH19, - CAN_RXCODE_FIFO_CH20, - CAN_RXCODE_FIFO_CH21, - CAN_RXCODE_FIFO_CH22, - CAN_RXCODE_FIFO_CH23, - CAN_RXCODE_FIFO_CH24, - CAN_RXCODE_FIFO_CH25, - CAN_RXCODE_FIFO_CH26, - CAN_RXCODE_FIFO_CH27, - CAN_RXCODE_FIFO_CH28, - CAN_RXCODE_FIFO_CH29, - CAN_RXCODE_FIFO_CH30, - CAN_RXCODE_FIFO_CH31, - CAN_RXCODE_TOTAL_CHANNELS, - CAN_RXCODE_NO_INT = 0x40, - CAN_RXCODE_RESERVED -} CAN_RXCODE; - -//! TXCODE - -typedef enum { - CAN_TXCODE_FIFO_CH0, - CAN_TXCODE_FIFO_CH1, - CAN_TXCODE_FIFO_CH2, - CAN_TXCODE_FIFO_CH3, - CAN_TXCODE_FIFO_CH4, - CAN_TXCODE_FIFO_CH5, - CAN_TXCODE_FIFO_CH6, - CAN_TXCODE_FIFO_CH7, - CAN_TXCODE_FIFO_CH8, - CAN_TXCODE_FIFO_CH9, - CAN_TXCODE_FIFO_CH10, - CAN_TXCODE_FIFO_CH11, - CAN_TXCODE_FIFO_CH12, - CAN_TXCODE_FIFO_CH13, - CAN_TXCODE_FIFO_CH14, - CAN_TXCODE_FIFO_CH15, - CAN_TXCODE_FIFO_CH16, - CAN_TXCODE_FIFO_CH17, - CAN_TXCODE_FIFO_CH18, - CAN_TXCODE_FIFO_CH19, - CAN_TXCODE_FIFO_CH20, - CAN_TXCODE_FIFO_CH21, - CAN_TXCODE_FIFO_CH22, - CAN_TXCODE_FIFO_CH23, - CAN_TXCODE_FIFO_CH24, - CAN_TXCODE_FIFO_CH25, - CAN_TXCODE_FIFO_CH26, - CAN_TXCODE_FIFO_CH27, - CAN_TXCODE_FIFO_CH28, - CAN_TXCODE_FIFO_CH29, - CAN_TXCODE_FIFO_CH30, - CAN_TXCODE_FIFO_CH31, - CAN_TXCODE_TOTAL_CHANNELS, - CAN_TXCODE_NO_INT = 0x40, - CAN_TXCODE_RESERVED -} CAN_TXCODE; - -//! System Clock Selection - -typedef enum { - CAN_SYSCLK_40M = MCP2518FD_40MHz, - CAN_SYSCLK_20M = MCP2518FD_20MHz, - CAN_SYSCLK_10M = MCP2518FD_10MHz, -} CAN_SYSCLK_SPEED; - -//! CLKO Divide - -typedef enum { - OSC_CLKO_DIV1, - OSC_CLKO_DIV2, - OSC_CLKO_DIV4, - OSC_CLKO_DIV10 -} OSC_CLKO_DIVIDE; - -// ***************************************************************************** -//! General 32-bit Register - -typedef union _REG_t { - uint8_t byte[4]; - uint32_t word; -} REG_t; - -// ***************************************************************************** -// ***************************************************************************** -/* CAN FD Controller */ - -// ***************************************************************************** -//! CAN Control Register - -typedef union _REG_CiCON { - - struct { - uint32_t DNetFilterCount : 5; - uint32_t IsoCrcEnable : 1; - uint32_t ProtocolExceptionEventDisable : 1; - uint32_t unimplemented1 : 1; - uint32_t WakeUpFilterEnable : 1; - uint32_t WakeUpFilterTime : 2; - uint32_t unimplemented2 : 1; - uint32_t BitRateSwitchDisable : 1; - uint32_t unimplemented3 : 3; - uint32_t RestrictReTxAttempts : 1; - uint32_t EsiInGatewayMode : 1; - uint32_t SystemErrorToListenOnly : 1; - uint32_t StoreInTEF : 1; - uint32_t TXQEnable : 1; - uint32_t OpMode : 3; - uint32_t RequestOpMode : 3; - uint32_t AbortAllTx : 1; - uint32_t TxBandWidthSharing : 4; - } bF; - uint32_t word; - uint8_t byte[4]; -} REG_CiCON; - -// ***************************************************************************** -//! Nominal Bit Time Configuration Register - -typedef union _REG_CiNBTCFG { - - struct { - uint32_t SJW : 7; - uint32_t unimplemented1 : 1; - uint32_t TSEG2 : 7; - uint32_t unimplemented2 : 1; - uint32_t TSEG1 : 8; - uint32_t BRP : 8; - } bF; - uint32_t word; - uint8_t byte[4]; -} REG_CiNBTCFG; - -// ***************************************************************************** -//! Data Bit Time Configuration Register - -typedef union _REG_CiDBTCFG { - - struct { - uint32_t SJW : 4; - uint32_t unimplemented1 : 4; - uint32_t TSEG2 : 4; - uint32_t unimplemented2 : 4; - uint32_t TSEG1 : 5; - uint32_t unimplemented3 : 3; - uint32_t BRP : 8; - } bF; - uint32_t word; - uint8_t byte[4]; -} REG_CiDBTCFG; - -// ***************************************************************************** -//! Transmitter Delay Compensation Register - -typedef union _REG_CiTDC { - - struct { - uint32_t TDCValue : 6; - uint32_t unimplemented1 : 2; - uint32_t TDCOffset : 7; - uint32_t unimplemented2 : 1; - uint32_t TDCMode : 2; - uint32_t unimplemented3 : 6; - uint32_t SID11Enable : 1; - uint32_t EdgeFilterEnable : 1; - uint32_t unimplemented4 : 6; - } bF; - uint32_t word; - uint8_t byte[4]; -} REG_CiTDC; - -// ***************************************************************************** -//! Time Stamp Configuration Register - -typedef union _REG_CiTSCON { - - struct { - uint32_t TBCPrescaler : 10; - uint32_t unimplemented1 : 6; - uint32_t TBCEnable : 1; - uint32_t TimeStampEOF : 1; - uint32_t unimplemented2 : 14; - } bF; - uint32_t word; - uint8_t byte[4]; -} REG_CiTSCON; - -// ***************************************************************************** -//! Interrupt Vector Register - -typedef union _REG_CiVEC { - - struct { - uint32_t ICODE : 7; - uint32_t unimplemented1 : 1; - uint32_t FilterHit : 5; - uint32_t unimplemented2 : 3; - uint32_t TXCODE : 7; - uint32_t unimplemented3 : 1; - uint32_t RXCODE : 7; - uint32_t unimplemented4 : 1; - } bF; - uint32_t word; - uint8_t byte[4]; -} REG_CiVEC; - -// ***************************************************************************** -//! Interrupt Flags - -typedef struct _CAN_INT_FLAGS { - uint32_t TXIF : 1; - uint32_t RXIF : 1; - uint32_t TBCIF : 1; - uint32_t MODIF : 1; - uint32_t TEFIF : 1; - uint32_t unimplemented1 : 3; - - uint32_t ECCIF : 1; - uint32_t SPICRCIF : 1; - uint32_t TXATIF : 1; - uint32_t RXOVIF : 1; - uint32_t SERRIF : 1; - uint32_t CERRIF : 1; - uint32_t WAKIF : 1; - uint32_t IVMIF : 1; -} CAN_INT_FLAGS; - -// ***************************************************************************** -//! Interrupt Enables - -typedef struct _CAN_INT_ENABLES { - uint32_t TXIE : 1; - uint32_t RXIE : 1; - uint32_t TBCIE : 1; - uint32_t MODIE : 1; - uint32_t TEFIE : 1; - uint32_t unimplemented2 : 3; - - uint32_t ECCIE : 1; - uint32_t SPICRCIE : 1; - uint32_t TXATIE : 1; - uint32_t RXOVIE : 1; - uint32_t SERRIE : 1; - uint32_t CERRIE : 1; - uint32_t WAKIE : 1; - uint32_t IVMIE : 1; -} CAN_INT_ENABLES; - -// ***************************************************************************** -//! Interrupt Register - -typedef union _REG_CiINT { - - struct { - CAN_INT_FLAGS IF; - CAN_INT_ENABLES IE; - } bF; - uint32_t word; - uint8_t byte[4]; -} REG_CiINT; - -// ***************************************************************************** -//! Interrupt Flag Register - -typedef union _REG_CiINTFLAG { - CAN_INT_FLAGS IF; - uint16_t word; - uint8_t byte[2]; -} REG_CiINTFLAG; - -// ***************************************************************************** -//! Interrupt Enable Register - -typedef union _REG_CiINTENABLE { - CAN_INT_ENABLES IE; - uint16_t word; - uint8_t byte[2]; -} REG_CiINTENABLE; - -// ***************************************************************************** -//! Transmit/Receive Error Count Register - -typedef union _REG_CiTREC { - - struct { - uint32_t RxErrorCount : 8; - uint32_t TxErrorCount : 8; - uint32_t ErrorStateWarning : 1; - uint32_t RxErrorStateWarning : 1; - uint32_t TxErrorStateWarning : 1; - uint32_t RxErrorStatePassive : 1; - uint32_t TxErrorStatePassive : 1; - uint32_t TxErrorStateBusOff : 1; - uint32_t unimplemented1 : 10; - } bF; - uint32_t word; - uint8_t byte[4]; -} REG_CiTREC; - -// ***************************************************************************** -//! Diagnostic Register 0 - -typedef union _REG_CiBDIAG0 { - - struct { - uint32_t NRxErrorCount : 8; - uint32_t NTxErrorCount : 8; - uint32_t DRxErrorCount : 8; - uint32_t DTxErrorCount : 8; - } bF; - uint32_t word; - uint8_t byte[4]; -} REG_CiBDIAG0; - -// ***************************************************************************** -//! Diagnostic Register 1 - -typedef union _REG_CiBDIAG1 { - - struct { - uint32_t ErrorFreeMsgCount : 16; - - uint32_t NBit0Error : 1; - uint32_t NBit1Error : 1; - uint32_t NAckError : 1; - uint32_t NFormError : 1; - uint32_t NStuffError : 1; - uint32_t NCRCError : 1; - uint32_t unimplemented1 : 1; - uint32_t TXBOError : 1; - uint32_t DBit0Error : 1; - uint32_t DBit1Error : 1; - uint32_t DAckError : 1; - uint32_t DFormError : 1; - uint32_t DStuffError : 1; - uint32_t DCRCError : 1; - uint32_t ESI : 1; - uint32_t unimplemented2 : 1; - } bF; - uint32_t word; - uint8_t byte[4]; -} REG_CiBDIAG1; - -// ***************************************************************************** -//! Transmit Event FIFO Control Register - -typedef union _REG_CiTEFCON { - - struct { - uint32_t TEFNEIE : 1; - uint32_t TEFHFIE : 1; - uint32_t TEFFULIE : 1; - uint32_t TEFOVIE : 1; - uint32_t unimplemented1 : 1; - uint32_t TimeStampEnable : 1; - uint32_t unimplemented2 : 2; - uint32_t UINC : 1; - uint32_t unimplemented3 : 1; - uint32_t FRESET : 1; - uint32_t unimplemented4 : 13; - uint32_t FifoSize : 5; - uint32_t unimplemented5 : 3; - } bF; - uint32_t word; - uint8_t byte[4]; -} REG_CiTEFCON; - -// ***************************************************************************** -//! Transmit Event FIFO Status Register - -typedef union _REG_CiTEFSTA { - - struct { - uint32_t TEFNotEmptyIF : 1; - uint32_t TEFHalfFullIF : 1; - uint32_t TEFFullIF : 1; - uint32_t TEFOVIF : 1; - uint32_t unimplemented1 : 28; - } bF; - uint32_t word; - uint8_t byte[4]; -} REG_CiTEFSTA; - -// ***************************************************************************** -//! Transmit Queue Control Register - -typedef union _REG_CiTXQCON { - - struct { - uint32_t TxNotFullIE : 1; - uint32_t unimplemented1 : 1; - uint32_t TxEmptyIE : 1; - uint32_t unimplemented2 : 1; - uint32_t TxAttemptIE : 1; - uint32_t unimplemented3 : 2; - uint32_t TxEnable : 1; - uint32_t UINC : 1; - uint32_t TxRequest : 1; - uint32_t FRESET : 1; - uint32_t unimplemented4 : 5; - uint32_t TxPriority : 5; - uint32_t TxAttempts : 2; - uint32_t unimplemented5 : 1; - uint32_t FifoSize : 5; - uint32_t PayLoadSize : 3; - } txBF; - uint32_t word; - uint8_t byte[4]; -} REG_CiTXQCON; - -// ***************************************************************************** -//! Transmit Queue Status Register - -typedef union _REG_CiTXQSTA { - - struct { - uint32_t TxNotFullIF : 1; - uint32_t unimplemented1 : 1; - uint32_t TxEmptyIF : 1; - uint32_t unimplemented2 : 1; - uint32_t TxAttemptIF : 1; - uint32_t TxError : 1; - uint32_t TxLostArbitration : 1; - uint32_t TxAborted : 1; - uint32_t FifoIndex : 5; - uint32_t unimplemented3 : 19; - } txBF; - uint32_t word; - uint8_t byte[4]; -} REG_CiTXQSTA; - -// ***************************************************************************** -//! FIFO Control Register - -typedef union _REG_CiFIFOCON { - // Receive FIFO - - struct { - uint32_t RxNotEmptyIE : 1; - uint32_t RxHalfFullIE : 1; - uint32_t RxFullIE : 1; - uint32_t RxOverFlowIE : 1; - uint32_t unimplemented1 : 1; - uint32_t RxTimeStampEnable : 1; - uint32_t unimplemented2 : 1; - uint32_t TxEnable : 1; - uint32_t UINC : 1; - uint32_t unimplemented3 : 1; - uint32_t FRESET : 1; - uint32_t unimplemented4 : 13; - uint32_t FifoSize : 5; - uint32_t PayLoadSize : 3; - } rxBF; - - // Transmit FIFO - - struct { - uint32_t TxNotFullIE : 1; - uint32_t TxHalfFullIE : 1; - uint32_t TxEmptyIE : 1; - uint32_t unimplemented1 : 1; - uint32_t TxAttemptIE : 1; - uint32_t unimplemented2 : 1; - uint32_t RTREnable : 1; - uint32_t TxEnable : 1; - uint32_t UINC : 1; - uint32_t TxRequest : 1; - uint32_t FRESET : 1; - uint32_t unimplemented3 : 5; - uint32_t TxPriority : 5; - uint32_t TxAttempts : 2; - uint32_t unimplemented4 : 1; - uint32_t FifoSize : 5; - uint32_t PayLoadSize : 3; - } txBF; - uint32_t word; - uint8_t byte[4]; -} REG_CiFIFOCON; - -// ***************************************************************************** -//! FIFO Status Register - -typedef union _REG_CiFIFOSTA { - // Receive FIFO - - struct { - uint32_t RxNotEmptyIF : 1; - uint32_t RxHalfFullIF : 1; - uint32_t RxFullIF : 1; - uint32_t RxOverFlowIF : 1; - uint32_t unimplemented1 : 4; - uint32_t FifoIndex : 5; - uint32_t unimplemented2 : 19; - } rxBF; - - // Transmit FIFO - - struct { - uint32_t TxNotFullIF : 1; - uint32_t TxHalfFullIF : 1; - uint32_t TxEmptyIF : 1; - uint32_t unimplemented1 : 1; - uint32_t TxAttemptIF : 1; - uint32_t TxError : 1; - uint32_t TxLostArbitration : 1; - uint32_t TxAborted : 1; - uint32_t FifoIndex : 5; - uint32_t unimplemented2 : 19; - } txBF; - uint32_t word; - uint8_t byte[4]; -} REG_CiFIFOSTA; - -// ***************************************************************************** -//! FIFO User Address Register - -typedef union _REG_CiFIFOUA { - - struct { - uint32_t UserAddress : 12; - uint32_t unimplemented1 : 20; - } bF; - uint32_t word; - uint8_t byte[4]; -} REG_CiFIFOUA; - -// ***************************************************************************** -//! Filter Control Register - -typedef union _REG_CiFLTCON_BYTE { - - struct { - uint32_t BufferPointer : 5; - uint32_t unimplemented1 : 2; - uint32_t Enable : 1; - } bF; - uint8_t byte; -} REG_CiFLTCON_BYTE; - -// ***************************************************************************** -//! Filter Object Register - -typedef union _REG_CiFLTOBJ { - CAN_FILTEROBJ_ID bF; - uint32_t word; - uint8_t byte[4]; -} REG_CiFLTOBJ; - -// ***************************************************************************** -//! Mask Object Register - -typedef union _REG_CiMASK { - CAN_MASKOBJ_ID bF; - uint32_t word; - uint8_t byte[4]; -} REG_CiMASK; - -// ***************************************************************************** -// ***************************************************************************** -/* MCP25xxFD Specific */ - -// ***************************************************************************** -//! Oscillator Control Register - -typedef union _REG_OSC { - - struct { - uint32_t PllEnable : 1; - uint32_t unimplemented1 : 1; - uint32_t OscDisable : 1; -#ifdef MCP2517FD - uint32_t unimplemented2 : 1; -#else - uint32_t LowPowerModeEnable : 1; -#endif - uint32_t SCLKDIV : 1; - uint32_t CLKODIV : 2; - uint32_t unimplemented3 : 1; - uint32_t PllReady : 1; - uint32_t unimplemented4 : 1; - uint32_t OscReady : 1; - uint32_t unimplemented5 : 1; - uint32_t SclkReady : 1; - uint32_t unimplemented6 : 19; - } bF; - uint32_t word; - uint8_t byte[4]; -} REG_OSC; - -// ***************************************************************************** -//! I/O Control Register - -typedef union _REG_IOCON { - - struct { - uint32_t TRIS0 : 1; - uint32_t TRIS1 : 1; - uint32_t unimplemented1 : 2; - uint32_t ClearAutoSleepOnMatch : 1; - uint32_t AutoSleepEnable : 1; - uint32_t XcrSTBYEnable : 1; - uint32_t unimplemented2 : 1; - uint32_t LAT0 : 1; - uint32_t LAT1 : 1; - uint32_t unimplemented3 : 5; - uint32_t HVDETSEL : 1; - uint32_t GPIO0 : 1; - uint32_t GPIO1 : 1; - uint32_t unimplemented4 : 6; - uint32_t PinMode0 : 1; - uint32_t PinMode1 : 1; - uint32_t unimplemented5 : 2; - uint32_t TXCANOpenDrain : 1; - uint32_t SOFOutputEnable : 1; - uint32_t INTPinOpenDrain : 1; - uint32_t unimplemented6 : 1; - } bF; - uint32_t word; - uint8_t byte[4]; -} REG_IOCON; - -// ***************************************************************************** -//! CRC Regsiter - -typedef union _REG_CRC { - - struct { - uint32_t CRC : 16; - uint32_t CRCERRIF : 1; - uint32_t FERRIF : 1; - uint32_t unimplemented1 : 6; - uint32_t CRCERRIE : 1; - uint32_t FERRIE : 1; - uint32_t unimplemented2 : 6; - } bF; - uint32_t word; - uint8_t byte[4]; -} REG_CRC; - -// ***************************************************************************** -//! ECC Control Register - -typedef union _REG_ECCCON { - - struct { - uint32_t EccEn : 1; - uint32_t SECIE : 1; - uint32_t DEDIE : 1; - uint32_t unimplemented1 : 5; - uint32_t Parity : 7; - uint32_t unimplemented2 : 17; - } bF; - uint32_t word; - uint8_t byte[4]; -} REG_ECCCON; - -// ***************************************************************************** -//! ECC Status Register - -typedef union _REG_ECCSTA { - - struct { - uint32_t unimplemented1 : 1; - uint32_t SECIF : 1; - uint32_t DEDIF : 1; - uint32_t unimplemented2 : 13; - uint32_t ErrorAddress : 12; - uint32_t unimplemented3 : 4; - } bF; - uint32_t word; - uint8_t byte[4]; -} REG_ECCSTA; - -// ***************************************************************************** -//! DEVID Register - -#ifndef MCP2517FD -typedef union _REG_DEVID { - - struct { - uint32_t REV : 4; - uint32_t DEV : 4; - uint32_t unimplemented : 24; - } bF; - uint32_t word; - uint8_t byte[4]; -} REG_DEVID; -#endif - -// ***************************************************************************** -// ***************************************************************************** -/* Register Reset Values */ - -// ***************************************************************************** -/* CAN FD Controller */ - -// Control Register Reset Values up to FIFOs -static const uint32_t canControlResetValues[] = { - /* Address 0x000 to 0x00C */ - 0x04980760, 0x003E0F0F, 0x000E0303, 0x00021000, - /* Address 0x010 to 0x01C */ - 0x00000000, 0x00000000, 0x40400040, 0x00000000, - /* Address 0x020 to 0x02C */ - 0x00000000, 0x00000000, 0x00000000, 0x00000000, - /* Address 0x030 to 0x03C */ - 0x00000000, 0x00200000, 0x00000000, 0x00000000, - /* Address 0x040 to 0x04C */ - 0x00000400, 0x00000000, 0x00000000, 0x00000000}; - -// FIFO Register Reset Values -static const uint32_t canFifoResetValues[] = {0x00600400, 0x00000000, - 0x00000000}; - -// Filter Control Register Reset Values -static const uint32_t canFilterControlResetValue = 0x00000000; - -// Filter and Mask Object Reset Values -static const uint32_t canFilterObjectResetValues[] = {0x00000000, 0x00000000}; - -// ***************************************************************************** -/* MCP25xxFD */ - -#if defined(MCP2517FD) || defined(MCP2518FD) -static const uint32_t mcp25xxfdControlResetValues[] = { - 0x00000460, 0x00000003, 0x00000000, 0x00000000, 0x00000000}; -#endif - - - -#ifdef __cplusplus // Provide C++ Compatibility -} -#endif -#endif // _DRV_CANFDSPI_REGISTER_H diff --git a/arduino/src/mcp/mcp_can.cpp b/arduino/src/mcp/mcp_can.cpp deleted file mode 100644 index ef5e176..0000000 --- a/arduino/src/mcp/mcp_can.cpp +++ /dev/null @@ -1,31 +0,0 @@ -#include "mcp_can.h" - -/********************************************************************************************************* -** Function name: MCP_CAN -** Descriptions: Constructor -*********************************************************************************************************/ -MCP_CAN::MCP_CAN(byte _CS) -{ - pSPI = &SPI; - init_CS(_CS); -} - -/********************************************************************************************************* -** Function name: init_CS -** Descriptions: init CS pin and set UNSELECTED -*********************************************************************************************************/ -void MCP_CAN::init_CS(byte _CS) -{ - if (_CS == 0) - { - return; - } - SPICS = _CS; - pinMode(SPICS, OUTPUT); - digitalWrite(SPICS, HIGH); -} - -void MCP_CAN::setSPI(SPIClass *_pSPI) -{ - pSPI = _pSPI; // define SPI port to use before begin() -} diff --git a/arduino/src/mcp/mcp_can.h b/arduino/src/mcp/mcp_can.h deleted file mode 100644 index 33fc7d5..0000000 --- a/arduino/src/mcp/mcp_can.h +++ /dev/null @@ -1,120 +0,0 @@ -#ifndef _MCP_CAN_H_ -#define _MCP_CAN_H_ - -#include -#include -#include - -#define CAN_OK (0) -#define CAN_FAILINIT (1) -#define CAN_FAILTX (2) -#define CAN_MSGAVAIL (3) -#define CAN_NOMSG (4) -#define CAN_CTRLERROR (5) -#define CAN_GETTXBFTIMEOUT (6) -#define CAN_SENDMSGTIMEOUT (7) -#define CAN_FAIL (0xff) - -// clock -typedef enum { - MCP_NO_MHz, - /* apply to MCP2515 */ - MCP_16MHz, - MCP_8MHz, - /* apply to MCP2518FD */ - MCP2518FD_40MHz = MCP_16MHz /* To compatible MCP2515 shield */, - MCP2518FD_20MHz, - MCP2518FD_10MHz, -} MCP_CLOCK_T; - -typedef enum { - CAN_NOBPS, - CAN_5KBPS, - CAN_10KBPS, - CAN_20KBPS, - CAN_25KBPS, - CAN_31K25BPS, - CAN_33KBPS , - CAN_40KBPS , - CAN_50KBPS , - CAN_80KBPS , - CAN_83K3BPS , - CAN_95KBPS , - CAN_100KBPS , - CAN_125KBPS , - CAN_200KBPS , - CAN_250KBPS , - CAN_500KBPS , - CAN_666KBPS , - CAN_800KBPS , - CAN_1000KBPS -} MCP_BITTIME_SETUP; - - -class MCP_CAN -{ -public: - virtual void enableTxInterrupt(bool enable = true) = 0; // enable transmit interrupt - virtual void reserveTxBuffers(byte nTxBuf = 0) = 0; - virtual byte getLastTxBuffer() = 0; - /* - * speedset be in MCP_BITTIME_SETUP - * clockset be in MCP_CLOCK_T - */ - virtual byte begin(uint32_t speedset, const byte clockset) = 0; // init can - virtual byte init_Mask(byte num, byte ext, unsigned long ulData) = 0; // init Masks - virtual byte init_Filt(byte num, byte ext, unsigned long ulData) = 0; // init filters - virtual void setSleepWakeup(byte enable) = 0; // Enable or disable the wake up interrupt - // (If disabled the MCP2515 will not be woken up by CAN bus activity, making it send only) - virtual byte sleep() = 0; // Put the MCP2515 in sleep mode - virtual byte wake() = 0; // Wake MCP2515 manually from sleep - virtual byte setMode(byte opMode) = 0; // Set operational mode - virtual byte getMode() = 0; // Get operational mode - virtual byte checkError(uint8_t* err_ptr = NULL) = 0; // if something error - - /* ---- receiving ---- */ - virtual byte checkReceive(void) = 0; // if something received - virtual byte readMsgBufID(byte status, - volatile unsigned long *id, volatile byte *ext, volatile byte *rtr, - volatile byte *len, volatile byte *buf) = 0; // read buf with object ID - /* wrapper */ - virtual byte readMsgBufID(unsigned long *ID, byte *len, byte *buf) = 0; - virtual byte readMsgBuf(byte *len, byte *buf) = 0; - - /* could be called after a successful readMsgBufID() */ - unsigned long getCanId(void) { return can_id; } - byte isRemoteRequest(void) { return rtr; } - byte isExtendedFrame(void) { return ext_flg;} - - /* ---- sending ---- */ - virtual byte trySendMsgBuf(unsigned long id, byte ext, byte rtr, - byte len, const byte *buf, byte iTxBuf = 0xff) = 0; // as sendMsgBuf, but does not have any wait for free buffer - virtual byte sendMsgBuf(byte status, unsigned long id, byte ext, byte rtr, - byte len, volatile const byte *buf) = 0; // send message buf by using parsed buffer status - virtual byte sendMsgBuf(unsigned long id, byte ext, byte rtrBit, - byte len, const byte *buf, bool wait_sent = true) = 0; // send message with wait - - virtual void clearBufferTransmitIfFlags(byte flags = 0) = 0; // Clear transmit flags according to status - virtual byte readRxTxStatus(void) = 0; // read has something send or received - virtual byte checkClearRxStatus(byte *status) = 0; // read and clear and return first found rx status bit - virtual byte checkClearTxStatus(byte *status, byte iTxBuf = 0xff) = 0; // read and clear and return first found or buffer specified tx status bit - virtual bool mcpPinMode(const byte pin, const byte mode) = 0; // switch supported pins between HiZ, interrupt, output or input - virtual bool mcpDigitalWrite(const byte pin, const byte mode) = 0; // write HIGH or LOW to RX0BF/RX1BF - virtual byte mcpDigitalRead(const byte pin) = 0; // read HIGH or LOW from supported pins - -public: - MCP_CAN(byte _CS); - void init_CS(byte _CS); // define CS after construction before begin() - void setSPI(SPIClass *_pSPI); - -protected: - byte ext_flg; // identifier xxxID - // either extended (the 29 LSB) or standard (the 11 LSB) - unsigned long can_id; // can id - byte rtr; // is remote frame - byte SPICS; - SPIClass *pSPI; - byte mcpMode; // Current controller mode -}; - -#endif diff --git a/arduino/src/mcp/mcp_can_dfs.h b/arduino/src/mcp/mcp_can_dfs.h deleted file mode 100644 index 2948213..0000000 --- a/arduino/src/mcp/mcp_can_dfs.h +++ /dev/null @@ -1,504 +0,0 @@ -/* - mcp_can_dfs.h - 2012 Copyright (c) Seeed Technology Inc. All right reserved. - - Author:Loovee (loovee@seeed.cc) - 2014-1-16 - - Contributor: - - Cory J. Fowler - Latonita - Woodward1 - Mehtajaghvi - BykeBlast - TheRo0T - Tsipizic - ralfEdmund - Nathancheek - BlueAndi - Adlerweb - Btetz - Hurvajs - xboxpro1 - ttlappalainen - - The MIT License (MIT) - - Copyright (c) 2013 Seeed Technology Inc. - - 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 _MCP2515DFS_H_ -#define _MCP2515DFS_H_ - -#include -#include -#include - - -// if print debug information -#ifndef DEBUG_EN - #define DEBUG_EN 1 -#endif - -// Begin mt - -#define TIMEOUTVALUE 50 -#define MCP_SIDH 0 -#define MCP_SIDL 1 -#define MCP_EID8 2 -#define MCP_EID0 3 - -#define MCP_TXB_EXIDE_M 0x08 // In TXBnSIDL -#define MCP_DLC_MASK 0x0F // 4 LSBits -#define MCP_RTR_MASK 0x40 // (1<<6) Bit 6 - -#define MCP_RXB_RX_ANY 0x60 -#define MCP_RXB_RX_EXT 0x40 -#define MCP_RXB_RX_STD 0x20 -#define MCP_RXB_RX_STDEXT 0x00 -#define MCP_RXB_RX_MASK 0x60 -#define MCP_RXB_BUKT_MASK (1<<2) - - -// Bits in the TXBnCTRL registers. - -#define MCP_TXB_TXBUFE_M 0x80 -#define MCP_TXB_ABTF_M 0x40 -#define MCP_TXB_MLOA_M 0x20 -#define MCP_TXB_TXERR_M 0x10 -#define MCP_TXB_TXREQ_M 0x08 -#define MCP_TXB_TXIE_M 0x04 -#define MCP_TXB_TXP10_M 0x03 - -#define MCP_TXB_RTR_M 0x40 // In TXBnDLC -#define MCP_RXB_IDE_M 0x08 // In RXBnSIDL -#define MCP_RXB_RTR_M 0x40 // In RXBnDLC - -#define MCP_STAT_TX_PENDING_MASK (0x54) -#define MCP_STAT_TX0_PENDING (0x04) -#define MCP_STAT_TX1_PENDING (0x10) -#define MCP_STAT_TX2_PENDING (0x40) -#define MCP_STAT_TXIF_MASK (0xA8) -#define MCP_STAT_TX0IF (0x08) -#define MCP_STAT_TX1IF (0x20) -#define MCP_STAT_TX2IF (0x80) -#define MCP_STAT_RXIF_MASK (0x03) -#define MCP_STAT_RX0IF (1<<0) -#define MCP_STAT_RX1IF (1<<1) - -#define MCP_EFLG_RX1OVR (1<<7) -#define MCP_EFLG_RX0OVR (1<<6) -#define MCP_EFLG_TXBO (1<<5) -#define MCP_EFLG_TXEP (1<<4) -#define MCP_EFLG_RXEP (1<<3) -#define MCP_EFLG_TXWAR (1<<2) -#define MCP_EFLG_RXWAR (1<<1) -#define MCP_EFLG_EWARN (1<<0) -#define MCP_EFLG_ERRORMASK (0xF8) // 5 MS-Bits - -// Define MCP2515 register addresses - -#define MCP_RXF0SIDH 0x00 -#define MCP_RXF0SIDL 0x01 -#define MCP_RXF0EID8 0x02 -#define MCP_RXF0EID0 0x03 -#define MCP_RXF1SIDH 0x04 -#define MCP_RXF1SIDL 0x05 -#define MCP_RXF1EID8 0x06 -#define MCP_RXF1EID0 0x07 -#define MCP_RXF2SIDH 0x08 -#define MCP_RXF2SIDL 0x09 -#define MCP_RXF2EID8 0x0A -#define MCP_RXF2EID0 0x0B -#define MCP_BFPCTRL 0x0C -#define MCP_TXRTSCTRL 0x0D -#define MCP_CANSTAT 0x0E -#define MCP_CANCTRL 0x0F -#define MCP_RXF3SIDH 0x10 -#define MCP_RXF3SIDL 0x11 -#define MCP_RXF3EID8 0x12 -#define MCP_RXF3EID0 0x13 -#define MCP_RXF4SIDH 0x14 -#define MCP_RXF4SIDL 0x15 -#define MCP_RXF4EID8 0x16 -#define MCP_RXF4EID0 0x17 -#define MCP_RXF5SIDH 0x18 -#define MCP_RXF5SIDL 0x19 -#define MCP_RXF5EID8 0x1A -#define MCP_RXF5EID0 0x1B -#define MCP_TEC 0x1C -#define MCP_REC 0x1D -#define MCP_RXM0SIDH 0x20 -#define MCP_RXM0SIDL 0x21 -#define MCP_RXM0EID8 0x22 -#define MCP_RXM0EID0 0x23 -#define MCP_RXM1SIDH 0x24 -#define MCP_RXM1SIDL 0x25 -#define MCP_RXM1EID8 0x26 -#define MCP_RXM1EID0 0x27 -#define MCP_CNF3 0x28 -#define MCP_CNF2 0x29 -#define MCP_CNF1 0x2A -#define MCP_CANINTE 0x2B -#define MCP_CANINTF 0x2C -#define MCP_EFLG 0x2D -#define MCP_TXB0CTRL 0x30 -#define MCP_TXB0SIDH 0x31 -#define MCP_TXB1CTRL 0x40 -#define MCP_TXB1SIDH 0x41 -#define MCP_TXB2CTRL 0x50 -#define MCP_TXB2SIDH 0x51 -#define MCP_RXB0CTRL 0x60 -#define MCP_RXB0SIDH 0x61 -#define MCP_RXB1CTRL 0x70 -#define MCP_RXB1SIDH 0x71 - -#define MCP_TX_INT 0x1C // Enable all transmit interrup ts -#define MCP_TX01_INT 0x0C // Enable TXB0 and TXB1 interru pts -#define MCP_RX_INT 0x03 // Enable receive interrupts -#define MCP_NO_INT 0x00 // Disable all interrupts - -#define MCP_TX01_MASK 0x14 -#define MCP_TX_MASK 0x54 - - -// Define SPI Instruction Set - -#define MCP_WRITE 0x02 -#define MCP_READ 0x03 -#define MCP_BITMOD 0x05 -#define MCP_LOAD_TX0 0x40 -#define MCP_LOAD_TX1 0x42 -#define MCP_LOAD_TX2 0x44 - -#define MCP_RTS_TX0 0x81 -#define MCP_RTS_TX1 0x82 -#define MCP_RTS_TX2 0x84 -#define MCP_RTS_ALL 0x87 -#define MCP_READ_RX0 0x90 -#define MCP_READ_RX1 0x94 -#define MCP_READ_STATUS 0xA0 -#define MCP_RX_STATUS 0xB0 -#define MCP_RESET 0xC0 - - -// CANCTRL Register Values - -#define MODE_NORMAL 0x00 -#define MODE_SLEEP 0x20 -#define MODE_LOOPBACK 0x40 -#define MODE_LISTENONLY 0x60 -#define MODE_CONFIG 0x80 -#define MODE_POWERUP 0xE0 -#define MODE_MASK 0xE0 -#define ABORT_TX 0x10 -#define MODE_ONESHOT 0x08 -#define CLKOUT_ENABLE 0x04 -#define CLKOUT_DISABLE 0x00 -#define CLKOUT_PS1 0x00 -#define CLKOUT_PS2 0x01 -#define CLKOUT_PS4 0x02 -#define CLKOUT_PS8 0x03 - - -// CNF1 Register Values - -#define SJW1 0x00 -#define SJW2 0x40 -#define SJW3 0x80 -#define SJW4 0xC0 - - -// CNF2 Register Values - -#define BTLMODE 0x80 -#define SAMPLE_1X 0x00 -#define SAMPLE_3X 0x40 - - -// CNF3 Register Values - -#define SOF_ENABLE 0x80 -#define SOF_DISABLE 0x00 -#define WAKFIL_ENABLE 0x40 -#define WAKFIL_DISABLE 0x00 - - -// CANINTF Register Bits - -#define MCP_RX0IF 0x01 -#define MCP_RX1IF 0x02 -#define MCP_TX0IF 0x04 -#define MCP_TX1IF 0x08 -#define MCP_TX2IF 0x10 -#define MCP_ERRIF 0x20 -#define MCP_WAKIF 0x40 -#define MCP_MERRF 0x80 - -// BFPCTRL Register Bits - -#define B1BFS 0x20 -#define B0BFS 0x10 -#define B1BFE 0x08 -#define B0BFE 0x04 -#define B1BFM 0x02 -#define B0BFM 0x01 - -// TXRTCTRL Register Bits - -#define B2RTS 0x20 -#define B1RTS 0x10 -#define B0RTS 0x08 -#define B2RTSM 0x04 -#define B1RTSM 0x02 -#define B0RTSM 0x01 - -// clock - -#define MCP_16MHz 1 -#define MCP_8MHz 2 - -// speed 16M - -#define MCP_16MHz_1000kBPS_CFG1 (0x00) -#define MCP_16MHz_1000kBPS_CFG2 (0xD0) -#define MCP_16MHz_1000kBPS_CFG3 (0x82) - -#define MCP_16MHz_500kBPS_CFG1 (0x00) -#define MCP_16MHz_500kBPS_CFG2 (0xF0) -#define MCP_16MHz_500kBPS_CFG3 (0x86) - -#define MCP_16MHz_250kBPS_CFG1 (0x41) -#define MCP_16MHz_250kBPS_CFG2 (0xF1) -#define MCP_16MHz_250kBPS_CFG3 (0x85) - -#define MCP_16MHz_200kBPS_CFG1 (0x01) -#define MCP_16MHz_200kBPS_CFG2 (0xFA) -#define MCP_16MHz_200kBPS_CFG3 (0x87) - -#define MCP_16MHz_125kBPS_CFG1 (0x03) -#define MCP_16MHz_125kBPS_CFG2 (0xF0) -#define MCP_16MHz_125kBPS_CFG3 (0x86) - -#define MCP_16MHz_100kBPS_CFG1 (0x03) -#define MCP_16MHz_100kBPS_CFG2 (0xFA) -#define MCP_16MHz_100kBPS_CFG3 (0x87) - -#define MCP_16MHz_95kBPS_CFG1 (0x03) -#define MCP_16MHz_95kBPS_CFG2 (0xAD) -#define MCP_16MHz_95kBPS_CFG3 (0x07) - -#define MCP_16MHz_83k3BPS_CFG1 (0x03) -#define MCP_16MHz_83k3BPS_CFG2 (0xBE) -#define MCP_16MHz_83k3BPS_CFG3 (0x07) - -#define MCP_16MHz_80kBPS_CFG1 (0x03) -#define MCP_16MHz_80kBPS_CFG2 (0xFF) -#define MCP_16MHz_80kBPS_CFG3 (0x87) - -#define MCP_16MHz_50kBPS_CFG1 (0x07) -#define MCP_16MHz_50kBPS_CFG2 (0xFA) -#define MCP_16MHz_50kBPS_CFG3 (0x87) - -#define MCP_16MHz_40kBPS_CFG1 (0x07) -#define MCP_16MHz_40kBPS_CFG2 (0xFF) -#define MCP_16MHz_40kBPS_CFG3 (0x87) - -#define MCP_16MHz_33kBPS_CFG1 (0x09) -#define MCP_16MHz_33kBPS_CFG2 (0xBE) -#define MCP_16MHz_33kBPS_CFG3 (0x07) - -#define MCP_16MHz_31k25BPS_CFG1 (0x0F) -#define MCP_16MHz_31k25BPS_CFG2 (0xF1) -#define MCP_16MHz_31k25BPS_CFG3 (0x85) - -#define MCP_16MHz_25kBPS_CFG1 (0X0F) -#define MCP_16MHz_25kBPS_CFG2 (0XBA) -#define MCP_16MHz_25kBPS_CFG3 (0X07) - -#define MCP_16MHz_20kBPS_CFG1 (0x0F) -#define MCP_16MHz_20kBPS_CFG2 (0xFF) -#define MCP_16MHz_20kBPS_CFG3 (0x87) - -#define MCP_16MHz_10kBPS_CFG1 (0x1F) -#define MCP_16MHz_10kBPS_CFG2 (0xFF) -#define MCP_16MHz_10kBPS_CFG3 (0x87) - -#define MCP_16MHz_5kBPS_CFG1 (0x3F) -#define MCP_16MHz_5kBPS_CFG2 (0xFF) -#define MCP_16MHz_5kBPS_CFG3 (0x87) - -#define MCP_16MHz_666kBPS_CFG1 (0x00) -#define MCP_16MHz_666kBPS_CFG2 (0xA0) -#define MCP_16MHz_666kBPS_CFG3 (0x04) - - -// speed 8M - -#define MCP_8MHz_1000kBPS_CFG1 (0x00) -#define MCP_8MHz_1000kBPS_CFG2 (0x80) -#define MCP_8MHz_1000kBPS_CFG3 (0x00) - -#define MCP_8MHz_500kBPS_CFG1 (0x00) -#define MCP_8MHz_500kBPS_CFG2 (0x90) -#define MCP_8MHz_500kBPS_CFG3 (0x02) - -#define MCP_8MHz_250kBPS_CFG1 (0x00) -#define MCP_8MHz_250kBPS_CFG2 (0xb1) -#define MCP_8MHz_250kBPS_CFG3 (0x05) - -#define MCP_8MHz_200kBPS_CFG1 (0x00) -#define MCP_8MHz_200kBPS_CFG2 (0xb4) -#define MCP_8MHz_200kBPS_CFG3 (0x06) - -#define MCP_8MHz_125kBPS_CFG1 (0x01) -#define MCP_8MHz_125kBPS_CFG2 (0xb1) -#define MCP_8MHz_125kBPS_CFG3 (0x05) - -#define MCP_8MHz_100kBPS_CFG1 (0x01) -#define MCP_8MHz_100kBPS_CFG2 (0xb4) -#define MCP_8MHz_100kBPS_CFG3 (0x06) - -#define MCP_8MHz_80kBPS_CFG1 (0x01) -#define MCP_8MHz_80kBPS_CFG2 (0xbf) -#define MCP_8MHz_80kBPS_CFG3 (0x07) - -#define MCP_8MHz_50kBPS_CFG1 (0x03) -#define MCP_8MHz_50kBPS_CFG2 (0xb4) -#define MCP_8MHz_50kBPS_CFG3 (0x06) - -#define MCP_8MHz_40kBPS_CFG1 (0x03) -#define MCP_8MHz_40kBPS_CFG2 (0xbf) -#define MCP_8MHz_40kBPS_CFG3 (0x07) - -#define MCP_8MHz_31k25BPS_CFG1 (0x07) -#define MCP_8MHz_31k25BPS_CFG2 (0xa4) -#define MCP_8MHz_31k25BPS_CFG3 (0x04) - -#define MCP_8MHz_20kBPS_CFG1 (0x07) -#define MCP_8MHz_20kBPS_CFG2 (0xbf) -#define MCP_8MHz_20kBPS_CFG3 (0x07) - -#define MCP_8MHz_10kBPS_CFG1 (0x0f) -#define MCP_8MHz_10kBPS_CFG2 (0xbf) -#define MCP_8MHz_10kBPS_CFG3 (0x07) - -#define MCP_8MHz_5kBPS_CFG1 (0x1f) -#define MCP_8MHz_5kBPS_CFG2 (0xbf) -#define MCP_8MHz_5kBPS_CFG3 (0x07) - -#define MCPDEBUG (0) -#define MCPDEBUG_TXBUF (0) -#define MCP_N_TXBUFFERS (3) - -#define MCP_RXBUF_0 (MCP_RXB0SIDH) -#define MCP_RXBUF_1 (MCP_RXB1SIDH) - -#define MCP2515_SELECT() digitalWrite(SPICS, LOW) -#define MCP2515_UNSELECT() digitalWrite(SPICS, HIGH) - -#define MCP2515_OK (0) -#define MCP2515_FAIL (1) -#define MCP_ALLTXBUSY (2) - -#define CANDEBUG 1 - -#define CANUSELOOP 0 - -#define CANSENDTIMEOUT (200) // milliseconds - -#define MCP_PIN_HIZ (0) -#define MCP_PIN_INT (1) -#define MCP_PIN_OUT (2) -#define MCP_PIN_IN (3) - -#define MCP_RX0BF (0) -#define MCP_RX1BF (1) -#define MCP_TX0RTS (2) -#define MCP_TX1RTS (3) -#define MCP_TX2RTS (4) - - -// initial value of gCANAutoProcess - -#define CANAUTOPROCESS (1) -#define CANAUTOON (1) -#define CANAUTOOFF (0) -#define CAN_STDID (0) -#define CAN_EXTID (1) -#define CANDEFAULTIDENT (0x55CC) -#define CANDEFAULTIDENTEXT (CAN_EXTID) - - -typedef enum { - CAN_NOBPS, - CAN_5KBPS, - CAN_10KBPS, - CAN_20KBPS, - CAN_25KBPS, - CAN_31K25BPS, - CAN_33KBPS , - CAN_40KBPS , - CAN_50KBPS , - CAN_80KBPS , - CAN_83K3BPS , - CAN_95KBPS , - CAN_100KBPS , - CAN_125KBPS , - CAN_200KBPS , - CAN_250KBPS , - CAN_500KBPS , - CAN_666KBPS , - CAN_1000KBPS -} MCP2515_BITTIME_SETUP; - -#define CAN_OK (0) -#define CAN_FAILINIT (1) -#define CAN_FAILTX (2) -#define CAN_MSGAVAIL (3) -#define CAN_NOMSG (4) -#define CAN_CTRLERROR (5) -#define CAN_GETTXBFTIMEOUT (6) -#define CAN_SENDMSGTIMEOUT (7) -#define CAN_FAIL (0xff) - - -// #define CAN_OK (0) -// #define CAN_FAILINIT (1) -// #define CAN_FAILTX (2) -// #define CAN_MSGAVAIL (3) -#define CAN_NOMSG (4) -#define CAN_CTRLERROR (5) -#define CAN_GETTXBFTIMEOUT (6) -#define CAN_SENDMSGTIMEOUT (7) -#define CAN_FAIL (0xff) - - - - - - -#define CAN_MAX_CHAR_IN_MESSAGE (8) - -#endif -/********************************************************************************************************* - END FILE -*********************************************************************************************************/ diff --git a/plotter/datalog.csv b/plotter/datalog.csv new file mode 100644 index 0000000..e69de29 diff --git a/plotter/datalog_raw_final_40.csv b/plotter/datalog_raw_final_40.csv new file mode 100644 index 0000000..e69de29 diff --git a/plotter/plotter.py b/plotter/plotter.py new file mode 100644 index 0000000..73dfda7 --- /dev/null +++ b/plotter/plotter.py @@ -0,0 +1,124 @@ +# Import libraries +from numpy import * +from pyqtgraph.Qt import QtGui, QtCore, QtWidgets +import pyqtgraph as pg +import serial +import signal +import time +signal.signal(signal.SIGINT, signal.SIG_DFL) + +tmp_data = [] +import keyboard + +# Realtime data plot. Each time this function is called, the data display is updated +def update(): + start = time.time() + + global curve, ptr, Xm, Xn, tmp_data + Xm[:-1] = Xm[1:] # shift data in the temporal mean 1 sample left + Xn[:-1] = Xn[1:] # shift data in the temporal mean 1 sample left + #value = ser.readline() # read line (single value) from the serial port + value = ser.read(100) + + # print(value) + # g.write(value) + + + if len(tmp_data) == 0: + if b'D=x' in value: + tmp_data = value[value.index(b'D=x'):] + else: + pass + # print(value) + else: + plot_data = [] + plot_data = tmp_data[:tmp_data.rindex(b'\r\n')+2] + tmp_data = tmp_data[tmp_data.rindex(b'\r\n')+2:] + tmp_data = tmp_data + value + + + # g.write(plot_data) + + + dataa = plot_data.split(b'\r\n') + + #3 - 7 + #10 - 14 + #16 - 20 + #22 - 24 + if len(dataa) > 0: + d = dataa[0] + + if d != b'' and len(d) == 23: + # print(d) + try: + int32_time = int.from_bytes(d[3:7] , 'little', signed=True) + int32_pos = int.from_bytes(d[9:13] , 'little', signed=True) + + #int32_vel = int.from_bytes(d[15:19] , 'little', signed=False) + #int32_tor = int.from_bytes(d[21:23] , 'little', signed=True) + + angle = int32_pos*(0.00086666666) + 90 # in rad + #velocity = int32_vel*0.10472*(10**(-3)) + + # f.write(str(int32_time) + ";" + str(angle) + ";" + str(velocity) + ";" + str(int32_tor) + "\n") + # print(int32_time) + + i = float(int32_time) + Xn[-1] = angle + + curve.setData(Xn) # set the curve with this data + curve.setPos(i,0) # set x position in the graph to 0 + QtGui.QApplication.processEvents() # you MUST process the plot now + except Exception as e: + print(e) + + ende = time.time() + +def setYRange(self): + self.enableAutoRange(axis='y') + self.setAutoVisible(y=True) + +f = open("./datalog.csv", "w") +g = open("./datalog_raw_final_40.csv", "wb") +f.write("Time in s; Position in rad; Velocity in rad/s; Torque in mNm\n") + + +portName = "COM3" # replace this port name by yours! +baudrate = 921600 +try: + print("er111") + + ### START QtApp ##### + app = QtWidgets.QApplication([]) + + ser = serial.Serial(portName,baudrate) + win = pg.GraphicsWindow(title="Signal from serial port") # creates a window + p = win.addPlot(title="Realtime plot") # creates empty space for the plot in the window + curve = p.plot() + # create an empty "plot" (a curve to plot) + keyboard.on_press_key("p", lambda _:ser.write(b'start\r\n')) + + # vb = p.getViewBox() + # vb.sigXRangeChanged.connect(setYRange) + + p.setYRange(-20, 190, padding=0) + windowWidth = 2000 # width of the window displaying the curve + Xm = linspace(0,0,windowWidth) # create array that will contain the relevant time series + Xn = linspace(0,0,windowWidth) # create array that will contain the relevant time series + ptr = -windowWidth # set first x position + + ### MAIN PROGRAM ##### + # this is a brutal infinite loop calling your realtime data plot + while True: update() + + f.close() +except Exception as e: + print(e) + f.close() + + +### END QtApp #### +pg.QtGui.QApplication.exec() +# pg.QtGui.QApplication.exec_() # you MUST put this at the end +################## diff --git a/plotter/pythonploter2.py b/plotter/pythonploter2.py deleted file mode 100644 index 7fa9569..0000000 --- a/plotter/pythonploter2.py +++ /dev/null @@ -1,67 +0,0 @@ -# Import libraries -from numpy import * -from pyqtgraph.Qt import QtGui, QtCore -import pyqtgraph as pg -import serial - - - # Realtime data plot. Each time this function is called, the data display is updated -def update(): - global curve, ptr, Xm, Xn - Xm[:-1] = Xm[1:] # shift data in the temporal mean 1 sample left - Xn[:-1] = Xn[1:] # shift data in the temporal mean 1 sample left - value = ser.readline() # read line (single value) from the serial port - if value[0:4] == b'Data': - line_as_list = value.split(b'===')[1].split(b',') - - try: - i = float(line_as_list[0]) - Xn[-1] = float(line_as_list[1].split(b'\r')[0]) - Xm[-1] = float(line_as_list[2].split(b'\r')[0]) - - print(i, end=",") - print(float(line_as_list[1].split(b'\r')[0]), end=",") - print(float(line_as_list[2].split(b'\r')[0])) - - - # update x position for displaying the curve - curve.setData(Xn) # set the curve with this data - curve.setPos(i,0) # set x position in the graph to 0 - QtGui.QApplication.processEvents() # you MUST process the plot now - - except Exception as e: - print(e) - - ser.flushInput() - ser.flushOutput() -# Create object serial port -portName = "/dev/ttyUSB0" # replace this port name by yours! -baudrate = 115200 -try: - print("er111") - - ### START QtApp ##### - app = QtGui.QApplication([]) - - ser = serial.Serial(portName,baudrate) - win = pg.GraphicsWindow(title="Signal from serial port") # creates a window - p = win.addPlot(title="Realtime plot") # creates empty space for the plot in the window - curve = p.plot() - # create an empty "plot" (a curve to plot) - - p.setYRange(-1.5, 1.5, padding=0) - windowWidth = 500 # width of the window displaying the curve - Xm = linspace(0,0,windowWidth) # create array that will contain the relevant time series - Xn = linspace(0,0,windowWidth) # create array that will contain the relevant time series - ptr = -windowWidth # set first x position - - ### MAIN PROGRAM ##### - # this is a brutal infinite loop calling your realtime data plot - while True: update() -except Exception as e: - print(e) - - -### END QtApp #### -pg.QtGui.QApplication.exec_() # you MUST put this at the end -################## diff --git a/zephyr/.west/config b/zephyr/.west/config deleted file mode 100644 index fd358f2..0000000 --- a/zephyr/.west/config +++ /dev/null @@ -1,7 +0,0 @@ -[manifest] -path = zephyr -file = west.yml - -[zephyr] -base = zephyr - diff --git a/zephyr/bootloader/mcuboot b/zephyr/bootloader/mcuboot deleted file mode 160000 index 6eca8bb..0000000 --- a/zephyr/bootloader/mcuboot +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 6eca8bbc2bdbf16d5ebbfd89ca27aaa9b3d88400 diff --git a/zephyr/build/CMakeCache.txt b/zephyr/build/CMakeCache.txt deleted file mode 100644 index 5a2a0fe..0000000 --- a/zephyr/build/CMakeCache.txt +++ /dev/null @@ -1,370 +0,0 @@ -# This is the CMakeCache file. -# For build in directory: /home/gebler/Dokumente/Medit/MedExo/epos4_zephyr/build -# It was generated by CMake: /usr/bin/cmake -# You can edit this file to change values found and used by cmake. -# If you do not want to change any of the values, simply exit the editor. -# If you do want to change a value, simply edit, save, and exit the editor. -# The syntax for the file is as follows: -# KEY:TYPE=VALUE -# KEY is the name of a variable in the cache. -# TYPE is a hint to GUIs for the type of VALUE, DO NOT EDIT TYPE!. -# VALUE is the current value for the KEY. - -######################## -# EXTERNAL cache entries -######################## - -//No help, variable specified on the command line. -BOARD:UNINITIALIZED=stm32f4_disco - -//Path to a program. -CMAKE_ADDR2LINE:FILEPATH=/usr/bin/addr2line - -//Path to a program. -CMAKE_AR:FILEPATH=/usr/bin/ar - -//Choose the type of build, options are: None Debug Release RelWithDebInfo -// MinSizeRel ... -CMAKE_BUILD_TYPE:STRING= - -//CXX compiler -CMAKE_CXX_COMPILER:FILEPATH=/usr/bin/c++ - -//A wrapper around 'ar' adding the appropriate '--plugin' option -// for the GCC compiler -CMAKE_CXX_COMPILER_AR:FILEPATH=/usr/bin/gcc-ar-9 - -//A wrapper around 'ranlib' adding the appropriate '--plugin' option -// for the GCC compiler -CMAKE_CXX_COMPILER_RANLIB:FILEPATH=/usr/bin/gcc-ranlib-9 - -//Flags used by the CXX compiler during all build types. -CMAKE_CXX_FLAGS:STRING= - -//Flags used by the CXX compiler during DEBUG builds. -CMAKE_CXX_FLAGS_DEBUG:STRING=-g - -//Flags used by the CXX compiler during MINSIZEREL builds. -CMAKE_CXX_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG - -//Flags used by the CXX compiler during RELEASE builds. -CMAKE_CXX_FLAGS_RELEASE:STRING=-O3 -DNDEBUG - -//Flags used by the CXX compiler during RELWITHDEBINFO builds. -CMAKE_CXX_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG - -//C compiler -CMAKE_C_COMPILER:FILEPATH=/usr/bin/cc - -//A wrapper around 'ar' adding the appropriate '--plugin' option -// for the GCC compiler -CMAKE_C_COMPILER_AR:FILEPATH=/usr/bin/gcc-ar-9 - -//A wrapper around 'ranlib' adding the appropriate '--plugin' option -// for the GCC compiler -CMAKE_C_COMPILER_RANLIB:FILEPATH=/usr/bin/gcc-ranlib-9 - -//Flags used by the C compiler during all build types. -CMAKE_C_FLAGS:STRING= - -//Flags used by the C compiler during DEBUG builds. -CMAKE_C_FLAGS_DEBUG:STRING=-g - -//Flags used by the C compiler during MINSIZEREL builds. -CMAKE_C_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG - -//Flags used by the C compiler during RELEASE builds. -CMAKE_C_FLAGS_RELEASE:STRING=-O3 -DNDEBUG - -//Flags used by the C compiler during RELWITHDEBINFO builds. -CMAKE_C_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG - -//Path to a program. -CMAKE_DLLTOOL:FILEPATH=CMAKE_DLLTOOL-NOTFOUND - -//Flags used by the linker during all build types. -CMAKE_EXE_LINKER_FLAGS:STRING= - -//Flags used by the linker during DEBUG builds. -CMAKE_EXE_LINKER_FLAGS_DEBUG:STRING= - -//Flags used by the linker during MINSIZEREL builds. -CMAKE_EXE_LINKER_FLAGS_MINSIZEREL:STRING= - -//Flags used by the linker during RELEASE builds. -CMAKE_EXE_LINKER_FLAGS_RELEASE:STRING= - -//Flags used by the linker during RELWITHDEBINFO builds. -CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO:STRING= - -//Enable/Disable output of compile commands during generation. -CMAKE_EXPORT_COMPILE_COMMANDS:BOOL= - -//Install path prefix, prepended onto install directories. -CMAKE_INSTALL_PREFIX:PATH=/usr/local - -//Path to a program. -CMAKE_LINKER:FILEPATH=/usr/bin/ld - -//Program used to build from build.ninja files. -CMAKE_MAKE_PROGRAM:FILEPATH=/usr/bin/ninja - -//Flags used by the linker during the creation of modules during -// all build types. -CMAKE_MODULE_LINKER_FLAGS:STRING= - -//Flags used by the linker during the creation of modules during -// DEBUG builds. -CMAKE_MODULE_LINKER_FLAGS_DEBUG:STRING= - -//Flags used by the linker during the creation of modules during -// MINSIZEREL builds. -CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL:STRING= - -//Flags used by the linker during the creation of modules during -// RELEASE builds. -CMAKE_MODULE_LINKER_FLAGS_RELEASE:STRING= - -//Flags used by the linker during the creation of modules during -// RELWITHDEBINFO builds. -CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO:STRING= - -//Path to a program. -CMAKE_NM:FILEPATH=/usr/bin/nm - -//Path to a program. -CMAKE_OBJCOPY:FILEPATH=/usr/bin/objcopy - -//Path to a program. -CMAKE_OBJDUMP:FILEPATH=/usr/bin/objdump - -//Value Computed by CMake -CMAKE_PROJECT_DESCRIPTION:STATIC= - -//Value Computed by CMake -CMAKE_PROJECT_HOMEPAGE_URL:STATIC= - -//Value Computed by CMake -CMAKE_PROJECT_NAME:STATIC=epos_controller - -//Path to a program. -CMAKE_RANLIB:FILEPATH=/usr/bin/ranlib - -//Path to a program. -CMAKE_READELF:FILEPATH=/usr/bin/readelf - -//Flags used by the linker during the creation of shared libraries -// during all build types. -CMAKE_SHARED_LINKER_FLAGS:STRING= - -//Flags used by the linker during the creation of shared libraries -// during DEBUG builds. -CMAKE_SHARED_LINKER_FLAGS_DEBUG:STRING= - -//Flags used by the linker during the creation of shared libraries -// during MINSIZEREL builds. -CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL:STRING= - -//Flags used by the linker during the creation of shared libraries -// during RELEASE builds. -CMAKE_SHARED_LINKER_FLAGS_RELEASE:STRING= - -//Flags used by the linker during the creation of shared libraries -// during RELWITHDEBINFO builds. -CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO:STRING= - -//If set, runtime paths are not added when installing shared libraries, -// but are added when building. -CMAKE_SKIP_INSTALL_RPATH:BOOL=NO - -//If set, runtime paths are not added when using shared libraries. -CMAKE_SKIP_RPATH:BOOL=NO - -//Flags used by the linker during the creation of static libraries -// during all build types. -CMAKE_STATIC_LINKER_FLAGS:STRING= - -//Flags used by the linker during the creation of static libraries -// during DEBUG builds. -CMAKE_STATIC_LINKER_FLAGS_DEBUG:STRING= - -//Flags used by the linker during the creation of static libraries -// during MINSIZEREL builds. -CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL:STRING= - -//Flags used by the linker during the creation of static libraries -// during RELEASE builds. -CMAKE_STATIC_LINKER_FLAGS_RELEASE:STRING= - -//Flags used by the linker during the creation of static libraries -// during RELWITHDEBINFO builds. -CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO:STRING= - -//Path to a program. -CMAKE_STRIP:FILEPATH=/usr/bin/strip - -//If this value is on, makefiles will be generated without the -// .SILENT directive, and all commands will be echoed to the console -// during the make. This is useful for debugging only. With Visual -// Studio IDE projects all commands are done without /nologo. -CMAKE_VERBOSE_MAKEFILE:BOOL=FALSE - -//No help, variable specified on the command line. -WEST_PYTHON:UNINITIALIZED=/usr/bin/python3 - -//The directory containing a CMake configuration file for Zephyr. -Zephyr_DIR:PATH=Zephyr_DIR-NOTFOUND - -//Value Computed by CMake -epos_controller_BINARY_DIR:STATIC=/home/gebler/Dokumente/Medit/MedExo/epos4_zephyr/build - -//Value Computed by CMake -epos_controller_SOURCE_DIR:STATIC=/home/gebler/Dokumente/Medit/MedExo/epos4_zephyr/epos_controller - - -######################## -# INTERNAL cache entries -######################## - -//ADVANCED property for variable: CMAKE_ADDR2LINE -CMAKE_ADDR2LINE-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_AR -CMAKE_AR-ADVANCED:INTERNAL=1 -//This is the directory where this CMakeCache.txt was created -CMAKE_CACHEFILE_DIR:INTERNAL=/home/gebler/Dokumente/Medit/MedExo/epos4_zephyr/build -//Major version of cmake used to create the current loaded cache -CMAKE_CACHE_MAJOR_VERSION:INTERNAL=3 -//Minor version of cmake used to create the current loaded cache -CMAKE_CACHE_MINOR_VERSION:INTERNAL=20 -//Patch version of cmake used to create the current loaded cache -CMAKE_CACHE_PATCH_VERSION:INTERNAL=2 -//Path to CMake executable. -CMAKE_COMMAND:INTERNAL=/usr/bin/cmake -//Path to cpack program executable. -CMAKE_CPACK_COMMAND:INTERNAL=/usr/bin/cpack -//Path to ctest program executable. -CMAKE_CTEST_COMMAND:INTERNAL=/usr/bin/ctest -//ADVANCED property for variable: CMAKE_CXX_COMPILER -CMAKE_CXX_COMPILER-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_CXX_COMPILER_AR -CMAKE_CXX_COMPILER_AR-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_CXX_COMPILER_RANLIB -CMAKE_CXX_COMPILER_RANLIB-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_CXX_FLAGS -CMAKE_CXX_FLAGS-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_CXX_FLAGS_DEBUG -CMAKE_CXX_FLAGS_DEBUG-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_CXX_FLAGS_MINSIZEREL -CMAKE_CXX_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELEASE -CMAKE_CXX_FLAGS_RELEASE-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELWITHDEBINFO -CMAKE_CXX_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_C_COMPILER -CMAKE_C_COMPILER-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_C_COMPILER_AR -CMAKE_C_COMPILER_AR-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_C_COMPILER_RANLIB -CMAKE_C_COMPILER_RANLIB-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_C_FLAGS -CMAKE_C_FLAGS-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_C_FLAGS_DEBUG -CMAKE_C_FLAGS_DEBUG-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_C_FLAGS_MINSIZEREL -CMAKE_C_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_C_FLAGS_RELEASE -CMAKE_C_FLAGS_RELEASE-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_C_FLAGS_RELWITHDEBINFO -CMAKE_C_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_DLLTOOL -CMAKE_DLLTOOL-ADVANCED:INTERNAL=1 -//Executable file format -CMAKE_EXECUTABLE_FORMAT:INTERNAL=ELF -//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS -CMAKE_EXE_LINKER_FLAGS-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_DEBUG -CMAKE_EXE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_MINSIZEREL -CMAKE_EXE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELEASE -CMAKE_EXE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO -CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_EXPORT_COMPILE_COMMANDS -CMAKE_EXPORT_COMPILE_COMMANDS-ADVANCED:INTERNAL=1 -//Name of external makefile project generator. -CMAKE_EXTRA_GENERATOR:INTERNAL= -//Name of generator. -CMAKE_GENERATOR:INTERNAL=Ninja -//Generator instance identifier. -CMAKE_GENERATOR_INSTANCE:INTERNAL= -//Name of generator platform. -CMAKE_GENERATOR_PLATFORM:INTERNAL= -//Name of generator toolset. -CMAKE_GENERATOR_TOOLSET:INTERNAL= -//Source directory with the top level CMakeLists.txt file for this -// project -CMAKE_HOME_DIRECTORY:INTERNAL=/home/gebler/Dokumente/Medit/MedExo/epos4_zephyr/epos_controller -//Install .so files without execute permission. -CMAKE_INSTALL_SO_NO_EXE:INTERNAL=1 -//ADVANCED property for variable: CMAKE_LINKER -CMAKE_LINKER-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_MAKE_PROGRAM -CMAKE_MAKE_PROGRAM-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS -CMAKE_MODULE_LINKER_FLAGS-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_DEBUG -CMAKE_MODULE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL -CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELEASE -CMAKE_MODULE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO -CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_NM -CMAKE_NM-ADVANCED:INTERNAL=1 -//number of local generators -CMAKE_NUMBER_OF_MAKEFILES:INTERNAL=1 -//ADVANCED property for variable: CMAKE_OBJCOPY -CMAKE_OBJCOPY-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_OBJDUMP -CMAKE_OBJDUMP-ADVANCED:INTERNAL=1 -//Platform information initialized -CMAKE_PLATFORM_INFO_INITIALIZED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_RANLIB -CMAKE_RANLIB-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_READELF -CMAKE_READELF-ADVANCED:INTERNAL=1 -//Path to CMake installation. -CMAKE_ROOT:INTERNAL=/usr/share/cmake-3.20 -//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS -CMAKE_SHARED_LINKER_FLAGS-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_DEBUG -CMAKE_SHARED_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL -CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELEASE -CMAKE_SHARED_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO -CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_SKIP_INSTALL_RPATH -CMAKE_SKIP_INSTALL_RPATH-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_SKIP_RPATH -CMAKE_SKIP_RPATH-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS -CMAKE_STATIC_LINKER_FLAGS-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_DEBUG -CMAKE_STATIC_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL -CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELEASE -CMAKE_STATIC_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO -CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 -//ADVANCED property for variable: CMAKE_STRIP -CMAKE_STRIP-ADVANCED:INTERNAL=1 -//uname command -CMAKE_UNAME:INTERNAL=/bin/uname -//ADVANCED property for variable: CMAKE_VERBOSE_MAKEFILE -CMAKE_VERBOSE_MAKEFILE-ADVANCED:INTERNAL=1 - diff --git a/zephyr/build/CMakeFiles/3.20.2/CMakeCCompiler.cmake b/zephyr/build/CMakeFiles/3.20.2/CMakeCCompiler.cmake deleted file mode 100644 index c3d6fb2..0000000 --- a/zephyr/build/CMakeFiles/3.20.2/CMakeCCompiler.cmake +++ /dev/null @@ -1,78 +0,0 @@ -set(CMAKE_C_COMPILER "/usr/bin/cc") -set(CMAKE_C_COMPILER_ARG1 "") -set(CMAKE_C_COMPILER_ID "GNU") -set(CMAKE_C_COMPILER_VERSION "9.3.0") -set(CMAKE_C_COMPILER_VERSION_INTERNAL "") -set(CMAKE_C_COMPILER_WRAPPER "") -set(CMAKE_C_STANDARD_COMPUTED_DEFAULT "11") -set(CMAKE_C_COMPILE_FEATURES "c_std_90;c_function_prototypes;c_std_99;c_restrict;c_variadic_macros;c_std_11;c_static_assert") -set(CMAKE_C90_COMPILE_FEATURES "c_std_90;c_function_prototypes") -set(CMAKE_C99_COMPILE_FEATURES "c_std_99;c_restrict;c_variadic_macros") -set(CMAKE_C11_COMPILE_FEATURES "c_std_11;c_static_assert") - -set(CMAKE_C_PLATFORM_ID "Linux") -set(CMAKE_C_SIMULATE_ID "") -set(CMAKE_C_COMPILER_FRONTEND_VARIANT "") -set(CMAKE_C_SIMULATE_VERSION "") - - - - -set(CMAKE_AR "/usr/bin/ar") -set(CMAKE_C_COMPILER_AR "/usr/bin/gcc-ar-9") -set(CMAKE_RANLIB "/usr/bin/ranlib") -set(CMAKE_C_COMPILER_RANLIB "/usr/bin/gcc-ranlib-9") -set(CMAKE_LINKER "/usr/bin/ld") -set(CMAKE_MT "") -set(CMAKE_COMPILER_IS_GNUCC 1) -set(CMAKE_C_COMPILER_LOADED 1) -set(CMAKE_C_COMPILER_WORKS TRUE) -set(CMAKE_C_ABI_COMPILED TRUE) -set(CMAKE_COMPILER_IS_MINGW ) -set(CMAKE_COMPILER_IS_CYGWIN ) -if(CMAKE_COMPILER_IS_CYGWIN) - set(CYGWIN 1) - set(UNIX 1) -endif() - -set(CMAKE_C_COMPILER_ENV_VAR "CC") - -if(CMAKE_COMPILER_IS_MINGW) - set(MINGW 1) -endif() -set(CMAKE_C_COMPILER_ID_RUN 1) -set(CMAKE_C_SOURCE_FILE_EXTENSIONS c;m) -set(CMAKE_C_IGNORE_EXTENSIONS h;H;o;O;obj;OBJ;def;DEF;rc;RC) -set(CMAKE_C_LINKER_PREFERENCE 10) - -# Save compiler ABI information. -set(CMAKE_C_SIZEOF_DATA_PTR "8") -set(CMAKE_C_COMPILER_ABI "ELF") -set(CMAKE_C_BYTE_ORDER "LITTLE_ENDIAN") -set(CMAKE_C_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") - -if(CMAKE_C_SIZEOF_DATA_PTR) - set(CMAKE_SIZEOF_VOID_P "${CMAKE_C_SIZEOF_DATA_PTR}") -endif() - -if(CMAKE_C_COMPILER_ABI) - set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_C_COMPILER_ABI}") -endif() - -if(CMAKE_C_LIBRARY_ARCHITECTURE) - set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") -endif() - -set(CMAKE_C_CL_SHOWINCLUDES_PREFIX "") -if(CMAKE_C_CL_SHOWINCLUDES_PREFIX) - set(CMAKE_CL_SHOWINCLUDES_PREFIX "${CMAKE_C_CL_SHOWINCLUDES_PREFIX}") -endif() - - - - - -set(CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/9/include;/usr/local/include;/usr/include/x86_64-linux-gnu;/usr/include") -set(CMAKE_C_IMPLICIT_LINK_LIBRARIES "gcc;gcc_s;c;gcc;gcc_s") -set(CMAKE_C_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/9;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") -set(CMAKE_C_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") diff --git a/zephyr/build/CMakeFiles/3.20.2/CMakeCXXCompiler.cmake b/zephyr/build/CMakeFiles/3.20.2/CMakeCXXCompiler.cmake deleted file mode 100644 index 5d092d2..0000000 --- a/zephyr/build/CMakeFiles/3.20.2/CMakeCXXCompiler.cmake +++ /dev/null @@ -1,91 +0,0 @@ -set(CMAKE_CXX_COMPILER "/usr/bin/c++") -set(CMAKE_CXX_COMPILER_ARG1 "") -set(CMAKE_CXX_COMPILER_ID "GNU") -set(CMAKE_CXX_COMPILER_VERSION "9.3.0") -set(CMAKE_CXX_COMPILER_VERSION_INTERNAL "") -set(CMAKE_CXX_COMPILER_WRAPPER "") -set(CMAKE_CXX_STANDARD_COMPUTED_DEFAULT "14") -set(CMAKE_CXX_COMPILE_FEATURES "cxx_std_98;cxx_template_template_parameters;cxx_std_11;cxx_alias_templates;cxx_alignas;cxx_alignof;cxx_attributes;cxx_auto_type;cxx_constexpr;cxx_decltype;cxx_decltype_incomplete_return_types;cxx_default_function_template_args;cxx_defaulted_functions;cxx_defaulted_move_initializers;cxx_delegating_constructors;cxx_deleted_functions;cxx_enum_forward_declarations;cxx_explicit_conversions;cxx_extended_friend_declarations;cxx_extern_templates;cxx_final;cxx_func_identifier;cxx_generalized_initializers;cxx_inheriting_constructors;cxx_inline_namespaces;cxx_lambdas;cxx_local_type_template_args;cxx_long_long_type;cxx_noexcept;cxx_nonstatic_member_init;cxx_nullptr;cxx_override;cxx_range_for;cxx_raw_string_literals;cxx_reference_qualified_functions;cxx_right_angle_brackets;cxx_rvalue_references;cxx_sizeof_member;cxx_static_assert;cxx_strong_enums;cxx_thread_local;cxx_trailing_return_types;cxx_unicode_literals;cxx_uniform_initialization;cxx_unrestricted_unions;cxx_user_literals;cxx_variadic_macros;cxx_variadic_templates;cxx_std_14;cxx_aggregate_default_initializers;cxx_attribute_deprecated;cxx_binary_literals;cxx_contextual_conversions;cxx_decltype_auto;cxx_digit_separators;cxx_generic_lambdas;cxx_lambda_init_captures;cxx_relaxed_constexpr;cxx_return_type_deduction;cxx_variable_templates;cxx_std_17;cxx_std_20") -set(CMAKE_CXX98_COMPILE_FEATURES "cxx_std_98;cxx_template_template_parameters") -set(CMAKE_CXX11_COMPILE_FEATURES "cxx_std_11;cxx_alias_templates;cxx_alignas;cxx_alignof;cxx_attributes;cxx_auto_type;cxx_constexpr;cxx_decltype;cxx_decltype_incomplete_return_types;cxx_default_function_template_args;cxx_defaulted_functions;cxx_defaulted_move_initializers;cxx_delegating_constructors;cxx_deleted_functions;cxx_enum_forward_declarations;cxx_explicit_conversions;cxx_extended_friend_declarations;cxx_extern_templates;cxx_final;cxx_func_identifier;cxx_generalized_initializers;cxx_inheriting_constructors;cxx_inline_namespaces;cxx_lambdas;cxx_local_type_template_args;cxx_long_long_type;cxx_noexcept;cxx_nonstatic_member_init;cxx_nullptr;cxx_override;cxx_range_for;cxx_raw_string_literals;cxx_reference_qualified_functions;cxx_right_angle_brackets;cxx_rvalue_references;cxx_sizeof_member;cxx_static_assert;cxx_strong_enums;cxx_thread_local;cxx_trailing_return_types;cxx_unicode_literals;cxx_uniform_initialization;cxx_unrestricted_unions;cxx_user_literals;cxx_variadic_macros;cxx_variadic_templates") -set(CMAKE_CXX14_COMPILE_FEATURES "cxx_std_14;cxx_aggregate_default_initializers;cxx_attribute_deprecated;cxx_binary_literals;cxx_contextual_conversions;cxx_decltype_auto;cxx_digit_separators;cxx_generic_lambdas;cxx_lambda_init_captures;cxx_relaxed_constexpr;cxx_return_type_deduction;cxx_variable_templates") -set(CMAKE_CXX17_COMPILE_FEATURES "cxx_std_17") -set(CMAKE_CXX20_COMPILE_FEATURES "cxx_std_20") -set(CMAKE_CXX23_COMPILE_FEATURES "") - -set(CMAKE_CXX_PLATFORM_ID "Linux") -set(CMAKE_CXX_SIMULATE_ID "") -set(CMAKE_CXX_COMPILER_FRONTEND_VARIANT "") -set(CMAKE_CXX_SIMULATE_VERSION "") - - - - -set(CMAKE_AR "/usr/bin/ar") -set(CMAKE_CXX_COMPILER_AR "/usr/bin/gcc-ar-9") -set(CMAKE_RANLIB "/usr/bin/ranlib") -set(CMAKE_CXX_COMPILER_RANLIB "/usr/bin/gcc-ranlib-9") -set(CMAKE_LINKER "/usr/bin/ld") -set(CMAKE_MT "") -set(CMAKE_COMPILER_IS_GNUCXX 1) -set(CMAKE_CXX_COMPILER_LOADED 1) -set(CMAKE_CXX_COMPILER_WORKS TRUE) -set(CMAKE_CXX_ABI_COMPILED TRUE) -set(CMAKE_COMPILER_IS_MINGW ) -set(CMAKE_COMPILER_IS_CYGWIN ) -if(CMAKE_COMPILER_IS_CYGWIN) - set(CYGWIN 1) - set(UNIX 1) -endif() - -set(CMAKE_CXX_COMPILER_ENV_VAR "CXX") - -if(CMAKE_COMPILER_IS_MINGW) - set(MINGW 1) -endif() -set(CMAKE_CXX_COMPILER_ID_RUN 1) -set(CMAKE_CXX_SOURCE_FILE_EXTENSIONS C;M;c++;cc;cpp;cxx;m;mm;mpp;CPP) -set(CMAKE_CXX_IGNORE_EXTENSIONS inl;h;hpp;HPP;H;o;O;obj;OBJ;def;DEF;rc;RC) - -foreach (lang C OBJC OBJCXX) - if (CMAKE_${lang}_COMPILER_ID_RUN) - foreach(extension IN LISTS CMAKE_${lang}_SOURCE_FILE_EXTENSIONS) - list(REMOVE_ITEM CMAKE_CXX_SOURCE_FILE_EXTENSIONS ${extension}) - endforeach() - endif() -endforeach() - -set(CMAKE_CXX_LINKER_PREFERENCE 30) -set(CMAKE_CXX_LINKER_PREFERENCE_PROPAGATES 1) - -# Save compiler ABI information. -set(CMAKE_CXX_SIZEOF_DATA_PTR "8") -set(CMAKE_CXX_COMPILER_ABI "ELF") -set(CMAKE_CXX_BYTE_ORDER "LITTLE_ENDIAN") -set(CMAKE_CXX_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") - -if(CMAKE_CXX_SIZEOF_DATA_PTR) - set(CMAKE_SIZEOF_VOID_P "${CMAKE_CXX_SIZEOF_DATA_PTR}") -endif() - -if(CMAKE_CXX_COMPILER_ABI) - set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_CXX_COMPILER_ABI}") -endif() - -if(CMAKE_CXX_LIBRARY_ARCHITECTURE) - set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") -endif() - -set(CMAKE_CXX_CL_SHOWINCLUDES_PREFIX "") -if(CMAKE_CXX_CL_SHOWINCLUDES_PREFIX) - set(CMAKE_CL_SHOWINCLUDES_PREFIX "${CMAKE_CXX_CL_SHOWINCLUDES_PREFIX}") -endif() - - - - - -set(CMAKE_CXX_IMPLICIT_INCLUDE_DIRECTORIES "/usr/include/c++/9;/usr/include/x86_64-linux-gnu/c++/9;/usr/include/c++/9/backward;/usr/lib/gcc/x86_64-linux-gnu/9/include;/usr/local/include;/usr/include/x86_64-linux-gnu;/usr/include") -set(CMAKE_CXX_IMPLICIT_LINK_LIBRARIES "stdc++;m;gcc_s;gcc;c;gcc_s;gcc") -set(CMAKE_CXX_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/9;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") -set(CMAKE_CXX_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") diff --git a/zephyr/build/CMakeFiles/3.20.2/CMakeDetermineCompilerABI_C.bin b/zephyr/build/CMakeFiles/3.20.2/CMakeDetermineCompilerABI_C.bin deleted file mode 100755 index 09f03a5..0000000 Binary files a/zephyr/build/CMakeFiles/3.20.2/CMakeDetermineCompilerABI_C.bin and /dev/null differ diff --git a/zephyr/build/CMakeFiles/3.20.2/CMakeDetermineCompilerABI_CXX.bin b/zephyr/build/CMakeFiles/3.20.2/CMakeDetermineCompilerABI_CXX.bin deleted file mode 100755 index 3ef6b10..0000000 Binary files a/zephyr/build/CMakeFiles/3.20.2/CMakeDetermineCompilerABI_CXX.bin and /dev/null differ diff --git a/zephyr/build/CMakeFiles/3.20.2/CMakeSystem.cmake b/zephyr/build/CMakeFiles/3.20.2/CMakeSystem.cmake deleted file mode 100644 index 344dc5f..0000000 --- a/zephyr/build/CMakeFiles/3.20.2/CMakeSystem.cmake +++ /dev/null @@ -1,15 +0,0 @@ -set(CMAKE_HOST_SYSTEM "Linux-5.4.0-77-generic") -set(CMAKE_HOST_SYSTEM_NAME "Linux") -set(CMAKE_HOST_SYSTEM_VERSION "5.4.0-77-generic") -set(CMAKE_HOST_SYSTEM_PROCESSOR "x86_64") - - - -set(CMAKE_SYSTEM "Linux-5.4.0-77-generic") -set(CMAKE_SYSTEM_NAME "Linux") -set(CMAKE_SYSTEM_VERSION "5.4.0-77-generic") -set(CMAKE_SYSTEM_PROCESSOR "x86_64") - -set(CMAKE_CROSSCOMPILING "FALSE") - -set(CMAKE_SYSTEM_LOADED 1) diff --git a/zephyr/build/CMakeFiles/3.20.2/CompilerIdC/CMakeCCompilerId.c b/zephyr/build/CMakeFiles/3.20.2/CompilerIdC/CMakeCCompilerId.c deleted file mode 100644 index 7e3bd53..0000000 --- a/zephyr/build/CMakeFiles/3.20.2/CompilerIdC/CMakeCCompilerId.c +++ /dev/null @@ -1,752 +0,0 @@ -#ifdef __cplusplus -# error "A C++ compiler has been selected for C." -#endif - -#if defined(__18CXX) -# define ID_VOID_MAIN -#endif -#if defined(__CLASSIC_C__) -/* cv-qualifiers did not exist in K&R C */ -# define const -# define volatile -#endif - - -/* Version number components: V=Version, R=Revision, P=Patch - Version date components: YYYY=Year, MM=Month, DD=Day */ - -#if defined(__INTEL_COMPILER) || defined(__ICC) -# define COMPILER_ID "Intel" -# if defined(_MSC_VER) -# define SIMULATE_ID "MSVC" -# endif -# if defined(__GNUC__) -# define SIMULATE_ID "GNU" -# endif - /* __INTEL_COMPILER = VRP prior to 2021, and then VVVV for 2021 and later, - except that a few beta releases use the old format with V=2021. */ -# if __INTEL_COMPILER < 2021 || __INTEL_COMPILER == 202110 || __INTEL_COMPILER == 202111 -# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100) -# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10) -# if defined(__INTEL_COMPILER_UPDATE) -# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER_UPDATE) -# else -# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10) -# endif -# else -# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER) -# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER_UPDATE) - /* The third version component from --version is an update index, - but no macro is provided for it. */ -# define COMPILER_VERSION_PATCH DEC(0) -# endif -# if defined(__INTEL_COMPILER_BUILD_DATE) - /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */ -# define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE) -# endif -# if defined(_MSC_VER) - /* _MSC_VER = VVRR */ -# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) -# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) -# endif -# if defined(__GNUC__) -# define SIMULATE_VERSION_MAJOR DEC(__GNUC__) -# elif defined(__GNUG__) -# define SIMULATE_VERSION_MAJOR DEC(__GNUG__) -# endif -# if defined(__GNUC_MINOR__) -# define SIMULATE_VERSION_MINOR DEC(__GNUC_MINOR__) -# endif -# if defined(__GNUC_PATCHLEVEL__) -# define SIMULATE_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) -# endif - -#elif (defined(__clang__) && defined(__INTEL_CLANG_COMPILER)) || defined(__INTEL_LLVM_COMPILER) -# define COMPILER_ID "IntelLLVM" -#if defined(_MSC_VER) -# define SIMULATE_ID "MSVC" -#endif -#if defined(__GNUC__) -# define SIMULATE_ID "GNU" -#endif -/* __INTEL_LLVM_COMPILER = VVVVRP prior to 2021.2.0, VVVVRRPP for 2021.2.0 and - * later. Look for 6 digit vs. 8 digit version number to decide encoding. - * VVVV is no smaller than the current year when a versio is released. - */ -#if __INTEL_LLVM_COMPILER < 1000000L -# define COMPILER_VERSION_MAJOR DEC(__INTEL_LLVM_COMPILER/100) -# define COMPILER_VERSION_MINOR DEC(__INTEL_LLVM_COMPILER/10 % 10) -# define COMPILER_VERSION_PATCH DEC(__INTEL_LLVM_COMPILER % 10) -#else -# define COMPILER_VERSION_MAJOR DEC(__INTEL_LLVM_COMPILER/10000) -# define COMPILER_VERSION_MINOR DEC(__INTEL_LLVM_COMPILER/100 % 100) -# define COMPILER_VERSION_PATCH DEC(__INTEL_LLVM_COMPILER % 100) -#endif -#if defined(_MSC_VER) - /* _MSC_VER = VVRR */ -# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) -# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) -#endif -#if defined(__GNUC__) -# define SIMULATE_VERSION_MAJOR DEC(__GNUC__) -#elif defined(__GNUG__) -# define SIMULATE_VERSION_MAJOR DEC(__GNUG__) -#endif -#if defined(__GNUC_MINOR__) -# define SIMULATE_VERSION_MINOR DEC(__GNUC_MINOR__) -#endif -#if defined(__GNUC_PATCHLEVEL__) -# define SIMULATE_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) -#endif - -#elif defined(__PATHCC__) -# define COMPILER_ID "PathScale" -# define COMPILER_VERSION_MAJOR DEC(__PATHCC__) -# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__) -# if defined(__PATHCC_PATCHLEVEL__) -# define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__) -# endif - -#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__) -# define COMPILER_ID "Embarcadero" -# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF) -# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF) -# define COMPILER_VERSION_PATCH DEC(__CODEGEARC_VERSION__ & 0xFFFF) - -#elif defined(__BORLANDC__) -# define COMPILER_ID "Borland" - /* __BORLANDC__ = 0xVRR */ -# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8) -# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF) - -#elif defined(__WATCOMC__) && __WATCOMC__ < 1200 -# define COMPILER_ID "Watcom" - /* __WATCOMC__ = VVRR */ -# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100) -# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10) -# if (__WATCOMC__ % 10) > 0 -# define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10) -# endif - -#elif defined(__WATCOMC__) -# define COMPILER_ID "OpenWatcom" - /* __WATCOMC__ = VVRP + 1100 */ -# define COMPILER_VERSION_MAJOR DEC((__WATCOMC__ - 1100) / 100) -# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10) -# if (__WATCOMC__ % 10) > 0 -# define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10) -# endif - -#elif defined(__SUNPRO_C) -# define COMPILER_ID "SunPro" -# if __SUNPRO_C >= 0x5100 - /* __SUNPRO_C = 0xVRRP */ -# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>12) -# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xFF) -# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF) -# else - /* __SUNPRO_CC = 0xVRP */ -# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>8) -# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xF) -# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF) -# endif - -#elif defined(__HP_cc) -# define COMPILER_ID "HP" - /* __HP_cc = VVRRPP */ -# define COMPILER_VERSION_MAJOR DEC(__HP_cc/10000) -# define COMPILER_VERSION_MINOR DEC(__HP_cc/100 % 100) -# define COMPILER_VERSION_PATCH DEC(__HP_cc % 100) - -#elif defined(__DECC) -# define COMPILER_ID "Compaq" - /* __DECC_VER = VVRRTPPPP */ -# define COMPILER_VERSION_MAJOR DEC(__DECC_VER/10000000) -# define COMPILER_VERSION_MINOR DEC(__DECC_VER/100000 % 100) -# define COMPILER_VERSION_PATCH DEC(__DECC_VER % 10000) - -#elif defined(__IBMC__) && defined(__COMPILER_VER__) -# define COMPILER_ID "zOS" - /* __IBMC__ = VRP */ -# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100) -# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10) -# define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10) - -#elif defined(__ibmxl__) && defined(__clang__) -# define COMPILER_ID "XLClang" -# define COMPILER_VERSION_MAJOR DEC(__ibmxl_version__) -# define COMPILER_VERSION_MINOR DEC(__ibmxl_release__) -# define COMPILER_VERSION_PATCH DEC(__ibmxl_modification__) -# define COMPILER_VERSION_TWEAK DEC(__ibmxl_ptf_fix_level__) - - -#elif defined(__IBMC__) && !defined(__COMPILER_VER__) && __IBMC__ >= 800 -# define COMPILER_ID "XL" - /* __IBMC__ = VRP */ -# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100) -# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10) -# define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10) - -#elif defined(__IBMC__) && !defined(__COMPILER_VER__) && __IBMC__ < 800 -# define COMPILER_ID "VisualAge" - /* __IBMC__ = VRP */ -# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100) -# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10) -# define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10) - -#elif defined(__NVCOMPILER) -# define COMPILER_ID "NVHPC" -# define COMPILER_VERSION_MAJOR DEC(__NVCOMPILER_MAJOR__) -# define COMPILER_VERSION_MINOR DEC(__NVCOMPILER_MINOR__) -# if defined(__NVCOMPILER_PATCHLEVEL__) -# define COMPILER_VERSION_PATCH DEC(__NVCOMPILER_PATCHLEVEL__) -# endif - -#elif defined(__PGI) -# define COMPILER_ID "PGI" -# define COMPILER_VERSION_MAJOR DEC(__PGIC__) -# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__) -# if defined(__PGIC_PATCHLEVEL__) -# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__) -# endif - -#elif defined(_CRAYC) -# define COMPILER_ID "Cray" -# define COMPILER_VERSION_MAJOR DEC(_RELEASE_MAJOR) -# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR) - -#elif defined(__TI_COMPILER_VERSION__) -# define COMPILER_ID "TI" - /* __TI_COMPILER_VERSION__ = VVVRRRPPP */ -# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000) -# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000) -# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000) - -#elif defined(__FUJITSU) || defined(__FCC_VERSION) || defined(__fcc_version) -# define COMPILER_ID "Fujitsu" - -#elif defined(__ghs__) -# define COMPILER_ID "GHS" -/* __GHS_VERSION_NUMBER = VVVVRP */ -# ifdef __GHS_VERSION_NUMBER -# define COMPILER_VERSION_MAJOR DEC(__GHS_VERSION_NUMBER / 100) -# define COMPILER_VERSION_MINOR DEC(__GHS_VERSION_NUMBER / 10 % 10) -# define COMPILER_VERSION_PATCH DEC(__GHS_VERSION_NUMBER % 10) -# endif - -#elif defined(__TINYC__) -# define COMPILER_ID "TinyCC" - -#elif defined(__BCC__) -# define COMPILER_ID "Bruce" - -#elif defined(__SCO_VERSION__) -# define COMPILER_ID "SCO" - -#elif defined(__ARMCC_VERSION) && !defined(__clang__) -# define COMPILER_ID "ARMCC" -#if __ARMCC_VERSION >= 1000000 - /* __ARMCC_VERSION = VRRPPPP */ - # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/1000000) - # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 100) - # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000) -#else - /* __ARMCC_VERSION = VRPPPP */ - # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/100000) - # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 10) - # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000) -#endif - - -#elif defined(__clang__) && defined(__apple_build_version__) -# define COMPILER_ID "AppleClang" -# if defined(_MSC_VER) -# define SIMULATE_ID "MSVC" -# endif -# define COMPILER_VERSION_MAJOR DEC(__clang_major__) -# define COMPILER_VERSION_MINOR DEC(__clang_minor__) -# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) -# if defined(_MSC_VER) - /* _MSC_VER = VVRR */ -# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) -# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) -# endif -# define COMPILER_VERSION_TWEAK DEC(__apple_build_version__) - -#elif defined(__clang__) && defined(__ARMCOMPILER_VERSION) -# define COMPILER_ID "ARMClang" - # define COMPILER_VERSION_MAJOR DEC(__ARMCOMPILER_VERSION/1000000) - # define COMPILER_VERSION_MINOR DEC(__ARMCOMPILER_VERSION/10000 % 100) - # define COMPILER_VERSION_PATCH DEC(__ARMCOMPILER_VERSION % 10000) -# define COMPILER_VERSION_INTERNAL DEC(__ARMCOMPILER_VERSION) - -#elif defined(__clang__) -# define COMPILER_ID "Clang" -# if defined(_MSC_VER) -# define SIMULATE_ID "MSVC" -# endif -# define COMPILER_VERSION_MAJOR DEC(__clang_major__) -# define COMPILER_VERSION_MINOR DEC(__clang_minor__) -# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) -# if defined(_MSC_VER) - /* _MSC_VER = VVRR */ -# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) -# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) -# endif - -#elif defined(__GNUC__) -# define COMPILER_ID "GNU" -# define COMPILER_VERSION_MAJOR DEC(__GNUC__) -# if defined(__GNUC_MINOR__) -# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__) -# endif -# if defined(__GNUC_PATCHLEVEL__) -# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) -# endif - -#elif defined(_MSC_VER) -# define COMPILER_ID "MSVC" - /* _MSC_VER = VVRR */ -# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100) -# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100) -# if defined(_MSC_FULL_VER) -# if _MSC_VER >= 1400 - /* _MSC_FULL_VER = VVRRPPPPP */ -# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000) -# else - /* _MSC_FULL_VER = VVRRPPPP */ -# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000) -# endif -# endif -# if defined(_MSC_BUILD) -# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD) -# endif - -#elif defined(__VISUALDSPVERSION__) || defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__) -# define COMPILER_ID "ADSP" -#if defined(__VISUALDSPVERSION__) - /* __VISUALDSPVERSION__ = 0xVVRRPP00 */ -# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24) -# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF) -# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF) -#endif - -#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC) -# define COMPILER_ID "IAR" -# if defined(__VER__) && defined(__ICCARM__) -# define COMPILER_VERSION_MAJOR DEC((__VER__) / 1000000) -# define COMPILER_VERSION_MINOR DEC(((__VER__) / 1000) % 1000) -# define COMPILER_VERSION_PATCH DEC((__VER__) % 1000) -# define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__) -# elif defined(__VER__) && (defined(__ICCAVR__) || defined(__ICCRX__) || defined(__ICCRH850__) || defined(__ICCRL78__) || defined(__ICC430__) || defined(__ICCRISCV__) || defined(__ICCV850__) || defined(__ICC8051__) || defined(__ICCSTM8__)) -# define COMPILER_VERSION_MAJOR DEC((__VER__) / 100) -# define COMPILER_VERSION_MINOR DEC((__VER__) - (((__VER__) / 100)*100)) -# define COMPILER_VERSION_PATCH DEC(__SUBVERSION__) -# define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__) -# endif - -#elif defined(__SDCC_VERSION_MAJOR) || defined(SDCC) -# define COMPILER_ID "SDCC" -# if defined(__SDCC_VERSION_MAJOR) -# define COMPILER_VERSION_MAJOR DEC(__SDCC_VERSION_MAJOR) -# define COMPILER_VERSION_MINOR DEC(__SDCC_VERSION_MINOR) -# define COMPILER_VERSION_PATCH DEC(__SDCC_VERSION_PATCH) -# else - /* SDCC = VRP */ -# define COMPILER_VERSION_MAJOR DEC(SDCC/100) -# define COMPILER_VERSION_MINOR DEC(SDCC/10 % 10) -# define COMPILER_VERSION_PATCH DEC(SDCC % 10) -# endif - - -/* These compilers are either not known or too old to define an - identification macro. Try to identify the platform and guess that - it is the native compiler. */ -#elif defined(__hpux) || defined(__hpua) -# define COMPILER_ID "HP" - -#else /* unknown compiler */ -# define COMPILER_ID "" -#endif - -/* Construct the string literal in pieces to prevent the source from - getting matched. Store it in a pointer rather than an array - because some compilers will just produce instructions to fill the - array rather than assigning a pointer to a static array. */ -char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]"; -#ifdef SIMULATE_ID -char const* info_simulate = "INFO" ":" "simulate[" SIMULATE_ID "]"; -#endif - -#ifdef __QNXNTO__ -char const* qnxnto = "INFO" ":" "qnxnto[]"; -#endif - -#if defined(__CRAYXT_COMPUTE_LINUX_TARGET) -char const *info_cray = "INFO" ":" "compiler_wrapper[CrayPrgEnv]"; -#endif - -#define STRINGIFY_HELPER(X) #X -#define STRINGIFY(X) STRINGIFY_HELPER(X) - -/* Identify known platforms by name. */ -#if defined(__linux) || defined(__linux__) || defined(linux) -# define PLATFORM_ID "Linux" - -#elif defined(__CYGWIN__) -# define PLATFORM_ID "Cygwin" - -#elif defined(__MINGW32__) -# define PLATFORM_ID "MinGW" - -#elif defined(__APPLE__) -# define PLATFORM_ID "Darwin" - -#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) -# define PLATFORM_ID "Windows" - -#elif defined(__FreeBSD__) || defined(__FreeBSD) -# define PLATFORM_ID "FreeBSD" - -#elif defined(__NetBSD__) || defined(__NetBSD) -# define PLATFORM_ID "NetBSD" - -#elif defined(__OpenBSD__) || defined(__OPENBSD) -# define PLATFORM_ID "OpenBSD" - -#elif defined(__sun) || defined(sun) -# define PLATFORM_ID "SunOS" - -#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__) -# define PLATFORM_ID "AIX" - -#elif defined(__hpux) || defined(__hpux__) -# define PLATFORM_ID "HP-UX" - -#elif defined(__HAIKU__) -# define PLATFORM_ID "Haiku" - -#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS) -# define PLATFORM_ID "BeOS" - -#elif defined(__QNX__) || defined(__QNXNTO__) -# define PLATFORM_ID "QNX" - -#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__) -# define PLATFORM_ID "Tru64" - -#elif defined(__riscos) || defined(__riscos__) -# define PLATFORM_ID "RISCos" - -#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__) -# define PLATFORM_ID "SINIX" - -#elif defined(__UNIX_SV__) -# define PLATFORM_ID "UNIX_SV" - -#elif defined(__bsdos__) -# define PLATFORM_ID "BSDOS" - -#elif defined(_MPRAS) || defined(MPRAS) -# define PLATFORM_ID "MP-RAS" - -#elif defined(__osf) || defined(__osf__) -# define PLATFORM_ID "OSF1" - -#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv) -# define PLATFORM_ID "SCO_SV" - -#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX) -# define PLATFORM_ID "ULTRIX" - -#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX) -# define PLATFORM_ID "Xenix" - -#elif defined(__WATCOMC__) -# if defined(__LINUX__) -# define PLATFORM_ID "Linux" - -# elif defined(__DOS__) -# define PLATFORM_ID "DOS" - -# elif defined(__OS2__) -# define PLATFORM_ID "OS2" - -# elif defined(__WINDOWS__) -# define PLATFORM_ID "Windows3x" - -# elif defined(__VXWORKS__) -# define PLATFORM_ID "VxWorks" - -# else /* unknown platform */ -# define PLATFORM_ID -# endif - -#elif defined(__INTEGRITY) -# if defined(INT_178B) -# define PLATFORM_ID "Integrity178" - -# else /* regular Integrity */ -# define PLATFORM_ID "Integrity" -# endif - -#else /* unknown platform */ -# define PLATFORM_ID - -#endif - -/* For windows compilers MSVC and Intel we can determine - the architecture of the compiler being used. This is because - the compilers do not have flags that can change the architecture, - but rather depend on which compiler is being used -*/ -#if defined(_WIN32) && defined(_MSC_VER) -# if defined(_M_IA64) -# define ARCHITECTURE_ID "IA64" - -# elif defined(_M_ARM64EC) -# define ARCHITECTURE_ID "ARM64EC" - -# elif defined(_M_X64) || defined(_M_AMD64) -# define ARCHITECTURE_ID "x64" - -# elif defined(_M_IX86) -# define ARCHITECTURE_ID "X86" - -# elif defined(_M_ARM64) -# define ARCHITECTURE_ID "ARM64" - -# elif defined(_M_ARM) -# if _M_ARM == 4 -# define ARCHITECTURE_ID "ARMV4I" -# elif _M_ARM == 5 -# define ARCHITECTURE_ID "ARMV5I" -# else -# define ARCHITECTURE_ID "ARMV" STRINGIFY(_M_ARM) -# endif - -# elif defined(_M_MIPS) -# define ARCHITECTURE_ID "MIPS" - -# elif defined(_M_SH) -# define ARCHITECTURE_ID "SHx" - -# else /* unknown architecture */ -# define ARCHITECTURE_ID "" -# endif - -#elif defined(__WATCOMC__) -# if defined(_M_I86) -# define ARCHITECTURE_ID "I86" - -# elif defined(_M_IX86) -# define ARCHITECTURE_ID "X86" - -# else /* unknown architecture */ -# define ARCHITECTURE_ID "" -# endif - -#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC) -# if defined(__ICCARM__) -# define ARCHITECTURE_ID "ARM" - -# elif defined(__ICCRX__) -# define ARCHITECTURE_ID "RX" - -# elif defined(__ICCRH850__) -# define ARCHITECTURE_ID "RH850" - -# elif defined(__ICCRL78__) -# define ARCHITECTURE_ID "RL78" - -# elif defined(__ICCRISCV__) -# define ARCHITECTURE_ID "RISCV" - -# elif defined(__ICCAVR__) -# define ARCHITECTURE_ID "AVR" - -# elif defined(__ICC430__) -# define ARCHITECTURE_ID "MSP430" - -# elif defined(__ICCV850__) -# define ARCHITECTURE_ID "V850" - -# elif defined(__ICC8051__) -# define ARCHITECTURE_ID "8051" - -# elif defined(__ICCSTM8__) -# define ARCHITECTURE_ID "STM8" - -# else /* unknown architecture */ -# define ARCHITECTURE_ID "" -# endif - -#elif defined(__ghs__) -# if defined(__PPC64__) -# define ARCHITECTURE_ID "PPC64" - -# elif defined(__ppc__) -# define ARCHITECTURE_ID "PPC" - -# elif defined(__ARM__) -# define ARCHITECTURE_ID "ARM" - -# elif defined(__x86_64__) -# define ARCHITECTURE_ID "x64" - -# elif defined(__i386__) -# define ARCHITECTURE_ID "X86" - -# else /* unknown architecture */ -# define ARCHITECTURE_ID "" -# endif - -#elif defined(__TI_COMPILER_VERSION__) -# if defined(__TI_ARM__) -# define ARCHITECTURE_ID "ARM" - -# elif defined(__MSP430__) -# define ARCHITECTURE_ID "MSP430" - -# elif defined(__TMS320C28XX__) -# define ARCHITECTURE_ID "TMS320C28x" - -# elif defined(__TMS320C6X__) || defined(_TMS320C6X) -# define ARCHITECTURE_ID "TMS320C6x" - -# else /* unknown architecture */ -# define ARCHITECTURE_ID "" -# endif - -#else -# define ARCHITECTURE_ID -#endif - -/* Convert integer to decimal digit literals. */ -#define DEC(n) \ - ('0' + (((n) / 10000000)%10)), \ - ('0' + (((n) / 1000000)%10)), \ - ('0' + (((n) / 100000)%10)), \ - ('0' + (((n) / 10000)%10)), \ - ('0' + (((n) / 1000)%10)), \ - ('0' + (((n) / 100)%10)), \ - ('0' + (((n) / 10)%10)), \ - ('0' + ((n) % 10)) - -/* Convert integer to hex digit literals. */ -#define HEX(n) \ - ('0' + ((n)>>28 & 0xF)), \ - ('0' + ((n)>>24 & 0xF)), \ - ('0' + ((n)>>20 & 0xF)), \ - ('0' + ((n)>>16 & 0xF)), \ - ('0' + ((n)>>12 & 0xF)), \ - ('0' + ((n)>>8 & 0xF)), \ - ('0' + ((n)>>4 & 0xF)), \ - ('0' + ((n) & 0xF)) - -/* Construct a string literal encoding the version number components. */ -#ifdef COMPILER_VERSION_MAJOR -char const info_version[] = { - 'I', 'N', 'F', 'O', ':', - 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[', - COMPILER_VERSION_MAJOR, -# ifdef COMPILER_VERSION_MINOR - '.', COMPILER_VERSION_MINOR, -# ifdef COMPILER_VERSION_PATCH - '.', COMPILER_VERSION_PATCH, -# ifdef COMPILER_VERSION_TWEAK - '.', COMPILER_VERSION_TWEAK, -# endif -# endif -# endif - ']','\0'}; -#endif - -/* Construct a string literal encoding the internal version number. */ -#ifdef COMPILER_VERSION_INTERNAL -char const info_version_internal[] = { - 'I', 'N', 'F', 'O', ':', - 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','_', - 'i','n','t','e','r','n','a','l','[', - COMPILER_VERSION_INTERNAL,']','\0'}; -#endif - -/* Construct a string literal encoding the version number components. */ -#ifdef SIMULATE_VERSION_MAJOR -char const info_simulate_version[] = { - 'I', 'N', 'F', 'O', ':', - 's','i','m','u','l','a','t','e','_','v','e','r','s','i','o','n','[', - SIMULATE_VERSION_MAJOR, -# ifdef SIMULATE_VERSION_MINOR - '.', SIMULATE_VERSION_MINOR, -# ifdef SIMULATE_VERSION_PATCH - '.', SIMULATE_VERSION_PATCH, -# ifdef SIMULATE_VERSION_TWEAK - '.', SIMULATE_VERSION_TWEAK, -# endif -# endif -# endif - ']','\0'}; -#endif - -/* Construct the string literal in pieces to prevent the source from - getting matched. Store it in a pointer rather than an array - because some compilers will just produce instructions to fill the - array rather than assigning a pointer to a static array. */ -char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]"; -char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]"; - - - -#if !defined(__STDC__) -# if (defined(_MSC_VER) && !defined(__clang__)) \ - || (defined(__ibmxl__) || defined(__IBMC__)) -# define C_DIALECT "90" -# else -# define C_DIALECT -# endif -#elif __STDC_VERSION__ >= 201000L -# define C_DIALECT "11" -#elif __STDC_VERSION__ >= 199901L -# define C_DIALECT "99" -#else -# define C_DIALECT "90" -#endif -const char* info_language_dialect_default = - "INFO" ":" "dialect_default[" C_DIALECT "]"; - -/*--------------------------------------------------------------------------*/ - -#ifdef ID_VOID_MAIN -void main() {} -#else -# if defined(__CLASSIC_C__) -int main(argc, argv) int argc; char *argv[]; -# else -int main(int argc, char* argv[]) -# endif -{ - int require = 0; - require += info_compiler[argc]; - require += info_platform[argc]; - require += info_arch[argc]; -#ifdef COMPILER_VERSION_MAJOR - require += info_version[argc]; -#endif -#ifdef COMPILER_VERSION_INTERNAL - require += info_version_internal[argc]; -#endif -#ifdef SIMULATE_ID - require += info_simulate[argc]; -#endif -#ifdef SIMULATE_VERSION_MAJOR - require += info_simulate_version[argc]; -#endif -#if defined(__CRAYXT_COMPUTE_LINUX_TARGET) - require += info_cray[argc]; -#endif - require += info_language_dialect_default[argc]; - (void)argv; - return require; -} -#endif diff --git a/zephyr/build/CMakeFiles/3.20.2/CompilerIdC/a.out b/zephyr/build/CMakeFiles/3.20.2/CompilerIdC/a.out deleted file mode 100755 index 46f1233..0000000 Binary files a/zephyr/build/CMakeFiles/3.20.2/CompilerIdC/a.out and /dev/null differ diff --git a/zephyr/build/CMakeFiles/3.20.2/CompilerIdCXX/CMakeCXXCompilerId.cpp b/zephyr/build/CMakeFiles/3.20.2/CompilerIdCXX/CMakeCXXCompilerId.cpp deleted file mode 100644 index 92e7655..0000000 --- a/zephyr/build/CMakeFiles/3.20.2/CompilerIdCXX/CMakeCXXCompilerId.cpp +++ /dev/null @@ -1,743 +0,0 @@ -/* This source file must have a .cpp extension so that all C++ compilers - recognize the extension without flags. Borland does not know .cxx for - example. */ -#ifndef __cplusplus -# error "A C compiler has been selected for C++." -#endif - - -/* Version number components: V=Version, R=Revision, P=Patch - Version date components: YYYY=Year, MM=Month, DD=Day */ - -#if defined(__COMO__) -# define COMPILER_ID "Comeau" - /* __COMO_VERSION__ = VRR */ -# define COMPILER_VERSION_MAJOR DEC(__COMO_VERSION__ / 100) -# define COMPILER_VERSION_MINOR DEC(__COMO_VERSION__ % 100) - -#elif defined(__INTEL_COMPILER) || defined(__ICC) -# define COMPILER_ID "Intel" -# if defined(_MSC_VER) -# define SIMULATE_ID "MSVC" -# endif -# if defined(__GNUC__) -# define SIMULATE_ID "GNU" -# endif - /* __INTEL_COMPILER = VRP prior to 2021, and then VVVV for 2021 and later, - except that a few beta releases use the old format with V=2021. */ -# if __INTEL_COMPILER < 2021 || __INTEL_COMPILER == 202110 || __INTEL_COMPILER == 202111 -# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100) -# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10) -# if defined(__INTEL_COMPILER_UPDATE) -# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER_UPDATE) -# else -# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10) -# endif -# else -# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER) -# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER_UPDATE) - /* The third version component from --version is an update index, - but no macro is provided for it. */ -# define COMPILER_VERSION_PATCH DEC(0) -# endif -# if defined(__INTEL_COMPILER_BUILD_DATE) - /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */ -# define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE) -# endif -# if defined(_MSC_VER) - /* _MSC_VER = VVRR */ -# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) -# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) -# endif -# if defined(__GNUC__) -# define SIMULATE_VERSION_MAJOR DEC(__GNUC__) -# elif defined(__GNUG__) -# define SIMULATE_VERSION_MAJOR DEC(__GNUG__) -# endif -# if defined(__GNUC_MINOR__) -# define SIMULATE_VERSION_MINOR DEC(__GNUC_MINOR__) -# endif -# if defined(__GNUC_PATCHLEVEL__) -# define SIMULATE_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) -# endif - -#elif (defined(__clang__) && defined(__INTEL_CLANG_COMPILER)) || defined(__INTEL_LLVM_COMPILER) -# define COMPILER_ID "IntelLLVM" -#if defined(_MSC_VER) -# define SIMULATE_ID "MSVC" -#endif -#if defined(__GNUC__) -# define SIMULATE_ID "GNU" -#endif -/* __INTEL_LLVM_COMPILER = VVVVRP prior to 2021.2.0, VVVVRRPP for 2021.2.0 and - * later. Look for 6 digit vs. 8 digit version number to decide encoding. - * VVVV is no smaller than the current year when a versio is released. - */ -#if __INTEL_LLVM_COMPILER < 1000000L -# define COMPILER_VERSION_MAJOR DEC(__INTEL_LLVM_COMPILER/100) -# define COMPILER_VERSION_MINOR DEC(__INTEL_LLVM_COMPILER/10 % 10) -# define COMPILER_VERSION_PATCH DEC(__INTEL_LLVM_COMPILER % 10) -#else -# define COMPILER_VERSION_MAJOR DEC(__INTEL_LLVM_COMPILER/10000) -# define COMPILER_VERSION_MINOR DEC(__INTEL_LLVM_COMPILER/100 % 100) -# define COMPILER_VERSION_PATCH DEC(__INTEL_LLVM_COMPILER % 100) -#endif -#if defined(_MSC_VER) - /* _MSC_VER = VVRR */ -# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) -# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) -#endif -#if defined(__GNUC__) -# define SIMULATE_VERSION_MAJOR DEC(__GNUC__) -#elif defined(__GNUG__) -# define SIMULATE_VERSION_MAJOR DEC(__GNUG__) -#endif -#if defined(__GNUC_MINOR__) -# define SIMULATE_VERSION_MINOR DEC(__GNUC_MINOR__) -#endif -#if defined(__GNUC_PATCHLEVEL__) -# define SIMULATE_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) -#endif - -#elif defined(__PATHCC__) -# define COMPILER_ID "PathScale" -# define COMPILER_VERSION_MAJOR DEC(__PATHCC__) -# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__) -# if defined(__PATHCC_PATCHLEVEL__) -# define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__) -# endif - -#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__) -# define COMPILER_ID "Embarcadero" -# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF) -# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF) -# define COMPILER_VERSION_PATCH DEC(__CODEGEARC_VERSION__ & 0xFFFF) - -#elif defined(__BORLANDC__) -# define COMPILER_ID "Borland" - /* __BORLANDC__ = 0xVRR */ -# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8) -# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF) - -#elif defined(__WATCOMC__) && __WATCOMC__ < 1200 -# define COMPILER_ID "Watcom" - /* __WATCOMC__ = VVRR */ -# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100) -# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10) -# if (__WATCOMC__ % 10) > 0 -# define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10) -# endif - -#elif defined(__WATCOMC__) -# define COMPILER_ID "OpenWatcom" - /* __WATCOMC__ = VVRP + 1100 */ -# define COMPILER_VERSION_MAJOR DEC((__WATCOMC__ - 1100) / 100) -# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10) -# if (__WATCOMC__ % 10) > 0 -# define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10) -# endif - -#elif defined(__SUNPRO_CC) -# define COMPILER_ID "SunPro" -# if __SUNPRO_CC >= 0x5100 - /* __SUNPRO_CC = 0xVRRP */ -# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>12) -# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xFF) -# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF) -# else - /* __SUNPRO_CC = 0xVRP */ -# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>8) -# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xF) -# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF) -# endif - -#elif defined(__HP_aCC) -# define COMPILER_ID "HP" - /* __HP_aCC = VVRRPP */ -# define COMPILER_VERSION_MAJOR DEC(__HP_aCC/10000) -# define COMPILER_VERSION_MINOR DEC(__HP_aCC/100 % 100) -# define COMPILER_VERSION_PATCH DEC(__HP_aCC % 100) - -#elif defined(__DECCXX) -# define COMPILER_ID "Compaq" - /* __DECCXX_VER = VVRRTPPPP */ -# define COMPILER_VERSION_MAJOR DEC(__DECCXX_VER/10000000) -# define COMPILER_VERSION_MINOR DEC(__DECCXX_VER/100000 % 100) -# define COMPILER_VERSION_PATCH DEC(__DECCXX_VER % 10000) - -#elif defined(__IBMCPP__) && defined(__COMPILER_VER__) -# define COMPILER_ID "zOS" - /* __IBMCPP__ = VRP */ -# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100) -# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10) -# define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10) - -#elif defined(__ibmxl__) && defined(__clang__) -# define COMPILER_ID "XLClang" -# define COMPILER_VERSION_MAJOR DEC(__ibmxl_version__) -# define COMPILER_VERSION_MINOR DEC(__ibmxl_release__) -# define COMPILER_VERSION_PATCH DEC(__ibmxl_modification__) -# define COMPILER_VERSION_TWEAK DEC(__ibmxl_ptf_fix_level__) - - -#elif defined(__IBMCPP__) && !defined(__COMPILER_VER__) && __IBMCPP__ >= 800 -# define COMPILER_ID "XL" - /* __IBMCPP__ = VRP */ -# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100) -# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10) -# define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10) - -#elif defined(__IBMCPP__) && !defined(__COMPILER_VER__) && __IBMCPP__ < 800 -# define COMPILER_ID "VisualAge" - /* __IBMCPP__ = VRP */ -# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100) -# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10) -# define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10) - -#elif defined(__NVCOMPILER) -# define COMPILER_ID "NVHPC" -# define COMPILER_VERSION_MAJOR DEC(__NVCOMPILER_MAJOR__) -# define COMPILER_VERSION_MINOR DEC(__NVCOMPILER_MINOR__) -# if defined(__NVCOMPILER_PATCHLEVEL__) -# define COMPILER_VERSION_PATCH DEC(__NVCOMPILER_PATCHLEVEL__) -# endif - -#elif defined(__PGI) -# define COMPILER_ID "PGI" -# define COMPILER_VERSION_MAJOR DEC(__PGIC__) -# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__) -# if defined(__PGIC_PATCHLEVEL__) -# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__) -# endif - -#elif defined(_CRAYC) -# define COMPILER_ID "Cray" -# define COMPILER_VERSION_MAJOR DEC(_RELEASE_MAJOR) -# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR) - -#elif defined(__TI_COMPILER_VERSION__) -# define COMPILER_ID "TI" - /* __TI_COMPILER_VERSION__ = VVVRRRPPP */ -# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000) -# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000) -# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000) - -#elif defined(__FUJITSU) || defined(__FCC_VERSION) || defined(__fcc_version) -# define COMPILER_ID "Fujitsu" - -#elif defined(__ghs__) -# define COMPILER_ID "GHS" -/* __GHS_VERSION_NUMBER = VVVVRP */ -# ifdef __GHS_VERSION_NUMBER -# define COMPILER_VERSION_MAJOR DEC(__GHS_VERSION_NUMBER / 100) -# define COMPILER_VERSION_MINOR DEC(__GHS_VERSION_NUMBER / 10 % 10) -# define COMPILER_VERSION_PATCH DEC(__GHS_VERSION_NUMBER % 10) -# endif - -#elif defined(__SCO_VERSION__) -# define COMPILER_ID "SCO" - -#elif defined(__ARMCC_VERSION) && !defined(__clang__) -# define COMPILER_ID "ARMCC" -#if __ARMCC_VERSION >= 1000000 - /* __ARMCC_VERSION = VRRPPPP */ - # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/1000000) - # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 100) - # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000) -#else - /* __ARMCC_VERSION = VRPPPP */ - # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/100000) - # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 10) - # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000) -#endif - - -#elif defined(__clang__) && defined(__apple_build_version__) -# define COMPILER_ID "AppleClang" -# if defined(_MSC_VER) -# define SIMULATE_ID "MSVC" -# endif -# define COMPILER_VERSION_MAJOR DEC(__clang_major__) -# define COMPILER_VERSION_MINOR DEC(__clang_minor__) -# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) -# if defined(_MSC_VER) - /* _MSC_VER = VVRR */ -# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) -# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) -# endif -# define COMPILER_VERSION_TWEAK DEC(__apple_build_version__) - -#elif defined(__clang__) && defined(__ARMCOMPILER_VERSION) -# define COMPILER_ID "ARMClang" - # define COMPILER_VERSION_MAJOR DEC(__ARMCOMPILER_VERSION/1000000) - # define COMPILER_VERSION_MINOR DEC(__ARMCOMPILER_VERSION/10000 % 100) - # define COMPILER_VERSION_PATCH DEC(__ARMCOMPILER_VERSION % 10000) -# define COMPILER_VERSION_INTERNAL DEC(__ARMCOMPILER_VERSION) - -#elif defined(__clang__) -# define COMPILER_ID "Clang" -# if defined(_MSC_VER) -# define SIMULATE_ID "MSVC" -# endif -# define COMPILER_VERSION_MAJOR DEC(__clang_major__) -# define COMPILER_VERSION_MINOR DEC(__clang_minor__) -# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) -# if defined(_MSC_VER) - /* _MSC_VER = VVRR */ -# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) -# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) -# endif - -#elif defined(__GNUC__) || defined(__GNUG__) -# define COMPILER_ID "GNU" -# if defined(__GNUC__) -# define COMPILER_VERSION_MAJOR DEC(__GNUC__) -# else -# define COMPILER_VERSION_MAJOR DEC(__GNUG__) -# endif -# if defined(__GNUC_MINOR__) -# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__) -# endif -# if defined(__GNUC_PATCHLEVEL__) -# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) -# endif - -#elif defined(_MSC_VER) -# define COMPILER_ID "MSVC" - /* _MSC_VER = VVRR */ -# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100) -# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100) -# if defined(_MSC_FULL_VER) -# if _MSC_VER >= 1400 - /* _MSC_FULL_VER = VVRRPPPPP */ -# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000) -# else - /* _MSC_FULL_VER = VVRRPPPP */ -# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000) -# endif -# endif -# if defined(_MSC_BUILD) -# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD) -# endif - -#elif defined(__VISUALDSPVERSION__) || defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__) -# define COMPILER_ID "ADSP" -#if defined(__VISUALDSPVERSION__) - /* __VISUALDSPVERSION__ = 0xVVRRPP00 */ -# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24) -# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF) -# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF) -#endif - -#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC) -# define COMPILER_ID "IAR" -# if defined(__VER__) && defined(__ICCARM__) -# define COMPILER_VERSION_MAJOR DEC((__VER__) / 1000000) -# define COMPILER_VERSION_MINOR DEC(((__VER__) / 1000) % 1000) -# define COMPILER_VERSION_PATCH DEC((__VER__) % 1000) -# define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__) -# elif defined(__VER__) && (defined(__ICCAVR__) || defined(__ICCRX__) || defined(__ICCRH850__) || defined(__ICCRL78__) || defined(__ICC430__) || defined(__ICCRISCV__) || defined(__ICCV850__) || defined(__ICC8051__) || defined(__ICCSTM8__)) -# define COMPILER_VERSION_MAJOR DEC((__VER__) / 100) -# define COMPILER_VERSION_MINOR DEC((__VER__) - (((__VER__) / 100)*100)) -# define COMPILER_VERSION_PATCH DEC(__SUBVERSION__) -# define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__) -# endif - - -/* These compilers are either not known or too old to define an - identification macro. Try to identify the platform and guess that - it is the native compiler. */ -#elif defined(__hpux) || defined(__hpua) -# define COMPILER_ID "HP" - -#else /* unknown compiler */ -# define COMPILER_ID "" -#endif - -/* Construct the string literal in pieces to prevent the source from - getting matched. Store it in a pointer rather than an array - because some compilers will just produce instructions to fill the - array rather than assigning a pointer to a static array. */ -char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]"; -#ifdef SIMULATE_ID -char const* info_simulate = "INFO" ":" "simulate[" SIMULATE_ID "]"; -#endif - -#ifdef __QNXNTO__ -char const* qnxnto = "INFO" ":" "qnxnto[]"; -#endif - -#if defined(__CRAYXT_COMPUTE_LINUX_TARGET) -char const *info_cray = "INFO" ":" "compiler_wrapper[CrayPrgEnv]"; -#endif - -#define STRINGIFY_HELPER(X) #X -#define STRINGIFY(X) STRINGIFY_HELPER(X) - -/* Identify known platforms by name. */ -#if defined(__linux) || defined(__linux__) || defined(linux) -# define PLATFORM_ID "Linux" - -#elif defined(__CYGWIN__) -# define PLATFORM_ID "Cygwin" - -#elif defined(__MINGW32__) -# define PLATFORM_ID "MinGW" - -#elif defined(__APPLE__) -# define PLATFORM_ID "Darwin" - -#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) -# define PLATFORM_ID "Windows" - -#elif defined(__FreeBSD__) || defined(__FreeBSD) -# define PLATFORM_ID "FreeBSD" - -#elif defined(__NetBSD__) || defined(__NetBSD) -# define PLATFORM_ID "NetBSD" - -#elif defined(__OpenBSD__) || defined(__OPENBSD) -# define PLATFORM_ID "OpenBSD" - -#elif defined(__sun) || defined(sun) -# define PLATFORM_ID "SunOS" - -#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__) -# define PLATFORM_ID "AIX" - -#elif defined(__hpux) || defined(__hpux__) -# define PLATFORM_ID "HP-UX" - -#elif defined(__HAIKU__) -# define PLATFORM_ID "Haiku" - -#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS) -# define PLATFORM_ID "BeOS" - -#elif defined(__QNX__) || defined(__QNXNTO__) -# define PLATFORM_ID "QNX" - -#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__) -# define PLATFORM_ID "Tru64" - -#elif defined(__riscos) || defined(__riscos__) -# define PLATFORM_ID "RISCos" - -#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__) -# define PLATFORM_ID "SINIX" - -#elif defined(__UNIX_SV__) -# define PLATFORM_ID "UNIX_SV" - -#elif defined(__bsdos__) -# define PLATFORM_ID "BSDOS" - -#elif defined(_MPRAS) || defined(MPRAS) -# define PLATFORM_ID "MP-RAS" - -#elif defined(__osf) || defined(__osf__) -# define PLATFORM_ID "OSF1" - -#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv) -# define PLATFORM_ID "SCO_SV" - -#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX) -# define PLATFORM_ID "ULTRIX" - -#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX) -# define PLATFORM_ID "Xenix" - -#elif defined(__WATCOMC__) -# if defined(__LINUX__) -# define PLATFORM_ID "Linux" - -# elif defined(__DOS__) -# define PLATFORM_ID "DOS" - -# elif defined(__OS2__) -# define PLATFORM_ID "OS2" - -# elif defined(__WINDOWS__) -# define PLATFORM_ID "Windows3x" - -# elif defined(__VXWORKS__) -# define PLATFORM_ID "VxWorks" - -# else /* unknown platform */ -# define PLATFORM_ID -# endif - -#elif defined(__INTEGRITY) -# if defined(INT_178B) -# define PLATFORM_ID "Integrity178" - -# else /* regular Integrity */ -# define PLATFORM_ID "Integrity" -# endif - -#else /* unknown platform */ -# define PLATFORM_ID - -#endif - -/* For windows compilers MSVC and Intel we can determine - the architecture of the compiler being used. This is because - the compilers do not have flags that can change the architecture, - but rather depend on which compiler is being used -*/ -#if defined(_WIN32) && defined(_MSC_VER) -# if defined(_M_IA64) -# define ARCHITECTURE_ID "IA64" - -# elif defined(_M_ARM64EC) -# define ARCHITECTURE_ID "ARM64EC" - -# elif defined(_M_X64) || defined(_M_AMD64) -# define ARCHITECTURE_ID "x64" - -# elif defined(_M_IX86) -# define ARCHITECTURE_ID "X86" - -# elif defined(_M_ARM64) -# define ARCHITECTURE_ID "ARM64" - -# elif defined(_M_ARM) -# if _M_ARM == 4 -# define ARCHITECTURE_ID "ARMV4I" -# elif _M_ARM == 5 -# define ARCHITECTURE_ID "ARMV5I" -# else -# define ARCHITECTURE_ID "ARMV" STRINGIFY(_M_ARM) -# endif - -# elif defined(_M_MIPS) -# define ARCHITECTURE_ID "MIPS" - -# elif defined(_M_SH) -# define ARCHITECTURE_ID "SHx" - -# else /* unknown architecture */ -# define ARCHITECTURE_ID "" -# endif - -#elif defined(__WATCOMC__) -# if defined(_M_I86) -# define ARCHITECTURE_ID "I86" - -# elif defined(_M_IX86) -# define ARCHITECTURE_ID "X86" - -# else /* unknown architecture */ -# define ARCHITECTURE_ID "" -# endif - -#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC) -# if defined(__ICCARM__) -# define ARCHITECTURE_ID "ARM" - -# elif defined(__ICCRX__) -# define ARCHITECTURE_ID "RX" - -# elif defined(__ICCRH850__) -# define ARCHITECTURE_ID "RH850" - -# elif defined(__ICCRL78__) -# define ARCHITECTURE_ID "RL78" - -# elif defined(__ICCRISCV__) -# define ARCHITECTURE_ID "RISCV" - -# elif defined(__ICCAVR__) -# define ARCHITECTURE_ID "AVR" - -# elif defined(__ICC430__) -# define ARCHITECTURE_ID "MSP430" - -# elif defined(__ICCV850__) -# define ARCHITECTURE_ID "V850" - -# elif defined(__ICC8051__) -# define ARCHITECTURE_ID "8051" - -# elif defined(__ICCSTM8__) -# define ARCHITECTURE_ID "STM8" - -# else /* unknown architecture */ -# define ARCHITECTURE_ID "" -# endif - -#elif defined(__ghs__) -# if defined(__PPC64__) -# define ARCHITECTURE_ID "PPC64" - -# elif defined(__ppc__) -# define ARCHITECTURE_ID "PPC" - -# elif defined(__ARM__) -# define ARCHITECTURE_ID "ARM" - -# elif defined(__x86_64__) -# define ARCHITECTURE_ID "x64" - -# elif defined(__i386__) -# define ARCHITECTURE_ID "X86" - -# else /* unknown architecture */ -# define ARCHITECTURE_ID "" -# endif - -#elif defined(__TI_COMPILER_VERSION__) -# if defined(__TI_ARM__) -# define ARCHITECTURE_ID "ARM" - -# elif defined(__MSP430__) -# define ARCHITECTURE_ID "MSP430" - -# elif defined(__TMS320C28XX__) -# define ARCHITECTURE_ID "TMS320C28x" - -# elif defined(__TMS320C6X__) || defined(_TMS320C6X) -# define ARCHITECTURE_ID "TMS320C6x" - -# else /* unknown architecture */ -# define ARCHITECTURE_ID "" -# endif - -#else -# define ARCHITECTURE_ID -#endif - -/* Convert integer to decimal digit literals. */ -#define DEC(n) \ - ('0' + (((n) / 10000000)%10)), \ - ('0' + (((n) / 1000000)%10)), \ - ('0' + (((n) / 100000)%10)), \ - ('0' + (((n) / 10000)%10)), \ - ('0' + (((n) / 1000)%10)), \ - ('0' + (((n) / 100)%10)), \ - ('0' + (((n) / 10)%10)), \ - ('0' + ((n) % 10)) - -/* Convert integer to hex digit literals. */ -#define HEX(n) \ - ('0' + ((n)>>28 & 0xF)), \ - ('0' + ((n)>>24 & 0xF)), \ - ('0' + ((n)>>20 & 0xF)), \ - ('0' + ((n)>>16 & 0xF)), \ - ('0' + ((n)>>12 & 0xF)), \ - ('0' + ((n)>>8 & 0xF)), \ - ('0' + ((n)>>4 & 0xF)), \ - ('0' + ((n) & 0xF)) - -/* Construct a string literal encoding the version number components. */ -#ifdef COMPILER_VERSION_MAJOR -char const info_version[] = { - 'I', 'N', 'F', 'O', ':', - 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[', - COMPILER_VERSION_MAJOR, -# ifdef COMPILER_VERSION_MINOR - '.', COMPILER_VERSION_MINOR, -# ifdef COMPILER_VERSION_PATCH - '.', COMPILER_VERSION_PATCH, -# ifdef COMPILER_VERSION_TWEAK - '.', COMPILER_VERSION_TWEAK, -# endif -# endif -# endif - ']','\0'}; -#endif - -/* Construct a string literal encoding the internal version number. */ -#ifdef COMPILER_VERSION_INTERNAL -char const info_version_internal[] = { - 'I', 'N', 'F', 'O', ':', - 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','_', - 'i','n','t','e','r','n','a','l','[', - COMPILER_VERSION_INTERNAL,']','\0'}; -#endif - -/* Construct a string literal encoding the version number components. */ -#ifdef SIMULATE_VERSION_MAJOR -char const info_simulate_version[] = { - 'I', 'N', 'F', 'O', ':', - 's','i','m','u','l','a','t','e','_','v','e','r','s','i','o','n','[', - SIMULATE_VERSION_MAJOR, -# ifdef SIMULATE_VERSION_MINOR - '.', SIMULATE_VERSION_MINOR, -# ifdef SIMULATE_VERSION_PATCH - '.', SIMULATE_VERSION_PATCH, -# ifdef SIMULATE_VERSION_TWEAK - '.', SIMULATE_VERSION_TWEAK, -# endif -# endif -# endif - ']','\0'}; -#endif - -/* Construct the string literal in pieces to prevent the source from - getting matched. Store it in a pointer rather than an array - because some compilers will just produce instructions to fill the - array rather than assigning a pointer to a static array. */ -char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]"; -char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]"; - - - -#if defined(__INTEL_COMPILER) && defined(_MSVC_LANG) && _MSVC_LANG < 201403L -# if defined(__INTEL_CXX11_MODE__) -# if defined(__cpp_aggregate_nsdmi) -# define CXX_STD 201402L -# else -# define CXX_STD 201103L -# endif -# else -# define CXX_STD 199711L -# endif -#elif defined(_MSC_VER) && defined(_MSVC_LANG) -# define CXX_STD _MSVC_LANG -#else -# define CXX_STD __cplusplus -#endif - -const char* info_language_dialect_default = "INFO" ":" "dialect_default[" -#if CXX_STD > 202002L - "23" -#elif CXX_STD > 201703L - "20" -#elif CXX_STD >= 201703L - "17" -#elif CXX_STD >= 201402L - "14" -#elif CXX_STD >= 201103L - "11" -#else - "98" -#endif -"]"; - -/*--------------------------------------------------------------------------*/ - -int main(int argc, char* argv[]) -{ - int require = 0; - require += info_compiler[argc]; - require += info_platform[argc]; -#ifdef COMPILER_VERSION_MAJOR - require += info_version[argc]; -#endif -#ifdef COMPILER_VERSION_INTERNAL - require += info_version_internal[argc]; -#endif -#ifdef SIMULATE_ID - require += info_simulate[argc]; -#endif -#ifdef SIMULATE_VERSION_MAJOR - require += info_simulate_version[argc]; -#endif -#if defined(__CRAYXT_COMPUTE_LINUX_TARGET) - require += info_cray[argc]; -#endif - require += info_language_dialect_default[argc]; - (void)argv; - return require; -} diff --git a/zephyr/build/CMakeFiles/3.20.2/CompilerIdCXX/a.out b/zephyr/build/CMakeFiles/3.20.2/CompilerIdCXX/a.out deleted file mode 100755 index c868426..0000000 Binary files a/zephyr/build/CMakeFiles/3.20.2/CompilerIdCXX/a.out and /dev/null differ diff --git a/zephyr/build/CMakeFiles/CMakeOutput.log b/zephyr/build/CMakeFiles/CMakeOutput.log deleted file mode 100644 index d6d2d74..0000000 --- a/zephyr/build/CMakeFiles/CMakeOutput.log +++ /dev/null @@ -1,419 +0,0 @@ -The system is: Linux - 5.4.0-77-generic - x86_64 -Compiling the C compiler identification source file "CMakeCCompilerId.c" succeeded. -Compiler: /usr/bin/cc -Build flags: -Id flags: - -The output was: -0 - - -Compilation of the C compiler identification source "CMakeCCompilerId.c" produced "a.out" - -The C compiler identification is GNU, found in "/home/gebler/Dokumente/Medit/MedExo/epos4_zephyr/build/CMakeFiles/3.20.2/CompilerIdC/a.out" - -Compiling the CXX compiler identification source file "CMakeCXXCompilerId.cpp" succeeded. -Compiler: /usr/bin/c++ -Build flags: -Id flags: - -The output was: -0 - - -Compilation of the CXX compiler identification source "CMakeCXXCompilerId.cpp" produced "a.out" - -The CXX compiler identification is GNU, found in "/home/gebler/Dokumente/Medit/MedExo/epos4_zephyr/build/CMakeFiles/3.20.2/CompilerIdCXX/a.out" - -Detecting C compiler ABI info compiled with the following output: -Change Dir: /home/gebler/Dokumente/Medit/MedExo/epos4_zephyr/build/CMakeFiles/CMakeTmp - -Run Build Command(s):/usr/bin/ninja cmTC_5a185 && [1/2] Building C object CMakeFiles/cmTC_5a185.dir/CMakeCCompilerABI.c.o -Using built-in specs. -COLLECT_GCC=/usr/bin/cc -OFFLOAD_TARGET_NAMES=nvptx-none:hsa -OFFLOAD_TARGET_DEFAULT=1 -Target: x86_64-linux-gnu -Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.3.0-17ubuntu1~20.04' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c,ada,c++,go,brig,d,fortran,objc,obj-c++,gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-HskZEa/gcc-9-9.3.0/debian/tmp-nvptx/usr,hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu -Thread model: posix -gcc version 9.3.0 (Ubuntu 9.3.0-17ubuntu1~20.04) -COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_5a185.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64' - /usr/lib/gcc/x86_64-linux-gnu/9/cc1 -quiet -v -imultiarch x86_64-linux-gnu /usr/share/cmake-3.20/Modules/CMakeCCompilerABI.c -quiet -dumpbase CMakeCCompilerABI.c -mtune=generic -march=x86-64 -auxbase-strip CMakeFiles/cmTC_5a185.dir/CMakeCCompilerABI.c.o -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -fcf-protection -o /tmp/cc8lF2F9.s -GNU C17 (Ubuntu 9.3.0-17ubuntu1~20.04) version 9.3.0 (x86_64-linux-gnu) - compiled by GNU C version 9.3.0, GMP version 6.2.0, MPFR version 4.0.2, MPC version 1.1.0, isl version isl-0.22.1-GMP - -GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072 -ignoring nonexistent directory "/usr/local/include/x86_64-linux-gnu" -ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/include-fixed" -ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/../../../../x86_64-linux-gnu/include" -#include "..." search starts here: -#include <...> search starts here: - /usr/lib/gcc/x86_64-linux-gnu/9/include - /usr/local/include - /usr/include/x86_64-linux-gnu - /usr/include -End of search list. -GNU C17 (Ubuntu 9.3.0-17ubuntu1~20.04) version 9.3.0 (x86_64-linux-gnu) - compiled by GNU C version 9.3.0, GMP version 6.2.0, MPFR version 4.0.2, MPC version 1.1.0, isl version isl-0.22.1-GMP - -GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072 -Compiler executable checksum: bbf13931d8de1abe14040c9909cb6969 -COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_5a185.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64' - as -v --64 -o CMakeFiles/cmTC_5a185.dir/CMakeCCompilerABI.c.o /tmp/cc8lF2F9.s -GNU assembler version 2.34 (x86_64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.34 -COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/ -LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/ -COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_5a185.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64' -[2/2] Linking C executable cmTC_5a185 -Using built-in specs. -COLLECT_GCC=/usr/bin/cc -COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper -OFFLOAD_TARGET_NAMES=nvptx-none:hsa -OFFLOAD_TARGET_DEFAULT=1 -Target: x86_64-linux-gnu -Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.3.0-17ubuntu1~20.04' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c,ada,c++,go,brig,d,fortran,objc,obj-c++,gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-HskZEa/gcc-9-9.3.0/debian/tmp-nvptx/usr,hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu -Thread model: posix -gcc version 9.3.0 (Ubuntu 9.3.0-17ubuntu1~20.04) -COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/ -LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/ -COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_5a185' '-mtune=generic' '-march=x86-64' - /usr/lib/gcc/x86_64-linux-gnu/9/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/9/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper -plugin-opt=-fresolution=/tmp/ccOH3o3r.res -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -dynamic-linker /lib64/ld-linux-x86-64.so.2 -pie -z now -z relro -o cmTC_5a185 /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o -L/usr/lib/gcc/x86_64-linux-gnu/9 -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/9/../../.. CMakeFiles/cmTC_5a185.dir/CMakeCCompilerABI.c.o -lgcc --push-state --as-needed -lgcc_s --pop-state -lc -lgcc --push-state --as-needed -lgcc_s --pop-state /usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o -COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_5a185' '-mtune=generic' '-march=x86-64' - - - -Parsed C implicit include dir info from above output: rv=done - found start of include info - found start of implicit include info - add: [/usr/lib/gcc/x86_64-linux-gnu/9/include] - add: [/usr/local/include] - add: [/usr/include/x86_64-linux-gnu] - add: [/usr/include] - end of search list found - collapse include dir [/usr/lib/gcc/x86_64-linux-gnu/9/include] ==> [/usr/lib/gcc/x86_64-linux-gnu/9/include] - collapse include dir [/usr/local/include] ==> [/usr/local/include] - collapse include dir [/usr/include/x86_64-linux-gnu] ==> [/usr/include/x86_64-linux-gnu] - collapse include dir [/usr/include] ==> [/usr/include] - implicit include dirs: [/usr/lib/gcc/x86_64-linux-gnu/9/include;/usr/local/include;/usr/include/x86_64-linux-gnu;/usr/include] - - -Parsed C implicit link information from above output: - link line regex: [^( *|.*[/\])(ld|CMAKE_LINK_STARTFILE-NOTFOUND|([^/\]+-)?ld|collect2)[^/\]*( |$)] - ignore line: [Change Dir: /home/gebler/Dokumente/Medit/MedExo/epos4_zephyr/build/CMakeFiles/CMakeTmp] - ignore line: [] - ignore line: [Run Build Command(s):/usr/bin/ninja cmTC_5a185 && [1/2] Building C object CMakeFiles/cmTC_5a185.dir/CMakeCCompilerABI.c.o] - ignore line: [Using built-in specs.] - ignore line: [COLLECT_GCC=/usr/bin/cc] - ignore line: [OFFLOAD_TARGET_NAMES=nvptx-none:hsa] - ignore line: [OFFLOAD_TARGET_DEFAULT=1] - ignore line: [Target: x86_64-linux-gnu] - ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.3.0-17ubuntu1~20.04' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c ada c++ go brig d fortran objc obj-c++ gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32 m64 mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-HskZEa/gcc-9-9.3.0/debian/tmp-nvptx/usr hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu] - ignore line: [Thread model: posix] - ignore line: [gcc version 9.3.0 (Ubuntu 9.3.0-17ubuntu1~20.04) ] - ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_5a185.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64'] - ignore line: [ /usr/lib/gcc/x86_64-linux-gnu/9/cc1 -quiet -v -imultiarch x86_64-linux-gnu /usr/share/cmake-3.20/Modules/CMakeCCompilerABI.c -quiet -dumpbase CMakeCCompilerABI.c -mtune=generic -march=x86-64 -auxbase-strip CMakeFiles/cmTC_5a185.dir/CMakeCCompilerABI.c.o -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -fcf-protection -o /tmp/cc8lF2F9.s] - ignore line: [GNU C17 (Ubuntu 9.3.0-17ubuntu1~20.04) version 9.3.0 (x86_64-linux-gnu)] - ignore line: [ compiled by GNU C version 9.3.0 GMP version 6.2.0 MPFR version 4.0.2 MPC version 1.1.0 isl version isl-0.22.1-GMP] - ignore line: [] - ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072] - ignore line: [ignoring nonexistent directory "/usr/local/include/x86_64-linux-gnu"] - ignore line: [ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/include-fixed"] - ignore line: [ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/../../../../x86_64-linux-gnu/include"] - ignore line: [#include "..." search starts here:] - ignore line: [#include <...> search starts here:] - ignore line: [ /usr/lib/gcc/x86_64-linux-gnu/9/include] - ignore line: [ /usr/local/include] - ignore line: [ /usr/include/x86_64-linux-gnu] - ignore line: [ /usr/include] - ignore line: [End of search list.] - ignore line: [GNU C17 (Ubuntu 9.3.0-17ubuntu1~20.04) version 9.3.0 (x86_64-linux-gnu)] - ignore line: [ compiled by GNU C version 9.3.0 GMP version 6.2.0 MPFR version 4.0.2 MPC version 1.1.0 isl version isl-0.22.1-GMP] - ignore line: [] - ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072] - ignore line: [Compiler executable checksum: bbf13931d8de1abe14040c9909cb6969] - ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_5a185.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64'] - ignore line: [ as -v --64 -o CMakeFiles/cmTC_5a185.dir/CMakeCCompilerABI.c.o /tmp/cc8lF2F9.s] - ignore line: [GNU assembler version 2.34 (x86_64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.34] - ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/] - ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/] - ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_5a185.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64'] - ignore line: [[2/2] Linking C executable cmTC_5a185] - ignore line: [Using built-in specs.] - ignore line: [COLLECT_GCC=/usr/bin/cc] - ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper] - ignore line: [OFFLOAD_TARGET_NAMES=nvptx-none:hsa] - ignore line: [OFFLOAD_TARGET_DEFAULT=1] - ignore line: [Target: x86_64-linux-gnu] - ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.3.0-17ubuntu1~20.04' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c ada c++ go brig d fortran objc obj-c++ gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32 m64 mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-HskZEa/gcc-9-9.3.0/debian/tmp-nvptx/usr hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu] - ignore line: [Thread model: posix] - ignore line: [gcc version 9.3.0 (Ubuntu 9.3.0-17ubuntu1~20.04) ] - ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/] - ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/] - ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_5a185' '-mtune=generic' '-march=x86-64'] - link line: [ /usr/lib/gcc/x86_64-linux-gnu/9/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/9/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper -plugin-opt=-fresolution=/tmp/ccOH3o3r.res -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -dynamic-linker /lib64/ld-linux-x86-64.so.2 -pie -z now -z relro -o cmTC_5a185 /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o -L/usr/lib/gcc/x86_64-linux-gnu/9 -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/9/../../.. CMakeFiles/cmTC_5a185.dir/CMakeCCompilerABI.c.o -lgcc --push-state --as-needed -lgcc_s --pop-state -lc -lgcc --push-state --as-needed -lgcc_s --pop-state /usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o] - arg [/usr/lib/gcc/x86_64-linux-gnu/9/collect2] ==> ignore - arg [-plugin] ==> ignore - arg [/usr/lib/gcc/x86_64-linux-gnu/9/liblto_plugin.so] ==> ignore - arg [-plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper] ==> ignore - arg [-plugin-opt=-fresolution=/tmp/ccOH3o3r.res] ==> ignore - arg [-plugin-opt=-pass-through=-lgcc] ==> ignore - arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore - arg [-plugin-opt=-pass-through=-lc] ==> ignore - arg [-plugin-opt=-pass-through=-lgcc] ==> ignore - arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore - arg [--build-id] ==> ignore - arg [--eh-frame-hdr] ==> ignore - arg [-m] ==> ignore - arg [elf_x86_64] ==> ignore - arg [--hash-style=gnu] ==> ignore - arg [--as-needed] ==> ignore - arg [-dynamic-linker] ==> ignore - arg [/lib64/ld-linux-x86-64.so.2] ==> ignore - arg [-pie] ==> ignore - arg [-znow] ==> ignore - arg [-zrelro] ==> ignore - arg [-o] ==> ignore - arg [cmTC_5a185] ==> ignore - arg [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o] - arg [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o] - arg [/usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o] - arg [-L/usr/lib/gcc/x86_64-linux-gnu/9] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9] - arg [-L/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu] - arg [-L/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib] - arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu] - arg [-L/lib/../lib] ==> dir [/lib/../lib] - arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu] - arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib] - arg [-L/usr/lib/gcc/x86_64-linux-gnu/9/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../..] - arg [CMakeFiles/cmTC_5a185.dir/CMakeCCompilerABI.c.o] ==> ignore - arg [-lgcc] ==> lib [gcc] - arg [--push-state] ==> ignore - arg [--as-needed] ==> ignore - arg [-lgcc_s] ==> lib [gcc_s] - arg [--pop-state] ==> ignore - arg [-lc] ==> lib [c] - arg [-lgcc] ==> lib [gcc] - arg [--push-state] ==> ignore - arg [--as-needed] ==> ignore - arg [-lgcc_s] ==> lib [gcc_s] - arg [--pop-state] ==> ignore - arg [/usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o] - arg [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o] - collapse obj [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o] ==> [/usr/lib/x86_64-linux-gnu/Scrt1.o] - collapse obj [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o] ==> [/usr/lib/x86_64-linux-gnu/crti.o] - collapse obj [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o] ==> [/usr/lib/x86_64-linux-gnu/crtn.o] - collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9] ==> [/usr/lib/gcc/x86_64-linux-gnu/9] - collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] - collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib] ==> [/usr/lib] - collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu] - collapse library dir [/lib/../lib] ==> [/lib] - collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] - collapse library dir [/usr/lib/../lib] ==> [/usr/lib] - collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../..] ==> [/usr/lib] - implicit libs: [gcc;gcc_s;c;gcc;gcc_s] - implicit objs: [/usr/lib/x86_64-linux-gnu/Scrt1.o;/usr/lib/x86_64-linux-gnu/crti.o;/usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o;/usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o;/usr/lib/x86_64-linux-gnu/crtn.o] - implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/9;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib] - implicit fwks: [] - - -Detecting CXX compiler ABI info compiled with the following output: -Change Dir: /home/gebler/Dokumente/Medit/MedExo/epos4_zephyr/build/CMakeFiles/CMakeTmp - -Run Build Command(s):/usr/bin/ninja cmTC_d0d42 && [1/2] Building CXX object CMakeFiles/cmTC_d0d42.dir/CMakeCXXCompilerABI.cpp.o -Using built-in specs. -COLLECT_GCC=/usr/bin/c++ -OFFLOAD_TARGET_NAMES=nvptx-none:hsa -OFFLOAD_TARGET_DEFAULT=1 -Target: x86_64-linux-gnu -Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.3.0-17ubuntu1~20.04' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c,ada,c++,go,brig,d,fortran,objc,obj-c++,gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-HskZEa/gcc-9-9.3.0/debian/tmp-nvptx/usr,hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu -Thread model: posix -gcc version 9.3.0 (Ubuntu 9.3.0-17ubuntu1~20.04) -COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_d0d42.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64' - /usr/lib/gcc/x86_64-linux-gnu/9/cc1plus -quiet -v -imultiarch x86_64-linux-gnu -D_GNU_SOURCE /usr/share/cmake-3.20/Modules/CMakeCXXCompilerABI.cpp -quiet -dumpbase CMakeCXXCompilerABI.cpp -mtune=generic -march=x86-64 -auxbase-strip CMakeFiles/cmTC_d0d42.dir/CMakeCXXCompilerABI.cpp.o -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -fcf-protection -o /tmp/cczb5UW1.s -GNU C++14 (Ubuntu 9.3.0-17ubuntu1~20.04) version 9.3.0 (x86_64-linux-gnu) - compiled by GNU C version 9.3.0, GMP version 6.2.0, MPFR version 4.0.2, MPC version 1.1.0, isl version isl-0.22.1-GMP - -GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072 -ignoring duplicate directory "/usr/include/x86_64-linux-gnu/c++/9" -ignoring nonexistent directory "/usr/local/include/x86_64-linux-gnu" -ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/include-fixed" -ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/../../../../x86_64-linux-gnu/include" -#include "..." search starts here: -#include <...> search starts here: - /usr/include/c++/9 - /usr/include/x86_64-linux-gnu/c++/9 - /usr/include/c++/9/backward - /usr/lib/gcc/x86_64-linux-gnu/9/include - /usr/local/include - /usr/include/x86_64-linux-gnu - /usr/include -End of search list. -GNU C++14 (Ubuntu 9.3.0-17ubuntu1~20.04) version 9.3.0 (x86_64-linux-gnu) - compiled by GNU C version 9.3.0, GMP version 6.2.0, MPFR version 4.0.2, MPC version 1.1.0, isl version isl-0.22.1-GMP - -GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072 -Compiler executable checksum: 466f818abe2f30ba03783f22bd12d815 -COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_d0d42.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64' - as -v --64 -o CMakeFiles/cmTC_d0d42.dir/CMakeCXXCompilerABI.cpp.o /tmp/cczb5UW1.s -GNU assembler version 2.34 (x86_64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.34 -COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/ -LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/ -COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_d0d42.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64' -[2/2] Linking CXX executable cmTC_d0d42 -Using built-in specs. -COLLECT_GCC=/usr/bin/c++ -COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper -OFFLOAD_TARGET_NAMES=nvptx-none:hsa -OFFLOAD_TARGET_DEFAULT=1 -Target: x86_64-linux-gnu -Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.3.0-17ubuntu1~20.04' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c,ada,c++,go,brig,d,fortran,objc,obj-c++,gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-HskZEa/gcc-9-9.3.0/debian/tmp-nvptx/usr,hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu -Thread model: posix -gcc version 9.3.0 (Ubuntu 9.3.0-17ubuntu1~20.04) -COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/ -LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/ -COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_d0d42' '-shared-libgcc' '-mtune=generic' '-march=x86-64' - /usr/lib/gcc/x86_64-linux-gnu/9/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/9/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper -plugin-opt=-fresolution=/tmp/ccNiLqOl.res -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -dynamic-linker /lib64/ld-linux-x86-64.so.2 -pie -z now -z relro -o cmTC_d0d42 /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o -L/usr/lib/gcc/x86_64-linux-gnu/9 -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/9/../../.. CMakeFiles/cmTC_d0d42.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o -COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_d0d42' '-shared-libgcc' '-mtune=generic' '-march=x86-64' - - - -Parsed CXX implicit include dir info from above output: rv=done - found start of include info - found start of implicit include info - add: [/usr/include/c++/9] - add: [/usr/include/x86_64-linux-gnu/c++/9] - add: [/usr/include/c++/9/backward] - add: [/usr/lib/gcc/x86_64-linux-gnu/9/include] - add: [/usr/local/include] - add: [/usr/include/x86_64-linux-gnu] - add: [/usr/include] - end of search list found - collapse include dir [/usr/include/c++/9] ==> [/usr/include/c++/9] - collapse include dir [/usr/include/x86_64-linux-gnu/c++/9] ==> [/usr/include/x86_64-linux-gnu/c++/9] - collapse include dir [/usr/include/c++/9/backward] ==> [/usr/include/c++/9/backward] - collapse include dir [/usr/lib/gcc/x86_64-linux-gnu/9/include] ==> [/usr/lib/gcc/x86_64-linux-gnu/9/include] - collapse include dir [/usr/local/include] ==> [/usr/local/include] - collapse include dir [/usr/include/x86_64-linux-gnu] ==> [/usr/include/x86_64-linux-gnu] - collapse include dir [/usr/include] ==> [/usr/include] - implicit include dirs: [/usr/include/c++/9;/usr/include/x86_64-linux-gnu/c++/9;/usr/include/c++/9/backward;/usr/lib/gcc/x86_64-linux-gnu/9/include;/usr/local/include;/usr/include/x86_64-linux-gnu;/usr/include] - - -Parsed CXX implicit link information from above output: - link line regex: [^( *|.*[/\])(ld|CMAKE_LINK_STARTFILE-NOTFOUND|([^/\]+-)?ld|collect2)[^/\]*( |$)] - ignore line: [Change Dir: /home/gebler/Dokumente/Medit/MedExo/epos4_zephyr/build/CMakeFiles/CMakeTmp] - ignore line: [] - ignore line: [Run Build Command(s):/usr/bin/ninja cmTC_d0d42 && [1/2] Building CXX object CMakeFiles/cmTC_d0d42.dir/CMakeCXXCompilerABI.cpp.o] - ignore line: [Using built-in specs.] - ignore line: [COLLECT_GCC=/usr/bin/c++] - ignore line: [OFFLOAD_TARGET_NAMES=nvptx-none:hsa] - ignore line: [OFFLOAD_TARGET_DEFAULT=1] - ignore line: [Target: x86_64-linux-gnu] - ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.3.0-17ubuntu1~20.04' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c ada c++ go brig d fortran objc obj-c++ gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32 m64 mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-HskZEa/gcc-9-9.3.0/debian/tmp-nvptx/usr hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu] - ignore line: [Thread model: posix] - ignore line: [gcc version 9.3.0 (Ubuntu 9.3.0-17ubuntu1~20.04) ] - ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_d0d42.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64'] - ignore line: [ /usr/lib/gcc/x86_64-linux-gnu/9/cc1plus -quiet -v -imultiarch x86_64-linux-gnu -D_GNU_SOURCE /usr/share/cmake-3.20/Modules/CMakeCXXCompilerABI.cpp -quiet -dumpbase CMakeCXXCompilerABI.cpp -mtune=generic -march=x86-64 -auxbase-strip CMakeFiles/cmTC_d0d42.dir/CMakeCXXCompilerABI.cpp.o -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -fcf-protection -o /tmp/cczb5UW1.s] - ignore line: [GNU C++14 (Ubuntu 9.3.0-17ubuntu1~20.04) version 9.3.0 (x86_64-linux-gnu)] - ignore line: [ compiled by GNU C version 9.3.0 GMP version 6.2.0 MPFR version 4.0.2 MPC version 1.1.0 isl version isl-0.22.1-GMP] - ignore line: [] - ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072] - ignore line: [ignoring duplicate directory "/usr/include/x86_64-linux-gnu/c++/9"] - ignore line: [ignoring nonexistent directory "/usr/local/include/x86_64-linux-gnu"] - ignore line: [ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/include-fixed"] - ignore line: [ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/../../../../x86_64-linux-gnu/include"] - ignore line: [#include "..." search starts here:] - ignore line: [#include <...> search starts here:] - ignore line: [ /usr/include/c++/9] - ignore line: [ /usr/include/x86_64-linux-gnu/c++/9] - ignore line: [ /usr/include/c++/9/backward] - ignore line: [ /usr/lib/gcc/x86_64-linux-gnu/9/include] - ignore line: [ /usr/local/include] - ignore line: [ /usr/include/x86_64-linux-gnu] - ignore line: [ /usr/include] - ignore line: [End of search list.] - ignore line: [GNU C++14 (Ubuntu 9.3.0-17ubuntu1~20.04) version 9.3.0 (x86_64-linux-gnu)] - ignore line: [ compiled by GNU C version 9.3.0 GMP version 6.2.0 MPFR version 4.0.2 MPC version 1.1.0 isl version isl-0.22.1-GMP] - ignore line: [] - ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072] - ignore line: [Compiler executable checksum: 466f818abe2f30ba03783f22bd12d815] - ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_d0d42.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64'] - ignore line: [ as -v --64 -o CMakeFiles/cmTC_d0d42.dir/CMakeCXXCompilerABI.cpp.o /tmp/cczb5UW1.s] - ignore line: [GNU assembler version 2.34 (x86_64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.34] - ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/] - ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/] - ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_d0d42.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64'] - ignore line: [[2/2] Linking CXX executable cmTC_d0d42] - ignore line: [Using built-in specs.] - ignore line: [COLLECT_GCC=/usr/bin/c++] - ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper] - ignore line: [OFFLOAD_TARGET_NAMES=nvptx-none:hsa] - ignore line: [OFFLOAD_TARGET_DEFAULT=1] - ignore line: [Target: x86_64-linux-gnu] - ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.3.0-17ubuntu1~20.04' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c ada c++ go brig d fortran objc obj-c++ gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32 m64 mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-HskZEa/gcc-9-9.3.0/debian/tmp-nvptx/usr hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu] - ignore line: [Thread model: posix] - ignore line: [gcc version 9.3.0 (Ubuntu 9.3.0-17ubuntu1~20.04) ] - ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/] - ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/] - ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_d0d42' '-shared-libgcc' '-mtune=generic' '-march=x86-64'] - link line: [ /usr/lib/gcc/x86_64-linux-gnu/9/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/9/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper -plugin-opt=-fresolution=/tmp/ccNiLqOl.res -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -dynamic-linker /lib64/ld-linux-x86-64.so.2 -pie -z now -z relro -o cmTC_d0d42 /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o -L/usr/lib/gcc/x86_64-linux-gnu/9 -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/9/../../.. CMakeFiles/cmTC_d0d42.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o] - arg [/usr/lib/gcc/x86_64-linux-gnu/9/collect2] ==> ignore - arg [-plugin] ==> ignore - arg [/usr/lib/gcc/x86_64-linux-gnu/9/liblto_plugin.so] ==> ignore - arg [-plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper] ==> ignore - arg [-plugin-opt=-fresolution=/tmp/ccNiLqOl.res] ==> ignore - arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore - arg [-plugin-opt=-pass-through=-lgcc] ==> ignore - arg [-plugin-opt=-pass-through=-lc] ==> ignore - arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore - arg [-plugin-opt=-pass-through=-lgcc] ==> ignore - arg [--build-id] ==> ignore - arg [--eh-frame-hdr] ==> ignore - arg [-m] ==> ignore - arg [elf_x86_64] ==> ignore - arg [--hash-style=gnu] ==> ignore - arg [--as-needed] ==> ignore - arg [-dynamic-linker] ==> ignore - arg [/lib64/ld-linux-x86-64.so.2] ==> ignore - arg [-pie] ==> ignore - arg [-znow] ==> ignore - arg [-zrelro] ==> ignore - arg [-o] ==> ignore - arg [cmTC_d0d42] ==> ignore - arg [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o] - arg [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o] - arg [/usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o] - arg [-L/usr/lib/gcc/x86_64-linux-gnu/9] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9] - arg [-L/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu] - arg [-L/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib] - arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu] - arg [-L/lib/../lib] ==> dir [/lib/../lib] - arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu] - arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib] - arg [-L/usr/lib/gcc/x86_64-linux-gnu/9/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../..] - arg [CMakeFiles/cmTC_d0d42.dir/CMakeCXXCompilerABI.cpp.o] ==> ignore - arg [-lstdc++] ==> lib [stdc++] - arg [-lm] ==> lib [m] - arg [-lgcc_s] ==> lib [gcc_s] - arg [-lgcc] ==> lib [gcc] - arg [-lc] ==> lib [c] - arg [-lgcc_s] ==> lib [gcc_s] - arg [-lgcc] ==> lib [gcc] - arg [/usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o] - arg [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o] - collapse obj [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o] ==> [/usr/lib/x86_64-linux-gnu/Scrt1.o] - collapse obj [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o] ==> [/usr/lib/x86_64-linux-gnu/crti.o] - collapse obj [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o] ==> [/usr/lib/x86_64-linux-gnu/crtn.o] - collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9] ==> [/usr/lib/gcc/x86_64-linux-gnu/9] - collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] - collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib] ==> [/usr/lib] - collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu] - collapse library dir [/lib/../lib] ==> [/lib] - collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] - collapse library dir [/usr/lib/../lib] ==> [/usr/lib] - collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../..] ==> [/usr/lib] - implicit libs: [stdc++;m;gcc_s;gcc;c;gcc_s;gcc] - implicit objs: [/usr/lib/x86_64-linux-gnu/Scrt1.o;/usr/lib/x86_64-linux-gnu/crti.o;/usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o;/usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o;/usr/lib/x86_64-linux-gnu/crtn.o] - implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/9;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib] - implicit fwks: [] - - diff --git a/zephyr/build/CMakeFiles/cmake.check_cache b/zephyr/build/CMakeFiles/cmake.check_cache deleted file mode 100644 index 3dccd73..0000000 --- a/zephyr/build/CMakeFiles/cmake.check_cache +++ /dev/null @@ -1 +0,0 @@ -# This file is generated by cmake for dependency checking of the CMakeCache.txt file diff --git a/zephyr/epos_controller/CMakeLists.txt b/zephyr/epos_controller/CMakeLists.txt deleted file mode 100644 index 9f516a0..0000000 --- a/zephyr/epos_controller/CMakeLists.txt +++ /dev/null @@ -1,20 +0,0 @@ -# Find Zephyr. This also loads Zephyr's build system. -cmake_minimum_required(VERSION 3.13.1) -find_package(Zephyr) -project(epos_controller) - -# Add your source file to the "app" target. This must come after -# find_package(Zephyr) which defines the target. -# target_sources(app PRIVATE src/test.cpp) - -target_sources(app PRIVATE - src/pos_controller.cpp - src/epos4/epos4.cpp - src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/Atomic.c - src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/Atomic_data.c -) - -target_include_directories(app PUBLIC src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw pos_controller.cpp) -target_include_directories(app PUBLIC src/simulinkcode/R2021a/extern/include pos_controller.cpp) -target_include_directories(app PUBLIC src/simulinkcode/R2021a/rtw/c/src pos_controller.cpp) -target_include_directories(app PUBLIC src/simulinkcode/R2021a/simulink/include pos_controller.cpp) \ No newline at end of file diff --git a/zephyr/epos_controller/src/main.cpp b/zephyr/epos_controller/src/main.cpp deleted file mode 100644 index 6be6082..0000000 --- a/zephyr/epos_controller/src/main.cpp +++ /dev/null @@ -1,103 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include - -#include "epos4/epos4.h" - -#define RX_THREAD_STACK_SIZE 512 -#define RX_THREAD_PRIORITY 2 -#define STATE_POLL_THREAD_STACK_SIZE 512 -#define STATE_POLL_THREAD_PRIORITY 2 -#define LED_MSG_ID 0x10 -#define COUNTER_MSG_ID 0x12345 -#define SET_LED 1 -#define RESET_LED 0 -#define SLEEP_TIME K_MSEC(250) - -K_THREAD_STACK_DEFINE(rx_thread_stack, RX_THREAD_STACK_SIZE); - -#define CAN_DEVICE_LABEL DT_PROP(DT_ALIAS(can_dev), label) - -const struct device* can_dev; -// const struct device *can_dev = DEVICE_DT_GET(DT_CHOSEN(zephyr_can_primary)); - -epos4* epos4_1_pointer = NULL; - - -struct k_thread rx_thread_data; -struct k_thread poll_state_thread_data; -struct zcan_work rx_work; -struct k_work state_change_work; -enum can_state current_state; -struct can_bus_err_cnt current_err_cnt; - -void rx_callback_function(struct zcan_frame *frame, void *arg) -{ - char *dat = (char*)(frame->data); - - if( dat[1] == 0x41 || dat[2] == 0x60 ) - { - uint16_t statusword = ( dat[5] << 8 ) | ( dat[4] ); - epos4_1_pointer->_target_reached = statusword & 0b0000010000000000; - epos4_1_pointer->_state_of_drive = statusword & 0b01101111; - } - - printk("MSG: "); - - for(int i = 0; i < 8; i+=1) - { - printk("%x",(unsigned char)(dat[i])); - } - - printk("\n"); -} - - - -void main(void) -{ - epos4 epos4_1(0x581,0x601, can_dev); - epos4_1_pointer = &epos4_1; - epos4_1_pointer->_can_interface = device_get_binding("CAN_1"); - - k_tid_t rx_tid; - - if (!device_is_ready(epos4_1_pointer->_can_interface)) { - printk("CAN: Device %s not ready.\n", epos4_1_pointer->_can_interface->name); - return; - }else{ - printk("CAN device %s is ready...\n", epos4_1_pointer->_can_interface->name); - } - can_set_mode(epos4_1_pointer->_can_interface, CAN_NORMAL_MODE); - - const struct zcan_filter my_filter = { - .id = 0x581, - .rtr = CAN_DATAFRAME, - .id_type = CAN_STANDARD_IDENTIFIER, - .id_mask = CAN_STD_ID_MASK, - .rtr_mask = 1 - }; - int filter_id; - - filter_id = can_attach_isr(epos4_1_pointer->_can_interface, rx_callback_function, NULL, &my_filter); - if (filter_id < 0) { - printk("Unable to attach isr [%d]", filter_id); - } - - printk("start init..."); - epos4_1_pointer->init(); - printk(" done!\nStart init CST-Mode: "); - epos4_1_pointer->initCST(); - - uint32_t posList[2] = {0,50000}; - while(1) - { - k_sleep(K_MSEC(7000)); - epos4_1_pointer->moveToPosition(posList,2); - // printk("Test ... \n"); - } -} \ No newline at end of file diff --git a/zephyr/epos_controller/src/pos_controller.cpp b/zephyr/epos_controller/src/pos_controller.cpp deleted file mode 100644 index dd315d8..0000000 --- a/zephyr/epos_controller/src/pos_controller.cpp +++ /dev/null @@ -1,185 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include -#include - -#ifdef __cplusplus -extern "C" -{ -#endif -#include "Atomic.h" -#ifdef __cplusplus -} -#endif - -#include "epos4/epos4.h" - - -#define RX_THREAD_STACK_SIZE 512 -#define RX_THREAD_PRIORITY 2 -#define STATE_POLL_THREAD_STACK_SIZE 512 -#define STATE_POLL_THREAD_PRIORITY 2 -#define LED_MSG_ID 0x10 -#define COUNTER_MSG_ID 0x12345 -#define SET_LED 1 -#define RESET_LED 0 -#define SLEEP_TIME K_MSEC(250) - -K_THREAD_STACK_DEFINE(rx_thread_stack, RX_THREAD_STACK_SIZE); - - -#define CAN_DEVICE_LABEL DT_PROP(DT_ALIAS(can_dev), label) - -const struct device* can_dev; -// const struct device *can_dev = DEVICE_DT_GET(DT_CHOSEN(zephyr_can_primary)); - -epos4* epos4_1_pointer = NULL; - - -struct k_thread rx_thread_data; -struct k_thread poll_state_thread_data; -struct zcan_work rx_work; -struct k_work state_change_work; -enum can_state current_state; -struct can_bus_err_cnt current_err_cnt; - - -CAN_DEFINE_MSGQ(my_can_msgq1, 100); -CAN_DEFINE_MSGQ(my_can_msgq2, 100); -struct zcan_frame rx_frame; - -struct k_timer sync_timer; -extern void sync_function(struct k_timer *timer_id); - -unsigned char torque_value[2] = {0}; - -void tx_irq_callback_main(uint32_t error_flags, void *arg) -{ - char *sender = (char *)arg; - - if (error_flags) { - printk("Sendig failed [%d]\nSender: %s\n", error_flags, sender); - } -} - -void sync_function(struct k_timer *timer_id) -{ - - epos4_1_pointer->sync(); - - // epos4 inc. to position in rad === 0.00000756309 | 120000 inc. === 104 Grad - float ac_pos = (((float)(epos4_1_pointer->position))*(0.00000756309)); - float ac_tor = (((float)(epos4_1_pointer->torque))); - if( ac_pos > 1.74532925199 ) ac_pos = 1.74532925199; - if( ac_pos < -1.74532925199 ) ac_pos = -1.74532925199; - Atomic_U.phi_m = -0.78539816339 - ac_pos; - Atomic_step(); - - - union { - int32_t float_variable; - unsigned char bytes_array[4]; - } my_union; - - // Output in mNm - //my_union.float_variable = Atomic_Y.Out1; - my_union.float_variable = 100.0; - - struct zcan_frame frame = { - .id = 0x401, - .rtr = CAN_DATAFRAME, - .id_type = CAN_STANDARD_IDENTIFIER, - .dlc = 2, - .data = {my_union.bytes_array[0],my_union.bytes_array[1]} - }; - - // printk("%d,%02x,%02x,%02x,%02x\n",my_union.float_variable,my_union.bytes_array[3],my_union.bytes_array[2],my_union.bytes_array[1],my_union.bytes_array[0]); - printk("Data===0.0,%f,%f,%f,%f\n",ac_pos,ac_tor,Atomic_Y.Out1,Atomic_U.phi_m); - if( 0 != can_send(epos4_1_pointer->_can_interface, &frame, K_FOREVER, tx_irq_callback_main, NULL) ) - { - printk("\n --- Error while sending sync frame --- \n"); - } - - - -} - -void main(void) -{ - - epos4 epos4_1(0x581,0x601, can_dev, &my_can_msgq1, &my_can_msgq2, &rx_frame); - epos4_1_pointer = &epos4_1; - epos4_1_pointer->_can_interface = device_get_binding("CAN_1"); - - k_tid_t rx_tid; - - if (!device_is_ready(epos4_1_pointer->_can_interface)) { - printk("CAN: Device %s not ready.\n", epos4_1_pointer->_can_interface->name); - return; - }else{ - printk("CAN device %s is ready...\n", epos4_1_pointer->_can_interface->name); - } - can_set_mode(epos4_1_pointer->_can_interface, CAN_NORMAL_MODE); - - - // Setting up the filters - - const struct zcan_filter my_filter = { - .id = 0x581, - .rtr = CAN_DATAFRAME, - .id_type = CAN_STANDARD_IDENTIFIER, - .id_mask = CAN_STD_ID_MASK, - .rtr_mask = 1 - }; - int filter_id; - - filter_id = can_attach_msgq(epos4_1_pointer->_can_interface, &my_can_msgq1, &my_filter); - if (filter_id < 0) { - printk("Unable to attach isr [%d]", filter_id); - return; - } - - const struct zcan_filter spo_recieve = { - .id = 0x181, - .rtr = CAN_DATAFRAME, - .id_type = CAN_STANDARD_IDENTIFIER, - .id_mask = CAN_STD_ID_MASK, - .rtr_mask = 1 - }; - int spo_recieve_filter_id; - - - spo_recieve_filter_id = can_attach_msgq(epos4_1_pointer->_can_interface, &my_can_msgq2, &spo_recieve); - if (spo_recieve_filter_id < 0) { - printk("Unable to attach isr [%d]", spo_recieve_filter_id); - return; - } - - - printk(" ------------------------------- \n"); - printk("Start init ... \n"); - epos4_1_pointer->init(); - printk("\ndone!\nStart init CST-Mode ... \n"); - epos4_1_pointer->initCST(); - printk("\ndone!\n"); - - k_msgq_cleanup(&my_can_msgq1); - k_msgq_cleanup(&my_can_msgq2); - - k_sleep(K_MSEC(2000)); - - Atomic_initialize(); - - k_timer_init( &sync_timer, sync_function, NULL); - k_timer_start( &sync_timer, K_MSEC(0), K_MSEC(10) ); - - while(1) - { - //k_sleep(K_MSEC(5000)); - //epos4_1_pointer->readStatusword(); - } -} diff --git a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/Atomic.c b/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/Atomic.c deleted file mode 100644 index 26f7668..0000000 --- a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/Atomic.c +++ /dev/null @@ -1,274 +0,0 @@ -/* - * Atomic.c - * - * Academic License - for use in teaching, academic research, and meeting - * course requirements at degree granting institutions only. Not for - * government, commercial, or other organizational use. - * - * Code generation for model "Atomic". - * - * Model version : 4.4 - * Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 - * C source code generated on : Wed Jun 16 17:30:13 2021 - * - * Target selection: grt.tlc - * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Intel->x86-64 (Windows64) - * Code generation objectives: Unspecified - * Validation result: Not run - */ - -#include "Atomic.h" -#include "Atomic_private.h" - -/* Block signals (default storage) */ -B_Atomic_T Atomic_B; - -/* Continuous states */ -X_Atomic_T Atomic_X; - -/* External inputs (root inport signals with default storage) */ -ExtU_Atomic_T Atomic_U; - -/* External outputs (root outports fed by signals with default storage) */ -ExtY_Atomic_T Atomic_Y; - -/* Real-time model */ -static RT_MODEL_Atomic_T Atomic_M_; -RT_MODEL_Atomic_T *const Atomic_M = &Atomic_M_; - -/* - * This function updates continuous states using the ODE3 fixed-step - * solver algorithm - */ -static void rt_ertODEUpdateContinuousStates(RTWSolverInfo *si ) -{ - /* Solver Matrices */ - static const real_T rt_ODE3_A[3] = { - 1.0/2.0, 3.0/4.0, 1.0 - }; - - static const real_T rt_ODE3_B[3][3] = { - { 1.0/2.0, 0.0, 0.0 }, - - { 0.0, 3.0/4.0, 0.0 }, - - { 2.0/9.0, 1.0/3.0, 4.0/9.0 } - }; - - time_T t = rtsiGetT(si); - time_T tnew = rtsiGetSolverStopTime(si); - time_T h = rtsiGetStepSize(si); - real_T *x = rtsiGetContStates(si); - ODE3_IntgData *id = (ODE3_IntgData *)rtsiGetSolverData(si); - real_T *y = id->y; - real_T *f0 = id->f[0]; - real_T *f1 = id->f[1]; - real_T *f2 = id->f[2]; - real_T hB[3]; - int_T i; - int_T nXc = 1; - rtsiSetSimTimeStep(si,MINOR_TIME_STEP); - - /* Save the state values at time t in y, we'll use x as ynew. */ - (void) memcpy(y, x, - (uint_T)nXc*sizeof(real_T)); - - /* Assumes that rtsiSetT and ModelOutputs are up-to-date */ - /* f0 = f(t,y) */ - rtsiSetdX(si, f0); - Atomic_derivatives(); - - /* f(:,2) = feval(odefile, t + hA(1), y + f*hB(:,1), args(:)(*)); */ - hB[0] = h * rt_ODE3_B[0][0]; - for (i = 0; i < nXc; i++) { - x[i] = y[i] + (f0[i]*hB[0]); - } - - rtsiSetT(si, t + h*rt_ODE3_A[0]); - rtsiSetdX(si, f1); - Atomic_step(); - Atomic_derivatives(); - - /* f(:,3) = feval(odefile, t + hA(2), y + f*hB(:,2), args(:)(*)); */ - for (i = 0; i <= 1; i++) { - hB[i] = h * rt_ODE3_B[1][i]; - } - - for (i = 0; i < nXc; i++) { - x[i] = y[i] + (f0[i]*hB[0] + f1[i]*hB[1]); - } - - rtsiSetT(si, t + h*rt_ODE3_A[1]); - rtsiSetdX(si, f2); - Atomic_step(); - Atomic_derivatives(); - - /* tnew = t + hA(3); - ynew = y + f*hB(:,3); */ - for (i = 0; i <= 2; i++) { - hB[i] = h * rt_ODE3_B[2][i]; - } - - for (i = 0; i < nXc; i++) { - x[i] = y[i] + (f0[i]*hB[0] + f1[i]*hB[1] + f2[i]*hB[2]); - } - - rtsiSetT(si, tnew); - rtsiSetSimTimeStep(si,MAJOR_TIME_STEP); -} - -/* Model step function */ -void Atomic_step(void) -{ - if (rtmIsMajorTimeStep(Atomic_M)) { - /* set solver stop time */ - if (!(Atomic_M->Timing.clockTick0+1)) { - rtsiSetSolverStopTime(&Atomic_M->solverInfo, - ((Atomic_M->Timing.clockTickH0 + 1) * - Atomic_M->Timing.stepSize0 * 4294967296.0)); - } else { - rtsiSetSolverStopTime(&Atomic_M->solverInfo, ((Atomic_M->Timing.clockTick0 - + 1) * Atomic_M->Timing.stepSize0 + Atomic_M->Timing.clockTickH0 * - Atomic_M->Timing.stepSize0 * 4294967296.0)); - } - } /* end MajorTimeStep */ - - /* Update absolute time of base rate at minor time step */ - if (rtmIsMinorTimeStep(Atomic_M)) { - Atomic_M->Timing.t[0] = rtsiGetT(&Atomic_M->solverInfo); - } - - /* Outputs for Atomic SubSystem: '/Atomic Subsystem' */ - /* Gain: '/Integral Gain' incorporates: - * Inport: '/In1' - */ - Atomic_B.IntegralGain = Atomic_P.PIDController_I * Atomic_U.phi_m; - - /* Outport: '/Out1' incorporates: - * Gain: '/Proportional Gain' - * Inport: '/In1' - * Integrator: '/Integrator' - * Sum: '/Sum' - */ - Atomic_Y.Out1 = Atomic_P.PIDController_P * Atomic_U.phi_m + - Atomic_X.Integrator_CSTATE; - - /* End of Outputs for SubSystem: '/Atomic Subsystem' */ - if (rtmIsMajorTimeStep(Atomic_M)) { - rt_ertODEUpdateContinuousStates(&Atomic_M->solverInfo); - - /* Update absolute time for base rate */ - /* The "clockTick0" counts the number of times the code of this task has - * been executed. The absolute time is the multiplication of "clockTick0" - * and "Timing.stepSize0". Size of "clockTick0" ensures timer will not - * overflow during the application lifespan selected. - * Timer of this task consists of two 32 bit unsigned integers. - * The two integers represent the low bits Timing.clockTick0 and the high bits - * Timing.clockTickH0. When the low bit overflows to 0, the high bits increment. - */ - if (!(++Atomic_M->Timing.clockTick0)) { - ++Atomic_M->Timing.clockTickH0; - } - - Atomic_M->Timing.t[0] = rtsiGetSolverStopTime(&Atomic_M->solverInfo); - - { - /* Update absolute timer for sample time: [0.01s, 0.0s] */ - /* The "clockTick1" counts the number of times the code of this task has - * been executed. The resolution of this integer timer is 0.01, which is the step size - * of the task. Size of "clockTick1" ensures timer will not overflow during the - * application lifespan selected. - * Timer of this task consists of two 32 bit unsigned integers. - * The two integers represent the low bits Timing.clockTick1 and the high bits - * Timing.clockTickH1. When the low bit overflows to 0, the high bits increment. - */ - Atomic_M->Timing.clockTick1++; - if (!Atomic_M->Timing.clockTick1) { - Atomic_M->Timing.clockTickH1++; - } - } - } /* end MajorTimeStep */ -} - -/* Derivatives for root system: '' */ -void Atomic_derivatives(void) -{ - XDot_Atomic_T *_rtXdot; - _rtXdot = ((XDot_Atomic_T *) Atomic_M->derivs); - - /* Derivatives for Atomic SubSystem: '/Atomic Subsystem' */ - /* Derivatives for Integrator: '/Integrator' */ - _rtXdot->Integrator_CSTATE = Atomic_B.IntegralGain; - - /* End of Derivatives for SubSystem: '/Atomic Subsystem' */ -} - -/* Model initialize function */ -void Atomic_initialize(void) -{ - /* Registration code */ - - /* initialize real-time model */ - (void) memset((void *)Atomic_M, 0, - sizeof(RT_MODEL_Atomic_T)); - - { - /* Setup solver object */ - rtsiSetSimTimeStepPtr(&Atomic_M->solverInfo, &Atomic_M->Timing.simTimeStep); - rtsiSetTPtr(&Atomic_M->solverInfo, &rtmGetTPtr(Atomic_M)); - rtsiSetStepSizePtr(&Atomic_M->solverInfo, &Atomic_M->Timing.stepSize0); - rtsiSetdXPtr(&Atomic_M->solverInfo, &Atomic_M->derivs); - rtsiSetContStatesPtr(&Atomic_M->solverInfo, (real_T **) - &Atomic_M->contStates); - rtsiSetNumContStatesPtr(&Atomic_M->solverInfo, - &Atomic_M->Sizes.numContStates); - rtsiSetNumPeriodicContStatesPtr(&Atomic_M->solverInfo, - &Atomic_M->Sizes.numPeriodicContStates); - rtsiSetPeriodicContStateIndicesPtr(&Atomic_M->solverInfo, - &Atomic_M->periodicContStateIndices); - rtsiSetPeriodicContStateRangesPtr(&Atomic_M->solverInfo, - &Atomic_M->periodicContStateRanges); - rtsiSetErrorStatusPtr(&Atomic_M->solverInfo, (&rtmGetErrorStatus(Atomic_M))); - rtsiSetRTModelPtr(&Atomic_M->solverInfo, Atomic_M); - } - - rtsiSetSimTimeStep(&Atomic_M->solverInfo, MAJOR_TIME_STEP); - Atomic_M->intgData.y = Atomic_M->odeY; - Atomic_M->intgData.f[0] = Atomic_M->odeF[0]; - Atomic_M->intgData.f[1] = Atomic_M->odeF[1]; - Atomic_M->intgData.f[2] = Atomic_M->odeF[2]; - Atomic_M->contStates = ((X_Atomic_T *) &Atomic_X); - rtsiSetSolverData(&Atomic_M->solverInfo, (void *)&Atomic_M->intgData); - rtsiSetSolverName(&Atomic_M->solverInfo,"ode3"); - rtmSetTPtr(Atomic_M, &Atomic_M->Timing.tArray[0]); - Atomic_M->Timing.stepSize0 = 0.01; - - /* block I/O */ - (void) memset(((void *) &Atomic_B), 0, - sizeof(B_Atomic_T)); - - /* states (continuous) */ - { - (void) memset((void *)&Atomic_X, 0, - sizeof(X_Atomic_T)); - } - - /* external inputs */ - Atomic_U.phi_m = 0.0; - - /* external outputs */ - Atomic_Y.Out1 = 0.0; - - /* SystemInitialize for Atomic SubSystem: '/Atomic Subsystem' */ - /* InitializeConditions for Integrator: '/Integrator' */ - Atomic_X.Integrator_CSTATE = Atomic_P.PIDController_InitialConditionF; - - /* End of SystemInitialize for SubSystem: '/Atomic Subsystem' */ -} - -/* Model terminate function */ -void Atomic_terminate(void) -{ - /* (no terminate code required) */ -} diff --git a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/Atomic.h b/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/Atomic.h deleted file mode 100644 index 5a73978..0000000 --- a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/Atomic.h +++ /dev/null @@ -1,346 +0,0 @@ -/* - * Atomic.h - * - * Academic License - for use in teaching, academic research, and meeting - * course requirements at degree granting institutions only. Not for - * government, commercial, or other organizational use. - * - * Code generation for model "Atomic". - * - * Model version : 4.4 - * Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 - * C source code generated on : Wed Jun 16 17:30:13 2021 - * - * Target selection: grt.tlc - * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Intel->x86-64 (Windows64) - * Code generation objectives: Unspecified - * Validation result: Not run - */ - -#ifndef RTW_HEADER_Atomic_h_ -#define RTW_HEADER_Atomic_h_ -#include -#ifndef Atomic_COMMON_INCLUDES_ -#define Atomic_COMMON_INCLUDES_ -#include "rtwtypes.h" -#include "rtw_continuous.h" -#include "rtw_solver.h" -#endif /* Atomic_COMMON_INCLUDES_ */ - -#include "Atomic_types.h" - -/* Shared type includes */ -#include "multiword_types.h" - -/* Macros for accessing real-time model data structure */ -#ifndef rtmGetContStateDisabled -#define rtmGetContStateDisabled(rtm) ((rtm)->contStateDisabled) -#endif - -#ifndef rtmSetContStateDisabled -#define rtmSetContStateDisabled(rtm, val) ((rtm)->contStateDisabled = (val)) -#endif - -#ifndef rtmGetContStates -#define rtmGetContStates(rtm) ((rtm)->contStates) -#endif - -#ifndef rtmSetContStates -#define rtmSetContStates(rtm, val) ((rtm)->contStates = (val)) -#endif - -#ifndef rtmGetContTimeOutputInconsistentWithStateAtMajorStepFlag -#define rtmGetContTimeOutputInconsistentWithStateAtMajorStepFlag(rtm) ((rtm)->CTOutputIncnstWithState) -#endif - -#ifndef rtmSetContTimeOutputInconsistentWithStateAtMajorStepFlag -#define rtmSetContTimeOutputInconsistentWithStateAtMajorStepFlag(rtm, val) ((rtm)->CTOutputIncnstWithState = (val)) -#endif - -#ifndef rtmGetDerivCacheNeedsReset -#define rtmGetDerivCacheNeedsReset(rtm) ((rtm)->derivCacheNeedsReset) -#endif - -#ifndef rtmSetDerivCacheNeedsReset -#define rtmSetDerivCacheNeedsReset(rtm, val) ((rtm)->derivCacheNeedsReset = (val)) -#endif - -#ifndef rtmGetIntgData -#define rtmGetIntgData(rtm) ((rtm)->intgData) -#endif - -#ifndef rtmSetIntgData -#define rtmSetIntgData(rtm, val) ((rtm)->intgData = (val)) -#endif - -#ifndef rtmGetOdeF -#define rtmGetOdeF(rtm) ((rtm)->odeF) -#endif - -#ifndef rtmSetOdeF -#define rtmSetOdeF(rtm, val) ((rtm)->odeF = (val)) -#endif - -#ifndef rtmGetOdeY -#define rtmGetOdeY(rtm) ((rtm)->odeY) -#endif - -#ifndef rtmSetOdeY -#define rtmSetOdeY(rtm, val) ((rtm)->odeY = (val)) -#endif - -#ifndef rtmGetPeriodicContStateIndices -#define rtmGetPeriodicContStateIndices(rtm) ((rtm)->periodicContStateIndices) -#endif - -#ifndef rtmSetPeriodicContStateIndices -#define rtmSetPeriodicContStateIndices(rtm, val) ((rtm)->periodicContStateIndices = (val)) -#endif - -#ifndef rtmGetPeriodicContStateRanges -#define rtmGetPeriodicContStateRanges(rtm) ((rtm)->periodicContStateRanges) -#endif - -#ifndef rtmSetPeriodicContStateRanges -#define rtmSetPeriodicContStateRanges(rtm, val) ((rtm)->periodicContStateRanges = (val)) -#endif - -#ifndef rtmGetZCCacheNeedsReset -#define rtmGetZCCacheNeedsReset(rtm) ((rtm)->zCCacheNeedsReset) -#endif - -#ifndef rtmSetZCCacheNeedsReset -#define rtmSetZCCacheNeedsReset(rtm, val) ((rtm)->zCCacheNeedsReset = (val)) -#endif - -#ifndef rtmGetdX -#define rtmGetdX(rtm) ((rtm)->derivs) -#endif - -#ifndef rtmSetdX -#define rtmSetdX(rtm, val) ((rtm)->derivs = (val)) -#endif - -#ifndef rtmGetErrorStatus -#define rtmGetErrorStatus(rtm) ((rtm)->errorStatus) -#endif - -#ifndef rtmSetErrorStatus -#define rtmSetErrorStatus(rtm, val) ((rtm)->errorStatus = (val)) -#endif - -#ifndef rtmGetStopRequested -#define rtmGetStopRequested(rtm) ((rtm)->Timing.stopRequestedFlag) -#endif - -#ifndef rtmSetStopRequested -#define rtmSetStopRequested(rtm, val) ((rtm)->Timing.stopRequestedFlag = (val)) -#endif - -#ifndef rtmGetStopRequestedPtr -#define rtmGetStopRequestedPtr(rtm) (&((rtm)->Timing.stopRequestedFlag)) -#endif - -#ifndef rtmGetT -#define rtmGetT(rtm) (rtmGetTPtr((rtm))[0]) -#endif - -#ifndef rtmGetTPtr -#define rtmGetTPtr(rtm) ((rtm)->Timing.t) -#endif - -/* Block signals (default storage) */ -typedef struct { - real_T IntegralGain; /* '/Integral Gain' */ -} B_Atomic_T; - -/* Continuous states (default storage) */ -typedef struct { - real_T Integrator_CSTATE; /* '/Integrator' */ -} X_Atomic_T; - -/* State derivatives (default storage) */ -typedef struct { - real_T Integrator_CSTATE; /* '/Integrator' */ -} XDot_Atomic_T; - -/* State disabled */ -typedef struct { - boolean_T Integrator_CSTATE; /* '/Integrator' */ -} XDis_Atomic_T; - -#ifndef ODE3_INTG -#define ODE3_INTG - -/* ODE3 Integration Data */ -typedef struct { - real_T *y; /* output */ - real_T *f[3]; /* derivatives */ -} ODE3_IntgData; - -#endif - -/* External inputs (root inport signals with default storage) */ -typedef struct { - real_T phi_m; /* '/In1' */ -} ExtU_Atomic_T; - -/* External outputs (root outports fed by signals with default storage) */ -typedef struct { - real_T Out1; /* '/Out1' */ -} ExtY_Atomic_T; - -/* Parameters (default storage) */ -struct P_Atomic_T_ { - real_T PIDController_I; /* Mask Parameter: PIDController_I - * Referenced by: '/Integral Gain' - */ - real_T PIDController_InitialConditionF; - /* Mask Parameter: PIDController_InitialConditionF - * Referenced by: '/Integrator' - */ - real_T PIDController_P; /* Mask Parameter: PIDController_P - * Referenced by: '/Proportional Gain' - */ -}; - -/* Real-time Model Data Structure */ -struct tag_RTM_Atomic_T { - const char_T *errorStatus; - RTWSolverInfo solverInfo; - X_Atomic_T *contStates; - int_T *periodicContStateIndices; - real_T *periodicContStateRanges; - real_T *derivs; - boolean_T *contStateDisabled; - boolean_T zCCacheNeedsReset; - boolean_T derivCacheNeedsReset; - boolean_T CTOutputIncnstWithState; - real_T odeY[1]; - real_T odeF[3][1]; - ODE3_IntgData intgData; - - /* - * Sizes: - * The following substructure contains sizes information - * for many of the model attributes such as inputs, outputs, - * dwork, sample times, etc. - */ - struct { - int_T numContStates; - int_T numPeriodicContStates; - int_T numSampTimes; - } Sizes; - - /* - * Timing: - * The following substructure contains information regarding - * the timing information for the model. - */ - struct { - uint32_T clockTick0; - uint32_T clockTickH0; - time_T stepSize0; - uint32_T clockTick1; - uint32_T clockTickH1; - SimTimeStep simTimeStep; - boolean_T stopRequestedFlag; - time_T *t; - time_T tArray[2]; - } Timing; -}; - -/* Block parameters (default storage) */ -extern P_Atomic_T Atomic_P; - -/* Block signals (default storage) */ -extern B_Atomic_T Atomic_B; - -/* Continuous states (default storage) */ -extern X_Atomic_T Atomic_X; - -/* External inputs (root inport signals with default storage) */ -extern ExtU_Atomic_T Atomic_U; - -/* External outputs (root outports fed by signals with default storage) */ -extern ExtY_Atomic_T Atomic_Y; - -/* Model entry point functions */ -extern void Atomic_initialize(void); -extern void Atomic_step(void); -extern void Atomic_terminate(void); - -/* Real-time Model object */ -extern RT_MODEL_Atomic_T *const Atomic_M; - -/*- - * The generated code includes comments that allow you to trace directly - * back to the appropriate location in the model. The basic format - * is /block_name, where system is the system number (uniquely - * assigned by Simulink) and block_name is the name of the block. - * - * Note that this particular code originates from a subsystem build, - * and has its own system numbers different from the parent model. - * Refer to the system hierarchy for this subsystem below, and use the - * MATLAB hilite_system command to trace the generated code back - * to the parent model. For example, - * - * hilite_system('non_lin_controll/Atomic Subsystem') - opens subsystem non_lin_controll/Atomic Subsystem - * hilite_system('non_lin_controll/Atomic Subsystem/Kp') - opens and selects block Kp - * - * Here is the system hierarchy for this model - * - * '' : 'non_lin_controll' - * '' : 'non_lin_controll/Atomic Subsystem' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Anti-windup' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/D Gain' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Filter' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Filter ICs' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/I Gain' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Ideal P Gain' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Ideal P Gain Fdbk' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Integrator' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Integrator ICs' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/N Copy' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/N Gain' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/P Copy' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Parallel P Gain' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Reset Signal' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Saturation' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Saturation Fdbk' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Sum' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Sum Fdbk' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Tracking Mode' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Tracking Mode Sum' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Tsamp - Integral' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Tsamp - Ngain' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/postSat Signal' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/preSat Signal' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Anti-windup/Passthrough' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/D Gain/Disabled' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Filter/Disabled' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Filter ICs/Disabled' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/I Gain/Internal Parameters' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Ideal P Gain/Passthrough' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Ideal P Gain Fdbk/Disabled' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Integrator/Continuous' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Integrator ICs/Internal IC' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/N Copy/Disabled wSignal Specification' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/N Gain/Disabled' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/P Copy/Disabled' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Parallel P Gain/Internal Parameters' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Reset Signal/Disabled' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Saturation/Passthrough' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Saturation Fdbk/Disabled' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Sum/Sum_PI' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Sum Fdbk/Disabled' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Tracking Mode/Disabled' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Tracking Mode Sum/Passthrough' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Tsamp - Integral/Passthrough' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/Tsamp - Ngain/Passthrough' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/postSat Signal/Forward_Path' - * '' : 'non_lin_controll/Atomic Subsystem/PID Controller/preSat Signal/Forward_Path' - */ -#endif /* RTW_HEADER_Atomic_h_ */ diff --git a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/Atomic_data.c b/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/Atomic_data.c deleted file mode 100644 index b6ad940..0000000 --- a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/Atomic_data.c +++ /dev/null @@ -1,40 +0,0 @@ -/* - * Atomic_data.c - * - * Academic License - for use in teaching, academic research, and meeting - * course requirements at degree granting institutions only. Not for - * government, commercial, or other organizational use. - * - * Code generation for model "Atomic". - * - * Model version : 4.4 - * Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 - * C source code generated on : Wed Jun 16 17:30:13 2021 - * - * Target selection: grt.tlc - * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Intel->x86-64 (Windows64) - * Code generation objectives: Unspecified - * Validation result: Not run - */ - -#include "Atomic.h" -#include "Atomic_private.h" - -/* Block parameters (default storage) */ -P_Atomic_T Atomic_P = { - /* Mask Parameter: PIDController_I - * Referenced by: '/Integral Gain' - */ - -10.0, - - /* Mask Parameter: PIDController_InitialConditionF - * Referenced by: '/Integrator' - */ - 0.0, - - /* Mask Parameter: PIDController_P - * Referenced by: '/Proportional Gain' - */ - -20.0 -}; diff --git a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/Atomic_private.h b/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/Atomic_private.h deleted file mode 100644 index 42e0c1b..0000000 --- a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/Atomic_private.h +++ /dev/null @@ -1,42 +0,0 @@ -/* - * Atomic_private.h - * - * Academic License - for use in teaching, academic research, and meeting - * course requirements at degree granting institutions only. Not for - * government, commercial, or other organizational use. - * - * Code generation for model "Atomic". - * - * Model version : 4.4 - * Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 - * C source code generated on : Wed Jun 16 17:30:13 2021 - * - * Target selection: grt.tlc - * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Intel->x86-64 (Windows64) - * Code generation objectives: Unspecified - * Validation result: Not run - */ - -#ifndef RTW_HEADER_Atomic_private_h_ -#define RTW_HEADER_Atomic_private_h_ -#include "rtwtypes.h" -#include "multiword_types.h" - -/* Private macros used by the generated code to access rtModel */ -#ifndef rtmIsMajorTimeStep -#define rtmIsMajorTimeStep(rtm) (((rtm)->Timing.simTimeStep) == MAJOR_TIME_STEP) -#endif - -#ifndef rtmIsMinorTimeStep -#define rtmIsMinorTimeStep(rtm) (((rtm)->Timing.simTimeStep) == MINOR_TIME_STEP) -#endif - -#ifndef rtmSetTPtr -#define rtmSetTPtr(rtm, val) ((rtm)->Timing.t = (val)) -#endif - -/* private model entry point functions */ -extern void Atomic_derivatives(void); - -#endif /* RTW_HEADER_Atomic_private_h_ */ diff --git a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/Atomic_types.h b/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/Atomic_types.h deleted file mode 100644 index 0104f90..0000000 --- a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/Atomic_types.h +++ /dev/null @@ -1,34 +0,0 @@ -/* - * Atomic_types.h - * - * Academic License - for use in teaching, academic research, and meeting - * course requirements at degree granting institutions only. Not for - * government, commercial, or other organizational use. - * - * Code generation for model "Atomic". - * - * Model version : 4.4 - * Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 - * C source code generated on : Wed Jun 16 17:30:13 2021 - * - * Target selection: grt.tlc - * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Intel->x86-64 (Windows64) - * Code generation objectives: Unspecified - * Validation result: Not run - */ - -#ifndef RTW_HEADER_Atomic_types_h_ -#define RTW_HEADER_Atomic_types_h_ -#include "rtwtypes.h" -#include "multiword_types.h" - -/* Model Code Variants */ - -/* Parameters (default storage) */ -typedef struct P_Atomic_T_ P_Atomic_T; - -/* Forward declaration for rtModel */ -typedef struct tag_RTM_Atomic_T RT_MODEL_Atomic_T; - -#endif /* RTW_HEADER_Atomic_types_h_ */ diff --git a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/buildInfo.mat b/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/buildInfo.mat deleted file mode 100644 index d68c58f..0000000 Binary files a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/buildInfo.mat and /dev/null differ diff --git a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/defines.txt b/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/defines.txt deleted file mode 100644 index 8dcfa81..0000000 --- a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/defines.txt +++ /dev/null @@ -1,15 +0,0 @@ -MODEL=Atomic -NUMST=2 -NCSTATES=1 -HAVESTDIO -RT -USE_RTMODEL -CLASSIC_INTERFACE=0 -ALLOCATIONFCN=0 -TID01EQ=1 -MAT_FILE=0 -ONESTEPFCN=1 -TERMFCN=1 -MULTI_INSTANCE_CODE=0 -INTEGER_CODE=0 -MT=0 diff --git a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/multiword_types.h b/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/multiword_types.h deleted file mode 100644 index ea4b8bc..0000000 --- a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/multiword_types.h +++ /dev/null @@ -1,1167 +0,0 @@ -/* - * multiword_types.h - * - * Academic License - for use in teaching, academic research, and meeting - * course requirements at degree granting institutions only. Not for - * government, commercial, or other organizational use. - * - * Code generation for model "Atomic". - * - * Model version : 4.4 - * Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 - * C source code generated on : Wed Jun 16 17:30:13 2021 - * - * Target selection: grt.tlc - * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Intel->x86-64 (Windows64) - * Code generation objectives: Unspecified - * Validation result: Not run - */ - -#ifndef MULTIWORD_TYPES_H -#define MULTIWORD_TYPES_H -#include "rtwtypes.h" - -/* - * MultiWord supporting definitions - */ -typedef long int long_T; - -/* - * MultiWord types - */ -typedef struct { - uint32_T chunks[2]; -} int64m_T; - -typedef struct { - int64m_T re; - int64m_T im; -} cint64m_T; - -typedef struct { - uint32_T chunks[2]; -} uint64m_T; - -typedef struct { - uint64m_T re; - uint64m_T im; -} cuint64m_T; - -typedef struct { - uint32_T chunks[3]; -} int96m_T; - -typedef struct { - int96m_T re; - int96m_T im; -} cint96m_T; - -typedef struct { - uint32_T chunks[3]; -} uint96m_T; - -typedef struct { - uint96m_T re; - uint96m_T im; -} cuint96m_T; - -typedef struct { - uint32_T chunks[4]; -} int128m_T; - -typedef struct { - int128m_T re; - int128m_T im; -} cint128m_T; - -typedef struct { - uint32_T chunks[4]; -} uint128m_T; - -typedef struct { - uint128m_T re; - uint128m_T im; -} cuint128m_T; - -typedef struct { - uint32_T chunks[5]; -} int160m_T; - -typedef struct { - int160m_T re; - int160m_T im; -} cint160m_T; - -typedef struct { - uint32_T chunks[5]; -} uint160m_T; - -typedef struct { - uint160m_T re; - uint160m_T im; -} cuint160m_T; - -typedef struct { - uint32_T chunks[6]; -} int192m_T; - -typedef struct { - int192m_T re; - int192m_T im; -} cint192m_T; - -typedef struct { - uint32_T chunks[6]; -} uint192m_T; - -typedef struct { - uint192m_T re; - uint192m_T im; -} cuint192m_T; - -typedef struct { - uint32_T chunks[7]; -} int224m_T; - -typedef struct { - int224m_T re; - int224m_T im; -} cint224m_T; - -typedef struct { - uint32_T chunks[7]; -} uint224m_T; - -typedef struct { - uint224m_T re; - uint224m_T im; -} cuint224m_T; - -typedef struct { - uint32_T chunks[8]; -} int256m_T; - -typedef struct { - int256m_T re; - int256m_T im; -} cint256m_T; - -typedef struct { - uint32_T chunks[8]; -} uint256m_T; - -typedef struct { - uint256m_T re; - uint256m_T im; -} cuint256m_T; - -typedef struct { - uint32_T chunks[9]; -} int288m_T; - -typedef struct { - int288m_T re; - int288m_T im; -} cint288m_T; - -typedef struct { - uint32_T chunks[9]; -} uint288m_T; - -typedef struct { - uint288m_T re; - uint288m_T im; -} cuint288m_T; - -typedef struct { - uint32_T chunks[10]; -} int320m_T; - -typedef struct { - int320m_T re; - int320m_T im; -} cint320m_T; - -typedef struct { - uint32_T chunks[10]; -} uint320m_T; - -typedef struct { - uint320m_T re; - uint320m_T im; -} cuint320m_T; - -typedef struct { - uint32_T chunks[11]; -} int352m_T; - -typedef struct { - int352m_T re; - int352m_T im; -} cint352m_T; - -typedef struct { - uint32_T chunks[11]; -} uint352m_T; - -typedef struct { - uint352m_T re; - uint352m_T im; -} cuint352m_T; - -typedef struct { - uint32_T chunks[12]; -} int384m_T; - -typedef struct { - int384m_T re; - int384m_T im; -} cint384m_T; - -typedef struct { - uint32_T chunks[12]; -} uint384m_T; - -typedef struct { - uint384m_T re; - uint384m_T im; -} cuint384m_T; - -typedef struct { - uint32_T chunks[13]; -} int416m_T; - -typedef struct { - int416m_T re; - int416m_T im; -} cint416m_T; - -typedef struct { - uint32_T chunks[13]; -} uint416m_T; - -typedef struct { - uint416m_T re; - uint416m_T im; -} cuint416m_T; - -typedef struct { - uint32_T chunks[14]; -} int448m_T; - -typedef struct { - int448m_T re; - int448m_T im; -} cint448m_T; - -typedef struct { - uint32_T chunks[14]; -} uint448m_T; - -typedef struct { - uint448m_T re; - uint448m_T im; -} cuint448m_T; - -typedef struct { - uint32_T chunks[15]; -} int480m_T; - -typedef struct { - int480m_T re; - int480m_T im; -} cint480m_T; - -typedef struct { - uint32_T chunks[15]; -} uint480m_T; - -typedef struct { - uint480m_T re; - uint480m_T im; -} cuint480m_T; - -typedef struct { - uint32_T chunks[16]; -} int512m_T; - -typedef struct { - int512m_T re; - int512m_T im; -} cint512m_T; - -typedef struct { - uint32_T chunks[16]; -} uint512m_T; - -typedef struct { - uint512m_T re; - uint512m_T im; -} cuint512m_T; - -typedef struct { - uint32_T chunks[17]; -} int544m_T; - -typedef struct { - int544m_T re; - int544m_T im; -} cint544m_T; - -typedef struct { - uint32_T chunks[17]; -} uint544m_T; - -typedef struct { - uint544m_T re; - uint544m_T im; -} cuint544m_T; - -typedef struct { - uint32_T chunks[18]; -} int576m_T; - -typedef struct { - int576m_T re; - int576m_T im; -} cint576m_T; - -typedef struct { - uint32_T chunks[18]; -} uint576m_T; - -typedef struct { - uint576m_T re; - uint576m_T im; -} cuint576m_T; - -typedef struct { - uint32_T chunks[19]; -} int608m_T; - -typedef struct { - int608m_T re; - int608m_T im; -} cint608m_T; - -typedef struct { - uint32_T chunks[19]; -} uint608m_T; - -typedef struct { - uint608m_T re; - uint608m_T im; -} cuint608m_T; - -typedef struct { - uint32_T chunks[20]; -} int640m_T; - -typedef struct { - int640m_T re; - int640m_T im; -} cint640m_T; - -typedef struct { - uint32_T chunks[20]; -} uint640m_T; - -typedef struct { - uint640m_T re; - uint640m_T im; -} cuint640m_T; - -typedef struct { - uint32_T chunks[21]; -} int672m_T; - -typedef struct { - int672m_T re; - int672m_T im; -} cint672m_T; - -typedef struct { - uint32_T chunks[21]; -} uint672m_T; - -typedef struct { - uint672m_T re; - uint672m_T im; -} cuint672m_T; - -typedef struct { - uint32_T chunks[22]; -} int704m_T; - -typedef struct { - int704m_T re; - int704m_T im; -} cint704m_T; - -typedef struct { - uint32_T chunks[22]; -} uint704m_T; - -typedef struct { - uint704m_T re; - uint704m_T im; -} cuint704m_T; - -typedef struct { - uint32_T chunks[23]; -} int736m_T; - -typedef struct { - int736m_T re; - int736m_T im; -} cint736m_T; - -typedef struct { - uint32_T chunks[23]; -} uint736m_T; - -typedef struct { - uint736m_T re; - uint736m_T im; -} cuint736m_T; - -typedef struct { - uint32_T chunks[24]; -} int768m_T; - -typedef struct { - int768m_T re; - int768m_T im; -} cint768m_T; - -typedef struct { - uint32_T chunks[24]; -} uint768m_T; - -typedef struct { - uint768m_T re; - uint768m_T im; -} cuint768m_T; - -typedef struct { - uint32_T chunks[25]; -} int800m_T; - -typedef struct { - int800m_T re; - int800m_T im; -} cint800m_T; - -typedef struct { - uint32_T chunks[25]; -} uint800m_T; - -typedef struct { - uint800m_T re; - uint800m_T im; -} cuint800m_T; - -typedef struct { - uint32_T chunks[26]; -} int832m_T; - -typedef struct { - int832m_T re; - int832m_T im; -} cint832m_T; - -typedef struct { - uint32_T chunks[26]; -} uint832m_T; - -typedef struct { - uint832m_T re; - uint832m_T im; -} cuint832m_T; - -typedef struct { - uint32_T chunks[27]; -} int864m_T; - -typedef struct { - int864m_T re; - int864m_T im; -} cint864m_T; - -typedef struct { - uint32_T chunks[27]; -} uint864m_T; - -typedef struct { - uint864m_T re; - uint864m_T im; -} cuint864m_T; - -typedef struct { - uint32_T chunks[28]; -} int896m_T; - -typedef struct { - int896m_T re; - int896m_T im; -} cint896m_T; - -typedef struct { - uint32_T chunks[28]; -} uint896m_T; - -typedef struct { - uint896m_T re; - uint896m_T im; -} cuint896m_T; - -typedef struct { - uint32_T chunks[29]; -} int928m_T; - -typedef struct { - int928m_T re; - int928m_T im; -} cint928m_T; - -typedef struct { - uint32_T chunks[29]; -} uint928m_T; - -typedef struct { - uint928m_T re; - uint928m_T im; -} cuint928m_T; - -typedef struct { - uint32_T chunks[30]; -} int960m_T; - -typedef struct { - int960m_T re; - int960m_T im; -} cint960m_T; - -typedef struct { - uint32_T chunks[30]; -} uint960m_T; - -typedef struct { - uint960m_T re; - uint960m_T im; -} cuint960m_T; - -typedef struct { - uint32_T chunks[31]; -} int992m_T; - -typedef struct { - int992m_T re; - int992m_T im; -} cint992m_T; - -typedef struct { - uint32_T chunks[31]; -} uint992m_T; - -typedef struct { - uint992m_T re; - uint992m_T im; -} cuint992m_T; - -typedef struct { - uint32_T chunks[32]; -} int1024m_T; - -typedef struct { - int1024m_T re; - int1024m_T im; -} cint1024m_T; - -typedef struct { - uint32_T chunks[32]; -} uint1024m_T; - -typedef struct { - uint1024m_T re; - uint1024m_T im; -} cuint1024m_T; - -typedef struct { - uint32_T chunks[33]; -} int1056m_T; - -typedef struct { - int1056m_T re; - int1056m_T im; -} cint1056m_T; - -typedef struct { - uint32_T chunks[33]; -} uint1056m_T; - -typedef struct { - uint1056m_T re; - uint1056m_T im; -} cuint1056m_T; - -typedef struct { - uint32_T chunks[34]; -} int1088m_T; - -typedef struct { - int1088m_T re; - int1088m_T im; -} cint1088m_T; - -typedef struct { - uint32_T chunks[34]; -} uint1088m_T; - -typedef struct { - uint1088m_T re; - uint1088m_T im; -} cuint1088m_T; - -typedef struct { - uint32_T chunks[35]; -} int1120m_T; - -typedef struct { - int1120m_T re; - int1120m_T im; -} cint1120m_T; - -typedef struct { - uint32_T chunks[35]; -} uint1120m_T; - -typedef struct { - uint1120m_T re; - uint1120m_T im; -} cuint1120m_T; - -typedef struct { - uint32_T chunks[36]; -} int1152m_T; - -typedef struct { - int1152m_T re; - int1152m_T im; -} cint1152m_T; - -typedef struct { - uint32_T chunks[36]; -} uint1152m_T; - -typedef struct { - uint1152m_T re; - uint1152m_T im; -} cuint1152m_T; - -typedef struct { - uint32_T chunks[37]; -} int1184m_T; - -typedef struct { - int1184m_T re; - int1184m_T im; -} cint1184m_T; - -typedef struct { - uint32_T chunks[37]; -} uint1184m_T; - -typedef struct { - uint1184m_T re; - uint1184m_T im; -} cuint1184m_T; - -typedef struct { - uint32_T chunks[38]; -} int1216m_T; - -typedef struct { - int1216m_T re; - int1216m_T im; -} cint1216m_T; - -typedef struct { - uint32_T chunks[38]; -} uint1216m_T; - -typedef struct { - uint1216m_T re; - uint1216m_T im; -} cuint1216m_T; - -typedef struct { - uint32_T chunks[39]; -} int1248m_T; - -typedef struct { - int1248m_T re; - int1248m_T im; -} cint1248m_T; - -typedef struct { - uint32_T chunks[39]; -} uint1248m_T; - -typedef struct { - uint1248m_T re; - uint1248m_T im; -} cuint1248m_T; - -typedef struct { - uint32_T chunks[40]; -} int1280m_T; - -typedef struct { - int1280m_T re; - int1280m_T im; -} cint1280m_T; - -typedef struct { - uint32_T chunks[40]; -} uint1280m_T; - -typedef struct { - uint1280m_T re; - uint1280m_T im; -} cuint1280m_T; - -typedef struct { - uint32_T chunks[41]; -} int1312m_T; - -typedef struct { - int1312m_T re; - int1312m_T im; -} cint1312m_T; - -typedef struct { - uint32_T chunks[41]; -} uint1312m_T; - -typedef struct { - uint1312m_T re; - uint1312m_T im; -} cuint1312m_T; - -typedef struct { - uint32_T chunks[42]; -} int1344m_T; - -typedef struct { - int1344m_T re; - int1344m_T im; -} cint1344m_T; - -typedef struct { - uint32_T chunks[42]; -} uint1344m_T; - -typedef struct { - uint1344m_T re; - uint1344m_T im; -} cuint1344m_T; - -typedef struct { - uint32_T chunks[43]; -} int1376m_T; - -typedef struct { - int1376m_T re; - int1376m_T im; -} cint1376m_T; - -typedef struct { - uint32_T chunks[43]; -} uint1376m_T; - -typedef struct { - uint1376m_T re; - uint1376m_T im; -} cuint1376m_T; - -typedef struct { - uint32_T chunks[44]; -} int1408m_T; - -typedef struct { - int1408m_T re; - int1408m_T im; -} cint1408m_T; - -typedef struct { - uint32_T chunks[44]; -} uint1408m_T; - -typedef struct { - uint1408m_T re; - uint1408m_T im; -} cuint1408m_T; - -typedef struct { - uint32_T chunks[45]; -} int1440m_T; - -typedef struct { - int1440m_T re; - int1440m_T im; -} cint1440m_T; - -typedef struct { - uint32_T chunks[45]; -} uint1440m_T; - -typedef struct { - uint1440m_T re; - uint1440m_T im; -} cuint1440m_T; - -typedef struct { - uint32_T chunks[46]; -} int1472m_T; - -typedef struct { - int1472m_T re; - int1472m_T im; -} cint1472m_T; - -typedef struct { - uint32_T chunks[46]; -} uint1472m_T; - -typedef struct { - uint1472m_T re; - uint1472m_T im; -} cuint1472m_T; - -typedef struct { - uint32_T chunks[47]; -} int1504m_T; - -typedef struct { - int1504m_T re; - int1504m_T im; -} cint1504m_T; - -typedef struct { - uint32_T chunks[47]; -} uint1504m_T; - -typedef struct { - uint1504m_T re; - uint1504m_T im; -} cuint1504m_T; - -typedef struct { - uint32_T chunks[48]; -} int1536m_T; - -typedef struct { - int1536m_T re; - int1536m_T im; -} cint1536m_T; - -typedef struct { - uint32_T chunks[48]; -} uint1536m_T; - -typedef struct { - uint1536m_T re; - uint1536m_T im; -} cuint1536m_T; - -typedef struct { - uint32_T chunks[49]; -} int1568m_T; - -typedef struct { - int1568m_T re; - int1568m_T im; -} cint1568m_T; - -typedef struct { - uint32_T chunks[49]; -} uint1568m_T; - -typedef struct { - uint1568m_T re; - uint1568m_T im; -} cuint1568m_T; - -typedef struct { - uint32_T chunks[50]; -} int1600m_T; - -typedef struct { - int1600m_T re; - int1600m_T im; -} cint1600m_T; - -typedef struct { - uint32_T chunks[50]; -} uint1600m_T; - -typedef struct { - uint1600m_T re; - uint1600m_T im; -} cuint1600m_T; - -typedef struct { - uint32_T chunks[51]; -} int1632m_T; - -typedef struct { - int1632m_T re; - int1632m_T im; -} cint1632m_T; - -typedef struct { - uint32_T chunks[51]; -} uint1632m_T; - -typedef struct { - uint1632m_T re; - uint1632m_T im; -} cuint1632m_T; - -typedef struct { - uint32_T chunks[52]; -} int1664m_T; - -typedef struct { - int1664m_T re; - int1664m_T im; -} cint1664m_T; - -typedef struct { - uint32_T chunks[52]; -} uint1664m_T; - -typedef struct { - uint1664m_T re; - uint1664m_T im; -} cuint1664m_T; - -typedef struct { - uint32_T chunks[53]; -} int1696m_T; - -typedef struct { - int1696m_T re; - int1696m_T im; -} cint1696m_T; - -typedef struct { - uint32_T chunks[53]; -} uint1696m_T; - -typedef struct { - uint1696m_T re; - uint1696m_T im; -} cuint1696m_T; - -typedef struct { - uint32_T chunks[54]; -} int1728m_T; - -typedef struct { - int1728m_T re; - int1728m_T im; -} cint1728m_T; - -typedef struct { - uint32_T chunks[54]; -} uint1728m_T; - -typedef struct { - uint1728m_T re; - uint1728m_T im; -} cuint1728m_T; - -typedef struct { - uint32_T chunks[55]; -} int1760m_T; - -typedef struct { - int1760m_T re; - int1760m_T im; -} cint1760m_T; - -typedef struct { - uint32_T chunks[55]; -} uint1760m_T; - -typedef struct { - uint1760m_T re; - uint1760m_T im; -} cuint1760m_T; - -typedef struct { - uint32_T chunks[56]; -} int1792m_T; - -typedef struct { - int1792m_T re; - int1792m_T im; -} cint1792m_T; - -typedef struct { - uint32_T chunks[56]; -} uint1792m_T; - -typedef struct { - uint1792m_T re; - uint1792m_T im; -} cuint1792m_T; - -typedef struct { - uint32_T chunks[57]; -} int1824m_T; - -typedef struct { - int1824m_T re; - int1824m_T im; -} cint1824m_T; - -typedef struct { - uint32_T chunks[57]; -} uint1824m_T; - -typedef struct { - uint1824m_T re; - uint1824m_T im; -} cuint1824m_T; - -typedef struct { - uint32_T chunks[58]; -} int1856m_T; - -typedef struct { - int1856m_T re; - int1856m_T im; -} cint1856m_T; - -typedef struct { - uint32_T chunks[58]; -} uint1856m_T; - -typedef struct { - uint1856m_T re; - uint1856m_T im; -} cuint1856m_T; - -typedef struct { - uint32_T chunks[59]; -} int1888m_T; - -typedef struct { - int1888m_T re; - int1888m_T im; -} cint1888m_T; - -typedef struct { - uint32_T chunks[59]; -} uint1888m_T; - -typedef struct { - uint1888m_T re; - uint1888m_T im; -} cuint1888m_T; - -typedef struct { - uint32_T chunks[60]; -} int1920m_T; - -typedef struct { - int1920m_T re; - int1920m_T im; -} cint1920m_T; - -typedef struct { - uint32_T chunks[60]; -} uint1920m_T; - -typedef struct { - uint1920m_T re; - uint1920m_T im; -} cuint1920m_T; - -typedef struct { - uint32_T chunks[61]; -} int1952m_T; - -typedef struct { - int1952m_T re; - int1952m_T im; -} cint1952m_T; - -typedef struct { - uint32_T chunks[61]; -} uint1952m_T; - -typedef struct { - uint1952m_T re; - uint1952m_T im; -} cuint1952m_T; - -typedef struct { - uint32_T chunks[62]; -} int1984m_T; - -typedef struct { - int1984m_T re; - int1984m_T im; -} cint1984m_T; - -typedef struct { - uint32_T chunks[62]; -} uint1984m_T; - -typedef struct { - uint1984m_T re; - uint1984m_T im; -} cuint1984m_T; - -typedef struct { - uint32_T chunks[63]; -} int2016m_T; - -typedef struct { - int2016m_T re; - int2016m_T im; -} cint2016m_T; - -typedef struct { - uint32_T chunks[63]; -} uint2016m_T; - -typedef struct { - uint2016m_T re; - uint2016m_T im; -} cuint2016m_T; - -typedef struct { - uint32_T chunks[64]; -} int2048m_T; - -typedef struct { - int2048m_T re; - int2048m_T im; -} cint2048m_T; - -typedef struct { - uint32_T chunks[64]; -} uint2048m_T; - -typedef struct { - uint2048m_T re; - uint2048m_T im; -} cuint2048m_T; - -#endif /* MULTIWORD_TYPES_H */ diff --git a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/rtwtypes.h b/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/rtwtypes.h deleted file mode 100644 index 93edbd0..0000000 --- a/zephyr/epos_controller/src/simulinkcode/Parameteridentification_example_lb/Atomic_grt_rtw/rtwtypes.h +++ /dev/null @@ -1,41 +0,0 @@ -/* - * rtwtypes.h - * - * Academic License - for use in teaching, academic research, and meeting - * course requirements at degree granting institutions only. Not for - * government, commercial, or other organizational use. - * - * Code generation for model "Atomic". - * - * Model version : 4.4 - * Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 - * C source code generated on : Wed Jun 16 17:30:13 2021 - * - * Target selection: grt.tlc - * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Intel->x86-64 (Windows64) - * Code generation objectives: Unspecified - * Validation result: Not run - */ - -#ifndef RTWTYPES_H -#define RTWTYPES_H -#include "tmwtypes.h" -#ifndef POINTER_T -#define POINTER_T - -typedef void * pointer_T; - -#endif - -/* Logical type definitions */ -#if (!defined(__cplusplus)) -#ifndef false -#define false (0U) -#endif - -#ifndef true -#define true (1U) -#endif -#endif -#endif /* RTWTYPES_H */ diff --git a/zephyr/epos_controller/src/test.cpp b/zephyr/epos_controller/src/test.cpp deleted file mode 100644 index 51f2be1..0000000 --- a/zephyr/epos_controller/src/test.cpp +++ /dev/null @@ -1,68 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include - -#define RX_THREAD_STACK_SIZE 512 -#define RX_THREAD_PRIORITY 2 -#define STATE_POLL_THREAD_STACK_SIZE 512 -#define STATE_POLL_THREAD_PRIORITY 2 -#define LED_MSG_ID 0x10 -#define COUNTER_MSG_ID 0x12345 -#define SET_LED 1 -#define RESET_LED 0 -#define SLEEP_TIME K_MSEC(250) - -struct k_thread rx_thread_data; -struct k_thread poll_state_thread_data; -struct zcan_work rx_work; -struct k_work state_change_work; -enum can_state current_state; -struct can_bus_err_cnt current_err_cnt; - - -// const struct device *can_dev = DEVICE_DT_GET(DT_ALIAS(can_dev)); -#define CAN_DEVICE_LABEL DT_PROP(DT_ALIAS(can_dev), label) - - -void main(void) -{ - k_tid_t rx_tid; - - struct zcan_frame frame = { - .id = 0x601, - .rtr = CAN_DATAFRAME, - .id_type = CAN_STANDARD_IDENTIFIER, - .dlc = 8, - .data = {0x40, 0x18, 0x10, 0x02, 0x00, 0x00, 0x00, 0x00} - }; - int ret; - - const struct device* can_dev = device_get_binding("CAN_1"); - - if (!device_is_ready(can_dev)) { - printk("CAN: Device %s not ready.\n", can_dev->name); - return; - }else{ - printk("CAN device %s is ready...\n", can_dev->name); - } - - can_set_mode(can_dev, CAN_NORMAL_MODE); - // can_set_mode(can_dev, CAN_LOOPBACK_MODE); - - while(1) - { - k_sleep(K_MSEC(1000)); - - - ret = can_send(can_dev, &frame, K_MSEC(1000), NULL, NULL); - if (ret != CAN_TX_OK) { - printk("Sending failed [%d]\n", ret); - } else { - printk("DID it :)\n"); - } - } -} \ No newline at end of file diff --git a/zephyr/epos_controller_mcp2515/CMakeLists.txt b/zephyr/epos_controller_mcp2515/CMakeLists.txt deleted file mode 100644 index 02f6fe2..0000000 --- a/zephyr/epos_controller_mcp2515/CMakeLists.txt +++ /dev/null @@ -1,10 +0,0 @@ -# Find Zephyr. This also loads Zephyr's build system. -cmake_minimum_required(VERSION 3.13.1) -find_package(Zephyr) -project(epos_controller) - -# Add your source file to the "app" target. This must come after -# find_package(Zephyr) which defines the target. -#target_sources(app PRIVATE src/test.cpp) -target_sources(app PRIVATE src/main.cpp) -target_sources(app PRIVATE src/epos4/epos4.cpp) \ No newline at end of file diff --git a/zephyr/epos_controller_mcp2515/prj.conf b/zephyr/epos_controller_mcp2515/prj.conf deleted file mode 100644 index 96e2b79..0000000 --- a/zephyr/epos_controller_mcp2515/prj.conf +++ /dev/null @@ -1,14 +0,0 @@ -CONFIG_CAN=y -CONFIG_CAN_MCP2515=y -CONFIG_CAN_STM32=n -CONFIG_CAN_INIT_PRIORITY=80 -CONFIG_CAN_MAX_FILTER=1 - -CONFIG_SPI=y -CONFIG_SPI_STM32_INTERRUPT=y - - -CONFIG_LOG=y -CONFIG_CAN_LOG_LEVEL_DBG=y -# CONFIG_SPI_LOG_LEVEL_DBG=y -CONFIG_DEBUG_OPTIMIZATIONS=y \ No newline at end of file diff --git a/zephyr/epos_controller_mcp2515/src/epos4/epos4.cpp b/zephyr/epos_controller_mcp2515/src/epos4/epos4.cpp deleted file mode 100644 index 4258ce2..0000000 --- a/zephyr/epos_controller_mcp2515/src/epos4/epos4.cpp +++ /dev/null @@ -1,438 +0,0 @@ -#include "epos4.h" - -#define MAX_DATA_SIZE 64 - -unsigned char tmp_data[MAX_DATA_SIZE] = {0}; -int32_t tmpper = 0; -uint8_t tmp_len; -uint32_t tmp_id; -uint8_t tmp_type; - -int32_t velo_inti = 0x00; - -epos4::epos4(uint32_t canid_epos, uint32_t canid_self, const struct device *CAN_INTERFACE) -{ - _canid_epos = canid_epos; - _canid_self = canid_self; - _softwareVersion = 0; - _hardwareVersion = 0; - _can_interface = CAN_INTERFACE; -} - -void epos4::init() -{ - // get state of drive - epos4::readStatusword(); - - switch( epos4::_state_of_drive ) - { - case epos4::Switch_on_disabled: - epos4::writeControlword(0x00, epos4::dcc_shutdown); - k_sleep(K_MSEC(10)); - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - k_sleep(K_MSEC(10)); - break; - - case epos4::Ready_to_switch_on: - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - k_sleep(K_MSEC(10)); - break; - - case epos4::Switched_on: - epos4::writeControlword(0x00, epos4::dcc_enableoperation); - k_sleep(K_MSEC(10)); - break; - - case epos4::Quick_stop_active: - epos4::writeControlword(0x00, epos4::dcc_enableoperation); - k_sleep(K_MSEC(10)); - break; - - case epos4::Fault: - epos4::writeControlword(0x00, epos4::dcc_faultreset); - k_sleep(K_MSEC(10)); - epos4::writeControlword(0x00, epos4::dcc_shutdown); - k_sleep(K_MSEC(10)); - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - k_sleep(K_MSEC(10)); - break; - - case epos4::Operation_enabled: - printk("Drive function is enabled and power is applied to the motor. "); - break; - - default: - printk("State of drive not found in enum ... may some error occured"); - } - - printk("Start SI config ... "); - epos4::initSI(); - printk("done!"); - - printk("Start TPDO config ... "); - epos4::configPDO(); - printk("done!"); - - - printk("EPOS enabled"); -} - -void epos4::initSI() -{ - epos4::writeControlword(0x00, epos4::dcc_shutdown); - k_sleep(K_MSEC(10)); - - char velocity_si[8] = {0x22, 0xA9, 0x60, 0x00, 0x00, 0x47, 0xB4, 0xFD}; // FD is maximum - can_write(epos4::_can_interface,(uint8_t*)velocity_si,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - - k_sleep(K_MSEC(10)); - - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - k_sleep(K_MSEC(10)); -} - -void epos4::initPPM() -{ - printk("Set Operationmode"); - unsigned char data0[8] = {0x22, 0x60, 0x60, 0x00, 0x01, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - - k_sleep(K_MSEC(10)); - - // Set all Profile Position Mode Parametersa here ... - - - // -------------------------------------------------------- - - printk("Switch on and enable ..."); - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - k_sleep(K_MSEC(10)); -} - -void epos4::initCSP() -{ - printk("Set Operationmode to CSP"); - unsigned char data0[8] = {0x22, 0x60, 0x60, 0x00, 0x08, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - // Interpolation time period value - unsigned char data01[8] = {0x22, 0xC2, 0x60, 0x01, 0x0A, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - - printk("Switch on and enable ..."); - epos4::writeControlword(0x00, epos4::dcc_shutdown); - k_sleep(K_MSEC(10)); - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - k_sleep(K_MSEC(10)); - -} - -void epos4::initCSV() -{ - printk("Set Operationmode to CSV"); - unsigned char data0[8] = {0x22, 0x60, 0x60, 0x00, 0x09, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - // Interpolation time period value - unsigned char data01[8] = {0x22, 0xC2, 0x60, 0x01, 0x0A, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data01,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - - printk("Switch on and enable ..."); - epos4::writeControlword(0x00, epos4::dcc_shutdown); - k_sleep(K_MSEC(10)); - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - k_sleep(K_MSEC(10)); -} - -void epos4::initCST() -{ - printk("Set Operationmode to CST"); - unsigned char data0[8] = {0x22, 0x60, 0x60, 0x00, 0x0A, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - - k_sleep(K_MSEC(10)); - - // Interpolation time period value - unsigned char data01[8] = {0x22, 0xC2, 0x60, 0x01, 0x0A, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data01,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - - k_sleep(K_MSEC(10)); - - - printk("Switch on and enable ..."); - epos4::writeControlword(0x00, epos4::dcc_shutdown); - k_sleep(K_MSEC(10)); - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - k_sleep(K_MSEC(10)); -} - -void epos4::sync() -{ - unsigned char data111[1] = {0x00}; - can_write(epos4::_can_interface,(uint8_t*)data111,1,0x80,CAN_DATAFRAME,K_FOREVER); -} - -/** - * @brief Send a controlword with SDO communication - * - * @details The first byte is the command specifier. For controlword its fixed with 0x2B because we want expedited transfer with const size of 2 Byte - * For more details look in >EPOS4 Firmware Specification< chapter 6.2.85 - Controlword and >EPOS4 Application Notes< chapter 5.4 - SDO Communication - * - * @param highByte - * @param lowByte - */ -void epos4::writeControlword(unsigned char highByte, unsigned char lowByte) -{ - unsigned char data[8] = {0x2B, 0x40, 0x60, 0x00, lowByte, highByte, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); -} -void epos4::readStatusword() -{ - unsigned char data[8] = {0x40, 0x41, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00}; - - printk("ask for statusword....\n"); - - can_write(epos4::_can_interface,(uint8_t*)data,8,epos4::_canid_self,CAN_DATAFRAME,K_MSEC(1000)); - printk("Sended...\n"); - while(epos4::_state_of_drive == 0x00){ - printk("Wait for Controllword...\n"); - } - printk("done!"); - -} - -void epos4::moveToPosition(uint8_t *position) -{ - // position is an 32 bit integer. Wen give the uint8 here because we can interate on the bytes from the uint32 - printk("Starte move to position ... "); - - unsigned char data[8] = {0x22, 0x7A, 0x60, 0x00, position[3], position[2], position[1], position[0]}; - //unsigned char data[8] = {0x22, 0x7A, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - - k_sleep(K_MSEC(10)); - - unsigned char data1[8] = {0x22, 0x40, 0x60, 0x00, 0x1F, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data1,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - - k_sleep(K_MSEC(10)); - - - printk("done!"); - -} - -void epos4::moveToPosition(uint32_t *posList, uint8_t len) -{ - epos4::initPPM(); - - uint32_t reversedPos; - uint32_t printPos; - uint8_t *n2; - n2 = (uint8_t *) &reversedPos; - - for( uint8_t i = 0; i < len; i+= 1 ) - { - n2[3] = (posList[i]); - n2[2] = (posList[i]) >> 8; - n2[1] = (posList[i]) >> 16; - n2[0] = (posList[i]) >> 24; - - moveToPosition(n2); - k_sleep(K_MSEC(1)); - - // printk("Toggle new poisition ..."); - epos4::writeControlword(0x00, 0x0F); - k_sleep(K_MSEC(1)); - } -} - -void epos4::configPDO() { - - // State Maschinbe of MNT Service to Pre Operational to checnge PDOs - can_write(epos4::_can_interface,(uint8_t*)(epos4::enter_preoperational),2,0x00,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - // Config of TxPDO 1 - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_transmissiontype_TxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_inhibit_time_TxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_null_TxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_first_mapped_obj_position_TxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_first_mapped_obj_velocity_TxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_TxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - - // Config of TxPDO 2 - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_transmissiontype_TxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_inhibit_time_TxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_null_TxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_first_mapped_obj_torque_TxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_TxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - - - - // Config of RxPDO 1 - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_transmissiontype_RxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_null_RxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_first_mapped_obj_position_RxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_RxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - - // Config of RxPDO 2 - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_transmissiontype_RxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_null_RxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_first_mapped_obj_position_RxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_RxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - - // Config of RxPDO 3 - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_transmissiontype_RxPDO3),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_null_RxPDO3),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_first_mapped_obj_position_RxPDO3),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_RxPDO3),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - - - // Set Statemaschine of NMT service back to Operational - can_write(epos4::_can_interface,(uint8_t*)(epos4::start_remotenode),2,0x00,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(100)); - - printk("TPDO Configured!"); -} - -/* -void epos4::getVersions(uint16_t* hardware_version, uint16_t* application_number, uint16_t* software_version, uint16_t* application_version) -{ - epos4::getProductCode(hardware_version,application_number); - epos4::getRevisionNumber(software_version,application_version); -} -void epos4::getProductCode(uint16_t* hardware_version, uint16_t* application_number) -{ - unsigned char getHardwareVersion[8] = {0x40, 0x18, 0x10, 0x02, 0x00, 0x00, 0x00, 0x00}; - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, getHardwareVersion); - - unsigned char data[MAX_DATA_SIZE] = {0}; - uint8_t len; - uint32_t id; - uint8_t type; - - epos4::checkReceivedData(data, &len, &id, &type); - epos4::printCANframe(data, &len, &id, &type); - - if( id == epos4::_canid_epos ) - { - if( data[0] == 0x43 && data[1] == 0x18 && data[2] == 0x10 && data[3] == 0x02 ) - { - (*hardware_version) = (data[7]<<8) | data[6]; - (*application_number) = (data[5]<<8) | data[4]; - epos4::_hardwareVersion = (*hardware_version); - } - } -} -void epos4::getRevisionNumber(uint16_t* software_version, uint16_t* application_version) -{ - char getSoftwareVersion[8] = {0x40, 0x18, 0x10, 0x03, 0x00, 0x00, 0x00, 0x00}; - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, getSoftwareVersion); - - unsigned char data[MAX_DATA_SIZE] = {0}; - uint8_t len; - uint32_t id; - uint8_t type; - - if( id == epos4::_canid_epos ) - { - if( data[0] == 0x43 && data[1] == 0x18 && data[2] == 0x10 && data[3] == 0x03 ) - { - (*software_version) = (data[7]<<8) | data[6]; - (*application_version) = (data[5]<<8) | data[4]; - epos4::_softwareVersion = (*software_version); - } - } -} - -void epos4::checkReceivedData(unsigned char *data, uint8_t *len, uint32_t *id, uint8_t *type, bool *check) -{ - - - if (CAN_MSGAVAIL == epos4::_can_interface->checkReceive()) - { - epos4::_can_interface->readMsgBuf(len, data); - *id = epos4::_can_interface->getCanId(); - *type = (epos4::_can_interface->isExtendedFrame() << 0) | - (epos4::_can_interface->isRemoteRequest() << 1); - if(check) *check = true; - - }else{ - if(check) *check = false; - *id = 0x0; - } -} - -void epos4::printCANframe(unsigned char *data, uint8_t *len, uint32_t *id, uint8_t *type) -{ - printk(*id, HEX); - printk(" | "); - - char buffer[2] = {0}; - - for( uint8_t i = 0; i < *len; i += 1 ) - { - // printk(data[i],HEX); - sprintf(buffer, "%02x", data[i]); - printk(buffer); - printk(" "); - } - printk(""); -} -*/ diff --git a/zephyr/epos_controller_mcp2515/src/epos4/epos4.h b/zephyr/epos_controller_mcp2515/src/epos4/epos4.h deleted file mode 100644 index 9f8c258..0000000 --- a/zephyr/epos_controller_mcp2515/src/epos4/epos4.h +++ /dev/null @@ -1,149 +0,0 @@ -#ifndef epos4_h -#define epos4_h - -#include -#include -#include -#include -#include -#include -#include - -class epos4 -{ -public: - epos4(uint32_t canid_epos, uint32_t canid_self, const struct device *CAN_INTERFACE); - - void init(); - void initSI(); - void initPPM(); - void initCSP(); - void initCSV(); - void initCST(); - void sync(); - - void moveToPosition(uint32_t *posList, uint8_t len); - void getVersions(uint16_t *hardware_version, uint16_t *application_number, uint16_t *software_version, uint16_t *application_version); - - void writeControlword(unsigned char highByte, unsigned char lowByte); - void readStatusword(); - - void checkReceivedData(unsigned char *data, uint8_t *len, uint32_t *id, uint8_t *type,bool *check=NULL); - void printCANframe(unsigned char *data, uint8_t *len, uint32_t *id, uint8_t *type); - - - const struct device *_can_interface; - - int32_t position = 0x00; - int32_t velocity = 0x00; - int16_t torque = 0x00; - - - int _softwareVersion; - int _hardwareVersion; - - uint8_t _state_of_drive = 0; - bool _target_reached = false; - - // Statemaschine enum - enum - { - Not_ready_to_switch_on = 0b00000000, - Switch_on_disabled = 0b01000000, - Ready_to_switch_on = 0b00100001, - Switched_on = 0b00100011, - Operation_enabled = 0b00100111, - Quick_stop_active = 0b00000111, - Fault_reaction_active = 0b00001111, - Fault = 0b00001000 - }; - - /** - * @addtogroup DeviceControlCommands - * @brief Device Control Commands - * @details For more details look in the EPOS4 Firmware Specification - 2.2 Device Control - * @{ - */ - enum - { - dcc_shutdown = 0x06, /**< will end in axis state >ready to switch on< */ - dcc_switchon = 0x07, /**< will end in axis state >switched on< */ - dcc_switchon_and_enable = 0x0F, /**< will end in axis state >switch on< then auto transition to >operation enabled< */ - dcc_disablevoltage = 0x00, /**< will end in axis state >switch on disabled< */ - dcc_quickstop = 0x02, /**< will end in axis state >quick stop active< */ - dcc_disableoperation = 0x07, /**< will end in axis state >switched on< */ - dcc_enableoperation = 0x0F, /**< will end in axis state >operation enabled< */ - dcc_faultreset = 0x80 /**< will end in axis state >Fault< and/or >switch on disabled< */ - }; - /** @} */ - - /** - * @addtogroup StatemaschineVariables - * @brief Statemaschine for NMT - * @details For more details look in the EPOS4 Communication Guide - 3.3.3.5 NMT Services - * @{ - */ - unsigned char enter_preoperational[2] = {0x80, 0x00}; /**< All CANopen nodes will enter NMT state >Pre-operational< */ - unsigned char reset_communication[2] = {0x82, 0x00}; /**< All CANopen nodes will first enter NMT state >Initialization< and then switch automatically >Pre-operational< */ - unsigned char reset_node[2] = {0x81, 0x00}; /**< All CANopen nodes will first enter NMT state >Initialization< and then switch automatically >Pre-operational< */ - unsigned char start_remotenode[2] = {0x01, 0x00}; /**< All CANopen nodes will enter NMT state >Operational< */ - unsigned char stop_remotenode[2] = {0x02, 0x00}; /**< All CANopen nodes will enter NMT state >Stopped< */ - /** @} */ - - - /** - * @addtogroup TxPDO config - * @brief set config for transmition pdos - * @details For more details look in the EPOS4 Communication Firmaware Specification - 6.2.21 Transmit PDO 1 parameter - * @{ - */ - // TxPDO 1 - unsigned char pdo_transmissiontype_TxPDO1[8] = {0x22, 0x00, 0x18, 0x02, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_inhibit_time_TxPDO1[8] = {0x22, 0x00, 0x18, 0x03, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_TxPDO1[8] = {0x22, 0x00, 0x1A, 0x00, 0x02, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_null_TxPDO1[8] = {0x22, 0x00, 0x1A, 0x00, 0x00, 0x00, 0x00, 0x00}; - unsigned char pdo_first_mapped_obj_position_TxPDO1[8] = {0x23, 0x00, 0x1A, 0x01, 0x20, 0x00, 0x64, 0x60}; // 104 Grad = 120000 inc - //unsigned char pdo_first_mapped_obj_velocity_TxPDO1[8] = {0x23, 0x00, 0x1A, 0x02, 0x20, 0x00, 0x6C, 0x60}; // e-10 rpm - unsigned char pdo_first_mapped_obj_velocity_TxPDO1[8] = {0x22, 0x00, 0x1A, 0x02, 0x10, 0x00, 0x77, 0x60}; // e-10 rpm - - // TxPDO 2 - unsigned char pdo_transmissiontype_TxPDO2[8] = {0x22, 0x01, 0x18, 0x02, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_inhibit_time_TxPDO2[8] = {0x22, 0x01, 0x18, 0x03, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_TxPDO2[8] = {0x22, 0x01, 0x1A, 0x00, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_null_TxPDO2[8] = {0x22, 0x01, 0x1A, 0x00, 0x00, 0x00, 0x00, 0x00}; - unsigned char pdo_first_mapped_obj_torque_TxPDO2[8] = {0x22, 0x01, 0x1A, 0x01, 0x10, 0x00, 0x77, 0x60}; - /** @} */ - - // RxPDO 1 - unsigned char pdo_transmissiontype_RxPDO1[8] = {0x22, 0x00, 0x14, 0x02, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_RxPDO1[8] = {0x22, 0x00, 0x16, 0x00, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_null_RxPDO1[8] = {0x22, 0x00, 0x16, 0x00, 0x00, 0x00, 0x00, 0x00}; - unsigned char pdo_first_mapped_obj_position_RxPDO1[8] = {0x23, 0x00, 0x16, 0x01, 0x20, 0x00, 0x7A, 0x60}; - - // RxPDO 2 - unsigned char pdo_transmissiontype_RxPDO2[8] = {0x22, 0x01, 0x14, 0x02, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_RxPDO2[8] = {0x22, 0x01, 0x16, 0x00, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_null_RxPDO2[8] = {0x22, 0x01, 0x16, 0x00, 0x00, 0x00, 0x00, 0x00}; - unsigned char pdo_first_mapped_obj_position_RxPDO2[8] = {0x23, 0x01, 0x16, 0x01, 0x20, 0x00, 0xFF, 0x60}; - - // RxPDO 3 - unsigned char pdo_transmissiontype_RxPDO3[8] = {0x22, 0x02, 0x14, 0x02, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_RxPDO3[8] = {0x22, 0x02, 0x16, 0x00, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_null_RxPDO3[8] = {0x22, 0x02, 0x16, 0x00, 0x00, 0x00, 0x00, 0x00}; - unsigned char pdo_first_mapped_obj_position_RxPDO3[8] = {0x23, 0x02, 0x16, 0x01, 0x10, 0x00, 0x71, 0x60}; - -private: - void getProductCode(uint16_t *hardware_version, uint16_t *application_number); - void getRevisionNumber(uint16_t *software_version, uint16_t *application_version); - void configPDO(); - void moveToPosition(uint8_t *position); - - uint32_t _canid_epos; - uint32_t _canid_self; - uint32_t _spi_cs_pin; - uint32_t _can_int_pin; - uint32_t _state; - -}; - -#endif diff --git a/zephyr/epos_controller_mcp2515/src/main.cpp b/zephyr/epos_controller_mcp2515/src/main.cpp deleted file mode 100644 index 77b6eb2..0000000 --- a/zephyr/epos_controller_mcp2515/src/main.cpp +++ /dev/null @@ -1,97 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include - -#include "epos4/epos4.h" - -#define RX_THREAD_STACK_SIZE 512 -#define RX_THREAD_PRIORITY 2 -#define STATE_POLL_THREAD_STACK_SIZE 512 -#define STATE_POLL_THREAD_PRIORITY 2 -#define LED_MSG_ID 0x10 -#define COUNTER_MSG_ID 0x12345 -#define SET_LED 1 -#define RESET_LED 0 -#define SLEEP_TIME K_MSEC(250) - -K_THREAD_STACK_DEFINE(rx_thread_stack, RX_THREAD_STACK_SIZE); - -#define CAN_DEVICE_LABEL DT_PROP(DT_ALIAS(can_dev), label) - -const struct device* can_dev; -// const struct device *can_dev = DEVICE_DT_GET(DT_CHOSEN(zephyr_can_primary)); - -epos4 epos4_1(0x581,0x601, can_dev); - - -struct k_thread rx_thread_data; -struct k_thread poll_state_thread_data; -struct zcan_work rx_work; -struct k_work state_change_work; -enum can_state current_state; -struct can_bus_err_cnt current_err_cnt; - -void rx_callback_function(struct zcan_frame *frame, void *arg) -{ - char *dat = (char*)(frame->data); - - if( dat[1] == 0x41 || dat[2] == 0x60 ) - { - uint16_t statusword = ( dat[5] << 8 ) | ( dat[4] ); - epos4_1._target_reached = statusword & 0b0000010000000000; - epos4_1._state_of_drive = statusword & 0b01101111; - } - - printk("MSG: "); - - for(int i = 0; i < 8; i+=1) - { - printk("%x",(unsigned char)(dat[i])); - } - - printk("\n"); -} - - - -void main(void) -{ - epos4_1._can_interface = device_get_binding("CAN_3"); - - k_tid_t rx_tid; - - if (!device_is_ready(epos4_1._can_interface)) { - printk("CAN: Device %s not ready.\n", epos4_1._can_interface->name); - return; - }else{ - printk("CAN device %s is ready...\n", epos4_1._can_interface->name); - } - can_set_mode(epos4_1._can_interface, CAN_NORMAL_MODE); - - const struct zcan_filter my_filter = { - .id = 0x581, - .rtr = CAN_DATAFRAME, - .id_type = CAN_STANDARD_IDENTIFIER, - .id_mask = CAN_STD_ID_MASK, - .rtr_mask = 1 - }; - int filter_id; - - filter_id = can_attach_isr(epos4_1._can_interface, rx_callback_function, NULL, &my_filter); - if (filter_id < 0) { - printk("Unable to attach isr [%d]", filter_id); - } - - printk("start init..."); - epos4_1.init(); - printk(" done!"); - while(1) - { - k_sleep(K_MSEC(1000)); - printk("Test ... \n"); - } -} \ No newline at end of file diff --git a/zephyr/epos_controller_mcp2515/src/test.cpp b/zephyr/epos_controller_mcp2515/src/test.cpp deleted file mode 100644 index 9462eb9..0000000 --- a/zephyr/epos_controller_mcp2515/src/test.cpp +++ /dev/null @@ -1,65 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include - -#define RX_THREAD_STACK_SIZE 512 -#define RX_THREAD_PRIORITY 2 -#define STATE_POLL_THREAD_STACK_SIZE 512 -#define STATE_POLL_THREAD_PRIORITY 2 -#define LED_MSG_ID 0x10 -#define COUNTER_MSG_ID 0x12345 -#define SET_LED 1 -#define RESET_LED 0 -#define SLEEP_TIME K_MSEC(250) - -struct k_thread rx_thread_data; -struct k_thread poll_state_thread_data; -struct zcan_work rx_work; -struct k_work state_change_work; -enum can_state current_state; -struct can_bus_err_cnt current_err_cnt; - - -// const struct device *can_dev = DEVICE_DT_GET(DT_ALIAS(can_dev)); -#define CAN_DEVICE_LABEL DT_PROP(DT_ALIAS(can_dev), label) - - -void main(void) -{ - k_tid_t rx_tid; - - struct zcan_frame frame = { - .id = 0x123, - .rtr = CAN_DATAFRAME, - .id_type = CAN_STANDARD_IDENTIFIER, - .dlc = 8, - .data = {1,2,3,4,5,6,7,8} - }; - int ret; - - const struct device* can_dev = device_get_binding("CAN_3"); - - if (!device_is_ready(can_dev)) { - printk("CAN: Device %s not ready.\n", can_dev->name); - return; - }else{ - printk("CAN device %s is ready...\n", can_dev->name); - } - - can_set_mode(can_dev, CAN_NORMAL_MODE); - - while(1) - { - k_sleep(K_MSEC(1000)); - - - ret = can_send(can_dev, &frame, K_FOREVER, NULL, NULL); - if (ret != CAN_TX_OK) { - printk("Sending failed [%d]\n", ret); - } - } -} \ No newline at end of file diff --git a/zephyr/epos_controller_mcp2515/stm32f4_disco.overlay b/zephyr/epos_controller_mcp2515/stm32f4_disco.overlay deleted file mode 100644 index 40cc48b..0000000 --- a/zephyr/epos_controller_mcp2515/stm32f4_disco.overlay +++ /dev/null @@ -1,31 +0,0 @@ -&spi2 { - status = "okay"; - // cs-gpios = <&arduino_header 16 GPIO_ACTIVE_LOW>; /* D10 */ - pinctrl-0 = <&spi2_mosi_pb15 &spi2_miso_pb14 &spi2_sck_pb13 &spi2_nss_pb12>; - can3: mcp2515@0 { - compatible = "microchip,mcp2515"; - spi-max-frequency = <1000000>; - int-gpios = <&gpioa 1 GPIO_ACTIVE_LOW>; /* D2 */ - status = "okay"; - label = "CAN_3"; - reg = <0x0>; - osc-freq = <16000000>; - bus-speed = <125000>; - sjw = <1>; - prop-seg = <2>; - phase-seg1 = <7>; - phase-seg2 = <6>; - #address-cells = <1>; - #size-cells = <0>; - }; -}; - -&can2 { - status = "disabled"; -}; - -/ { - aliases { - can-dev = &can3; - }; -}; \ No newline at end of file diff --git a/zephyr/epos_controller_model/CMakeLists.txt b/zephyr/epos_controller_model/CMakeLists.txt deleted file mode 100644 index bfc360d..0000000 --- a/zephyr/epos_controller_model/CMakeLists.txt +++ /dev/null @@ -1,15 +0,0 @@ -# Find Zephyr. This also loads Zephyr's build system. -cmake_minimum_required(VERSION 3.13.1) -find_package(Zephyr) -project(epos_controller_model) - -# Add your source file to the "app" target. This must come after -# find_package(Zephyr) which defines the target. -target_sources(app PRIVATE src/main.c - src/codegeneration/assdf_grt_rtw/assdf.c - src/codegeneration/assdf_grt_rtw/assdf_data.c -) - -target_include_directories(app PUBLIC src/codegeneration/assdf_grt_rtw main.c) -target_include_directories(app PUBLIC src/R2021a/extern/include main.c) -target_include_directories(app PUBLIC src/R2021a/simulink/include main.c) \ No newline at end of file diff --git a/zephyr/epos_controller_model/prj.conf b/zephyr/epos_controller_model/prj.conf deleted file mode 100644 index 3cf038e..0000000 --- a/zephyr/epos_controller_model/prj.conf +++ /dev/null @@ -1,9 +0,0 @@ -CONFIG_CAN=y -CONFIG_CAN_INIT_PRIORITY=80 -CONFIG_CAN_MAX_FILTER=1 - -CONFIG_LOG=y -CONFIG_CAN_LOG_LEVEL_DBG=y -CONFIG_DEBUG_OPTIMIZATIONS=y - -CONFIG_CBPRINTF_FP_SUPPORT=y \ No newline at end of file diff --git a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/assdf.c b/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/assdf.c deleted file mode 100644 index 709b1e8..0000000 --- a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/assdf.c +++ /dev/null @@ -1,248 +0,0 @@ -/* - * assdf.c - * - * Academic License - for use in teaching, academic research, and meeting - * course requirements at degree granting institutions only. Not for - * government, commercial, or other organizational use. - * - * Code generation for model "assdf". - * - * Model version : 1.1 - * Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 - * C source code generated on : Wed May 19 11:33:56 2021 - * - * Target selection: grt.tlc - * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Intel->x86-64 (Windows64) - * Code generation objectives: Unspecified - * Validation result: Not run - */ - -#include "assdf.h" -#include "assdf_private.h" - -/* Continuous states */ -X_assdf_T assdf_X; - -/* External inputs (root inport signals with default storage) */ -ExtU_assdf_T assdf_U; - -/* External outputs (root outports fed by signals with default storage) */ -ExtY_assdf_T assdf_Y; - -/* Real-time model */ -static RT_MODEL_assdf_T assdf_M_; -RT_MODEL_assdf_T *const assdf_M = &assdf_M_; - -/* - * This function updates continuous states using the ODE4 fixed-step - * solver algorithm - */ -static void rt_ertODEUpdateContinuousStates(RTWSolverInfo *si ) -{ - time_T t = rtsiGetT(si); - time_T tnew = rtsiGetSolverStopTime(si); - time_T h = rtsiGetStepSize(si); - real_T *x = rtsiGetContStates(si); - ODE4_IntgData *id = (ODE4_IntgData *)rtsiGetSolverData(si); - real_T *y = id->y; - real_T *f0 = id->f[0]; - real_T *f1 = id->f[1]; - real_T *f2 = id->f[2]; - real_T *f3 = id->f[3]; - real_T temp; - int_T i; - int_T nXc = 1; - rtsiSetSimTimeStep(si,MINOR_TIME_STEP); - - /* Save the state values at time t in y, we'll use x as ynew. */ - (void) memcpy(y, x, - (uint_T)nXc*sizeof(real_T)); - - /* Assumes that rtsiSetT and ModelOutputs are up-to-date */ - /* f0 = f(t,y) */ - rtsiSetdX(si, f0); - assdf_derivatives(); - - /* f1 = f(t + (h/2), y + (h/2)*f0) */ - temp = 0.5 * h; - for (i = 0; i < nXc; i++) { - x[i] = y[i] + (temp*f0[i]); - } - - rtsiSetT(si, t + temp); - rtsiSetdX(si, f1); - assdf_step(); - assdf_derivatives(); - - /* f2 = f(t + (h/2), y + (h/2)*f1) */ - for (i = 0; i < nXc; i++) { - x[i] = y[i] + (temp*f1[i]); - } - - rtsiSetdX(si, f2); - assdf_step(); - assdf_derivatives(); - - /* f3 = f(t + h, y + h*f2) */ - for (i = 0; i < nXc; i++) { - x[i] = y[i] + (h*f2[i]); - } - - rtsiSetT(si, tnew); - rtsiSetdX(si, f3); - assdf_step(); - assdf_derivatives(); - - /* tnew = t + h - ynew = y + (h/6)*(f0 + 2*f1 + 2*f2 + 2*f3) */ - temp = h / 6.0; - for (i = 0; i < nXc; i++) { - x[i] = y[i] + temp*(f0[i] + 2.0*f1[i] + 2.0*f2[i] + f3[i]); - } - - rtsiSetSimTimeStep(si,MAJOR_TIME_STEP); -} - -/* Model step function */ -void assdf_step(void) -{ - if (rtmIsMajorTimeStep(assdf_M)) { - /* set solver stop time */ - if (!(assdf_M->Timing.clockTick0+1)) { - rtsiSetSolverStopTime(&assdf_M->solverInfo, ((assdf_M->Timing.clockTickH0 - + 1) * assdf_M->Timing.stepSize0 * 4294967296.0)); - } else { - rtsiSetSolverStopTime(&assdf_M->solverInfo, ((assdf_M->Timing.clockTick0 + - 1) * assdf_M->Timing.stepSize0 + assdf_M->Timing.clockTickH0 * - assdf_M->Timing.stepSize0 * 4294967296.0)); - } - } /* end MajorTimeStep */ - - /* Update absolute time of base rate at minor time step */ - if (rtmIsMinorTimeStep(assdf_M)) { - assdf_M->Timing.t[0] = rtsiGetT(&assdf_M->solverInfo); - } - - /* Outputs for Atomic SubSystem: '/assdf' */ - /* Outport: '/Out1' incorporates: - * Gain: '/Gain' - * Integrator: '/Integrator' - */ - assdf_Y.Out1 = assdf_P.Gain_Gain * assdf_X.Integrator_CSTATE; - - /* End of Outputs for SubSystem: '/assdf' */ - if (rtmIsMajorTimeStep(assdf_M)) { - rt_ertODEUpdateContinuousStates(&assdf_M->solverInfo); - - /* Update absolute time for base rate */ - /* The "clockTick0" counts the number of times the code of this task has - * been executed. The absolute time is the multiplication of "clockTick0" - * and "Timing.stepSize0". Size of "clockTick0" ensures timer will not - * overflow during the application lifespan selected. - * Timer of this task consists of two 32 bit unsigned integers. - * The two integers represent the low bits Timing.clockTick0 and the high bits - * Timing.clockTickH0. When the low bit overflows to 0, the high bits increment. - */ - if (!(++assdf_M->Timing.clockTick0)) { - ++assdf_M->Timing.clockTickH0; - } - - assdf_M->Timing.t[0] = rtsiGetSolverStopTime(&assdf_M->solverInfo); - - { - /* Update absolute timer for sample time: [0.01s, 0.0s] */ - /* The "clockTick1" counts the number of times the code of this task has - * been executed. The resolution of this integer timer is 0.01, which is the step size - * of the task. Size of "clockTick1" ensures timer will not overflow during the - * application lifespan selected. - * Timer of this task consists of two 32 bit unsigned integers. - * The two integers represent the low bits Timing.clockTick1 and the high bits - * Timing.clockTickH1. When the low bit overflows to 0, the high bits increment. - */ - assdf_M->Timing.clockTick1++; - if (!assdf_M->Timing.clockTick1) { - assdf_M->Timing.clockTickH1++; - } - } - } /* end MajorTimeStep */ -} - -/* Derivatives for root system: '' */ -void assdf_derivatives(void) -{ - XDot_assdf_T *_rtXdot; - _rtXdot = ((XDot_assdf_T *) assdf_M->derivs); - - /* Derivatives for Atomic SubSystem: '/assdf' */ - /* Derivatives for Integrator: '/Integrator' incorporates: - * Inport: '/In1' - */ - _rtXdot->Integrator_CSTATE = assdf_U.In1; - - /* End of Derivatives for SubSystem: '/assdf' */ -} - -/* Model initialize function */ -void assdf_initialize(void) -{ - /* Registration code */ - - /* initialize real-time model */ - (void) memset((void *)assdf_M, 0, - sizeof(RT_MODEL_assdf_T)); - - { - /* Setup solver object */ - rtsiSetSimTimeStepPtr(&assdf_M->solverInfo, &assdf_M->Timing.simTimeStep); - rtsiSetTPtr(&assdf_M->solverInfo, &rtmGetTPtr(assdf_M)); - rtsiSetStepSizePtr(&assdf_M->solverInfo, &assdf_M->Timing.stepSize0); - rtsiSetdXPtr(&assdf_M->solverInfo, &assdf_M->derivs); - rtsiSetContStatesPtr(&assdf_M->solverInfo, (real_T **) &assdf_M->contStates); - rtsiSetNumContStatesPtr(&assdf_M->solverInfo, &assdf_M->Sizes.numContStates); - rtsiSetNumPeriodicContStatesPtr(&assdf_M->solverInfo, - &assdf_M->Sizes.numPeriodicContStates); - rtsiSetPeriodicContStateIndicesPtr(&assdf_M->solverInfo, - &assdf_M->periodicContStateIndices); - rtsiSetPeriodicContStateRangesPtr(&assdf_M->solverInfo, - &assdf_M->periodicContStateRanges); - rtsiSetErrorStatusPtr(&assdf_M->solverInfo, (&rtmGetErrorStatus(assdf_M))); - rtsiSetRTModelPtr(&assdf_M->solverInfo, assdf_M); - } - - rtsiSetSimTimeStep(&assdf_M->solverInfo, MAJOR_TIME_STEP); - assdf_M->intgData.y = assdf_M->odeY; - assdf_M->intgData.f[0] = assdf_M->odeF[0]; - assdf_M->intgData.f[1] = assdf_M->odeF[1]; - assdf_M->intgData.f[2] = assdf_M->odeF[2]; - assdf_M->intgData.f[3] = assdf_M->odeF[3]; - assdf_M->contStates = ((X_assdf_T *) &assdf_X); - rtsiSetSolverData(&assdf_M->solverInfo, (void *)&assdf_M->intgData); - rtsiSetSolverName(&assdf_M->solverInfo,"ode4"); - rtmSetTPtr(assdf_M, &assdf_M->Timing.tArray[0]); - assdf_M->Timing.stepSize0 = 0.01; - - /* states (continuous) */ - { - (void) memset((void *)&assdf_X, 0, - sizeof(X_assdf_T)); - } - - /* external inputs */ - assdf_U.In1 = 0.0; - - /* external outputs */ - assdf_Y.Out1 = 0.0; - - /* SystemInitialize for Atomic SubSystem: '/assdf' */ - /* InitializeConditions for Integrator: '/Integrator' */ - assdf_X.Integrator_CSTATE = assdf_P.Integrator_IC; - - /* End of SystemInitialize for SubSystem: '/assdf' */ -} - -/* Model terminate function */ -void assdf_terminate(void) -{ - /* (no terminate code required) */ -} diff --git a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/assdf.h b/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/assdf.h deleted file mode 100644 index d5d0ad3..0000000 --- a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/assdf.h +++ /dev/null @@ -1,285 +0,0 @@ -/* - * assdf.h - * - * Academic License - for use in teaching, academic research, and meeting - * course requirements at degree granting institutions only. Not for - * government, commercial, or other organizational use. - * - * Code generation for model "assdf". - * - * Model version : 1.1 - * Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 - * C source code generated on : Wed May 19 11:33:56 2021 - * - * Target selection: grt.tlc - * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Intel->x86-64 (Windows64) - * Code generation objectives: Unspecified - * Validation result: Not run - */ - -#ifndef RTW_HEADER_assdf_h_ -#define RTW_HEADER_assdf_h_ -#include -#ifndef assdf_COMMON_INCLUDES_ -#define assdf_COMMON_INCLUDES_ -#include "rtwtypes.h" -#include "rtw_continuous.h" -#include "rtw_solver.h" -#endif /* assdf_COMMON_INCLUDES_ */ - -#include "assdf_types.h" - -/* Shared type includes */ -#include "multiword_types.h" - -/* Macros for accessing real-time model data structure */ -#ifndef rtmGetContStateDisabled -#define rtmGetContStateDisabled(rtm) ((rtm)->contStateDisabled) -#endif - -#ifndef rtmSetContStateDisabled -#define rtmSetContStateDisabled(rtm, val) ((rtm)->contStateDisabled = (val)) -#endif - -#ifndef rtmGetContStates -#define rtmGetContStates(rtm) ((rtm)->contStates) -#endif - -#ifndef rtmSetContStates -#define rtmSetContStates(rtm, val) ((rtm)->contStates = (val)) -#endif - -#ifndef rtmGetContTimeOutputInconsistentWithStateAtMajorStepFlag -#define rtmGetContTimeOutputInconsistentWithStateAtMajorStepFlag(rtm) ((rtm)->CTOutputIncnstWithState) -#endif - -#ifndef rtmSetContTimeOutputInconsistentWithStateAtMajorStepFlag -#define rtmSetContTimeOutputInconsistentWithStateAtMajorStepFlag(rtm, val) ((rtm)->CTOutputIncnstWithState = (val)) -#endif - -#ifndef rtmGetDerivCacheNeedsReset -#define rtmGetDerivCacheNeedsReset(rtm) ((rtm)->derivCacheNeedsReset) -#endif - -#ifndef rtmSetDerivCacheNeedsReset -#define rtmSetDerivCacheNeedsReset(rtm, val) ((rtm)->derivCacheNeedsReset = (val)) -#endif - -#ifndef rtmGetIntgData -#define rtmGetIntgData(rtm) ((rtm)->intgData) -#endif - -#ifndef rtmSetIntgData -#define rtmSetIntgData(rtm, val) ((rtm)->intgData = (val)) -#endif - -#ifndef rtmGetOdeF -#define rtmGetOdeF(rtm) ((rtm)->odeF) -#endif - -#ifndef rtmSetOdeF -#define rtmSetOdeF(rtm, val) ((rtm)->odeF = (val)) -#endif - -#ifndef rtmGetOdeY -#define rtmGetOdeY(rtm) ((rtm)->odeY) -#endif - -#ifndef rtmSetOdeY -#define rtmSetOdeY(rtm, val) ((rtm)->odeY = (val)) -#endif - -#ifndef rtmGetPeriodicContStateIndices -#define rtmGetPeriodicContStateIndices(rtm) ((rtm)->periodicContStateIndices) -#endif - -#ifndef rtmSetPeriodicContStateIndices -#define rtmSetPeriodicContStateIndices(rtm, val) ((rtm)->periodicContStateIndices = (val)) -#endif - -#ifndef rtmGetPeriodicContStateRanges -#define rtmGetPeriodicContStateRanges(rtm) ((rtm)->periodicContStateRanges) -#endif - -#ifndef rtmSetPeriodicContStateRanges -#define rtmSetPeriodicContStateRanges(rtm, val) ((rtm)->periodicContStateRanges = (val)) -#endif - -#ifndef rtmGetZCCacheNeedsReset -#define rtmGetZCCacheNeedsReset(rtm) ((rtm)->zCCacheNeedsReset) -#endif - -#ifndef rtmSetZCCacheNeedsReset -#define rtmSetZCCacheNeedsReset(rtm, val) ((rtm)->zCCacheNeedsReset = (val)) -#endif - -#ifndef rtmGetdX -#define rtmGetdX(rtm) ((rtm)->derivs) -#endif - -#ifndef rtmSetdX -#define rtmSetdX(rtm, val) ((rtm)->derivs = (val)) -#endif - -#ifndef rtmGetErrorStatus -#define rtmGetErrorStatus(rtm) ((rtm)->errorStatus) -#endif - -#ifndef rtmSetErrorStatus -#define rtmSetErrorStatus(rtm, val) ((rtm)->errorStatus = (val)) -#endif - -#ifndef rtmGetStopRequested -#define rtmGetStopRequested(rtm) ((rtm)->Timing.stopRequestedFlag) -#endif - -#ifndef rtmSetStopRequested -#define rtmSetStopRequested(rtm, val) ((rtm)->Timing.stopRequestedFlag = (val)) -#endif - -#ifndef rtmGetStopRequestedPtr -#define rtmGetStopRequestedPtr(rtm) (&((rtm)->Timing.stopRequestedFlag)) -#endif - -#ifndef rtmGetT -#define rtmGetT(rtm) (rtmGetTPtr((rtm))[0]) -#endif - -#ifndef rtmGetTPtr -#define rtmGetTPtr(rtm) ((rtm)->Timing.t) -#endif - -/* Continuous states (default storage) */ -typedef struct { - real_T Integrator_CSTATE; /* '/Integrator' */ -} X_assdf_T; - -/* State derivatives (default storage) */ -typedef struct { - real_T Integrator_CSTATE; /* '/Integrator' */ -} XDot_assdf_T; - -/* State disabled */ -typedef struct { - boolean_T Integrator_CSTATE; /* '/Integrator' */ -} XDis_assdf_T; - -#ifndef ODE4_INTG -#define ODE4_INTG - -/* ODE4 Integration Data */ -typedef struct { - real_T *y; /* output */ - real_T *f[4]; /* derivatives */ -} ODE4_IntgData; - -#endif - -/* External inputs (root inport signals with default storage) */ -typedef struct { - real_T In1; /* '/In1' */ -} ExtU_assdf_T; - -/* External outputs (root outports fed by signals with default storage) */ -typedef struct { - real_T Out1; /* '/Out1' */ -} ExtY_assdf_T; - -/* Parameters (default storage) */ -struct P_assdf_T_ { - real_T Integrator_IC; /* Expression: 0 - * Referenced by: '/Integrator' - */ - real_T Gain_Gain; /* Expression: 2.5 - * Referenced by: '/Gain' - */ -}; - -/* Real-time Model Data Structure */ -struct tag_RTM_assdf_T { - const char_T *errorStatus; - RTWSolverInfo solverInfo; - X_assdf_T *contStates; - int_T *periodicContStateIndices; - real_T *periodicContStateRanges; - real_T *derivs; - boolean_T *contStateDisabled; - boolean_T zCCacheNeedsReset; - boolean_T derivCacheNeedsReset; - boolean_T CTOutputIncnstWithState; - real_T odeY[1]; - real_T odeF[4][1]; - ODE4_IntgData intgData; - - /* - * Sizes: - * The following substructure contains sizes information - * for many of the model attributes such as inputs, outputs, - * dwork, sample times, etc. - */ - struct { - int_T numContStates; - int_T numPeriodicContStates; - int_T numSampTimes; - } Sizes; - - /* - * Timing: - * The following substructure contains information regarding - * the timing information for the model. - */ - struct { - uint32_T clockTick0; - uint32_T clockTickH0; - time_T stepSize0; - uint32_T clockTick1; - uint32_T clockTickH1; - SimTimeStep simTimeStep; - boolean_T stopRequestedFlag; - time_T *t; - time_T tArray[2]; - } Timing; -}; - -/* Block parameters (default storage) */ -extern P_assdf_T assdf_P; - -/* Continuous states (default storage) */ -extern X_assdf_T assdf_X; - -/* External inputs (root inport signals with default storage) */ -extern ExtU_assdf_T assdf_U; - -/* External outputs (root outports fed by signals with default storage) */ -extern ExtY_assdf_T assdf_Y; - -/* Model entry point functions */ -extern void assdf_initialize(void); -extern void assdf_step(void); -extern void assdf_terminate(void); - -/* Real-time Model object */ -extern RT_MODEL_assdf_T *const assdf_M; - -/*- - * The generated code includes comments that allow you to trace directly - * back to the appropriate location in the model. The basic format - * is /block_name, where system is the system number (uniquely - * assigned by Simulink) and block_name is the name of the block. - * - * Note that this particular code originates from a subsystem build, - * and has its own system numbers different from the parent model. - * Refer to the system hierarchy for this subsystem below, and use the - * MATLAB hilite_system command to trace the generated code back - * to the parent model. For example, - * - * hilite_system('subsystem_test/assdf') - opens subsystem subsystem_test/assdf - * hilite_system('subsystem_test/assdf/Kp') - opens and selects block Kp - * - * Here is the system hierarchy for this model - * - * '' : 'subsystem_test' - * '' : 'subsystem_test/assdf' - */ -#endif /* RTW_HEADER_assdf_h_ */ diff --git a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/assdf_data.c b/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/assdf_data.c deleted file mode 100644 index 3ce5ad1..0000000 --- a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/assdf_data.c +++ /dev/null @@ -1,35 +0,0 @@ -/* - * assdf_data.c - * - * Academic License - for use in teaching, academic research, and meeting - * course requirements at degree granting institutions only. Not for - * government, commercial, or other organizational use. - * - * Code generation for model "assdf". - * - * Model version : 1.1 - * Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 - * C source code generated on : Wed May 19 11:33:56 2021 - * - * Target selection: grt.tlc - * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Intel->x86-64 (Windows64) - * Code generation objectives: Unspecified - * Validation result: Not run - */ - -#include "assdf.h" -#include "assdf_private.h" - -/* Block parameters (default storage) */ -P_assdf_T assdf_P = { - /* Expression: 0 - * Referenced by: '/Integrator' - */ - 0.0, - - /* Expression: 2.5 - * Referenced by: '/Gain' - */ - 2.5 -}; diff --git a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/assdf_private.h b/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/assdf_private.h deleted file mode 100644 index 037871a..0000000 --- a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/assdf_private.h +++ /dev/null @@ -1,42 +0,0 @@ -/* - * assdf_private.h - * - * Academic License - for use in teaching, academic research, and meeting - * course requirements at degree granting institutions only. Not for - * government, commercial, or other organizational use. - * - * Code generation for model "assdf". - * - * Model version : 1.1 - * Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 - * C source code generated on : Wed May 19 11:33:56 2021 - * - * Target selection: grt.tlc - * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Intel->x86-64 (Windows64) - * Code generation objectives: Unspecified - * Validation result: Not run - */ - -#ifndef RTW_HEADER_assdf_private_h_ -#define RTW_HEADER_assdf_private_h_ -#include "rtwtypes.h" -#include "multiword_types.h" - -/* Private macros used by the generated code to access rtModel */ -#ifndef rtmIsMajorTimeStep -#define rtmIsMajorTimeStep(rtm) (((rtm)->Timing.simTimeStep) == MAJOR_TIME_STEP) -#endif - -#ifndef rtmIsMinorTimeStep -#define rtmIsMinorTimeStep(rtm) (((rtm)->Timing.simTimeStep) == MINOR_TIME_STEP) -#endif - -#ifndef rtmSetTPtr -#define rtmSetTPtr(rtm, val) ((rtm)->Timing.t = (val)) -#endif - -/* private model entry point functions */ -extern void assdf_derivatives(void); - -#endif /* RTW_HEADER_assdf_private_h_ */ diff --git a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/assdf_types.h b/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/assdf_types.h deleted file mode 100644 index 0e77cca..0000000 --- a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/assdf_types.h +++ /dev/null @@ -1,34 +0,0 @@ -/* - * assdf_types.h - * - * Academic License - for use in teaching, academic research, and meeting - * course requirements at degree granting institutions only. Not for - * government, commercial, or other organizational use. - * - * Code generation for model "assdf". - * - * Model version : 1.1 - * Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 - * C source code generated on : Wed May 19 11:33:56 2021 - * - * Target selection: grt.tlc - * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Intel->x86-64 (Windows64) - * Code generation objectives: Unspecified - * Validation result: Not run - */ - -#ifndef RTW_HEADER_assdf_types_h_ -#define RTW_HEADER_assdf_types_h_ -#include "rtwtypes.h" -#include "multiword_types.h" - -/* Model Code Variants */ - -/* Parameters (default storage) */ -typedef struct P_assdf_T_ P_assdf_T; - -/* Forward declaration for rtModel */ -typedef struct tag_RTM_assdf_T RT_MODEL_assdf_T; - -#endif /* RTW_HEADER_assdf_types_h_ */ diff --git a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/buildInfo.mat b/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/buildInfo.mat deleted file mode 100644 index ab5ee31..0000000 Binary files a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/buildInfo.mat and /dev/null differ diff --git a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/defines.txt b/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/defines.txt deleted file mode 100644 index 42bd84e..0000000 --- a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/defines.txt +++ /dev/null @@ -1,15 +0,0 @@ -MODEL=assdf -NUMST=2 -NCSTATES=1 -HAVESTDIO -RT -USE_RTMODEL -CLASSIC_INTERFACE=0 -ALLOCATIONFCN=0 -TID01EQ=1 -MAT_FILE=0 -ONESTEPFCN=1 -TERMFCN=1 -MULTI_INSTANCE_CODE=0 -INTEGER_CODE=0 -MT=0 diff --git a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/multiword_types.h b/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/multiword_types.h deleted file mode 100644 index 95e1282..0000000 --- a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/multiword_types.h +++ /dev/null @@ -1,1167 +0,0 @@ -/* - * multiword_types.h - * - * Academic License - for use in teaching, academic research, and meeting - * course requirements at degree granting institutions only. Not for - * government, commercial, or other organizational use. - * - * Code generation for model "assdf". - * - * Model version : 1.1 - * Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 - * C source code generated on : Wed May 19 11:33:56 2021 - * - * Target selection: grt.tlc - * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Intel->x86-64 (Windows64) - * Code generation objectives: Unspecified - * Validation result: Not run - */ - -#ifndef MULTIWORD_TYPES_H -#define MULTIWORD_TYPES_H -#include "rtwtypes.h" - -/* - * MultiWord supporting definitions - */ -typedef long int long_T; - -/* - * MultiWord types - */ -typedef struct { - uint32_T chunks[2]; -} int64m_T; - -typedef struct { - int64m_T re; - int64m_T im; -} cint64m_T; - -typedef struct { - uint32_T chunks[2]; -} uint64m_T; - -typedef struct { - uint64m_T re; - uint64m_T im; -} cuint64m_T; - -typedef struct { - uint32_T chunks[3]; -} int96m_T; - -typedef struct { - int96m_T re; - int96m_T im; -} cint96m_T; - -typedef struct { - uint32_T chunks[3]; -} uint96m_T; - -typedef struct { - uint96m_T re; - uint96m_T im; -} cuint96m_T; - -typedef struct { - uint32_T chunks[4]; -} int128m_T; - -typedef struct { - int128m_T re; - int128m_T im; -} cint128m_T; - -typedef struct { - uint32_T chunks[4]; -} uint128m_T; - -typedef struct { - uint128m_T re; - uint128m_T im; -} cuint128m_T; - -typedef struct { - uint32_T chunks[5]; -} int160m_T; - -typedef struct { - int160m_T re; - int160m_T im; -} cint160m_T; - -typedef struct { - uint32_T chunks[5]; -} uint160m_T; - -typedef struct { - uint160m_T re; - uint160m_T im; -} cuint160m_T; - -typedef struct { - uint32_T chunks[6]; -} int192m_T; - -typedef struct { - int192m_T re; - int192m_T im; -} cint192m_T; - -typedef struct { - uint32_T chunks[6]; -} uint192m_T; - -typedef struct { - uint192m_T re; - uint192m_T im; -} cuint192m_T; - -typedef struct { - uint32_T chunks[7]; -} int224m_T; - -typedef struct { - int224m_T re; - int224m_T im; -} cint224m_T; - -typedef struct { - uint32_T chunks[7]; -} uint224m_T; - -typedef struct { - uint224m_T re; - uint224m_T im; -} cuint224m_T; - -typedef struct { - uint32_T chunks[8]; -} int256m_T; - -typedef struct { - int256m_T re; - int256m_T im; -} cint256m_T; - -typedef struct { - uint32_T chunks[8]; -} uint256m_T; - -typedef struct { - uint256m_T re; - uint256m_T im; -} cuint256m_T; - -typedef struct { - uint32_T chunks[9]; -} int288m_T; - -typedef struct { - int288m_T re; - int288m_T im; -} cint288m_T; - -typedef struct { - uint32_T chunks[9]; -} uint288m_T; - -typedef struct { - uint288m_T re; - uint288m_T im; -} cuint288m_T; - -typedef struct { - uint32_T chunks[10]; -} int320m_T; - -typedef struct { - int320m_T re; - int320m_T im; -} cint320m_T; - -typedef struct { - uint32_T chunks[10]; -} uint320m_T; - -typedef struct { - uint320m_T re; - uint320m_T im; -} cuint320m_T; - -typedef struct { - uint32_T chunks[11]; -} int352m_T; - -typedef struct { - int352m_T re; - int352m_T im; -} cint352m_T; - -typedef struct { - uint32_T chunks[11]; -} uint352m_T; - -typedef struct { - uint352m_T re; - uint352m_T im; -} cuint352m_T; - -typedef struct { - uint32_T chunks[12]; -} int384m_T; - -typedef struct { - int384m_T re; - int384m_T im; -} cint384m_T; - -typedef struct { - uint32_T chunks[12]; -} uint384m_T; - -typedef struct { - uint384m_T re; - uint384m_T im; -} cuint384m_T; - -typedef struct { - uint32_T chunks[13]; -} int416m_T; - -typedef struct { - int416m_T re; - int416m_T im; -} cint416m_T; - -typedef struct { - uint32_T chunks[13]; -} uint416m_T; - -typedef struct { - uint416m_T re; - uint416m_T im; -} cuint416m_T; - -typedef struct { - uint32_T chunks[14]; -} int448m_T; - -typedef struct { - int448m_T re; - int448m_T im; -} cint448m_T; - -typedef struct { - uint32_T chunks[14]; -} uint448m_T; - -typedef struct { - uint448m_T re; - uint448m_T im; -} cuint448m_T; - -typedef struct { - uint32_T chunks[15]; -} int480m_T; - -typedef struct { - int480m_T re; - int480m_T im; -} cint480m_T; - -typedef struct { - uint32_T chunks[15]; -} uint480m_T; - -typedef struct { - uint480m_T re; - uint480m_T im; -} cuint480m_T; - -typedef struct { - uint32_T chunks[16]; -} int512m_T; - -typedef struct { - int512m_T re; - int512m_T im; -} cint512m_T; - -typedef struct { - uint32_T chunks[16]; -} uint512m_T; - -typedef struct { - uint512m_T re; - uint512m_T im; -} cuint512m_T; - -typedef struct { - uint32_T chunks[17]; -} int544m_T; - -typedef struct { - int544m_T re; - int544m_T im; -} cint544m_T; - -typedef struct { - uint32_T chunks[17]; -} uint544m_T; - -typedef struct { - uint544m_T re; - uint544m_T im; -} cuint544m_T; - -typedef struct { - uint32_T chunks[18]; -} int576m_T; - -typedef struct { - int576m_T re; - int576m_T im; -} cint576m_T; - -typedef struct { - uint32_T chunks[18]; -} uint576m_T; - -typedef struct { - uint576m_T re; - uint576m_T im; -} cuint576m_T; - -typedef struct { - uint32_T chunks[19]; -} int608m_T; - -typedef struct { - int608m_T re; - int608m_T im; -} cint608m_T; - -typedef struct { - uint32_T chunks[19]; -} uint608m_T; - -typedef struct { - uint608m_T re; - uint608m_T im; -} cuint608m_T; - -typedef struct { - uint32_T chunks[20]; -} int640m_T; - -typedef struct { - int640m_T re; - int640m_T im; -} cint640m_T; - -typedef struct { - uint32_T chunks[20]; -} uint640m_T; - -typedef struct { - uint640m_T re; - uint640m_T im; -} cuint640m_T; - -typedef struct { - uint32_T chunks[21]; -} int672m_T; - -typedef struct { - int672m_T re; - int672m_T im; -} cint672m_T; - -typedef struct { - uint32_T chunks[21]; -} uint672m_T; - -typedef struct { - uint672m_T re; - uint672m_T im; -} cuint672m_T; - -typedef struct { - uint32_T chunks[22]; -} int704m_T; - -typedef struct { - int704m_T re; - int704m_T im; -} cint704m_T; - -typedef struct { - uint32_T chunks[22]; -} uint704m_T; - -typedef struct { - uint704m_T re; - uint704m_T im; -} cuint704m_T; - -typedef struct { - uint32_T chunks[23]; -} int736m_T; - -typedef struct { - int736m_T re; - int736m_T im; -} cint736m_T; - -typedef struct { - uint32_T chunks[23]; -} uint736m_T; - -typedef struct { - uint736m_T re; - uint736m_T im; -} cuint736m_T; - -typedef struct { - uint32_T chunks[24]; -} int768m_T; - -typedef struct { - int768m_T re; - int768m_T im; -} cint768m_T; - -typedef struct { - uint32_T chunks[24]; -} uint768m_T; - -typedef struct { - uint768m_T re; - uint768m_T im; -} cuint768m_T; - -typedef struct { - uint32_T chunks[25]; -} int800m_T; - -typedef struct { - int800m_T re; - int800m_T im; -} cint800m_T; - -typedef struct { - uint32_T chunks[25]; -} uint800m_T; - -typedef struct { - uint800m_T re; - uint800m_T im; -} cuint800m_T; - -typedef struct { - uint32_T chunks[26]; -} int832m_T; - -typedef struct { - int832m_T re; - int832m_T im; -} cint832m_T; - -typedef struct { - uint32_T chunks[26]; -} uint832m_T; - -typedef struct { - uint832m_T re; - uint832m_T im; -} cuint832m_T; - -typedef struct { - uint32_T chunks[27]; -} int864m_T; - -typedef struct { - int864m_T re; - int864m_T im; -} cint864m_T; - -typedef struct { - uint32_T chunks[27]; -} uint864m_T; - -typedef struct { - uint864m_T re; - uint864m_T im; -} cuint864m_T; - -typedef struct { - uint32_T chunks[28]; -} int896m_T; - -typedef struct { - int896m_T re; - int896m_T im; -} cint896m_T; - -typedef struct { - uint32_T chunks[28]; -} uint896m_T; - -typedef struct { - uint896m_T re; - uint896m_T im; -} cuint896m_T; - -typedef struct { - uint32_T chunks[29]; -} int928m_T; - -typedef struct { - int928m_T re; - int928m_T im; -} cint928m_T; - -typedef struct { - uint32_T chunks[29]; -} uint928m_T; - -typedef struct { - uint928m_T re; - uint928m_T im; -} cuint928m_T; - -typedef struct { - uint32_T chunks[30]; -} int960m_T; - -typedef struct { - int960m_T re; - int960m_T im; -} cint960m_T; - -typedef struct { - uint32_T chunks[30]; -} uint960m_T; - -typedef struct { - uint960m_T re; - uint960m_T im; -} cuint960m_T; - -typedef struct { - uint32_T chunks[31]; -} int992m_T; - -typedef struct { - int992m_T re; - int992m_T im; -} cint992m_T; - -typedef struct { - uint32_T chunks[31]; -} uint992m_T; - -typedef struct { - uint992m_T re; - uint992m_T im; -} cuint992m_T; - -typedef struct { - uint32_T chunks[32]; -} int1024m_T; - -typedef struct { - int1024m_T re; - int1024m_T im; -} cint1024m_T; - -typedef struct { - uint32_T chunks[32]; -} uint1024m_T; - -typedef struct { - uint1024m_T re; - uint1024m_T im; -} cuint1024m_T; - -typedef struct { - uint32_T chunks[33]; -} int1056m_T; - -typedef struct { - int1056m_T re; - int1056m_T im; -} cint1056m_T; - -typedef struct { - uint32_T chunks[33]; -} uint1056m_T; - -typedef struct { - uint1056m_T re; - uint1056m_T im; -} cuint1056m_T; - -typedef struct { - uint32_T chunks[34]; -} int1088m_T; - -typedef struct { - int1088m_T re; - int1088m_T im; -} cint1088m_T; - -typedef struct { - uint32_T chunks[34]; -} uint1088m_T; - -typedef struct { - uint1088m_T re; - uint1088m_T im; -} cuint1088m_T; - -typedef struct { - uint32_T chunks[35]; -} int1120m_T; - -typedef struct { - int1120m_T re; - int1120m_T im; -} cint1120m_T; - -typedef struct { - uint32_T chunks[35]; -} uint1120m_T; - -typedef struct { - uint1120m_T re; - uint1120m_T im; -} cuint1120m_T; - -typedef struct { - uint32_T chunks[36]; -} int1152m_T; - -typedef struct { - int1152m_T re; - int1152m_T im; -} cint1152m_T; - -typedef struct { - uint32_T chunks[36]; -} uint1152m_T; - -typedef struct { - uint1152m_T re; - uint1152m_T im; -} cuint1152m_T; - -typedef struct { - uint32_T chunks[37]; -} int1184m_T; - -typedef struct { - int1184m_T re; - int1184m_T im; -} cint1184m_T; - -typedef struct { - uint32_T chunks[37]; -} uint1184m_T; - -typedef struct { - uint1184m_T re; - uint1184m_T im; -} cuint1184m_T; - -typedef struct { - uint32_T chunks[38]; -} int1216m_T; - -typedef struct { - int1216m_T re; - int1216m_T im; -} cint1216m_T; - -typedef struct { - uint32_T chunks[38]; -} uint1216m_T; - -typedef struct { - uint1216m_T re; - uint1216m_T im; -} cuint1216m_T; - -typedef struct { - uint32_T chunks[39]; -} int1248m_T; - -typedef struct { - int1248m_T re; - int1248m_T im; -} cint1248m_T; - -typedef struct { - uint32_T chunks[39]; -} uint1248m_T; - -typedef struct { - uint1248m_T re; - uint1248m_T im; -} cuint1248m_T; - -typedef struct { - uint32_T chunks[40]; -} int1280m_T; - -typedef struct { - int1280m_T re; - int1280m_T im; -} cint1280m_T; - -typedef struct { - uint32_T chunks[40]; -} uint1280m_T; - -typedef struct { - uint1280m_T re; - uint1280m_T im; -} cuint1280m_T; - -typedef struct { - uint32_T chunks[41]; -} int1312m_T; - -typedef struct { - int1312m_T re; - int1312m_T im; -} cint1312m_T; - -typedef struct { - uint32_T chunks[41]; -} uint1312m_T; - -typedef struct { - uint1312m_T re; - uint1312m_T im; -} cuint1312m_T; - -typedef struct { - uint32_T chunks[42]; -} int1344m_T; - -typedef struct { - int1344m_T re; - int1344m_T im; -} cint1344m_T; - -typedef struct { - uint32_T chunks[42]; -} uint1344m_T; - -typedef struct { - uint1344m_T re; - uint1344m_T im; -} cuint1344m_T; - -typedef struct { - uint32_T chunks[43]; -} int1376m_T; - -typedef struct { - int1376m_T re; - int1376m_T im; -} cint1376m_T; - -typedef struct { - uint32_T chunks[43]; -} uint1376m_T; - -typedef struct { - uint1376m_T re; - uint1376m_T im; -} cuint1376m_T; - -typedef struct { - uint32_T chunks[44]; -} int1408m_T; - -typedef struct { - int1408m_T re; - int1408m_T im; -} cint1408m_T; - -typedef struct { - uint32_T chunks[44]; -} uint1408m_T; - -typedef struct { - uint1408m_T re; - uint1408m_T im; -} cuint1408m_T; - -typedef struct { - uint32_T chunks[45]; -} int1440m_T; - -typedef struct { - int1440m_T re; - int1440m_T im; -} cint1440m_T; - -typedef struct { - uint32_T chunks[45]; -} uint1440m_T; - -typedef struct { - uint1440m_T re; - uint1440m_T im; -} cuint1440m_T; - -typedef struct { - uint32_T chunks[46]; -} int1472m_T; - -typedef struct { - int1472m_T re; - int1472m_T im; -} cint1472m_T; - -typedef struct { - uint32_T chunks[46]; -} uint1472m_T; - -typedef struct { - uint1472m_T re; - uint1472m_T im; -} cuint1472m_T; - -typedef struct { - uint32_T chunks[47]; -} int1504m_T; - -typedef struct { - int1504m_T re; - int1504m_T im; -} cint1504m_T; - -typedef struct { - uint32_T chunks[47]; -} uint1504m_T; - -typedef struct { - uint1504m_T re; - uint1504m_T im; -} cuint1504m_T; - -typedef struct { - uint32_T chunks[48]; -} int1536m_T; - -typedef struct { - int1536m_T re; - int1536m_T im; -} cint1536m_T; - -typedef struct { - uint32_T chunks[48]; -} uint1536m_T; - -typedef struct { - uint1536m_T re; - uint1536m_T im; -} cuint1536m_T; - -typedef struct { - uint32_T chunks[49]; -} int1568m_T; - -typedef struct { - int1568m_T re; - int1568m_T im; -} cint1568m_T; - -typedef struct { - uint32_T chunks[49]; -} uint1568m_T; - -typedef struct { - uint1568m_T re; - uint1568m_T im; -} cuint1568m_T; - -typedef struct { - uint32_T chunks[50]; -} int1600m_T; - -typedef struct { - int1600m_T re; - int1600m_T im; -} cint1600m_T; - -typedef struct { - uint32_T chunks[50]; -} uint1600m_T; - -typedef struct { - uint1600m_T re; - uint1600m_T im; -} cuint1600m_T; - -typedef struct { - uint32_T chunks[51]; -} int1632m_T; - -typedef struct { - int1632m_T re; - int1632m_T im; -} cint1632m_T; - -typedef struct { - uint32_T chunks[51]; -} uint1632m_T; - -typedef struct { - uint1632m_T re; - uint1632m_T im; -} cuint1632m_T; - -typedef struct { - uint32_T chunks[52]; -} int1664m_T; - -typedef struct { - int1664m_T re; - int1664m_T im; -} cint1664m_T; - -typedef struct { - uint32_T chunks[52]; -} uint1664m_T; - -typedef struct { - uint1664m_T re; - uint1664m_T im; -} cuint1664m_T; - -typedef struct { - uint32_T chunks[53]; -} int1696m_T; - -typedef struct { - int1696m_T re; - int1696m_T im; -} cint1696m_T; - -typedef struct { - uint32_T chunks[53]; -} uint1696m_T; - -typedef struct { - uint1696m_T re; - uint1696m_T im; -} cuint1696m_T; - -typedef struct { - uint32_T chunks[54]; -} int1728m_T; - -typedef struct { - int1728m_T re; - int1728m_T im; -} cint1728m_T; - -typedef struct { - uint32_T chunks[54]; -} uint1728m_T; - -typedef struct { - uint1728m_T re; - uint1728m_T im; -} cuint1728m_T; - -typedef struct { - uint32_T chunks[55]; -} int1760m_T; - -typedef struct { - int1760m_T re; - int1760m_T im; -} cint1760m_T; - -typedef struct { - uint32_T chunks[55]; -} uint1760m_T; - -typedef struct { - uint1760m_T re; - uint1760m_T im; -} cuint1760m_T; - -typedef struct { - uint32_T chunks[56]; -} int1792m_T; - -typedef struct { - int1792m_T re; - int1792m_T im; -} cint1792m_T; - -typedef struct { - uint32_T chunks[56]; -} uint1792m_T; - -typedef struct { - uint1792m_T re; - uint1792m_T im; -} cuint1792m_T; - -typedef struct { - uint32_T chunks[57]; -} int1824m_T; - -typedef struct { - int1824m_T re; - int1824m_T im; -} cint1824m_T; - -typedef struct { - uint32_T chunks[57]; -} uint1824m_T; - -typedef struct { - uint1824m_T re; - uint1824m_T im; -} cuint1824m_T; - -typedef struct { - uint32_T chunks[58]; -} int1856m_T; - -typedef struct { - int1856m_T re; - int1856m_T im; -} cint1856m_T; - -typedef struct { - uint32_T chunks[58]; -} uint1856m_T; - -typedef struct { - uint1856m_T re; - uint1856m_T im; -} cuint1856m_T; - -typedef struct { - uint32_T chunks[59]; -} int1888m_T; - -typedef struct { - int1888m_T re; - int1888m_T im; -} cint1888m_T; - -typedef struct { - uint32_T chunks[59]; -} uint1888m_T; - -typedef struct { - uint1888m_T re; - uint1888m_T im; -} cuint1888m_T; - -typedef struct { - uint32_T chunks[60]; -} int1920m_T; - -typedef struct { - int1920m_T re; - int1920m_T im; -} cint1920m_T; - -typedef struct { - uint32_T chunks[60]; -} uint1920m_T; - -typedef struct { - uint1920m_T re; - uint1920m_T im; -} cuint1920m_T; - -typedef struct { - uint32_T chunks[61]; -} int1952m_T; - -typedef struct { - int1952m_T re; - int1952m_T im; -} cint1952m_T; - -typedef struct { - uint32_T chunks[61]; -} uint1952m_T; - -typedef struct { - uint1952m_T re; - uint1952m_T im; -} cuint1952m_T; - -typedef struct { - uint32_T chunks[62]; -} int1984m_T; - -typedef struct { - int1984m_T re; - int1984m_T im; -} cint1984m_T; - -typedef struct { - uint32_T chunks[62]; -} uint1984m_T; - -typedef struct { - uint1984m_T re; - uint1984m_T im; -} cuint1984m_T; - -typedef struct { - uint32_T chunks[63]; -} int2016m_T; - -typedef struct { - int2016m_T re; - int2016m_T im; -} cint2016m_T; - -typedef struct { - uint32_T chunks[63]; -} uint2016m_T; - -typedef struct { - uint2016m_T re; - uint2016m_T im; -} cuint2016m_T; - -typedef struct { - uint32_T chunks[64]; -} int2048m_T; - -typedef struct { - int2048m_T re; - int2048m_T im; -} cint2048m_T; - -typedef struct { - uint32_T chunks[64]; -} uint2048m_T; - -typedef struct { - uint2048m_T re; - uint2048m_T im; -} cuint2048m_T; - -#endif /* MULTIWORD_TYPES_H */ diff --git a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/rtmodel.h b/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/rtmodel.h deleted file mode 100644 index baffa8c..0000000 --- a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/rtmodel.h +++ /dev/null @@ -1,29 +0,0 @@ -/* - * rtmodel.h: - * - * Academic License - for use in teaching, academic research, and meeting - * course requirements at degree granting institutions only. Not for - * government, commercial, or other organizational use. - * - * Code generation for model "assdf". - * - * Model version : 1.1 - * Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 - * C source code generated on : Wed May 19 11:33:56 2021 - * - * Target selection: grt.tlc - * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Intel->x86-64 (Windows64) - * Code generation objectives: Unspecified - * Validation result: Not run - */ - -#ifndef RTW_HEADER_rtmodel_h_ -#define RTW_HEADER_rtmodel_h_ - -/* - * Includes the appropriate headers when we are using rtModel - */ -#include "assdf.h" -#define GRTINTERFACE 0 -#endif /* RTW_HEADER_rtmodel_h_ */ diff --git a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/rtwtypes.h b/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/rtwtypes.h deleted file mode 100644 index a369383..0000000 --- a/zephyr/epos_controller_model/src/codegeneration/assdf_grt_rtw/rtwtypes.h +++ /dev/null @@ -1,41 +0,0 @@ -/* - * rtwtypes.h - * - * Academic License - for use in teaching, academic research, and meeting - * course requirements at degree granting institutions only. Not for - * government, commercial, or other organizational use. - * - * Code generation for model "assdf". - * - * Model version : 1.1 - * Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 - * C source code generated on : Wed May 19 11:33:56 2021 - * - * Target selection: grt.tlc - * Note: GRT includes extra infrastructure and instrumentation for prototyping - * Embedded hardware selection: Intel->x86-64 (Windows64) - * Code generation objectives: Unspecified - * Validation result: Not run - */ - -#ifndef RTWTYPES_H -#define RTWTYPES_H -#include "tmwtypes.h" -#ifndef POINTER_T -#define POINTER_T - -typedef void * pointer_T; - -#endif - -/* Logical type definitions */ -#if (!defined(__cplusplus)) -#ifndef false -#define false (0U) -#endif - -#ifndef true -#define true (1U) -#endif -#endif -#endif /* RTWTYPES_H */ diff --git a/zephyr/epos_controller_model/src/epos4/epos4.cpp b/zephyr/epos_controller_model/src/epos4/epos4.cpp deleted file mode 100644 index 4258ce2..0000000 --- a/zephyr/epos_controller_model/src/epos4/epos4.cpp +++ /dev/null @@ -1,438 +0,0 @@ -#include "epos4.h" - -#define MAX_DATA_SIZE 64 - -unsigned char tmp_data[MAX_DATA_SIZE] = {0}; -int32_t tmpper = 0; -uint8_t tmp_len; -uint32_t tmp_id; -uint8_t tmp_type; - -int32_t velo_inti = 0x00; - -epos4::epos4(uint32_t canid_epos, uint32_t canid_self, const struct device *CAN_INTERFACE) -{ - _canid_epos = canid_epos; - _canid_self = canid_self; - _softwareVersion = 0; - _hardwareVersion = 0; - _can_interface = CAN_INTERFACE; -} - -void epos4::init() -{ - // get state of drive - epos4::readStatusword(); - - switch( epos4::_state_of_drive ) - { - case epos4::Switch_on_disabled: - epos4::writeControlword(0x00, epos4::dcc_shutdown); - k_sleep(K_MSEC(10)); - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - k_sleep(K_MSEC(10)); - break; - - case epos4::Ready_to_switch_on: - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - k_sleep(K_MSEC(10)); - break; - - case epos4::Switched_on: - epos4::writeControlword(0x00, epos4::dcc_enableoperation); - k_sleep(K_MSEC(10)); - break; - - case epos4::Quick_stop_active: - epos4::writeControlword(0x00, epos4::dcc_enableoperation); - k_sleep(K_MSEC(10)); - break; - - case epos4::Fault: - epos4::writeControlword(0x00, epos4::dcc_faultreset); - k_sleep(K_MSEC(10)); - epos4::writeControlword(0x00, epos4::dcc_shutdown); - k_sleep(K_MSEC(10)); - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - k_sleep(K_MSEC(10)); - break; - - case epos4::Operation_enabled: - printk("Drive function is enabled and power is applied to the motor. "); - break; - - default: - printk("State of drive not found in enum ... may some error occured"); - } - - printk("Start SI config ... "); - epos4::initSI(); - printk("done!"); - - printk("Start TPDO config ... "); - epos4::configPDO(); - printk("done!"); - - - printk("EPOS enabled"); -} - -void epos4::initSI() -{ - epos4::writeControlword(0x00, epos4::dcc_shutdown); - k_sleep(K_MSEC(10)); - - char velocity_si[8] = {0x22, 0xA9, 0x60, 0x00, 0x00, 0x47, 0xB4, 0xFD}; // FD is maximum - can_write(epos4::_can_interface,(uint8_t*)velocity_si,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - - k_sleep(K_MSEC(10)); - - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - k_sleep(K_MSEC(10)); -} - -void epos4::initPPM() -{ - printk("Set Operationmode"); - unsigned char data0[8] = {0x22, 0x60, 0x60, 0x00, 0x01, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - - k_sleep(K_MSEC(10)); - - // Set all Profile Position Mode Parametersa here ... - - - // -------------------------------------------------------- - - printk("Switch on and enable ..."); - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - k_sleep(K_MSEC(10)); -} - -void epos4::initCSP() -{ - printk("Set Operationmode to CSP"); - unsigned char data0[8] = {0x22, 0x60, 0x60, 0x00, 0x08, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - // Interpolation time period value - unsigned char data01[8] = {0x22, 0xC2, 0x60, 0x01, 0x0A, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - - printk("Switch on and enable ..."); - epos4::writeControlword(0x00, epos4::dcc_shutdown); - k_sleep(K_MSEC(10)); - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - k_sleep(K_MSEC(10)); - -} - -void epos4::initCSV() -{ - printk("Set Operationmode to CSV"); - unsigned char data0[8] = {0x22, 0x60, 0x60, 0x00, 0x09, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - // Interpolation time period value - unsigned char data01[8] = {0x22, 0xC2, 0x60, 0x01, 0x0A, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data01,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - - printk("Switch on and enable ..."); - epos4::writeControlword(0x00, epos4::dcc_shutdown); - k_sleep(K_MSEC(10)); - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - k_sleep(K_MSEC(10)); -} - -void epos4::initCST() -{ - printk("Set Operationmode to CST"); - unsigned char data0[8] = {0x22, 0x60, 0x60, 0x00, 0x0A, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data0,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - - k_sleep(K_MSEC(10)); - - // Interpolation time period value - unsigned char data01[8] = {0x22, 0xC2, 0x60, 0x01, 0x0A, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data01,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - - k_sleep(K_MSEC(10)); - - - printk("Switch on and enable ..."); - epos4::writeControlword(0x00, epos4::dcc_shutdown); - k_sleep(K_MSEC(10)); - epos4::writeControlword(0x00, epos4::dcc_switchon_and_enable); - k_sleep(K_MSEC(10)); -} - -void epos4::sync() -{ - unsigned char data111[1] = {0x00}; - can_write(epos4::_can_interface,(uint8_t*)data111,1,0x80,CAN_DATAFRAME,K_FOREVER); -} - -/** - * @brief Send a controlword with SDO communication - * - * @details The first byte is the command specifier. For controlword its fixed with 0x2B because we want expedited transfer with const size of 2 Byte - * For more details look in >EPOS4 Firmware Specification< chapter 6.2.85 - Controlword and >EPOS4 Application Notes< chapter 5.4 - SDO Communication - * - * @param highByte - * @param lowByte - */ -void epos4::writeControlword(unsigned char highByte, unsigned char lowByte) -{ - unsigned char data[8] = {0x2B, 0x40, 0x60, 0x00, lowByte, highByte, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); -} -void epos4::readStatusword() -{ - unsigned char data[8] = {0x40, 0x41, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00}; - - printk("ask for statusword....\n"); - - can_write(epos4::_can_interface,(uint8_t*)data,8,epos4::_canid_self,CAN_DATAFRAME,K_MSEC(1000)); - printk("Sended...\n"); - while(epos4::_state_of_drive == 0x00){ - printk("Wait for Controllword...\n"); - } - printk("done!"); - -} - -void epos4::moveToPosition(uint8_t *position) -{ - // position is an 32 bit integer. Wen give the uint8 here because we can interate on the bytes from the uint32 - printk("Starte move to position ... "); - - unsigned char data[8] = {0x22, 0x7A, 0x60, 0x00, position[3], position[2], position[1], position[0]}; - //unsigned char data[8] = {0x22, 0x7A, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - - k_sleep(K_MSEC(10)); - - unsigned char data1[8] = {0x22, 0x40, 0x60, 0x00, 0x1F, 0x00, 0x00, 0x00}; - can_write(epos4::_can_interface,(uint8_t*)data1,8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - - k_sleep(K_MSEC(10)); - - - printk("done!"); - -} - -void epos4::moveToPosition(uint32_t *posList, uint8_t len) -{ - epos4::initPPM(); - - uint32_t reversedPos; - uint32_t printPos; - uint8_t *n2; - n2 = (uint8_t *) &reversedPos; - - for( uint8_t i = 0; i < len; i+= 1 ) - { - n2[3] = (posList[i]); - n2[2] = (posList[i]) >> 8; - n2[1] = (posList[i]) >> 16; - n2[0] = (posList[i]) >> 24; - - moveToPosition(n2); - k_sleep(K_MSEC(1)); - - // printk("Toggle new poisition ..."); - epos4::writeControlword(0x00, 0x0F); - k_sleep(K_MSEC(1)); - } -} - -void epos4::configPDO() { - - // State Maschinbe of MNT Service to Pre Operational to checnge PDOs - can_write(epos4::_can_interface,(uint8_t*)(epos4::enter_preoperational),2,0x00,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - // Config of TxPDO 1 - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_transmissiontype_TxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_inhibit_time_TxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_null_TxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_first_mapped_obj_position_TxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_first_mapped_obj_velocity_TxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_TxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - - // Config of TxPDO 2 - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_transmissiontype_TxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_inhibit_time_TxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_null_TxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_first_mapped_obj_torque_TxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_TxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - - - - // Config of RxPDO 1 - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_transmissiontype_RxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_null_RxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_first_mapped_obj_position_RxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_RxPDO1),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - - // Config of RxPDO 2 - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_transmissiontype_RxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_null_RxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_first_mapped_obj_position_RxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_RxPDO2),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - - // Config of RxPDO 3 - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_transmissiontype_RxPDO3),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_null_RxPDO3),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_first_mapped_obj_position_RxPDO3),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - can_write(epos4::_can_interface,(uint8_t*)(epos4::pdo_number_of_mapped_objects_RxPDO3),8,epos4::_canid_self,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(10)); - - - - // Set Statemaschine of NMT service back to Operational - can_write(epos4::_can_interface,(uint8_t*)(epos4::start_remotenode),2,0x00,CAN_DATAFRAME,K_FOREVER); - k_sleep(K_MSEC(100)); - - printk("TPDO Configured!"); -} - -/* -void epos4::getVersions(uint16_t* hardware_version, uint16_t* application_number, uint16_t* software_version, uint16_t* application_version) -{ - epos4::getProductCode(hardware_version,application_number); - epos4::getRevisionNumber(software_version,application_version); -} -void epos4::getProductCode(uint16_t* hardware_version, uint16_t* application_number) -{ - unsigned char getHardwareVersion[8] = {0x40, 0x18, 0x10, 0x02, 0x00, 0x00, 0x00, 0x00}; - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, getHardwareVersion); - - unsigned char data[MAX_DATA_SIZE] = {0}; - uint8_t len; - uint32_t id; - uint8_t type; - - epos4::checkReceivedData(data, &len, &id, &type); - epos4::printCANframe(data, &len, &id, &type); - - if( id == epos4::_canid_epos ) - { - if( data[0] == 0x43 && data[1] == 0x18 && data[2] == 0x10 && data[3] == 0x02 ) - { - (*hardware_version) = (data[7]<<8) | data[6]; - (*application_number) = (data[5]<<8) | data[4]; - epos4::_hardwareVersion = (*hardware_version); - } - } -} -void epos4::getRevisionNumber(uint16_t* software_version, uint16_t* application_version) -{ - char getSoftwareVersion[8] = {0x40, 0x18, 0x10, 0x03, 0x00, 0x00, 0x00, 0x00}; - - epos4::_can_interface->sendMsgBuf(epos4::_canid_self, 0, 8, getSoftwareVersion); - - unsigned char data[MAX_DATA_SIZE] = {0}; - uint8_t len; - uint32_t id; - uint8_t type; - - if( id == epos4::_canid_epos ) - { - if( data[0] == 0x43 && data[1] == 0x18 && data[2] == 0x10 && data[3] == 0x03 ) - { - (*software_version) = (data[7]<<8) | data[6]; - (*application_version) = (data[5]<<8) | data[4]; - epos4::_softwareVersion = (*software_version); - } - } -} - -void epos4::checkReceivedData(unsigned char *data, uint8_t *len, uint32_t *id, uint8_t *type, bool *check) -{ - - - if (CAN_MSGAVAIL == epos4::_can_interface->checkReceive()) - { - epos4::_can_interface->readMsgBuf(len, data); - *id = epos4::_can_interface->getCanId(); - *type = (epos4::_can_interface->isExtendedFrame() << 0) | - (epos4::_can_interface->isRemoteRequest() << 1); - if(check) *check = true; - - }else{ - if(check) *check = false; - *id = 0x0; - } -} - -void epos4::printCANframe(unsigned char *data, uint8_t *len, uint32_t *id, uint8_t *type) -{ - printk(*id, HEX); - printk(" | "); - - char buffer[2] = {0}; - - for( uint8_t i = 0; i < *len; i += 1 ) - { - // printk(data[i],HEX); - sprintf(buffer, "%02x", data[i]); - printk(buffer); - printk(" "); - } - printk(""); -} -*/ diff --git a/zephyr/epos_controller_model/src/epos4/epos4.h b/zephyr/epos_controller_model/src/epos4/epos4.h deleted file mode 100644 index 9f8c258..0000000 --- a/zephyr/epos_controller_model/src/epos4/epos4.h +++ /dev/null @@ -1,149 +0,0 @@ -#ifndef epos4_h -#define epos4_h - -#include -#include -#include -#include -#include -#include -#include - -class epos4 -{ -public: - epos4(uint32_t canid_epos, uint32_t canid_self, const struct device *CAN_INTERFACE); - - void init(); - void initSI(); - void initPPM(); - void initCSP(); - void initCSV(); - void initCST(); - void sync(); - - void moveToPosition(uint32_t *posList, uint8_t len); - void getVersions(uint16_t *hardware_version, uint16_t *application_number, uint16_t *software_version, uint16_t *application_version); - - void writeControlword(unsigned char highByte, unsigned char lowByte); - void readStatusword(); - - void checkReceivedData(unsigned char *data, uint8_t *len, uint32_t *id, uint8_t *type,bool *check=NULL); - void printCANframe(unsigned char *data, uint8_t *len, uint32_t *id, uint8_t *type); - - - const struct device *_can_interface; - - int32_t position = 0x00; - int32_t velocity = 0x00; - int16_t torque = 0x00; - - - int _softwareVersion; - int _hardwareVersion; - - uint8_t _state_of_drive = 0; - bool _target_reached = false; - - // Statemaschine enum - enum - { - Not_ready_to_switch_on = 0b00000000, - Switch_on_disabled = 0b01000000, - Ready_to_switch_on = 0b00100001, - Switched_on = 0b00100011, - Operation_enabled = 0b00100111, - Quick_stop_active = 0b00000111, - Fault_reaction_active = 0b00001111, - Fault = 0b00001000 - }; - - /** - * @addtogroup DeviceControlCommands - * @brief Device Control Commands - * @details For more details look in the EPOS4 Firmware Specification - 2.2 Device Control - * @{ - */ - enum - { - dcc_shutdown = 0x06, /**< will end in axis state >ready to switch on< */ - dcc_switchon = 0x07, /**< will end in axis state >switched on< */ - dcc_switchon_and_enable = 0x0F, /**< will end in axis state >switch on< then auto transition to >operation enabled< */ - dcc_disablevoltage = 0x00, /**< will end in axis state >switch on disabled< */ - dcc_quickstop = 0x02, /**< will end in axis state >quick stop active< */ - dcc_disableoperation = 0x07, /**< will end in axis state >switched on< */ - dcc_enableoperation = 0x0F, /**< will end in axis state >operation enabled< */ - dcc_faultreset = 0x80 /**< will end in axis state >Fault< and/or >switch on disabled< */ - }; - /** @} */ - - /** - * @addtogroup StatemaschineVariables - * @brief Statemaschine for NMT - * @details For more details look in the EPOS4 Communication Guide - 3.3.3.5 NMT Services - * @{ - */ - unsigned char enter_preoperational[2] = {0x80, 0x00}; /**< All CANopen nodes will enter NMT state >Pre-operational< */ - unsigned char reset_communication[2] = {0x82, 0x00}; /**< All CANopen nodes will first enter NMT state >Initialization< and then switch automatically >Pre-operational< */ - unsigned char reset_node[2] = {0x81, 0x00}; /**< All CANopen nodes will first enter NMT state >Initialization< and then switch automatically >Pre-operational< */ - unsigned char start_remotenode[2] = {0x01, 0x00}; /**< All CANopen nodes will enter NMT state >Operational< */ - unsigned char stop_remotenode[2] = {0x02, 0x00}; /**< All CANopen nodes will enter NMT state >Stopped< */ - /** @} */ - - - /** - * @addtogroup TxPDO config - * @brief set config for transmition pdos - * @details For more details look in the EPOS4 Communication Firmaware Specification - 6.2.21 Transmit PDO 1 parameter - * @{ - */ - // TxPDO 1 - unsigned char pdo_transmissiontype_TxPDO1[8] = {0x22, 0x00, 0x18, 0x02, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_inhibit_time_TxPDO1[8] = {0x22, 0x00, 0x18, 0x03, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_TxPDO1[8] = {0x22, 0x00, 0x1A, 0x00, 0x02, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_null_TxPDO1[8] = {0x22, 0x00, 0x1A, 0x00, 0x00, 0x00, 0x00, 0x00}; - unsigned char pdo_first_mapped_obj_position_TxPDO1[8] = {0x23, 0x00, 0x1A, 0x01, 0x20, 0x00, 0x64, 0x60}; // 104 Grad = 120000 inc - //unsigned char pdo_first_mapped_obj_velocity_TxPDO1[8] = {0x23, 0x00, 0x1A, 0x02, 0x20, 0x00, 0x6C, 0x60}; // e-10 rpm - unsigned char pdo_first_mapped_obj_velocity_TxPDO1[8] = {0x22, 0x00, 0x1A, 0x02, 0x10, 0x00, 0x77, 0x60}; // e-10 rpm - - // TxPDO 2 - unsigned char pdo_transmissiontype_TxPDO2[8] = {0x22, 0x01, 0x18, 0x02, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_inhibit_time_TxPDO2[8] = {0x22, 0x01, 0x18, 0x03, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_TxPDO2[8] = {0x22, 0x01, 0x1A, 0x00, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_null_TxPDO2[8] = {0x22, 0x01, 0x1A, 0x00, 0x00, 0x00, 0x00, 0x00}; - unsigned char pdo_first_mapped_obj_torque_TxPDO2[8] = {0x22, 0x01, 0x1A, 0x01, 0x10, 0x00, 0x77, 0x60}; - /** @} */ - - // RxPDO 1 - unsigned char pdo_transmissiontype_RxPDO1[8] = {0x22, 0x00, 0x14, 0x02, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_RxPDO1[8] = {0x22, 0x00, 0x16, 0x00, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_null_RxPDO1[8] = {0x22, 0x00, 0x16, 0x00, 0x00, 0x00, 0x00, 0x00}; - unsigned char pdo_first_mapped_obj_position_RxPDO1[8] = {0x23, 0x00, 0x16, 0x01, 0x20, 0x00, 0x7A, 0x60}; - - // RxPDO 2 - unsigned char pdo_transmissiontype_RxPDO2[8] = {0x22, 0x01, 0x14, 0x02, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_RxPDO2[8] = {0x22, 0x01, 0x16, 0x00, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_null_RxPDO2[8] = {0x22, 0x01, 0x16, 0x00, 0x00, 0x00, 0x00, 0x00}; - unsigned char pdo_first_mapped_obj_position_RxPDO2[8] = {0x23, 0x01, 0x16, 0x01, 0x20, 0x00, 0xFF, 0x60}; - - // RxPDO 3 - unsigned char pdo_transmissiontype_RxPDO3[8] = {0x22, 0x02, 0x14, 0x02, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_RxPDO3[8] = {0x22, 0x02, 0x16, 0x00, 0x01, 0x00, 0x00, 0x00}; - unsigned char pdo_number_of_mapped_objects_null_RxPDO3[8] = {0x22, 0x02, 0x16, 0x00, 0x00, 0x00, 0x00, 0x00}; - unsigned char pdo_first_mapped_obj_position_RxPDO3[8] = {0x23, 0x02, 0x16, 0x01, 0x10, 0x00, 0x71, 0x60}; - -private: - void getProductCode(uint16_t *hardware_version, uint16_t *application_number); - void getRevisionNumber(uint16_t *software_version, uint16_t *application_version); - void configPDO(); - void moveToPosition(uint8_t *position); - - uint32_t _canid_epos; - uint32_t _canid_self; - uint32_t _spi_cs_pin; - uint32_t _can_int_pin; - uint32_t _state; - -}; - -#endif diff --git a/zephyr/epos_controller_model/src/main.c b/zephyr/epos_controller_model/src/main.c deleted file mode 100644 index 40c0c78..0000000 --- a/zephyr/epos_controller_model/src/main.c +++ /dev/null @@ -1,28 +0,0 @@ -#include -#include -#include -#include - -#include "assdf.h" - - -void main() -{ - assdf_initialize(); - - for(float i = 0; i < 10; i+=0.01) - { - if( i >= 1.0 && i < 2.0 ) - { - assdf_U.In1 = 1.0; - }else{ - assdf_U.In1 = 0.0; - } - - assdf_step(); - - printf("X: %.2f Y: %.2f\n", assdf_U.In1, assdf_Y.Out1); - } - - return 0; -} diff --git a/zephyr/epos_controller_model/src/test.cpp b/zephyr/epos_controller_model/src/test.cpp deleted file mode 100644 index 1227fe6..0000000 --- a/zephyr/epos_controller_model/src/test.cpp +++ /dev/null @@ -1,43 +0,0 @@ -/* - * Copyright (c) 2016 Intel Corporation - * - * SPDX-License-Identifier: Apache-2.0 - */ - -#include -#include -#include -#include - -#include "assdf.h" - - -void main(void) -{ - ExtU_assdf_T inp{0.0}; - - assdfModelClass* subsys = new assdfModelClass(); - - subsys->initialize(); - - subsys->setExternalInputs(&inp); - - for(float i = 0; i < 10; i+=0.01) - { - if( i >= 1.0 && i < 2.0 ) - { - inp.In1 = 1.0; - }else{ - inp.In1 = 0.0; - } - - subsys->setExternalInputs(&inp); - subsys->step(); - - // std::cout << inp.In1 << " " << (subsys->getExternalOutputs()).Out1 << "\n"; - } - - subsys->~assdfModelClass(); - - return 0; -} diff --git a/zephyr/modules/audio/sof b/zephyr/modules/audio/sof deleted file mode 160000 index 2f8ef20..0000000 --- a/zephyr/modules/audio/sof +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 2f8ef204454d278f0c189e8c7cc70e84f745561a diff --git a/zephyr/modules/bsim_hw_models/nrf_hw_models b/zephyr/modules/bsim_hw_models/nrf_hw_models deleted file mode 160000 index a47e326..0000000 --- a/zephyr/modules/bsim_hw_models/nrf_hw_models +++ /dev/null @@ -1 +0,0 @@ -Subproject commit a47e326ca772ddd14cc3b9d4ca30a9ab44ecca16 diff --git a/zephyr/modules/crypto/mbedtls b/zephyr/modules/crypto/mbedtls deleted file mode 160000 index 5304416..0000000 --- a/zephyr/modules/crypto/mbedtls +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 53044168b43f06ec5654b906a2cdd260bf477edd diff --git a/zephyr/modules/crypto/tinycrypt b/zephyr/modules/crypto/tinycrypt deleted file mode 160000 index 3e9a49d..0000000 --- a/zephyr/modules/crypto/tinycrypt +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 3e9a49d2672ec01435ffbf0d788db6d95ef28de0 diff --git a/zephyr/modules/debug/mipi-sys-t b/zephyr/modules/debug/mipi-sys-t deleted file mode 160000 index 75e6715..0000000 --- a/zephyr/modules/debug/mipi-sys-t +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 75e671550ac1acb502f315fe4952514dc73f7bfb diff --git a/zephyr/modules/debug/segger b/zephyr/modules/debug/segger deleted file mode 160000 index 38c79a4..0000000 --- a/zephyr/modules/debug/segger +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 38c79a447e4a47d413b4e8d34448316a5cece77c diff --git a/zephyr/modules/fs/fatfs b/zephyr/modules/fs/fatfs deleted file mode 160000 index 1d1fcc7..0000000 --- a/zephyr/modules/fs/fatfs +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 1d1fcc725aa1cb3c32f366e0c53d7490d0fe1109 diff --git a/zephyr/modules/fs/littlefs b/zephyr/modules/fs/littlefs deleted file mode 160000 index 9e4498d..0000000 --- a/zephyr/modules/fs/littlefs +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 9e4498d1c73009acd84bb36036ee5e2869112a6c diff --git a/zephyr/modules/hal/altera b/zephyr/modules/hal/altera deleted file mode 160000 index 23c1c1d..0000000 --- a/zephyr/modules/hal/altera +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 23c1c1dd7a0c1cc9a399509d1819375847c95b97 diff --git a/zephyr/modules/hal/atmel b/zephyr/modules/hal/atmel deleted file mode 160000 index d17b7dd..0000000 --- a/zephyr/modules/hal/atmel +++ /dev/null @@ -1 +0,0 @@ -Subproject commit d17b7dd92d209b20bc1e15431d068edc29bf438d diff --git a/zephyr/modules/hal/cmsis b/zephyr/modules/hal/cmsis deleted file mode 160000 index c3bd209..0000000 --- a/zephyr/modules/hal/cmsis +++ /dev/null @@ -1 +0,0 @@ -Subproject commit c3bd2094f92d574377f7af2aec147ae181aa5f8e diff --git a/zephyr/modules/hal/cypress b/zephyr/modules/hal/cypress deleted file mode 160000 index 81a059f..0000000 --- a/zephyr/modules/hal/cypress +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 81a059f21435bc7e315bccd720da5a9b615bbb50 diff --git a/zephyr/modules/hal/espressif b/zephyr/modules/hal/espressif deleted file mode 160000 index 90952df..0000000 --- a/zephyr/modules/hal/espressif +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 90952df320f30c696ea73a22a0e50f20b8f94fd3 diff --git a/zephyr/modules/hal/infineon b/zephyr/modules/hal/infineon deleted file mode 160000 index f1fa824..0000000 --- a/zephyr/modules/hal/infineon +++ /dev/null @@ -1 +0,0 @@ -Subproject commit f1fa8241f8786198ba41155413243de36ed878a5 diff --git a/zephyr/modules/hal/libmetal b/zephyr/modules/hal/libmetal deleted file mode 160000 index 39d049d..0000000 --- a/zephyr/modules/hal/libmetal +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 39d049d4ae68e6f6d595fce7de1dcfc1024fb4eb diff --git a/zephyr/modules/hal/microchip b/zephyr/modules/hal/microchip deleted file mode 160000 index b280eec..0000000 --- a/zephyr/modules/hal/microchip +++ /dev/null @@ -1 +0,0 @@ -Subproject commit b280eec5d3b1296b231117c1999bcd0269b6ecc4 diff --git a/zephyr/modules/hal/nordic b/zephyr/modules/hal/nordic deleted file mode 160000 index fc301b9..0000000 --- a/zephyr/modules/hal/nordic +++ /dev/null @@ -1 +0,0 @@ -Subproject commit fc301b97581d01cb5be47f837087a41632070434 diff --git a/zephyr/modules/hal/nuvoton b/zephyr/modules/hal/nuvoton deleted file mode 160000 index b4d31f3..0000000 --- a/zephyr/modules/hal/nuvoton +++ /dev/null @@ -1 +0,0 @@ -Subproject commit b4d31f33238713a568e23618845702fadd67386f diff --git a/zephyr/modules/hal/nxp b/zephyr/modules/hal/nxp deleted file mode 160000 index 0d11138..0000000 --- a/zephyr/modules/hal/nxp +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 0d11138724959e1162777d9206f841ccdf64348e diff --git a/zephyr/modules/hal/openisa b/zephyr/modules/hal/openisa deleted file mode 160000 index 40d049f..0000000 --- a/zephyr/modules/hal/openisa +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 40d049f69c50b58ea20473bee14cf93f518bf262 diff --git a/zephyr/modules/hal/quicklogic b/zephyr/modules/hal/quicklogic deleted file mode 160000 index b3a66fe..0000000 --- a/zephyr/modules/hal/quicklogic +++ /dev/null @@ -1 +0,0 @@ -Subproject commit b3a66fe6d04d87fd1533a5c8de51d0599fcd08d0 diff --git a/zephyr/modules/hal/silabs b/zephyr/modules/hal/silabs deleted file mode 160000 index be39d4e..0000000 --- a/zephyr/modules/hal/silabs +++ /dev/null @@ -1 +0,0 @@ -Subproject commit be39d4eebeddac6e18e9c0c3ba1b31ad1e82eaed diff --git a/zephyr/modules/hal/st b/zephyr/modules/hal/st deleted file mode 160000 index b52fdbf..0000000 --- a/zephyr/modules/hal/st +++ /dev/null @@ -1 +0,0 @@ -Subproject commit b52fdbf4b62439be9fab9bb4bae9690a42d2fb14 diff --git a/zephyr/modules/hal/stm32 b/zephyr/modules/hal/stm32 deleted file mode 160000 index 68bfdab..0000000 --- a/zephyr/modules/hal/stm32 +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 68bfdabe97aa60934e1519e98593abaa9745501e diff --git a/zephyr/modules/hal/ti b/zephyr/modules/hal/ti deleted file mode 160000 index 3da6fae..0000000 --- a/zephyr/modules/hal/ti +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 3da6fae25fc44ec830fac4a92787b585ff55435e diff --git a/zephyr/modules/hal/xtensa b/zephyr/modules/hal/xtensa deleted file mode 160000 index 2f04b61..0000000 --- a/zephyr/modules/hal/xtensa +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 2f04b615cd5ad3a1b8abef33f9bdd10cc1990ed6 diff --git a/zephyr/modules/lib/canopennode b/zephyr/modules/lib/canopennode deleted file mode 160000 index 468d350..0000000 --- a/zephyr/modules/lib/canopennode +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 468d350028a975b96563e58344de48281a0ab371 diff --git a/zephyr/modules/lib/civetweb b/zephyr/modules/lib/civetweb deleted file mode 160000 index e6903b8..0000000 --- a/zephyr/modules/lib/civetweb +++ /dev/null @@ -1 +0,0 @@ -Subproject commit e6903b80c09d17cd1a8bb32e40080005558aad29 diff --git a/zephyr/modules/lib/gui/lvgl b/zephyr/modules/lib/gui/lvgl deleted file mode 160000 index 31acbaa..0000000 --- a/zephyr/modules/lib/gui/lvgl +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 31acbaa36e9e74ab88ac81e3d21e7f1d00a71136 diff --git a/zephyr/modules/lib/loramac-node b/zephyr/modules/lib/loramac-node deleted file mode 160000 index 2cee5f7..0000000 --- a/zephyr/modules/lib/loramac-node +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 2cee5f7295ff0ff804bf06fea5de006bc7cd121e diff --git a/zephyr/modules/lib/mcumgr b/zephyr/modules/lib/mcumgr deleted file mode 160000 index 5c5055f..0000000 --- a/zephyr/modules/lib/mcumgr +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 5c5055f5a7565f8152d75fcecf07262928b4d56e diff --git a/zephyr/modules/lib/nanopb b/zephyr/modules/lib/nanopb deleted file mode 160000 index d148bd2..0000000 --- a/zephyr/modules/lib/nanopb +++ /dev/null @@ -1 +0,0 @@ -Subproject commit d148bd26718e4c10414f07a7eb1bd24c62e56c5d diff --git a/zephyr/modules/lib/open-amp b/zephyr/modules/lib/open-amp deleted file mode 160000 index 6010f05..0000000 --- a/zephyr/modules/lib/open-amp +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 6010f0523cbc75f551d9256cf782f173177acdef diff --git a/zephyr/modules/lib/openthread b/zephyr/modules/lib/openthread deleted file mode 160000 index cdb9570..0000000 --- a/zephyr/modules/lib/openthread +++ /dev/null @@ -1 +0,0 @@ -Subproject commit cdb9570901e87ab247aed0a96ccd8f94beee5834 diff --git a/zephyr/modules/lib/tensorflow b/zephyr/modules/lib/tensorflow deleted file mode 160000 index dc70a45..0000000 --- a/zephyr/modules/lib/tensorflow +++ /dev/null @@ -1 +0,0 @@ -Subproject commit dc70a45a7cc12c25726a32cd91b28be59e7bc596 diff --git a/zephyr/modules/lib/tinycbor b/zephyr/modules/lib/tinycbor deleted file mode 160000 index 40daca9..0000000 --- a/zephyr/modules/lib/tinycbor +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 40daca97b478989884bffb5226e9ab73ca54b8c4 diff --git a/zephyr/modules/tee/tfm b/zephyr/modules/tee/tfm deleted file mode 160000 index 2c2aa37..0000000 --- a/zephyr/modules/tee/tfm +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 2c2aa3724a040233095a5c41ab79c8ad36134c8e diff --git a/zephyr/modules/tee/tfm-mcuboot b/zephyr/modules/tee/tfm-mcuboot deleted file mode 160000 index 4aa516e..0000000 --- a/zephyr/modules/tee/tfm-mcuboot +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 4aa516e7281fc6f9a2dce0b0efda9acc580fa254 diff --git a/zephyr/stlink b/zephyr/stlink deleted file mode 160000 index 48ebad3..0000000 --- a/zephyr/stlink +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 48ebad35132761210674c3fa8e4abd15a5a5695f diff --git a/zephyr/tools/edtt b/zephyr/tools/edtt deleted file mode 160000 index 7dd56fc..0000000 --- a/zephyr/tools/edtt +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 7dd56fc100d79cc45c33d43e7401d1803e26f6e7 diff --git a/zephyr/tools/net-tools b/zephyr/tools/net-tools deleted file mode 160000 index f49bd13..0000000 --- a/zephyr/tools/net-tools +++ /dev/null @@ -1 +0,0 @@ -Subproject commit f49bd1354616fae4093bf36e5eaee43c51a55127 diff --git a/zephyr/zephyr b/zephyr/zephyr deleted file mode 160000 index d54d75b..0000000 --- a/zephyr/zephyr +++ /dev/null @@ -1 +0,0 @@ -Subproject commit d54d75b6fd6bd559fde3e808cd424765b662fe19