From 3c4b79d271504cd30dfade4b641ca3310494e271 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Tue, 2 Jan 2018 14:39:05 -0800 Subject: [PATCH 01/80] Add software vehicle CAN and improve io signals Prior to this commit the vehicle CAN was forwarded through hardware only. Also used the older signal handler rather than the sigaction callback leaving the signals prone to a known race condition in the signal handler. This commit adds the initial layout and framework for supporting vehicle CAN through a device on the computer rather than forwarding from the OSCC hardware. This commit also moves to the sigaction callback rather than the signal handler and uses the thread id incase the API is called within a thread for improved reliability. --- api/include/oscc.h | 26 +++- api/src/internal/oscc.h | 17 +++ api/src/oscc.c | 328 ++++++++++++++++++++++++++++++++++++---- 3 files changed, 342 insertions(+), 29 deletions(-) diff --git a/api/include/oscc.h b/api/include/oscc.h index 39c06314..01a65e19 100644 --- a/api/include/oscc.h +++ b/api/include/oscc.h @@ -25,10 +25,19 @@ typedef enum OSCC_WARNING } oscc_result_t; +/** + * @brief Looks for available CAN channels and automaticcaly detects which + * channel is OSCC control and which channel is vehicle CAN for feedback. + * + * @return OSCC_ERROR or OSCC_OK + * + */ +oscc_result_t oscc_open(); /** - * @brief Use provided CAN channel to open communications - * to CAN bus connected to the OSCC modules. + * @brief Use provided CAN channel to open communications to CAN bus connected + * to the OSCC modules. If CAN gateway does not forward Vehicle CAN + * automatically detect if a CAN channel has Vehicle CAN available. * * @param [in] channel - CAN channel connected to OSCC modules. * @@ -37,6 +46,18 @@ typedef enum */ oscc_result_t oscc_open( unsigned int channel ); +/** + * @brief Initializes connection to the specified CAN channels for OSCC control + * and vehicle CAN for feedback. + * + * @param [in] oscc_channel - CAN channel connected to OSCC modules. + * @param [in] vehicle_channel - CAN channel connected to OSCC modules. + * + * @return OSCC_ERROR or OSCC_OK + * + */ +oscc_result_t oscc_open( const char * const oscc_channel, + const char * const vehicle_channel ); /** * @brief Use provided CAN channel to close communications @@ -177,4 +198,3 @@ oscc_result_t oscc_subscribe_to_obd_messages( void( *callback )( struct can_fram #endif /* _OSCC_H */ - diff --git a/api/src/internal/oscc.h b/api/src/internal/oscc.h index e86edf2e..c201f94e 100644 --- a/api/src/internal/oscc.h +++ b/api/src/internal/oscc.h @@ -7,6 +7,7 @@ #ifndef _OSCC_INTERNAL_H #define _OSCC_INTERNAL_H +#include #define CONSTRAIN(amt, low, high) ((amt) < (low) ? (low) : ((amt) > (high) ? (high) : (amt))) @@ -30,6 +31,9 @@ void (*obd_frame_callback)( oscc_result_t oscc_init_can( const char *can_channel ); +oscc_result_t vehicle_init_can( + const char *can_channel ); + oscc_result_t oscc_can_write( long id, void *msg, @@ -58,5 +62,18 @@ oscc_result_t oscc_disable_throttle( void oscc_update_status( ); +//These are all detection function for determining CAN signals +//Might be worth putting in their own location... + +struct dev_name { + struct dev_name *next, *prev; + char name[IFNAMSIZ]; +}; + +char * get_dev_name(char *string); + +oscc_result_t add_dev_name(const char * const name, struct dev_name * const list_ptr); + +oscc_result_t construct_interfaces_list(struct dev_name * const list_ptr); #endif /* _OSCC_INTERNAL_H */ diff --git a/api/src/oscc.c b/api/src/oscc.c index c700ebbc..7e19210a 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -1,6 +1,7 @@ #include #include #include +#include #include #include #include @@ -9,40 +10,109 @@ #include #include #include +#include #include #include "oscc.h" #include "internal/oscc.h" -static int can_socket = -1; +static int oscc_can_socket = -1; +static int vehicle_can_socket = -1; +static uint64_t dummy_counter = 0; +oscc_result_t oscc_open() +{ + oscc_result_t result = OSCC_ERROR; + + result = register_can_signal(); + + if( retsult != OSCC_ERROR ) + { + static struct dev_name *dev_list, temp_ptr; + dev_list = malloc(sizeof(struct dev_name)); + + ret = construct_interfaces_list(dev_list); + + temp_ptr = dev_list; + + do + { + if (strstr(temp_ptr->name,"can") != NULL) + { + printf("%s\n", temp_ptr->name); + //Check and assign if OSCC CAN + //Check and assign if Vehicle CAN + } + + temp_ptr = temp_ptr->next; + }while(temp_ptr != dev_list); + } + +} oscc_result_t oscc_open( unsigned int channel ) { oscc_result_t result = OSCC_ERROR; + result = register_can_signal(); - char can_string_buffer[16]; + if( result != OSCC_ERROR ) + { + char can_string_buffer[16]; - snprintf( can_string_buffer, 16, "can%u", channel ); + snprintf( can_string_buffer, 16, "can%u", channel ); - printf( "Opening CAN channel: %s\n", can_string_buffer ); + printf( "Opening CAN channel: %s\n", can_string_buffer ); - result = oscc_init_can( can_string_buffer ); + result = oscc_init_can( can_string_buffer ); + } + //If no vehicle CAN through OSCC add CAN detection here for second channel... + //Warn if no vehicle CAN is found. return result; } -oscc_result_t oscc_close( unsigned int channel ) +oscc_result_t oscc_open( const char * const oscc_channel, + const char * const vehicle_channel ) { oscc_result_t result = OSCC_ERROR; + result = register_can_signal(); + + if( result != OSCC_ERROR ) + { + char can_string_buffer[16]; + + snprintf( can_string_buffer, 16, oscc_channel ); + + printf( "Opening CAN channel: %s\n", can_string_buffer ); + + result = oscc_init_can( can_string_buffer ); + } - if( can_socket != -1 ) + if(result != OSCC_ERROR) { - int result = close( can_socket ); + char veh_can_string_buffer[16]; + + snprintf( veh_can_string_buffer, 16, vehicle_can ); + + printf( "Opening CAN channel: %s\n", veh_can_string_buffer ); + + result = vehicle_init_can( veh_can_string_buffer ); + } + + return result; +}; + +oscc_result_t oscc_close( unsigned int channel ) +{ + oscc_result_t result = OSCC_ERROR; + + if( oscc_can_socket != -1 ) + { + int result = close( oscc_can_socket ); if ( result > 0 ) { @@ -50,6 +120,15 @@ oscc_result_t oscc_close( unsigned int channel ) } } + if( vehicle_can_socket != -1 ) + { + int result = close( vehicle_can_socket ); + + if ( result > 0 ) + { + result = OSCC_OK; + } + } return result; } @@ -451,14 +530,15 @@ oscc_result_t oscc_disable_steering( void ) return result; } -void oscc_update_status( ) + +void oscc_update_status( int sig, siginfo_t *siginfo, void *context ) { struct can_frame rx_frame; memset( &rx_frame, 0, sizeof(rx_frame) ); - if ( can_socket != -1 ) + if ( oscc_can_socket != -1 ) { - int ret = read( can_socket, &rx_frame, CAN_MTU ); + int ret = read( oscc_can_socket, &rx_frame, CAN_MTU ); while ( ret > 0 ) { @@ -508,15 +588,30 @@ void oscc_update_status( ) } else { - if ( obd_frame_callback != NULL ) + if ( obd_frame_callback != NULL && vehicle_can_socket < 0 ) { obd_frame_callback( &rx_frame ); } } - ret = read( can_socket, &rx_frame, CAN_MTU ); + ret = read( oscc_can_socket, &rx_frame, CAN_MTU ); } } + + if ( vehicle_can_socket != -1 ) + { + int veh_ret = read( vehicle_can_socket, &rx_frame, CAN_MTU ); + + while( veh_ret > 0 ) + { + if ( obd_frame_callback != NULL ) + { + obd_frame_callback( &rx_frame ); + } + + veh_ret = read( vehicle_can_socket, &rx_frame, CAN_MTU ); + } + } } oscc_result_t oscc_can_write( long id, void *msg, unsigned int dlc ) @@ -524,7 +619,7 @@ oscc_result_t oscc_can_write( long id, void *msg, unsigned int dlc ) oscc_result_t result = OSCC_ERROR; - if ( can_socket != -1 ) + if ( oscc_can_socket != -1 ) { struct can_frame tx_frame; @@ -533,7 +628,7 @@ oscc_result_t oscc_can_write( long id, void *msg, unsigned int dlc ) tx_frame.can_dlc = dlc; memcpy( tx_frame.data, msg, dlc ); - int ret = write( can_socket, &tx_frame, sizeof(tx_frame) ); + int ret = write( oscc_can_socket, &tx_frame, sizeof(tx_frame) ); if ( ret > 0 ) { @@ -554,7 +649,7 @@ oscc_result_t oscc_async_enable( int socket ) oscc_result_t result = OSCC_ERROR; - int ret = fcntl( socket, F_SETOWN, getpid( ) ); + int ret = fcntl( socket, F_SETOWN, (pid_t) syscall (SYS_gettid) ); if ( ret < 0 ) { @@ -582,20 +677,27 @@ oscc_result_t oscc_async_enable( int socket ) return result; } +oscc_result_t register_can_signal() +{ + int result = OSCC_ERROR; + struct sigaction sig; + memset( &sig, 0, sizeof(sig) ); + sigemptyset( &sig.sa_mask ); + sig.sa_sigaction = oscc_update_status; + sig.sa_flags = SA_SIGINFO; + if( sigaction( SIGIO, &sig, NULL ) == 0 ) + { + result = OSCC_OK; + } + + return result; +} + oscc_result_t oscc_init_can( const char *can_channel ) { int result = OSCC_ERROR; int ret = -1; - - struct sigaction sig; - - memset( &sig, 0, sizeof(sig) ); - sigemptyset( &sig.sa_mask ); - sig.sa_flags = SA_RESTART; - sig.sa_handler = oscc_update_status; - sigaction( SIGIO, &sig, NULL ); - int sock = socket( PF_CAN, SOCK_RAW, CAN_RAW ); if ( sock < 0 ) @@ -682,10 +784,184 @@ oscc_result_t oscc_init_can( const char *can_channel ) } else { - can_socket = sock; + oscc_can_socket = sock; } } return result; } + +oscc_result_t vehicle_init_can( const char *can_channel ) +{ + int result = OSCC_ERROR; + int ret = -1; + + int sock = socket( PF_CAN, SOCK_RAW, CAN_RAW ); + + if ( sock < 0 ) + { + printf( "Opening CAN socket failed: %s\n", strerror(errno) ); + } + else + { + result = OSCC_OK; + } + + + struct ifreq ifr; + memset( &ifr, 0, sizeof(ifr) ); + + if ( result == OSCC_OK ) + { + strncpy( ifr.ifr_name, can_channel, IFNAMSIZ ); + + ret = ioctl( sock, SIOCGIFINDEX, &ifr ); + + if ( ret < 0 ) + { + printf( "Finding CAN index failed: %s\n", strerror(errno) ); + + result = OSCC_ERROR; + } + } + + + if ( result == OSCC_OK ) + { + struct sockaddr_can can_address; + + memset( &can_address, 0, sizeof(can_address) ); + can_address.can_family = AF_CAN; + can_address.can_ifindex = ifr.ifr_ifindex; + + ret = bind( + sock, + (struct sockaddr *) &can_address, + sizeof(can_address) ); + + if ( ret < 0 ) + { + printf( "Socket binding failed: %s\n", strerror(errno) ); + + result = OSCC_ERROR; + } + } + + struct can_filter rfilter[4]; + + rfilter[0].can_id = KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID; + rfilter[0].can_mask = CAN_SFF_MASK; + rfilter[1].can_id = KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID; + rfilter[1].can_mask = CAN_SFF_MASK; + rfilter[2].can_id = KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID; + rfilter[2].can_mask = CAN_SFF_MASK; + rfilter[2].can_id = KIA_SOUL_OBD_VEHICLE_SPEED_CAN_ID; + rfilter[2].can_mask = CAN_SFF_MASK; + + + setsockopt(sock, SOL_CAN_RAW, CAN_RAW_FILTER, &rfilter, sizeof(rfilter)); + + + if ( result == OSCC_OK ) + { + ret = oscc_async_enable( sock ); + + if ( ret != OSCC_OK ) + { + printf( "Enabling asynchronous socket I/O failed\n" ); + + result = OSCC_ERROR; + } + } + + + if ( result == OSCC_OK ) + { + vehicle_can_socket = sock; + } + + + return result; +} + +//Might want to put these CAN detection functions in their own library... + +char * get_dev_name(char *string) +{ + size_t span = strcspn(string, ":"); + static char temp_name[IFNAMSIZ]; + strncpy(temp_name, string, span); + size_t leading_spaces = strspn(temp_name, " "); + + if(leading_spaces == 0) + { + return temp_name; + } + + static char new_name[IFNAMSIZ]; + + strncpy(new_name, temp_name + leading_spaces, span - leading_spaces + 1); + + return new_name; +} + +oscc_result_t add_dev_name(const char * const name, struct dev_name * const list_ptr) +{ + if(list_ptr == NULL){ + fprintf(stderr, + "dev list is uninitialized (%s)\n", + strerror(errno)); + return -1; + } + + if(strlen(list_ptr->name) != 0) + { + struct dev_name * old_tail; + struct dev_name * new_name = malloc(sizeof(struct dev_name)); + strncpy(new_name->name, name, IFNAMSIZ); + + if(list_ptr->next == list_ptr){ + list_ptr->next = new_name; + } + old_tail = list_ptr->prev; + old_tail->next = new_name; + new_name->prev = old_tail; + new_name->next = list_ptr; + list_ptr->prev = new_name; + } + else{ + strncpy(list_ptr->name, name, IFNAMSIZ); + list_ptr->prev = list_ptr; + list_ptr->next = list_ptr; + } + + return OSCC_OK; +} + +oscc_result_t construct_interfaces_list(struct dev_name * const list_ptr) +{ + FILE *fh; + char buffer[512]; + oscc_result_t ret = OSCC_ERROR; + + fh = fopen("/proc/net/dev", "r"); + if (!fh) { + fprintf(stderr, + "Cannot read: /proc/net/dev (%s).\n", + strerror(errno)); + return -2; + } + + //Consume the first two lines since they are headers + fgets(buffer, sizeof buffer, fh); + fgets(buffer, sizeof buffer, fh); + + while (fgets(buffer, sizeof buffer, fh)) { + char *socket_name; + socket_name = get_dev_name(buffer); + ret = add_dev_name(socket_name, list_ptr); + } + + return ret; +} From 8bea8fcc3741c2db0269d50afee241e92c15c921 Mon Sep 17 00:00:00 2001 From: Adrien Thebo Date: Fri, 2 Feb 2018 13:33:27 -0800 Subject: [PATCH 02/80] testing: deduplicate step definitions The DriveKit module implementations share a lot of the same logic but copied files instead of sharing implementations. This commit adds a partial refactoring of the cucumber-cpp tests to share test initialization and step definitions where reasonable. --- .../tests/features/checking_faults.feature | 6 +- .../step_definitions/checking_faults.cpp | 36 ----- .../features/step_definitions/common.cpp | 146 +---------------- .../tests/features/step_definitions/test.cpp | 2 + .../tests/features/checking_faults.feature | 8 +- .../step_definitions/checking_faults.cpp | 49 ------ .../features/step_definitions/common.cpp | 73 +-------- .../tests/features/step_definitions/test.cpp | 2 + .../testing/step_definitions/common.cpp | 84 ++++++++++ .../step_definitions/fault_checking.cpp | 39 +++++ .../common/testing/step_definitions/vcm.cpp | 49 ++++++ .../tests/features/checking_faults.feature | 6 +- .../step_definitions/checking_faults.cpp | 38 ----- .../features/step_definitions/common.cpp | 147 +---------------- .../tests/features/step_definitions/test.cpp | 2 + .../tests/features/checking_faults.feature | 6 +- .../step_definitions/checking_faults.cpp | 36 ----- .../features/step_definitions/common.cpp | 150 +----------------- .../tests/features/step_definitions/test.cpp | 2 + 19 files changed, 209 insertions(+), 672 deletions(-) create mode 100644 firmware/common/testing/step_definitions/common.cpp create mode 100644 firmware/common/testing/step_definitions/fault_checking.cpp create mode 100644 firmware/common/testing/step_definitions/vcm.cpp diff --git a/firmware/brake/kia_soul_ev_niro/tests/features/checking_faults.feature b/firmware/brake/kia_soul_ev_niro/tests/features/checking_faults.feature index 00daab88..46a8a5f8 100644 --- a/firmware/brake/kia_soul_ev_niro/tests/features/checking_faults.feature +++ b/firmware/brake/kia_soul_ev_niro/tests/features/checking_faults.feature @@ -9,10 +9,10 @@ Feature: Checking for faults Scenario: A sensor becomes permanently disconnected Given brake control is enabled - When a sensor becomes permanently disconnected + When a sensor is grounded for 200 ms Then control should be disabled - And a fault report should be published + And a fault report should be published with origin ID 0 Scenario Outline: Operator override @@ -21,7 +21,7 @@ Feature: Checking for faults When the operator applies to the brake pedal for 200 ms Then control should be disabled - And a fault report should be published + And a fault report should be published with origin ID 0 Examples: | sensor_val | diff --git a/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/checking_faults.cpp b/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/checking_faults.cpp index 245b8b8d..ffe232e7 100644 --- a/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/checking_faults.cpp +++ b/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/checking_faults.cpp @@ -1,16 +1,3 @@ -WHEN("^a sensor becomes permanently disconnected$") -{ - g_mock_arduino_analog_read_return[0] = 0; - g_mock_arduino_analog_read_return[1] = 0; - - g_mock_arduino_millis_return = 1; - check_for_faults(); - - g_mock_arduino_millis_return += FAULT_HYSTERESIS * 2; - check_for_faults(); -} - - WHEN("^the operator applies (.*) to the brake pedal for (\\d+) ms$") { REGEX_PARAM(int, brake_sensor_val); @@ -25,26 +12,3 @@ WHEN("^the operator applies (.*) to the brake pedal for (\\d+) ms$") g_mock_arduino_millis_return += duration; check_for_faults(); } - - -THEN("^a fault report should be published$") -{ - assert_that(g_mock_mcp_can_send_msg_buf_id, is_equal_to(OSCC_FAULT_REPORT_CAN_ID)); - assert_that(g_mock_mcp_can_send_msg_buf_ext, is_equal_to(CAN_STANDARD)); - assert_that(g_mock_mcp_can_send_msg_buf_len, is_equal_to(OSCC_FAULT_REPORT_CAN_DLC)); - - oscc_fault_report_s * fault_report = - (oscc_fault_report_s *) g_mock_mcp_can_send_msg_buf_buf; - - assert_that( - fault_report->magic[0], - is_equal_to(OSCC_MAGIC_BYTE_0)); - - assert_that( - fault_report->magic[1], - is_equal_to(OSCC_MAGIC_BYTE_1)); - - assert_that( - fault_report->fault_origin_id, - is_equal_to(FAULT_ORIGIN_BRAKE)); -} diff --git a/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/common.cpp b/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/common.cpp index d3ca2dd0..77539bfe 100644 --- a/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/common.cpp +++ b/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/common.cpp @@ -1,149 +1,11 @@ -#include -#include -#include -#include -#include - -#include "Arduino.h" #include "communications.h" -#include "oscc_can.h" -#include "mcp_can.h" #include "brake_control.h" -#include "can_protocols/fault_can_protocol.h" #include "can_protocols/brake_can_protocol.h" #include "globals.h" -#include "vehicles.h" - -using namespace cgreen; - - -extern uint8_t g_mock_arduino_digital_write_pins[100]; -extern uint8_t g_mock_arduino_digital_write_val[100]; -extern int g_mock_arduino_digital_write_count; - -extern int g_mock_arduino_analog_read_return[100]; - -extern uint8_t g_mock_mcp_can_check_receive_return; -extern uint32_t g_mock_mcp_can_read_msg_buf_id; -extern uint8_t g_mock_mcp_can_read_msg_buf_buf[8]; -extern uint32_t g_mock_mcp_can_send_msg_buf_id; -extern uint8_t g_mock_mcp_can_send_msg_buf_ext; -extern uint8_t g_mock_mcp_can_send_msg_buf_len; -extern uint8_t *g_mock_mcp_can_send_msg_buf_buf; - -extern unsigned short g_mock_dac_output_a; -extern unsigned short g_mock_dac_output_b; extern volatile brake_control_state_s g_brake_control_state; -extern volatile unsigned long g_mock_arduino_millis_return; - -// return to known state before every scenario -BEFORE() -{ - g_mock_arduino_digital_write_count = 0; - memset(&g_mock_arduino_digital_write_pins, 0, sizeof(g_mock_arduino_digital_write_pins)); - memset(&g_mock_arduino_digital_write_val, 0, sizeof(g_mock_arduino_digital_write_val)); - - memset(&g_mock_arduino_analog_read_return, 0, sizeof(g_mock_arduino_analog_read_return)); - - g_mock_mcp_can_check_receive_return = UINT8_MAX; - g_mock_mcp_can_read_msg_buf_id = UINT32_MAX; - memset(&g_mock_mcp_can_read_msg_buf_buf, 0, sizeof(g_mock_mcp_can_read_msg_buf_buf)); - - g_mock_mcp_can_send_msg_buf_id = UINT32_MAX; - g_mock_mcp_can_send_msg_buf_ext = UINT8_MAX; - g_mock_mcp_can_send_msg_buf_len = UINT8_MAX; - - g_mock_dac_output_a = USHRT_MAX; - g_mock_dac_output_b = USHRT_MAX; - - g_brake_control_state.enabled = false; - g_brake_control_state.operator_override = false; - g_brake_control_state.dtcs = 0; - - // A small amount of time elapsed after boot - g_mock_arduino_millis_return = 1; -} - - -GIVEN("^brake control is enabled$") -{ - g_brake_control_state.enabled = 1; -} - - -GIVEN("^brake control is disabled$") -{ - g_brake_control_state.enabled = 0; -} - - -GIVEN("^the accelerator position sensors have a reading of (.*)$") -{ - REGEX_PARAM(int, sensor_val); - - g_mock_arduino_analog_read_return[0] = sensor_val; -} - - -GIVEN("^the operator has applied (.*) to the accelerator$") -{ - - REGEX_PARAM(int, brake_sensor_val); - - g_mock_arduino_analog_read_return[0] = brake_sensor_val; - - check_for_faults(); -} - - -THEN("^control should be enabled$") -{ - assert_that( - g_brake_control_state.enabled, - is_equal_to(1)); - - assert_that( - g_mock_arduino_digital_write_pins[0], - is_equal_to(PIN_SPOOF_ENABLE)); - - assert_that( - g_mock_arduino_digital_write_val[0], - is_equal_to(HIGH)); -} - - -THEN("^control should be disabled$") -{ - assert_that( - g_brake_control_state.enabled, - is_equal_to(0)); - - assert_that( - g_mock_arduino_digital_write_pins[0], - is_equal_to(PIN_SPOOF_ENABLE)); - - assert_that( - g_mock_arduino_digital_write_val[0], - is_equal_to(LOW)); -} - - -THEN("^(.*) should be sent to DAC A$") -{ - REGEX_PARAM(int, dac_output_a); - - assert_that( - g_mock_dac_output_a, - is_equal_to(dac_output_a)); -} - - -THEN("^(.*) should be sent to DAC B$") -{ - REGEX_PARAM(int, dac_output_b); - assert_that( - g_mock_dac_output_b, - is_equal_to(dac_output_b)); -} +#define FIRMWARE_NAME "brake" +#define g_vcm_control_state g_brake_control_state +#include "../../common/testing/step_definitions/common.cpp" +#include "../../common/testing/step_definitions/vcm.cpp" diff --git a/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/test.cpp b/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/test.cpp index 5f7d398e..990913dd 100644 --- a/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/test.cpp +++ b/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/test.cpp @@ -3,3 +3,5 @@ #include "checking_faults.cpp" #include "receiving_messages.cpp" #include "sending_reports.cpp" + +#include "../../common/testing/step_definitions/fault_checking.cpp" diff --git a/firmware/brake/kia_soul_petrol/tests/features/checking_faults.feature b/firmware/brake/kia_soul_petrol/tests/features/checking_faults.feature index 9aa560b0..f43e008a 100644 --- a/firmware/brake/kia_soul_petrol/tests/features/checking_faults.feature +++ b/firmware/brake/kia_soul_petrol/tests/features/checking_faults.feature @@ -10,7 +10,7 @@ Feature: Timeouts and overrides Scenario: A sensor becomes temporarily disconnected Given brake control is enabled - When a sensor becomes temporarily disconnected + When a sensor is grounded for 50 ms Then control should remain enabled @@ -18,10 +18,10 @@ Feature: Timeouts and overrides Scenario: A sensor becomes permanently disconnected Given brake control is enabled - When a sensor becomes permanently disconnected + When a sensor is grounded for 200 ms Then control should be disabled - And a fault report should be published + And a fault report should be published with origin ID 0 Scenario Outline: Operator override @@ -30,7 +30,7 @@ Feature: Timeouts and overrides When the operator applies to the brake pedal for 200 ms Then control should be disabled - And a fault report should be published + And a fault report should be published with origin ID 0 Examples: | sensor_val | diff --git a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/checking_faults.cpp b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/checking_faults.cpp index 79c7f1bb..c28637d5 100644 --- a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/checking_faults.cpp +++ b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/checking_faults.cpp @@ -1,29 +1,3 @@ -WHEN("^a sensor becomes temporarily disconnected$") -{ - g_mock_arduino_analog_read_return[0] = 0; - g_mock_arduino_analog_read_return[1] = 0; - - g_mock_arduino_millis_return = 1; - check_for_sensor_faults(); - - g_mock_arduino_millis_return += FAULT_HYSTERESIS / 2; - check_for_sensor_faults(); -} - - -WHEN("^a sensor becomes permanently disconnected$") -{ - g_mock_arduino_analog_read_return[0] = 0; - g_mock_arduino_analog_read_return[1] = 0; - - g_mock_arduino_millis_return = 1; - check_for_sensor_faults(); - - g_mock_arduino_millis_return += FAULT_HYSTERESIS * 2; - check_for_sensor_faults(); -} - - WHEN("^the operator applies (.*) to the brake pedal for (\\d+) ms$") { REGEX_PARAM(int, pedal_val); @@ -46,26 +20,3 @@ THEN("^control should remain enabled") g_brake_control_state.enabled, is_equal_to(1)); } - - -THEN("^a fault report should be published$") -{ - assert_that(g_mock_mcp_can_send_msg_buf_id, is_equal_to(OSCC_FAULT_REPORT_CAN_ID)); - assert_that(g_mock_mcp_can_send_msg_buf_ext, is_equal_to(CAN_STANDARD)); - assert_that(g_mock_mcp_can_send_msg_buf_len, is_equal_to(OSCC_FAULT_REPORT_CAN_DLC)); - - oscc_fault_report_s * fault_report = - (oscc_fault_report_s *) g_mock_mcp_can_send_msg_buf_buf; - - assert_that( - fault_report->magic[0], - is_equal_to(OSCC_MAGIC_BYTE_0)); - - assert_that( - fault_report->magic[1], - is_equal_to(OSCC_MAGIC_BYTE_1)); - - assert_that( - fault_report->fault_origin_id, - is_equal_to(FAULT_ORIGIN_BRAKE)); -} diff --git a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/common.cpp b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/common.cpp index d7c806e6..c75d4873 100644 --- a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/common.cpp +++ b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/common.cpp @@ -1,81 +1,16 @@ -#include -#include -#include -#include -#include - -#include "Arduino.h" #include "communications.h" -#include "oscc_can.h" -#include "mcp_can.h" #include "brake_control.h" #include "can_protocols/brake_can_protocol.h" -#include "can_protocols/fault_can_protocol.h" #include "vehicles.h" #include "globals.h" -using namespace cgreen; - -extern unsigned long g_mock_arduino_micros_return; -extern unsigned long g_mock_arduino_millis_return; - -extern uint8_t g_mock_arduino_digital_write_pins[100]; -extern uint8_t g_mock_arduino_digital_write_val[100]; -extern int g_mock_arduino_digital_write_count; - -extern int g_mock_arduino_analog_read_return[100]; -extern int g_mock_arduino_analog_write_count; -extern uint8_t g_mock_arduino_analog_write_pins[100]; -extern int g_mock_arduino_analog_write_val[100]; - -extern uint8_t g_mock_mcp_can_check_receive_return; -extern uint32_t g_mock_mcp_can_read_msg_buf_id; -extern uint8_t g_mock_mcp_can_read_msg_buf_buf[8]; -extern uint32_t g_mock_mcp_can_send_msg_buf_id; -extern uint8_t g_mock_mcp_can_send_msg_buf_ext; -extern uint8_t g_mock_mcp_can_send_msg_buf_len; -extern uint8_t *g_mock_mcp_can_send_msg_buf_buf; - extern volatile brake_control_state_s g_brake_control_state; +#define FIRMWARE_NAME "brake" +#define g_vcm_control_state g_brake_control_state +#include "../../common/testing/step_definitions/common.cpp" -// return to known state before every scenario -BEFORE() -{ - g_mock_arduino_digital_write_count = 0; - memset(&g_mock_arduino_digital_write_pins, 0, sizeof(g_mock_arduino_digital_write_pins)); - memset(&g_mock_arduino_digital_write_val, 0, sizeof(g_mock_arduino_digital_write_val)); - - g_mock_arduino_analog_read_return[0] = INT_MAX; - g_mock_arduino_analog_write_count = 0; - memset(&g_mock_arduino_analog_write_pins, 0, sizeof(g_mock_arduino_analog_write_pins)); - memset(&g_mock_arduino_analog_write_val, 0, sizeof(g_mock_arduino_analog_write_val)); - - g_mock_mcp_can_check_receive_return = UINT8_MAX; - g_mock_mcp_can_read_msg_buf_id = UINT32_MAX; - memset(&g_mock_mcp_can_read_msg_buf_buf, 0, sizeof(g_mock_mcp_can_read_msg_buf_buf)); - - g_mock_mcp_can_send_msg_buf_id = UINT32_MAX; - g_mock_mcp_can_send_msg_buf_ext = UINT8_MAX; - g_mock_mcp_can_send_msg_buf_len = UINT8_MAX; - - g_brake_control_state.enabled = false; - g_brake_control_state.operator_override = false; - g_brake_control_state.dtcs = 0; -} - - -GIVEN("^brake control is enabled$") -{ - g_brake_control_state.enabled = 1; -} - - -GIVEN("^brake control is disabled$") -{ - g_brake_control_state.enabled = 0; -} - +#define check_for_faults() (check_for_sensor_faults()) THEN("^control should be enabled$") { diff --git a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/test.cpp b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/test.cpp index 5f7d398e..990913dd 100644 --- a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/test.cpp +++ b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/test.cpp @@ -3,3 +3,5 @@ #include "checking_faults.cpp" #include "receiving_messages.cpp" #include "sending_reports.cpp" + +#include "../../common/testing/step_definitions/fault_checking.cpp" diff --git a/firmware/common/testing/step_definitions/common.cpp b/firmware/common/testing/step_definitions/common.cpp new file mode 100644 index 00000000..a0634456 --- /dev/null +++ b/firmware/common/testing/step_definitions/common.cpp @@ -0,0 +1,84 @@ +#include +#include +#include + +#include "Arduino.h" +#include "oscc_can.h" +#include "mcp_can.h" +#include "can_protocols/fault_can_protocol.h" +#include "vehicles.h" + +using namespace cgreen; + +extern uint8_t g_mock_arduino_digital_write_pins[100]; +extern uint8_t g_mock_arduino_digital_write_val[100]; +extern int g_mock_arduino_digital_write_count; + +extern int g_mock_arduino_analog_read_return[100]; +extern int g_mock_arduino_analog_write_count; +extern uint8_t g_mock_arduino_analog_write_pins[100]; +extern int g_mock_arduino_analog_write_val[100]; + +extern uint8_t g_mock_mcp_can_check_receive_return; +extern uint32_t g_mock_mcp_can_read_msg_buf_id; +extern uint8_t g_mock_mcp_can_read_msg_buf_buf[8]; +extern uint32_t g_mock_mcp_can_send_msg_buf_id; +extern uint8_t g_mock_mcp_can_send_msg_buf_ext; +extern uint8_t g_mock_mcp_can_send_msg_buf_len; +extern uint8_t *g_mock_mcp_can_send_msg_buf_buf; + +extern unsigned short g_mock_dac_output_a; +extern unsigned short g_mock_dac_output_b; + +extern volatile unsigned long g_mock_arduino_millis_return; +extern volatile unsigned long g_mock_arduino_micros_return; + +// return to known state before every scenario +BEFORE() +{ + g_mock_arduino_digital_write_count = 0; + memset(&g_mock_arduino_digital_write_pins, 0, sizeof(g_mock_arduino_digital_write_pins)); + memset(&g_mock_arduino_digital_write_val, 0, sizeof(g_mock_arduino_digital_write_val)); + + g_mock_arduino_analog_read_return[0] = INT_MAX; + g_mock_arduino_analog_read_return[1] = INT_MAX; + g_mock_arduino_analog_write_count = 0; + memset(&g_mock_arduino_analog_write_pins, 0, sizeof(g_mock_arduino_analog_write_pins)); + memset(&g_mock_arduino_analog_write_val, 0, sizeof(g_mock_arduino_analog_write_val)); + + g_mock_mcp_can_check_receive_return = UINT8_MAX; + g_mock_mcp_can_read_msg_buf_id = UINT32_MAX; + memset(&g_mock_mcp_can_read_msg_buf_buf, 0, sizeof(g_mock_mcp_can_read_msg_buf_buf)); + + g_mock_mcp_can_send_msg_buf_id = UINT32_MAX; + g_mock_mcp_can_send_msg_buf_ext = UINT8_MAX; + g_mock_mcp_can_send_msg_buf_len = UINT8_MAX; + + g_mock_dac_output_a = USHRT_MAX; + g_mock_dac_output_b = USHRT_MAX; + + g_vcm_control_state.enabled = false; + g_vcm_control_state.operator_override = false; + g_vcm_control_state.dtcs = 0; + + // A small amount of time elapsed after boot + g_mock_arduino_millis_return = 1; +} + +GIVEN("^(\\w+) control is enabled$") +{ + REGEX_PARAM(std::string, module_name); + + assert_that(module_name, is_equal_to_string(FIRMWARE_NAME)); + + g_vcm_control_state.enabled = 1; +} + +GIVEN("^(\\w+) control is disabled$") +{ + REGEX_PARAM(std::string, module_name); + + assert_that(module_name, is_equal_to_string(FIRMWARE_NAME)); + + g_vcm_control_state.enabled = 0; +} diff --git a/firmware/common/testing/step_definitions/fault_checking.cpp b/firmware/common/testing/step_definitions/fault_checking.cpp new file mode 100644 index 00000000..484d534b --- /dev/null +++ b/firmware/common/testing/step_definitions/fault_checking.cpp @@ -0,0 +1,39 @@ +// fault_checking.cpp + +WHEN("^a sensor is grounded for (\\d+) ms$") +{ + REGEX_PARAM(int, duration); + + g_mock_arduino_analog_read_return[0] = 0; + g_mock_arduino_analog_read_return[1] = 0; + + g_mock_arduino_millis_return = 1; + check_for_faults(); + + g_mock_arduino_millis_return += duration; + check_for_faults(); +} + +THEN("^a fault report should be published with origin ID (\\d+)$") +{ + REGEX_PARAM(int, fault_origin_id); + + assert_that(g_mock_mcp_can_send_msg_buf_id, is_equal_to(OSCC_FAULT_REPORT_CAN_ID)); + assert_that(g_mock_mcp_can_send_msg_buf_ext, is_equal_to(CAN_STANDARD)); + assert_that(g_mock_mcp_can_send_msg_buf_len, is_equal_to(OSCC_FAULT_REPORT_CAN_DLC)); + + oscc_fault_report_s * fault_report = + (oscc_fault_report_s *) g_mock_mcp_can_send_msg_buf_buf; + + assert_that( + fault_report->magic[0], + is_equal_to(OSCC_MAGIC_BYTE_0)); + + assert_that( + fault_report->magic[1], + is_equal_to(OSCC_MAGIC_BYTE_1)); + + assert_that( + fault_report->fault_origin_id, + is_equal_to(fault_origin_id)); +} diff --git a/firmware/common/testing/step_definitions/vcm.cpp b/firmware/common/testing/step_definitions/vcm.cpp new file mode 100644 index 00000000..a4c1c638 --- /dev/null +++ b/firmware/common/testing/step_definitions/vcm.cpp @@ -0,0 +1,49 @@ +THEN("^control should be enabled$") +{ + assert_that( + g_vcm_control_state.enabled, + is_equal_to(1)); + + assert_that( + g_mock_arduino_digital_write_pins[0], + is_equal_to(PIN_SPOOF_ENABLE)); + + assert_that( + g_mock_arduino_digital_write_val[0], + is_equal_to(HIGH)); +} + + +THEN("^control should be disabled$") +{ + assert_that( + g_vcm_control_state.enabled, + is_equal_to(0)); + + assert_that( + g_mock_arduino_digital_write_pins[0], + is_equal_to(PIN_SPOOF_ENABLE)); + + assert_that( + g_mock_arduino_digital_write_val[0], + is_equal_to(LOW)); +} + +THEN("^(.*) should be sent to DAC A$") +{ + REGEX_PARAM(int, dac_output_a); + + assert_that( + g_mock_dac_output_a, + is_equal_to(dac_output_a)); +} + + +THEN("^(.*) should be sent to DAC B$") +{ + REGEX_PARAM(int, dac_output_b); + + assert_that( + g_mock_dac_output_b, + is_equal_to(dac_output_b)); +} diff --git a/firmware/steering/tests/features/checking_faults.feature b/firmware/steering/tests/features/checking_faults.feature index 6cfb190a..0c364b3d 100644 --- a/firmware/steering/tests/features/checking_faults.feature +++ b/firmware/steering/tests/features/checking_faults.feature @@ -9,10 +9,10 @@ Feature: Checking for faults Scenario: A sensor becomes permanently disconnected Given steering control is enabled - When a sensor becomes permanently disconnected + When a sensor is grounded for 200 ms Then control should be disabled - And a fault report should be published + And a fault report should be published with origin ID 1 Scenario Outline: Operator override @@ -21,7 +21,7 @@ Feature: Checking for faults When the operator applies to the steering wheel Then control should be disabled - And a fault report should be published + And a fault report should be published with origin ID 1 Examples: | sensor_val | diff --git a/firmware/steering/tests/features/step_definitions/checking_faults.cpp b/firmware/steering/tests/features/step_definitions/checking_faults.cpp index afd44ae3..b221c18f 100644 --- a/firmware/steering/tests/features/step_definitions/checking_faults.cpp +++ b/firmware/steering/tests/features/step_definitions/checking_faults.cpp @@ -1,18 +1,3 @@ -WHEN("^a sensor becomes permanently disconnected$") -{ - g_mock_arduino_analog_read_return[0] = 0; - g_mock_arduino_analog_read_return[1] = 0; - - check_for_faults(); - - // must call function enough times to exceed the fault limit - g_mock_arduino_millis_return = 105; - - check_for_faults(); - -} - - WHEN("^the operator applies (.*) to the steering wheel$") { REGEX_PARAM(int, steering_sensor_val); @@ -33,26 +18,3 @@ WHEN("^the operator applies (.*) to the steering wheel$") check_for_faults(); } - - -THEN("^a fault report should be published$") -{ - assert_that(g_mock_mcp_can_send_msg_buf_id, is_equal_to(OSCC_FAULT_REPORT_CAN_ID)); - assert_that(g_mock_mcp_can_send_msg_buf_ext, is_equal_to(CAN_STANDARD)); - assert_that(g_mock_mcp_can_send_msg_buf_len, is_equal_to(OSCC_FAULT_REPORT_CAN_DLC)); - - oscc_fault_report_s * fault_report = - (oscc_fault_report_s *) g_mock_mcp_can_send_msg_buf_buf; - - assert_that( - fault_report->magic[0], - is_equal_to(OSCC_MAGIC_BYTE_0)); - - assert_that( - fault_report->magic[1], - is_equal_to(OSCC_MAGIC_BYTE_1)); - - assert_that( - fault_report->fault_origin_id, - is_equal_to(FAULT_ORIGIN_STEERING)); -} diff --git a/firmware/steering/tests/features/step_definitions/common.cpp b/firmware/steering/tests/features/step_definitions/common.cpp index b0775daa..4c83c5b4 100644 --- a/firmware/steering/tests/features/step_definitions/common.cpp +++ b/firmware/steering/tests/features/step_definitions/common.cpp @@ -1,150 +1,11 @@ -#include -#include -#include -#include -#include - -#include "Arduino.h" #include "communications.h" -#include "oscc_can.h" -#include "mcp_can.h" #include "steering_control.h" -#include "can_protocols/fault_can_protocol.h" #include "can_protocols/steering_can_protocol.h" #include "globals.h" -using namespace cgreen; - - -extern uint8_t g_mock_arduino_digital_write_pins[100]; -extern uint8_t g_mock_arduino_digital_write_val[100]; -extern int g_mock_arduino_digital_write_count; - -extern int g_mock_arduino_analog_read_return[100]; - -extern uint8_t g_mock_mcp_can_check_receive_return; -extern uint32_t g_mock_mcp_can_read_msg_buf_id; -extern uint8_t g_mock_mcp_can_read_msg_buf_buf[8]; -extern uint32_t g_mock_mcp_can_send_msg_buf_id; -extern uint8_t g_mock_mcp_can_send_msg_buf_ext; -extern uint8_t g_mock_mcp_can_send_msg_buf_len; -extern uint8_t *g_mock_mcp_can_send_msg_buf_buf; - -extern unsigned short g_mock_dac_output_a; -extern unsigned short g_mock_dac_output_b; - extern volatile steering_control_state_s g_steering_control_state; -extern volatile unsigned long g_mock_arduino_millis_return; - -// return to known state before every scenario -BEFORE() -{ - g_mock_arduino_digital_write_count = 0; - memset(&g_mock_arduino_digital_write_pins, 0, sizeof(g_mock_arduino_digital_write_pins)); - memset(&g_mock_arduino_digital_write_val, 0, sizeof(g_mock_arduino_digital_write_val)); - - g_mock_arduino_analog_read_return[0] = INT_MAX; - g_mock_arduino_analog_read_return[1] = INT_MAX; - - g_mock_mcp_can_check_receive_return = UINT8_MAX; - g_mock_mcp_can_read_msg_buf_id = UINT32_MAX; - memset(&g_mock_mcp_can_read_msg_buf_buf, 0, sizeof(g_mock_mcp_can_read_msg_buf_buf)); - - g_mock_mcp_can_send_msg_buf_id = UINT32_MAX; - g_mock_mcp_can_send_msg_buf_ext = UINT8_MAX; - g_mock_mcp_can_send_msg_buf_len = UINT8_MAX; - - g_mock_dac_output_a = USHRT_MAX; - g_mock_dac_output_b = USHRT_MAX; - - g_steering_control_state.enabled = false; - g_steering_control_state.operator_override = false; - g_steering_control_state.dtcs = 0; - - // A small amount of time elapsed after boot - g_mock_arduino_millis_return = 1; -} - - -GIVEN("^steering control is enabled$") -{ - g_steering_control_state.enabled = 1; -} - - -GIVEN("^steering control is disabled$") -{ - g_steering_control_state.enabled = 0; -} - - -GIVEN("^the torque sensors have a reading of (.*)$") -{ - REGEX_PARAM(int, sensor_val); - - g_mock_arduino_analog_read_return[0] = sensor_val; - g_mock_arduino_analog_read_return[1] = sensor_val; -} - - -GIVEN("^the operator has applied (.*) to the steering wheel$") -{ - REGEX_PARAM(int, steering_sensor_val); - - g_mock_arduino_analog_read_return[0] = steering_sensor_val; - g_mock_arduino_analog_read_return[1] = steering_sensor_val; - - check_for_faults(); -} - - -THEN("^control should be enabled$") -{ - assert_that( - g_steering_control_state.enabled, - is_equal_to(1)); - - assert_that( - g_mock_arduino_digital_write_pins[0], - is_equal_to(PIN_SPOOF_ENABLE)); - - assert_that( - g_mock_arduino_digital_write_val[0], - is_equal_to(HIGH)); -} - - -THEN("^control should be disabled$") -{ - assert_that( - g_steering_control_state.enabled, - is_equal_to(0)); - - assert_that( - g_mock_arduino_digital_write_pins[0], - is_equal_to(PIN_SPOOF_ENABLE)); - - assert_that( - g_mock_arduino_digital_write_val[0], - is_equal_to(LOW)); -} - - -THEN("^(.*) should be sent to DAC A$") -{ - REGEX_PARAM(int, dac_output_a); - - assert_that( - g_mock_dac_output_a, - is_equal_to(dac_output_a)); -} - - -THEN("^(.*) should be sent to DAC B$") -{ - REGEX_PARAM(int, dac_output_b); - assert_that( - g_mock_dac_output_b, - is_equal_to(dac_output_b)); -} +#define FIRMWARE_NAME "steering" +#define g_vcm_control_state g_steering_control_state +#include "../../common/testing/step_definitions/common.cpp" +#include "../../common/testing/step_definitions/vcm.cpp" diff --git a/firmware/steering/tests/features/step_definitions/test.cpp b/firmware/steering/tests/features/step_definitions/test.cpp index 5f7d398e..990913dd 100644 --- a/firmware/steering/tests/features/step_definitions/test.cpp +++ b/firmware/steering/tests/features/step_definitions/test.cpp @@ -3,3 +3,5 @@ #include "checking_faults.cpp" #include "receiving_messages.cpp" #include "sending_reports.cpp" + +#include "../../common/testing/step_definitions/fault_checking.cpp" diff --git a/firmware/throttle/tests/features/checking_faults.feature b/firmware/throttle/tests/features/checking_faults.feature index e3f0c823..912f275f 100644 --- a/firmware/throttle/tests/features/checking_faults.feature +++ b/firmware/throttle/tests/features/checking_faults.feature @@ -8,10 +8,10 @@ Feature: Checking for faults Scenario: A sensor becomes permanently disconnected Given throttle control is enabled - When a sensor becomes permanently disconnected + When a sensor is grounded for 200 ms Then control should be disabled - And a fault report should be published + And a fault report should be published with origin ID 2 Scenario Outline: Operator override @@ -20,7 +20,7 @@ Feature: Checking for faults When the operator applies to the accelerator for 200 ms Then control should be disabled - And a fault report should be published + And a fault report should be published with origin ID 2 Examples: | sensor_val | diff --git a/firmware/throttle/tests/features/step_definitions/checking_faults.cpp b/firmware/throttle/tests/features/step_definitions/checking_faults.cpp index e32b2cb9..ff666a51 100644 --- a/firmware/throttle/tests/features/step_definitions/checking_faults.cpp +++ b/firmware/throttle/tests/features/step_definitions/checking_faults.cpp @@ -1,16 +1,3 @@ -WHEN("^a sensor becomes permanently disconnected$") -{ - g_mock_arduino_analog_read_return[0] = 0; - g_mock_arduino_analog_read_return[1] = 0; - - g_mock_arduino_millis_return = 1; - check_for_faults(); - - g_mock_arduino_millis_return += FAULT_HYSTERESIS * 2; - check_for_faults(); -} - - WHEN("^the operator applies (.*) to the accelerator for (\\d+) ms$") { REGEX_PARAM(int, throttle_sensor_val); @@ -25,26 +12,3 @@ WHEN("^the operator applies (.*) to the accelerator for (\\d+) ms$") g_mock_arduino_millis_return += duration; check_for_faults(); } - - -THEN("^a fault report should be published$") -{ - assert_that(g_mock_mcp_can_send_msg_buf_id, is_equal_to(OSCC_FAULT_REPORT_CAN_ID)); - assert_that(g_mock_mcp_can_send_msg_buf_ext, is_equal_to(CAN_STANDARD)); - assert_that(g_mock_mcp_can_send_msg_buf_len, is_equal_to(OSCC_FAULT_REPORT_CAN_DLC)); - - oscc_fault_report_s * fault_report = - (oscc_fault_report_s *) g_mock_mcp_can_send_msg_buf_buf; - - assert_that( - fault_report->magic[0], - is_equal_to(OSCC_MAGIC_BYTE_0)); - - assert_that( - fault_report->magic[1], - is_equal_to(OSCC_MAGIC_BYTE_1)); - - assert_that( - fault_report->fault_origin_id, - is_equal_to(FAULT_ORIGIN_THROTTLE)); -} diff --git a/firmware/throttle/tests/features/step_definitions/common.cpp b/firmware/throttle/tests/features/step_definitions/common.cpp index 5440350e..a2c2b963 100644 --- a/firmware/throttle/tests/features/step_definitions/common.cpp +++ b/firmware/throttle/tests/features/step_definitions/common.cpp @@ -1,153 +1,11 @@ -#include -#include -#include -#include -#include - -#include "Arduino.h" #include "communications.h" -#include "oscc_can.h" -#include "mcp_can.h" #include "throttle_control.h" -#include "can_protocols/fault_can_protocol.h" #include "can_protocols/throttle_can_protocol.h" #include "globals.h" -#include "vehicles.h" - -using namespace cgreen; - - -extern uint8_t g_mock_arduino_digital_write_pins[100]; -extern uint8_t g_mock_arduino_digital_write_val[100]; -extern int g_mock_arduino_digital_write_count; - -extern int g_mock_arduino_analog_read_return[100]; - -extern uint8_t g_mock_mcp_can_check_receive_return; -extern uint32_t g_mock_mcp_can_read_msg_buf_id; -extern uint8_t g_mock_mcp_can_read_msg_buf_buf[8]; -extern uint32_t g_mock_mcp_can_send_msg_buf_id; -extern uint8_t g_mock_mcp_can_send_msg_buf_ext; -extern uint8_t g_mock_mcp_can_send_msg_buf_len; -extern uint8_t *g_mock_mcp_can_send_msg_buf_buf; - -extern unsigned short g_mock_dac_output_a; -extern unsigned short g_mock_dac_output_b; extern volatile throttle_control_state_s g_throttle_control_state; -extern volatile unsigned long g_mock_arduino_millis_return; - - -// return to known state before every scenario -BEFORE() -{ - g_mock_arduino_digital_write_count = 0; - memset(&g_mock_arduino_digital_write_pins, 0, sizeof(g_mock_arduino_digital_write_pins)); - memset(&g_mock_arduino_digital_write_val, 0, sizeof(g_mock_arduino_digital_write_val)); - - g_mock_arduino_analog_read_return[0] = INT_MAX; - g_mock_arduino_analog_read_return[1] = INT_MAX; - - g_mock_mcp_can_check_receive_return = UINT8_MAX; - g_mock_mcp_can_read_msg_buf_id = UINT32_MAX; - memset(&g_mock_mcp_can_read_msg_buf_buf, 0, sizeof(g_mock_mcp_can_read_msg_buf_buf)); - - g_mock_mcp_can_send_msg_buf_id = UINT32_MAX; - g_mock_mcp_can_send_msg_buf_ext = UINT8_MAX; - g_mock_mcp_can_send_msg_buf_len = UINT8_MAX; - - g_mock_dac_output_a = USHRT_MAX; - g_mock_dac_output_b = USHRT_MAX; - - g_throttle_control_state.enabled = false; - g_throttle_control_state.operator_override = false; - g_throttle_control_state.dtcs = 0; - - // A small amount of time elapsed after boot - g_mock_arduino_millis_return = 1; -} - - -GIVEN("^throttle control is enabled$") -{ - g_throttle_control_state.enabled = 1; -} - - -GIVEN("^throttle control is disabled$") -{ - g_throttle_control_state.enabled = 0; -} - - -GIVEN("^the accelerator position sensors have a reading of (.*)$") -{ - REGEX_PARAM(int, sensor_val); - - g_mock_arduino_analog_read_return[0] = sensor_val; - g_mock_arduino_analog_read_return[1] = sensor_val; -} - - -GIVEN("^the operator has applied (.*) to the accelerator$") -{ - - REGEX_PARAM(int, throttle_sensor_val); - - g_mock_arduino_analog_read_return[0] = throttle_sensor_val; - g_mock_arduino_analog_read_return[1] = throttle_sensor_val; - - check_for_faults(); -} - - -THEN("^control should be enabled$") -{ - assert_that( - g_throttle_control_state.enabled, - is_equal_to(1)); - - assert_that( - g_mock_arduino_digital_write_pins[0], - is_equal_to(PIN_SPOOF_ENABLE)); - - assert_that( - g_mock_arduino_digital_write_val[0], - is_equal_to(HIGH)); -} - - -THEN("^control should be disabled$") -{ - assert_that( - g_throttle_control_state.enabled, - is_equal_to(0)); - - assert_that( - g_mock_arduino_digital_write_pins[0], - is_equal_to(PIN_SPOOF_ENABLE)); - - assert_that( - g_mock_arduino_digital_write_val[0], - is_equal_to(LOW)); -} - - -THEN("^(.*) should be sent to DAC A$") -{ - REGEX_PARAM(int, dac_output_a); - - assert_that( - g_mock_dac_output_a, - is_equal_to(dac_output_a)); -} - - -THEN("^(.*) should be sent to DAC B$") -{ - REGEX_PARAM(int, dac_output_b); - assert_that( - g_mock_dac_output_b, - is_equal_to(dac_output_b)); -} +#define FIRMWARE_NAME "throttle" +#define g_vcm_control_state g_throttle_control_state +#include "../../common/testing/step_definitions/common.cpp" +#include "../../common/testing/step_definitions/vcm.cpp" diff --git a/firmware/throttle/tests/features/step_definitions/test.cpp b/firmware/throttle/tests/features/step_definitions/test.cpp index 5f7d398e..990913dd 100644 --- a/firmware/throttle/tests/features/step_definitions/test.cpp +++ b/firmware/throttle/tests/features/step_definitions/test.cpp @@ -3,3 +3,5 @@ #include "checking_faults.cpp" #include "receiving_messages.cpp" #include "sending_reports.cpp" + +#include "../../common/testing/step_definitions/fault_checking.cpp" From 2715b284e475ca8f362bfc25754c42d1fa5f3bf9 Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Mon, 5 Feb 2018 12:39:34 -0800 Subject: [PATCH 03/80] Add BOM for each board Prior to this commit there was not a reliable BOM associated with the boards we tracked schematics. This commit represents the addition of the BOM for each board as well as a corresponding MacroFab XYRS data file. Each of these files are in a comma delimited CSV format that can be imported into spreadsheet software. Closes #227 --- .../polysync_actuator_v_1_2_0_BOM.csv | 52 ++++ ...nc_actuator_v_1_2_0_MacroFab_XYRS_Data.csv | 265 ++++++++++++++++++ .../gateway/polysync_gateway_v_1_0_0_BOM.csv | 28 ++ ...ync_gateway_v_1_0_0_MacroFab_XYRS_Data.csv | 57 ++++ .../polysync_sensor_v_1_1_0-1_BOM.csv | 33 +++ ...ync_sensor_v_1_1_0-1_MacrFab_XTRS_Data.csv | 57 ++++ .../polysync_vcm_v_0_1_0_BOM.csv | 33 +++ ...olysync_vcm_v_0_1_0_MacroFab_XYRS_Data.csv | 57 ++++ 8 files changed, 582 insertions(+) create mode 100644 hardware/boards/actuator_control/polysync_actuator_v_1_2_0_BOM.csv create mode 100644 hardware/boards/actuator_control/polysync_actuator_v_1_2_0_MacroFab_XYRS_Data.csv create mode 100644 hardware/boards/gateway/polysync_gateway_v_1_0_0_BOM.csv create mode 100644 hardware/boards/gateway/polysync_gateway_v_1_0_0_MacroFab_XYRS_Data.csv create mode 100644 hardware/boards/sensor_interface/polysync_sensor_v_1_1_0-1_BOM.csv create mode 100644 hardware/boards/sensor_interface/polysync_sensor_v_1_1_0-1_MacrFab_XTRS_Data.csv create mode 100644 hardware/boards/vehicle_control_module/polysync_vcm_v_0_1_0_BOM.csv create mode 100644 hardware/boards/vehicle_control_module/polysync_vcm_v_0_1_0_MacroFab_XYRS_Data.csv diff --git a/hardware/boards/actuator_control/polysync_actuator_v_1_2_0_BOM.csv b/hardware/boards/actuator_control/polysync_actuator_v_1_2_0_BOM.csv new file mode 100644 index 00000000..94914a7f --- /dev/null +++ b/hardware/boards/actuator_control/polysync_actuator_v_1_2_0_BOM.csv @@ -0,0 +1,52 @@ +Polysync Actuator Board BOM V1.2.0,,,,,,,, +,,,,,,,, +Quantity,Reference Designator,Description,Mfg,Mfg Part No.,Distributor,Distributor Part No.,Price,Total Price +8,"R7, R8, R11, R12, R25, R26, R27, R28",RES SMD 0.02 OHM 1% 1W 1206,Panasonic Electronic Components,ERJ-8CWFR020V,Digikey,P0.02BVCT-ND,0.69,5.52 +1,R101,RES SMD 0.3 OHM 1% 1/6W 0402,Panasonic Electronic Components,ERJ-2BQFR30X,Digikey,P.30AKCT-ND,0.59,0.59 +5,"R106, R107, R108, R109, R110",RES SMD 0.0OHM JUMPER 1/10W 0402,Panasonic Electronic Components,ERJ-2GE0R00X,Digikey,P0.0JCT-ND,0.1,0.5 +8,"R9, R10, R15, R16, R29, R30, R31, R32",RES SMD 0.0 OHM JUMPER 1/8W 0805,Panasonic Electronic Components,ERJ-6GEY0R00V,Digikey,P0.0ACT-ND,0.1,0.8 +8,"R3, R4, R5, R6, R21, R22, R23, R24",RES SMD 100 OHM 1% 1/8W 0805,Panasonic Electronic Components,ERJ-6ENF1000V,Digikey,P100CCT-ND,0.1,0.8 +24,"R33, R34, R35, R45, R46, R47, R48, R49, R50, R57, R61, R62, R65, R66, R67, R77, R78, R79, R80, R81, R82, R89, R93, R94",RES SMD 100K OHM 1% 1/10W 0402,Panasonic Electronic Components,ERJ-2RKF1003X,Digikey,P100KLCT-ND,0.1,2.4 +10,"R1, R2, R13, R14, R17, R18, R19, R20, R104, R121",RES SMD 10K OHM 1% 1/10W 0402,Panasonic Electronic Components,ERJ-2RKF1002X,Digikey,P10.0KLCT-ND,0.1,1 +1,R102,RES SMD 120 OHM 1% 1/10W 0402,Panasonic Electronic Components,ERJ-2RKF1200X,Digikey,P120LCT-ND,0.1,0.1 +48,"R36, R37, R38, R39, R40, R41, R42, R43, R44, R51, R52, R53, R54, R55, R56, R58, R59, R60, R63, R64, R68, R69, R70, R71, R72, R73, R74, R75, R76, R83, R84, R85, R86, R87, R88, R90, R91, R92, R95, R96, R97, R98, R99, R100, R103, R116, R117, R119",RES SMD 1K OHM 1% 1/10W 0402,Panasonic Electronic Components,ERJ-2RKF1001X,Digikey,P1.00KLCT-ND,0.1,4.8 +2,"R105, R120",RES SMD 47K OHM 1% 1/10W 0402,Panasonic Electronic Components,ERJ-2RKF4702X,Digikey,P47.0KLCT-ND,0.1,0.2 +1,R118,RES SMD 5.1K OHM 1% 1/10W 0402,Panasonic Electronic Components,ERJ-2RKF5101X,Digikey,P5.10KLCT-ND,0.1,0.1 +18,"C26, C27, C29, C30, C32, C33, C35, C36, C38, C39, C41, C42, C44, C45, C47, C48, C49, C51",0.10µF ±10% 100V Ceramic Capacitor X5R 0402 (1005 Metric),Murata Electronics North America,GRM155R62A104KE14D,Digikey,490-10458-1-ND,0.1,1.8 +12,"C3, C4, C7, C8, C11, C12, C19, C20, C21, C22, C23, C24",0.10µF ±10% 100V Ceramic Capacitor X7R 0805 (2012 Metric),"Samsung Electro-Mechanics America, Inc.",CL21B104KCFNNNE,Digikey,1276-6840-1-ND,0.1,1.2 +8,"C25, C28, C31, C34, C37, C40, C43, C46","100pF ±5% 50V Ceramic Capacitor C0G, NP0 0402 (1005 Metric)",Yageo,CC0402JRNPO9BN101,Digikey,311-1024-1-ND,0.1,0.8 +12,"C1, C2, C5, C6, C9, C10, C13, C14, C15, C16, C17, C18",1µF ±10% 100V Ceramic Capacitor X7R 1206 (3216 Metric),"Samsung Electro-Mechanics America, Inc.",CL31B105KCHNNNE,Digikey,1276-1838-1-ND,0.29,3.48 +2,"C52, C53","22pF ±5% 50V Ceramic Capacitor C0G, NP0 0402 (1005 Metric)",Murata Electronics North America,GRM1555C1H220JA01J,Digikey,490-11382-1-ND,0.1,0.2 +1,C50,33µF ±10% Molded Tantalum Capacitors 10V 1206 (3216 Metric) 1.7 Ohm,AVX Corporation,TAJA336K010RNJ,Digikey,478-8882-1-ND,0.6,0.6 +3,"Q9, Q11, Q12",MOSFET N-CH 60V 6A,Toshiba Semiconductor and Storage,"SSM3K341R,LF",Digikey,SSM3K341RLFCT-ND,0.43,1.29 +8,"Q1, Q2, Q3, Q4, Q5, Q6, Q7, Q8",MOSFET N-CH 60V 50A 8SON,Texas Instruments,CSD18537NQ5A,Digikey,296-36455-1-ND,0.85,6.8 +1,Q10,MOSFET N-CH 20V 0.2A EMT3,Rohm Semiconductor,RE1C002UNTCL,Digikey,RE1C002UNTCLCT-ND,0.2,0.2 +1,D21,Blue 470nm LED Indication - Discrete 3.2V 0603 (1608 Metric),Wurth Electronics Inc,150060BS75000,Digikey,732-4966-1-ND,0.26,0.26 +2,"D17, D20",LED RED CLEAR 0603 SMD,Wurth Electronics Inc,150060RS75000,Digikey,732-4978-1-ND,0.24,0.48 +2,"D18, D19",LED GREEN CLEAR 0603 SMD,Wurth Electronics Inc,150060GS75000,Digikey,732-4971-1-ND,0.24,0.48 +8,"D1, D2, D3, D4, D5, D6, D7, D8",Diode Standard 100V 1A Surface Mount SMA,Diodes Incorporated,US1B-13-F,Digikey,US1B-FDICT-ND,0.42,3.36 +8,"D9, D10, D11, D12, D13, D14, D15, D16",Diode Schottky 20V 500mA Surface Mount SOD-123,Diodes Incorporated,B0520LW-7-F,Digikey,B0520LW-FDICT-ND,0.32,2.56 +8,"L1, L2, L3, L4, L5, L6, L7, L8",2.2µH Shielded Wirewound Inductor 10A 12 mOhm Max Nonstandard,Bourns Inc.,SRP7050TA-2R2M,Digikey,SRP7050TA-2R2MCT-ND,1.18,9.44 +1,X1,16MHz ±30ppm Crystal 18pF 40 Ohm -40°C ~ 85°C Surface Mount HC49/US,Abracon LLC,ABLS-16.000MHZ-D-4-T,Digikey,535-13436-1-ND,0.24,0.24 +1,U15,CAN Controller CAN 2.0 SPI Interface 18-SOIC,Microchip Technology,MCP2515-I/SO,Digikey,MCP2515-I/SO-ND,1.82,1.82 +1,U14,1/1 Transceiver Half CAN 8-SOIC,Microchip Technology,MCP2551-I/SN,Digikey,MCP2551-I/SN-ND,1.02,1.02 +8,"U5, U6, U7, U8, U9, U10, U11, U12",General Purpose Amplifier 1 Circuit Rail-to-Rail SOT-23-5,Texas Instruments,OPA170AIDBVT,Digikey,296-29496-1-ND,1.41,11.28 +1,U13,Linear Voltage Regulator IC Positive Fixed 1 Output 5V 750mA DDPAK/TO-263-3,Texas Instruments,TL750M05CKTTR,Digikey,296-20776-1-ND,1.47,1.47 +4,"U1, U2, U3, U4",Low-Side Gate Driver IC Non-Inverting 8-SOIC,Texas Instruments,UCC27524DR,Digikey,296-30129-1-ND,1.94,7.76 +1,RELAY1,General Purpose Relay DPDT (2 Form C) Surface Mount,Kemet,EE2-5NU-L,Digikey,399-11017-1-ND,1.91,1.91 +1,RELAY2,Automotive Relay SPDT (1 Form C) 12VDC Coil Through Hole,TE Connectivity Potter & Brumfield Relays,1432868-1,Digikey,PB1040-ND,3.46,3.46 +1,RELAY3,Relay Socket Through Hole,TE Connectivity Potter & Brumfield Relays,VCF4-1000,Digikey,PB232-ND,1.8,1.8 +1,JP2,"2 Positions Header, Unshrouded Connector 0.100"" (2.54mm) Through Hole Gold or Gold, GXT™",Amphenol FCI,77311-118-02LF,Digikey,609-4434-ND,0.18,0.18 +1,JP1,"10 Positions Header, Unshrouded Connector 0.100"" (2.54mm) Through Hole Gold",Wurth Electronics Inc,61301011121,Digikey,732-2670-ND,1.01,1.01 +1,XIO,"36 Positions Header, Unshrouded Connector 0.100"" (2.54mm) Through Hole Gold",Wurth Electronics Inc,61303621121,Digikey,732-5309-ND,1.64,1.64 +5,"ADCH, ADCL, COMMUNICATION, POWER, PWML","8 Positions Header, Unshrouded Connector 0.100"" (2.54mm) Through Hole Gold",Wurth Electronics Inc,61300811121,Digikey,732-5321-ND,0.35,1.75 +2,"CON11, CON17","2 Position Wire to Board Terminal Block Horizontal with Board 0.400"" (10.16mm) Through Hole",Phoenix Contact,1773976,Digikey,277-5761-ND,8.66,17.32 +11,"CON1, CON2, CON3, CON4, CON5, CON6, CON7, CON8, CON12, CON14, CON16","2 Position Wire to Board Terminal Block 45° (135°) Angle with Board 0.138"" (3.50mm) Through Hole",Phoenix Contact,1988956,Digikey,277-1779-ND,0.41,4.51 +3,"CON9, CON10, CON13","3 Position Wire to Board Terminal Block 45° (135°) Angle with Board 0.138"" (3.50mm) Through Hole",Phoenix Contact,1988969,Digikey,277-1780-ND,0.61,1.83 +1,CON15,"5 Position Wire to Board Terminal Block 45° (135°) Angle with Board 0.138"" (3.50mm) Through Hole",Phoenix Contact,1988985,Digikey,277-1782-ND,0.97,0.97 +2,"F1, F3",Fuse Holder 80V 1 Circuit Blade PCB,Littelfuse Inc.,178.6165.0001,Digikey,F5197-ND,3.24,6.48 +,,,,,,,, +1,For F3,FUSE AUTO 40A 32VDC BLADE,Littelfuse Inc.,0257040.PXAPC,Digikey,F5952-ND,0.47,0.47 +1,For F1,FUSE AUTOMOTIVE 20A 32VDC BLADE,Littelfuse Inc.,0287020.PXCN,Digikey,F4201-ND,0.28,0.28 +1,For JP2,"2 (1 x 2) Position Shunt Connector White Open Top 0.100"" (2.54mm) Gold or Gold, GXT™",Amphenol FCI,68786-102LF,Digikey,609-3121-ND,0.19,0.19 +Total,,,,,,,,$117.15 diff --git a/hardware/boards/actuator_control/polysync_actuator_v_1_2_0_MacroFab_XYRS_Data.csv b/hardware/boards/actuator_control/polysync_actuator_v_1_2_0_MacroFab_XYRS_Data.csv new file mode 100644 index 00000000..977ba214 --- /dev/null +++ b/hardware/boards/actuator_control/polysync_actuator_v_1_2_0_MacroFab_XYRS_Data.csv @@ -0,0 +1,265 @@ +"# Generated by MacroFab for PCB 0yg5f4, version 1.",,,,,,,,,,,,,,, +# DESIGNATOR,X_LOC,Y_LOC,ROTATION,SIDE,TYPE,X_SIZE,Y_SIZE,VALUE,FOOTPRINT,POPULATE,MPN,MPN1,MPN2,MPN3, +ADCH,3810,2170,0,2,2,733.46,33.46,8x1F-H8.5,1X08,1,,,,,61300811121 +ADCL,2910,2170,0,2,2,733.46,33.46,8x1F-H8.5,1X08,1,,,,,61300811121 +C1,1760,1045,0,2,1,149.61,62.99,1u,C1206,1,,,,,CL31B105KCHNNNE +C10,6185,1045,0,2,1,149.61,62.99,1u,C1206,1,,,,,CL31B105KCHNNNE +C11,510,770,270,2,1,102.36,51.18,0.1u,C0805,1,,,,,CL21B104KCFNNNE +C12,3560,770,270,2,1,102.36,51.18,0.1u,C0805,1,,,,,CL21B104KCFNNNE +C13,760,5145,180,2,1,149.61,62.99,1u,C1206,1,,,,,CL31B105KCHNNNE +C14,2235,5145,180,2,1,149.61,62.99,1u,C1206,1,,,,,CL31B105KCHNNNE +C15,3710,5145,180,2,1,149.61,62.99,1u,C1206,1,,,,,CL31B105KCHNNNE +C16,5185,5145,180,2,1,149.61,62.99,1u,C1206,1,,,,,CL31B105KCHNNNE +C17,3485,5420,90,2,1,149.61,62.99,1u,C1206,1,,,,,CL31B105KCHNNNE +C18,6460,5420,90,2,1,149.61,62.99,1u,C1206,1,,,,,CL31B105KCHNNNE +C19,1760,4820,180,2,1,102.36,51.18,0.1u,C0805,1,,,,,CL21B104KCFNNNE +C2,3235,1045,0,2,1,149.61,62.99,1u,C1206,1,,,,,CL31B105KCHNNNE +C20,3235,4820,180,2,1,102.36,51.18,0.1u,C0805,1,,,,,CL21B104KCFNNNE +C21,4710,4820,180,2,1,102.36,51.18,0.1u,C0805,1,,,,,CL21B104KCFNNNE +C22,6185,4820,180,2,1,102.36,51.18,0.1u,C0805,1,,,,,CL21B104KCFNNNE +C23,3385,5420,90,2,1,102.36,51.18,0.1u,C0805,1,,,,,CL21B104KCFNNNE +C24,6360,5420,90,2,1,102.36,51.18,0.1u,C0805,1,,,,,CL21B104KCFNNNE +C25,585,1445,180,2,1,62.99,23.62,100p,C0402,1,,,,,CC0402JRNPO9BN101 +C26,460,1720,270,2,1,62.99,23.62,.1u,C0402,1,,,,,GRM155R62A104KE14D +C27,560,1770,90,2,1,62.99,23.62,.1u,C0402,1,,,,,GRM155R62A104KE14D +C28,2060,1445,180,2,1,62.99,23.62,100p,C0402,1,,,,,CC0402JRNPO9BN101 +C29,1935,1720,270,2,1,62.99,23.62,.1u,C0402,1,,,,,GRM155R62A104KE14D +C3,3710,1370,0,2,1,102.36,51.18,0.1u,C0805,1,,,,,CL21B104KCFNNNE +C30,2035,1770,90,2,1,62.99,23.62,.1u,C0402,1,,,,,GRM155R62A104KE14D +C31,3535,1445,180,2,1,62.99,23.62,100p,C0402,1,,,,,CC0402JRNPO9BN101 +C32,3410,1720,270,2,1,62.99,23.62,.1u,C0402,1,,,,,GRM155R62A104KE14D +C33,3510,1770,90,2,1,62.99,23.62,.1u,C0402,1,,,,,GRM155R62A104KE14D +C34,5010,1445,180,2,1,62.99,23.62,100p,C0402,1,,,,,CC0402JRNPO9BN101 +C35,4885,1720,270,2,1,62.99,23.62,.1u,C0402,1,,,,,GRM155R62A104KE14D +C36,4985,1770,90,2,1,62.99,23.62,.1u,C0402,1,,,,,GRM155R62A104KE14D +C37,1935,4745,0,2,1,62.99,23.62,100p,C0402,1,,,,,CC0402JRNPO9BN101 +C38,2060,4470,90,2,1,62.99,23.62,.1u,C0402,1,,,,,GRM155R62A104KE14D +C39,1960,4420,270,2,1,62.99,23.62,.1u,C0402,1,,,,,GRM155R62A104KE14D +C4,5185,1370,0,2,1,102.36,51.18,0.1u,C0805,1,,,,,CL21B104KCFNNNE +C40,3410,4745,0,2,1,62.99,23.62,100p,C0402,1,,,,,CC0402JRNPO9BN101 +C41,3535,4470,90,2,1,62.99,23.62,.1u,C0402,1,,,,,GRM155R62A104KE14D +C42,3435,4420,270,2,1,62.99,23.62,.1u,C0402,1,,,,,GRM155R62A104KE14D +C43,4885,4745,0,2,1,62.99,23.62,100p,C0402,1,,,,,CC0402JRNPO9BN101 +C44,6485,4470,90,2,1,62.99,23.62,.1u,C0402,1,,,,,GRM155R62A104KE14D +C45,4910,4420,270,2,1,62.99,23.62,.1u,C0402,1,,,,,GRM155R62A104KE14D +C46,6360,4745,0,2,1,62.99,23.62,100p,C0402,1,,,,,CC0402JRNPO9BN101 +C47,5010,4470,90,2,1,62.99,23.62,.1u,C0402,1,,,,,GRM155R62A104KE14D +C48,6385,4420,270,2,1,62.99,23.62,.1u,C0402,1,,,,,GRM155R62A104KE14D +C49,6310,2820,180,2,1,62.99,23.62,.1u,C0402,1,,,,,GRM155R62A104KE14D +C5,3460,770,270,2,1,149.61,62.99,1u,C1206,1,,,,,CL31B105KCHNNNE +C50,6260,2745,180,2,1,149.61,62.99,33u,CP1206,1,,,,,TAJA336K010RNJ +C51,5390,4190,90,2,1,62.99,23.62,.1u,C0402,1,,,,,GRM155R62A104KE14D +C52,5385,2395,270,2,1,62.99,23.62,22p,C0402,1,,,,, +C53,5385,2295,90,2,1,62.99,23.62,22p,C0402,1,,,,, +C6,410,770,270,2,1,149.61,62.99,1u,C1206,1,,,,,CL31B105KCHNNNE +C7,760,1370,0,2,1,102.36,51.18,0.1u,C0805,1,,,,,CL21B104KCFNNNE +C8,2235,1370,0,2,1,102.36,51.18,0.1u,C0805,1,,,,,CL21B104KCFNNNE +C9,4710,1045,0,2,1,149.61,62.99,1u,C1206,1,,,,,CL31B105KCHNNNE +COMMUNICATION,3610,4070,180,2,2,733.46,33.46,8x1F-H8.5,1X08,1,,,,,61300811121 +CON1,4666.1,470,0,2,2,192.91,55.12,CON23.5MM,PHOENIX_2_45,1,,,,,1988956 +CON10,4847.8,4145,180,2,2,330.71,55.12,CON3,PHOENIX_3_45,1,,,,,1988969 +CON11,7785,1245,90,2,2,459.06,459.06,CON210.16MM,PHOENIX_2_10.16MM,1,,,,,1773976 +CON12,7328.11,3134.17,90,2,2,212.6,555.12,CON1,1932575,1,,,,,1932575 +CON13,7328.11,4409.17,90,2,2,212.6,555.12,CON1,1932575,1,,,,,1932575 +CON14,6253.9,4145,180,2,2,192.91,55.12,CON23.5MM,PHOENIX_2_45,1,,,,,1988956 +CON15,5633.23,2995,0,2,2,606.3,55.12,CON5,PHOENIX_5_45,1,,,,,1988985 +CON2,6141.1,470,0,2,2,192.91,55.12,CON23.5MM,PHOENIX_2_45,1,,,,,1988956 +CON3,1716.1,470,0,2,2,192.91,55.12,CON23.5MM,PHOENIX_2_45,1,,,,,1988956 +CON4,3191.1,470,0,2,2,192.91,55.12,CON23.5MM,PHOENIX_2_45,1,,,,,1988956 +CON5,803.9,5720,180,2,2,192.91,55.12,CON23.5MM,PHOENIX_2_45,1,,,,,1988956 +CON6,2278.9,5720,180,2,2,192.91,55.12,CON23.5MM,PHOENIX_2_45,1,,,,,1988956 +CON7,3753.9,5720,180,2,2,192.91,55.12,CON23.5MM,PHOENIX_2_45,1,,,,,1988956 +CON8,5228.9,5720,180,2,2,192.91,55.12,CON23.5MM,PHOENIX_2_45,1,,,,,1988956 +CON9,4847.2,2995,0,2,2,330.71,55.12,CON3,PHOENIX_3_45,1,,,,,1988969 +D1,4660,895,0,2,1,255.91,66.93,DIODES_SMA,SMA,1,,,,,US1B-13-F +D10,735,1770,90,2,1,165.35,47.24,DIODES_SOD-123,SOD-123,1,,,,,B0520LW-7-F +D11,2210,1770,90,2,1,165.35,47.24,DIODES_SOD-123,SOD-123,1,,,,,B0520LW-7-F +D12,3685,1770,90,2,1,165.35,47.24,DIODES_SOD-123,SOD-123,1,,,,,B0520LW-7-F +D13,6210,4420,270,2,1,165.35,47.24,DIODES_SOD-123,SOD-123,1,,,,,B0520LW-7-F +D14,1785,4420,270,2,1,165.35,47.24,DIODES_SOD-123,SOD-123,1,,,,,B0520LW-7-F +D15,3260,4420,270,2,1,165.35,47.24,DIODES_SOD-123,SOD-123,1,,,,,B0520LW-7-F +D16,4735,4420,270,2,1,165.35,47.24,DIODES_SOD-123,SOD-123,1,,,,,B0520LW-7-F +D17,5260,3680,90,2,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +D18,6110,2680,270,2,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +D19,5275,4120,0,2,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +D2,6135,895,0,2,1,255.91,66.93,DIODES_SMA,SMA,1,,,,,US1B-13-F +D20,5275,4270,0,2,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +D21,4735,2370,0,2,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +D3,1710,895,0,2,1,255.91,66.93,DIODES_SMA,SMA,1,,,,,US1B-13-F +D4,3185,895,0,2,1,255.91,66.93,DIODES_SMA,SMA,1,,,,,US1B-13-F +D5,810,5295,180,2,1,255.91,66.93,DIODES_SMA,SMA,1,,,,,US1B-13-F +D6,2285,5295,180,2,1,255.91,66.93,DIODES_SMA,SMA,1,,,,,US1B-13-F +D7,3760,5295,180,2,1,255.91,66.93,DIODES_SMA,SMA,1,,,,,US1B-13-F +D8,5235,5295,180,2,1,255.91,66.93,DIODES_SMA,SMA,1,,,,,US1B-13-F +D9,5160,1770,90,2,1,165.35,47.24,DIODES_SOD-123,SOD-123,1,,,,,B0520LW-7-F +F1,6785,570,0,2,2,559.06,153.54,20A,FUSE_ATO,1,,,,,178.6165.0001 +F2,6910,5655,0,2,2,559.06,153.54,20A,FUSE_ATO,1,,,,,178.6165.0001 +F3,6785,2820,270,2,2,559.06,153.54,40A,FUSE_ATO,1,,,,,178.6165.0001 +H1,4210,1095,270,2,1,614.17,540.16,HEATSINK-TO-263,HEATSINK-TO-263,1,,,,,219-263B-TR +H2,5685,1095,270,2,1,614.17,540.16,HEATSINK-TO-263,HEATSINK-TO-263,1,,,,,219-263B-TR +H3,1260,1095,270,2,1,614.17,540.16,HEATSINK-TO-263,HEATSINK-TO-263,1,,,,,219-263B-TR +H4,2735,1095,270,2,1,614.17,540.16,HEATSINK-TO-263,HEATSINK-TO-263,1,,,,,219-263B-TR +H5,1260,5095,90,2,1,614.17,540.16,HEATSINK-TO-263,HEATSINK-TO-263,1,,,,,219-263B-TR +H6,2735,5095,90,2,1,614.17,540.16,HEATSINK-TO-263,HEATSINK-TO-263,1,,,,,219-263B-TR +H7,4210,5095,90,2,1,614.17,540.16,HEATSINK-TO-263,HEATSINK-TO-263,1,,,,,219-263B-TR +H8,5685,5095,90,2,1,614.17,540.16,HEATSINK-TO-263,HEATSINK-TO-263,1,,,,,219-263B-TR +JP1,1750,4070,0,2,2,933.46,33.46,10x1F-H8.5,1X10,1,,,,,61301011121 +JP2,5945,4085,0,2,2,36,136,,JP1,1,,,,,77311-118-02LF +L1,4710,1320,90,2,1,352.36,137.8,2.2u,SRP7050,1,,,,,SRP7050TA-2R2M +L2,6185,1320,90,2,1,352.36,137.8,2.2u,SRP7050,1,,,,,SRP7050TA-2R2M +L3,1760,1320,90,2,1,352.36,137.8,2.2u,SRP7050,1,,,,,SRP7050TA-2R2M +L4,3235,1320,90,2,1,352.36,137.8,2.2u,SRP7050,1,,,,,SRP7050TA-2R2M +L5,760,4870,270,2,1,352.36,137.8,2.2u,SRP7050,1,,,,,SRP7050TA-2R2M +L6,2235,4870,270,2,1,352.36,137.8,2.2u,SRP7050,1,,,,,SRP7050TA-2R2M +L7,3710,4870,270,2,1,352.36,137.8,2.2u,SRP7050,1,,,,,SRP7050TA-2R2M +L8,5185,4870,270,2,1,352.36,137.8,2.2u,SRP7050,1,,,,,SRP7050TA-2R2M +POWER,2010,2170,0,2,2,733.46,33.46,8x1F-H8.5,1X08,1,,,,,61300811121 +PWML,2710,4070,180,2,2,733.46,33.46,8x1F-H8.5,1X08,1,,,,,61300811121 +Q1,3998.98,1095,270,2,1,267.72,653.54,N-FET-TO263,TO-263-3,1,,,,,IPB090N06N3 G +Q10,5145,3849.33,180,2,1,57.48,66.93,RE1C002UN,EMT3F,1,,,,,RE1C002UNTCL +Q2,5473.98,1095,270,2,1,267.72,653.54,N-FET-TO263,TO-263-3,1,,,,,IPB090N06N3 G +Q3,1048.98,1095,270,2,1,267.72,653.54,N-FET-TO263,TO-263-3,1,,,,,IPB090N06N3 G +Q4,2523.98,1095,270,2,1,267.72,653.54,N-FET-TO263,TO-263-3,1,,,,,IPB090N06N3 G +Q5,1471.02,5095,90,2,1,267.72,653.54,N-FET-TO263,TO-263-3,1,,,,,IPB090N06N3 G +Q6,2946.02,5095,90,2,1,267.72,653.54,N-FET-TO263,TO-263-3,1,,,,,IPB090N06N3 G +Q7,4421.02,5095,90,2,1,267.72,653.54,N-FET-TO263,TO-263-3,1,,,,,IPB090N06N3 G +Q8,5896.02,5095,90,2,1,267.72,653.54,N-FET-TO263,TO-263-3,1,,,,,IPB090N06N3 G +Q9,6735,2195,180,2,1,114.17,106.3,,SOT-23-3,1,,,,,"SSM3K341R,LF" +R1,710,995,0,2,1,62.99,23.62,10k,R0402,1,,,,, +R10,4960,1195,180,2,1,102.36,51.18,0,R0805,0,,,,,MF-RES-0402-0 +R100,4610,2370,0,2,1,62.99,23.62,1k,R0402,1,,,,, +R101,6210,2820,0,2,1,62.99,23.62,0.3,R0402,1,,,,,ERJ-2BQFR30X +R102,5835,4140,90,2,1,62.99,23.62,120,R0402,1,,,,,ERJ-2RKF1200X +R103,5265,3550,90,2,1,62.99,23.62,1k,R0402,1,,,,, +R104,4735,2645,90,2,1,62.99,23.62,10k,R0402,1,,,,, +R105,5665,4040,90,2,1,62.99,23.62,47k,R0402,1,,,,,ERJ-2RKF4702X +R106,5910,3420,90,2,1,62.99,23.62,0,R0402,1,,,,, +R107,5785,3420,90,2,1,62.99,23.62,0,R0402,1,,,,, +R108,5635,3420,90,2,1,62.99,23.62,0,R0402,1,,,,, +R109,5510,3420,90,2,1,62.99,23.62,0,R0402,1,,,,, +R11,685,1195,0,2,1,149.61,62.99,0.02,R1206,1,,,,,ERJ8CWFR020V +R110,5360,3420,90,2,1,62.99,23.62,0,R0402,1,,,,, +R111,5360,3520,270,2,1,62.99,23.62,DNP,R0402,0,,,,, +R112,5510,3520,270,2,1,62.99,23.62,DNP,R0402,0,,,,, +R113,5635,3520,270,2,1,62.99,23.62,DNP,R0402,0,,,,, +R114,5785,3520,270,2,1,62.99,23.62,DNP,R0402,0,,,,, +R115,5910,3520,270,2,1,62.99,23.62,DNP,R0402,0,,,,, +R12,2160,1195,0,2,1,149.61,62.99,0.02,R1206,1,,,,,ERJ8CWFR020V +R13,3660,995,0,2,1,62.99,23.62,10k,R0402,1,,,,, +R14,5135,995,0,2,1,62.99,23.62,10k,R0402,1,,,,, +R15,535,1195,180,2,1,102.36,51.18,0,R0805,0,,,,,MF-RES-0402-0 +R16,2010,1195,180,2,1,102.36,51.18,0,R0805,0,,,,,MF-RES-0402-0 +R17,1810,5195,180,2,1,62.99,23.62,10k,R0402,1,,,,, +R18,3285,5195,180,2,1,62.99,23.62,10k,R0402,1,,,,, +R19,4760,5195,180,2,1,62.99,23.62,10k,R0402,1,,,,, +R2,2185,995,0,2,1,62.99,23.62,10k,R0402,1,,,,, +R20,6235,5195,180,2,1,62.99,23.62,10k,R0402,1,,,,, +R21,1610,4820,180,2,1,102.36,51.18,100,R0805,1,,,,, +R22,3085,4820,180,2,1,102.36,51.18,100,R0805,1,,,,, +R23,4560,4820,180,2,1,102.36,51.18,100,R0805,1,,,,, +R24,6035,4820,180,2,1,102.36,51.18,100,R0805,1,,,,, +R25,1835,4995,180,2,1,149.61,62.99,0.02,R1206,1,,,,,ERJ8CWFR020V +R26,3310,4995,180,2,1,149.61,62.99,0.02,R1206,1,,,,,ERJ8CWFR020V +R27,4785,4995,180,2,1,149.61,62.99,0.02,R1206,1,,,,,ERJ8CWFR020V +R28,6260,4995,180,2,1,149.61,62.99,0.02,R1206,1,,,,,ERJ8CWFR020V +R29,1985,4995,0,2,1,102.36,51.18,0,R0805,0,,,,,MF-RES-0402-0 +R3,3860,1370,0,2,1,102.36,51.18,100,R0805,1,,,,, +R30,3460,4995,0,2,1,102.36,51.18,0,R0805,0,,,,,MF-RES-0402-0 +R31,4935,4995,0,2,1,102.36,51.18,0,R0805,0,,,,,MF-RES-0402-0 +R32,6410,4995,0,2,1,102.36,51.18,0,R0805,0,,,,,MF-RES-0402-0 +R33,510,1770,270,2,1,62.99,23.62,100k,R0402,1,,,,, +R34,1985,1770,270,2,1,62.99,23.62,100k,R0402,1,,,,, +R35,3460,1770,270,2,1,62.99,23.62,100k,R0402,1,,,,, +R36,560,1370,270,2,1,62.99,23.62,1k,R0402,1,,,,, +R37,610,1370,270,2,1,62.99,23.62,1k,R0402,1,,,,, +R38,2035,1370,270,2,1,62.99,23.62,1k,R0402,1,,,,, +R39,2085,1370,270,2,1,62.99,23.62,1k,R0402,1,,,,, +R4,5335,1370,0,2,1,102.36,51.18,100,R0805,1,,,,, +R40,3510,1370,270,2,1,62.99,23.62,1k,R0402,1,,,,, +R41,3560,1370,270,2,1,62.99,23.62,1k,R0402,1,,,,, +R42,635,1795,0,2,1,62.99,23.62,1k,R0402,1,,,,, +R43,2110,1795,0,2,1,62.99,23.62,1k,R0402,1,,,,, +R44,3585,1795,0,2,1,62.99,23.62,1k,R0402,1,,,,, +R45,710,1620,90,2,1,62.99,23.62,100k,R0402,1,,,,, +R46,2185,1620,90,2,1,62.99,23.62,100k,R0402,1,,,,, +R47,3660,1620,90,2,1,62.99,23.62,100k,R0402,1,,,,, +R48,635,1745,0,2,1,62.99,23.62,100k,R0402,1,,,,, +R49,2110,1745,0,2,1,62.99,23.62,100k,R0402,1,,,,, +R5,910,1370,0,2,1,102.36,51.18,100,R0805,1,,,,, +R50,3585,1745,0,2,1,62.99,23.62,100k,R0402,1,,,,, +R51,560,1520,270,2,1,62.99,23.62,1k,R0402,1,,,,, +R52,610,1520,270,2,1,62.99,23.62,1k,R0402,1,,,,, +R53,2035,1520,270,2,1,62.99,23.62,1k,R0402,1,,,,, +R54,2085,1520,270,2,1,62.99,23.62,1k,R0402,1,,,,, +R55,3510,1520,270,2,1,62.99,23.62,1k,R0402,1,,,,, +R56,3560,1520,270,2,1,62.99,23.62,1k,R0402,1,,,,, +R57,4935,1770,270,2,1,62.99,23.62,100k,R0402,1,,,,, +R58,4985,1370,270,2,1,62.99,23.62,1k,R0402,1,,,,, +R59,5035,1370,270,2,1,62.99,23.62,1k,R0402,1,,,,, +R6,2385,1370,0,2,1,102.36,51.18,100,R0805,1,,,,, +R60,5060,1795,0,2,1,62.99,23.62,1k,R0402,1,,,,, +R61,5135,1620,90,2,1,62.99,23.62,100k,R0402,1,,,,, +R62,5060,1745,0,2,1,62.99,23.62,100k,R0402,1,,,,, +R63,4985,1520,270,2,1,62.99,23.62,1k,R0402,1,,,,, +R64,5035,1520,270,2,1,62.99,23.62,1k,R0402,1,,,,, +R65,2010,4420,90,2,1,62.99,23.62,100k,R0402,1,,,,, +R66,3485,4420,90,2,1,62.99,23.62,100k,R0402,1,,,,, +R67,4960,4420,90,2,1,62.99,23.62,100k,R0402,1,,,,, +R68,1960,4820,90,2,1,62.99,23.62,1k,R0402,1,,,,, +R69,1910,4820,90,2,1,62.99,23.62,1k,R0402,1,,,,, +R7,3635,1195,0,2,1,149.61,62.99,0.02,R1206,1,,,,,ERJ8CWFR020V +R70,3435,4820,90,2,1,62.99,23.62,1k,R0402,1,,,,, +R71,3385,4820,90,2,1,62.99,23.62,1k,R0402,1,,,,, +R72,4910,4820,90,2,1,62.99,23.62,1k,R0402,1,,,,, +R73,4860,4820,90,2,1,62.99,23.62,1k,R0402,1,,,,, +R74,1885,4395,180,2,1,62.99,23.62,1k,R0402,1,,,,, +R75,3360,4395,180,2,1,62.99,23.62,1k,R0402,1,,,,, +R76,4835,4395,180,2,1,62.99,23.62,1k,R0402,1,,,,, +R77,1810,4570,270,2,1,62.99,23.62,100k,R0402,1,,,,, +R78,3285,4570,270,2,1,62.99,23.62,100k,R0402,1,,,,, +R79,4760,4570,270,2,1,62.99,23.62,100k,R0402,1,,,,, +R8,5110,1195,0,2,1,149.61,62.99,0.02,R1206,1,,,,,ERJ8CWFR020V +R80,1885,4445,180,2,1,62.99,23.62,100k,R0402,1,,,,, +R81,3360,4445,180,2,1,62.99,23.62,100k,R0402,1,,,,, +R82,4835,4445,180,2,1,62.99,23.62,100k,R0402,1,,,,, +R83,1960,4670,90,2,1,62.99,23.62,1k,R0402,1,,,,, +R84,1910,4670,90,2,1,62.99,23.62,1k,R0402,1,,,,, +R85,3435,4670,90,2,1,62.99,23.62,1k,R0402,1,,,,, +R86,3385,4670,90,2,1,62.99,23.62,1k,R0402,1,,,,, +R87,4910,4670,90,2,1,62.99,23.62,1k,R0402,1,,,,, +R88,4860,4670,90,2,1,62.99,23.62,1k,R0402,1,,,,, +R89,6435,4420,90,2,1,62.99,23.62,100k,R0402,1,,,,, +R9,3485,1195,180,2,1,102.36,51.18,0,R0805,0,,,,,MF-RES-0402-0 +R90,6385,4820,90,2,1,62.99,23.62,1k,R0402,1,,,,, +R91,6335,4820,90,2,1,62.99,23.62,1k,R0402,1,,,,, +R92,6310,4395,180,2,1,62.99,23.62,1k,R0402,1,,,,, +R93,6235,4570,270,2,1,62.99,23.62,100k,R0402,1,,,,, +R94,6310,4445,180,2,1,62.99,23.62,100k,R0402,1,,,,, +R95,6385,4670,90,2,1,62.99,23.62,1k,R0402,1,,,,, +R96,6335,4670,90,2,1,62.99,23.62,1k,R0402,1,,,,, +R97,6120,2795,270,2,1,62.99,23.62,1k,R0402,1,,,,, +R98,5160,4115,0,2,1,62.99,23.62,1k,R0402,1,,,,, +R99,5155,4270,0,2,1,62.99,23.62,1k,R0402,1,,,,, +RELAY1,4938.94,3570,0,2,1,443.31,405.12,RELAY_DPDT,KEMET_EE2,1,,,,,EE2-5NU-L +RELAY2,7485,2245,180,2,1,0,0,RELAY_BOM,VCF4_RELAY,1,,,,,1432868-1 +RELAY3,7460,2222.36,270,2,2,795.28,755.91,RELAY_VF4,VCF4-SOCKET,1,,,,,VCF4-1000 +TP1,1365,2115,0,2,1,45,45,,TP_4545,0,,,,, +TP2,6525,950,0,2,1,45,45,,TP_4545,0,,,,, +TP3,545,3890,0,2,1,45,45,,TP_4545,0,,,,, +U1,760,620,90,2,1,173.62,267.72,UCC27524,SOIC-8,1,,,,,UCC27524DR +U10,1935,4545,180,2,1,147.64,98.43,OPA170,SOT-23-5,1,,,,,OPA170AIDBVT +U11,3410,4545,180,2,1,147.64,98.43,OPA170,SOT-23-5,1,,,,,OPA170AIDBVT +U12,4885,4545,180,2,1,147.64,98.43,OPA170,SOT-23-5,1,,,,,OPA170AIDBVT +U13,6335,3204.84,0,2,1,421.26,653.54,TL750M,TO-263,1,,,,,TL750M05CKVURG3 +U14,5560,4195,270,2,1,173.62,267.72,MCP2551,SOIC8-6.0,1,,,,,MCP2551-I/SN +U15,5060,2470,90,2,1,430,457,MCP2515,SOIC18,1,,,,,MCP2515-I/SO +U2,3735,620,90,2,1,173.62,267.72,UCC27524,SOIC-8,1,,,,,UCC27524DR +U3,3205,5570,270,2,1,173.62,267.72,UCC27524,SOIC-8,1,,,,,UCC27524DR +U4,6160,5570,270,2,1,173.62,267.72,UCC27524,SOIC-8,1,,,,,UCC27524DR +U5,5010,1645,0,2,1,147.64,98.43,OPA170,SOT-23-5,1,,,,,OPA170AIDBVT +U6,585,1645,0,2,1,147.64,98.43,OPA170,SOT-23-5,1,,,,,OPA170AIDBVT +U7,2060,1645,0,2,1,147.64,98.43,OPA170,SOT-23-5,1,,,,,OPA170AIDBVT +U8,3535,1645,0,2,1,147.64,98.43,OPA170,SOT-23-5,1,,,,,OPA170AIDBVT +U9,6360,4545,180,2,1,147.64,98.43,OPA170,SOT-23-5,1,,,,,OPA170AIDBVT +X1,5535,2345,270,2,1,590,76,16MHz,HC49UP,1,,,,,ABLS-16.000MHZ-D-4-T +XIO,4310,3220,270,2,2,1737.4,137.4,18x2F-H8.5,2X18,1,,,,,61303621121 diff --git a/hardware/boards/gateway/polysync_gateway_v_1_0_0_BOM.csv b/hardware/boards/gateway/polysync_gateway_v_1_0_0_BOM.csv new file mode 100644 index 00000000..6e63a455 --- /dev/null +++ b/hardware/boards/gateway/polysync_gateway_v_1_0_0_BOM.csv @@ -0,0 +1,28 @@ +Polysync Gateway Board BOM V1.0.0,,,,,,,, +,,,,,,,, +Quantity,Reference Designator,Description,Mfg,Mfg Part No.,Distributor,Distributor Part No.,Price,Total Price +1,R8,RES SMD 0.3 OHM 1% 1/6W 0402,Panasonic Electronic Components,ERJ-2BQFR30X,Digikey,P.30AKCT-ND,0.59,0.59 +10,"R2, R3, R9, R16, R17, R18, R19, R20, R21, R22",RES SMD 10K OHM 1% 1/10W 0402,Panasonic Electronic Components,ERJ-2RKF1002X,Digikey,P10.0KLCT-ND,0.1,1 +2,"R13, R15",RES SMD 120 OHM 1% 1/10W 0402,Panasonic Electronic Components,ERJ-2RKF1200X,Digikey,P120LCT-ND,0.1,0.2 +7,"R4, R5, R6, R7, R10, R11, R12",RES SMD 1K OHM 1% 1/10W 0402,Panasonic Electronic Components,ERJ-2RKF1001X,Digikey,P1.00KLCT-ND,0.1,0.7 +2,"R1, R14",RES SMD 47K OHM 1% 1/10W 0402,Panasonic Electronic Components,ERJ-2RKF4702X,Digikey,P47.0KLCT-ND,0.1,0.2 +4,"C1, C2, C6, C9",0.10µF ±10% 16V Ceramic Capacitor X7R 0402 (1005 Metric),Murata Electronics North America,GRM155R71C104KA88J,Digikey,490-6328-1-ND,0.1,0.4 +4,"C4, C5, C7, C8","22pF ±5% 50V Ceramic Capacitor C0G, NP0 0402 (1005 Metric)",Murata Electronics North America,GRM1555C1H220JA01J,Digikey,490-11382-1-ND,0.1,0.4 +1,C3,33µF ±10% Molded Tantalum Capacitors 10V 1206 (3216 Metric) 1.7 Ohm,AVX Corporation,TAJA336K010RNJ,Digikey,478-8882-1-ND,0.6,0.6 +2,"D5, D8",Blue 470nm LED Indication - Discrete 3.2V 0603 (1608 Metric),Wurth Electronics Inc,150060BS75000,Digikey,732-4966-1-ND,0.26,0.52 +2,"D4, D7",LED RED CLEAR 0603 SMD,Wurth Electronics Inc,150060RS75000,Digikey,732-4978-1-ND,0.24,0.48 +3,"D2, D3, D6",LED GREEN CLEAR 0603 SMD,Wurth Electronics Inc,150060GS75000,Digikey,732-4971-1-ND,0.24,0.72 +2,"X1, X2",16MHz ±30ppm Crystal 18pF 40 Ohm -40°C ~ 85°C Surface Mount HC49/US,Abracon LLC,ABLS-16.000MHZ-D-4-T,Digikey,535-13436-1-ND,0.24,0.48 +2,"U2, U5",CAN Controller CAN 2.0 SPI Interface 18-SOIC,Microchip Technology,MCP2515-I/SO,Digikey,MCP2515-I/SO-ND,1.82,3.64 +2,"U1, U3",1/1 Transceiver Half CAN 8-SOIC,Microchip Technology,MCP2551-I/SN,Digikey,MCP2551-I/SN-ND,1.02,2.04 +1,U4,Linear Voltage Regulator IC Positive Fixed 1 Output 5V 750mA DDPAK/TO-263-3,Texas Instruments,TL750M05CKTTR,Digikey,296-20776-1-ND,1.47,1.47 +1,U6,IC BUFF/DVR TRI-ST DUAL 20TSSOP,Texas Instruments,SN74AC241PWR,Digikey,296-4309-1-ND,0.75,0.75 +1,JP1,"10 Positions Header, Unshrouded Connector 0.100"" (2.54mm) Through Hole Gold or Gold, GXT™",Amphenol FCI,68002-210HLF,Digikey,609-3301-ND,0.44,0.44 +2,"JP2, JP5","8 Positions Header, Unshrouded Connector 0.100"" (2.54mm) Through Hole Gold or Gold, GXT™",Amphenol FCI,68000-208HLF,Digikey,609-3257-ND,0.43,0.86 +1,JP3,"6 Position Receptacle Connector 0.100"" (2.54mm) Through Hole Gold",Amphenol FCI,68683-303LF,Digikey,609-3582-ND,1.61,1.61 +1,JP4,"6 Positions Header, Unshrouded Connector 0.100"" (2.54mm) Through Hole Gold or Gold, GXT™",Amphenol FCI,68000-206HLF,Digikey,609-3256-ND,0.32,0.32 +2,"JP6, JP7","2 Positions Header, Unshrouded Connector 0.100"" (2.54mm) Through Hole Gold or Gold, GXT™",Amphenol FCI,77311-118-02LF,Digikey,609-4434-ND,0.18,0.36 +3,"CON1, CON2, CON3","2 Position Wire to Board Terminal Block 45° (135°) Angle with Board 0.138"" (3.50mm) Through Hole",Phoenix Contact,1988956,Digikey,277-1779-ND,0.41,1.23 +1,CON4 ,CONN HEADER PH SIDE 8POS 2MM SMD,JST Sales America Inc.,S8B-PH-SM4-TB(LF)(SN),Digikey,455-1755-1-ND,0.97,0.97 +2,"For JP6, JP7","2 (1 x 2) Position Shunt Connector White Open Top 0.100"" (2.54mm) Gold or Gold, GXT™",Amphenol FCI,68786-102LF,Digikey,609-3121-ND,0.19,0.38 +Total,,,,,,,,$20.36 diff --git a/hardware/boards/gateway/polysync_gateway_v_1_0_0_MacroFab_XYRS_Data.csv b/hardware/boards/gateway/polysync_gateway_v_1_0_0_MacroFab_XYRS_Data.csv new file mode 100644 index 00000000..b513eb94 --- /dev/null +++ b/hardware/boards/gateway/polysync_gateway_v_1_0_0_MacroFab_XYRS_Data.csv @@ -0,0 +1,57 @@ +"# Generated by MacroFab for PCB 7n6gav, version 1.",,,,,,,,,,,,,,, +# DESIGNATOR,X_LOC,Y_LOC,ROTATION,SIDE,TYPE,X_SIZE,Y_SIZE,VALUE,FOOTPRINT,POPULATE,MPN,MPN1,MPN2,MPN3, +C1,780,1555,90,1,1,62.99,23.62,.1u,C0402,1,,,,, +C2,1040,1225,0,1,1,62.99,23.62,.1u,C0402,1,,,,, +C3,680,1530,90,1,1,149.61,62.99,33u,CP1206,1,,,,,TAJA336K010RNJ +C4,1005,405,270,1,1,62.99,23.62,22p,C0402,1,,,,, +C5,1065,1295,0,1,1,102.36,51.18,10u,C0805,1,,,,,LMK212B7106KG-TD +C6,745,850,270,1,1,62.99,23.62,.1u,C0402,1,,,,, +C7,1005,505,90,1,1,62.99,23.62,22p,C0402,1,,,,, +CON1,180,1686.1,270,1,2,192.91,55.12,CON2,PHOENIX_2_45,1,,,,,1988956 +CON2,180,536.1,270,1,2,192.91,55.12,CON2,PHOENIX_2_45,1,,,,,1988956 +CON3,2380,636.69,90,1,2,468.5,55.12,CON4,PHOENIX_4_45,1,,,,,1988972 +CON4,2380,1586.69,90,1,2,468.5,55.12,CON4,PHOENIX_4_45,1,,,,,1988972 +D1,2205,1180,270,1,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +D2,230,330,180,1,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +D3,230,255,180,1,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +D4,230,180,180,1,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +D5,230,105,180,1,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +JP1,1195,2005,0,2,2,935,35,ARDUINO_JP1,ARDUINO_JP1,1,,,,,68002-210HLF +JP2,2155,2005,0,2,2,735,35,ARDUINO_JP2,ARDUINO_JP2,1,,,,,68000-208HLF +JP3,2555,1105,0,2,2,135,235,ARDUINO_JP3,ARDUINO_JP3,1,,,,,68683-303LF +JP4,2255,105,0,2,2,535,35,ARDUINO_JP4,ARDUINO_JP4,1,,,,,68000-206HLF +JP5,1455,105,0,2,2,735,35,ARDUINO_JP5,ARDUINO_JP5,1,,,,,68000-208HLF +JP6,180,855,270,1,2,36,136,,JP1,1,,,,,77311-118-02LF +Q1,1660,1389.33,180,1,1,57.48,66.93,RE1C002UN,EMT3F,1,,,,,RE1C002UNTCL +R1,2205,1030,270,1,1,62.99,23.62,1k,R0402,1,,,,, +R10,1380,1140,180,1,1,62.99,23.62,DNP,R0402,0,,,,, +R11,1410,980,90,1,1,62.99,23.62,10k,R0402,1,,,,, +R12,1360,980,270,1,1,62.99,23.62,DNP,R0402,0,,,,, +R13,380,855,180,1,1,62.99,23.62,120,R0402,1,,,,,ERJ-2RKF1200X +R14,380,780,180,1,1,62.99,23.62,47k,R0402,1,,,,,ERJ-2RKF4702X +R15,1830,505,270,1,1,62.99,23.62,0,R0402,1,,,,, +R16,1880,505,270,1,1,62.99,23.62,0,R0402,1,,,,, +R17,1830,355,270,1,1,62.99,23.62,DNP,R0402,0,,,,, +R18,1880,355,270,1,1,62.99,23.62,DNP,R0402,0,,,,, +R19,1935,505,270,1,1,62.99,23.62,0,R0402,1,,,,, +R2,1725,755,270,1,1,62.99,23.62,10k,R0402,1,,,,, +R20,1985,505,270,1,1,62.99,23.62,0,R0402,1,,,,, +R21,1935,355,270,1,1,62.99,23.62,DNP,R0402,0,,,,, +R22,1985,355,270,1,1,62.99,23.62,DNP,R0402,0,,,,, +R3,1380,1190,180,1,1,62.99,23.62,0,R0402,1,,,,, +R4,105,330,180,1,1,62.99,23.62,1k,R0402,1,,,,, +R5,105,255,180,1,1,62.99,23.62,1k,R0402,1,,,,, +R6,105,180,180,1,1,62.99,23.62,1k,R0402,1,,,,, +R7,105,105,180,1,1,62.99,23.62,1k,R0402,1,,,,, +R8,780,1455,270,1,1,62.99,23.62,0.3,R0402,1,,,,,ERJ-2BQFR30X +R9,1310,980,270,1,1,62.99,23.62,10k,R0402,1,,,,, +RELAY1,1781.06,1115,0,1,1,443.31,405.12,RELAY_DPDT,KEMET_EE2,1,,,,,EE2-5NU-L +TP1,640,320,0,1,1,45,45,,TP_4545,0,,,,, +TP2,2355,1090,0,1,1,45,45,,TP_4545,0,,,,, +TP3,75,2040,0,1,1,45,45,,TP_4545,0,,,,, +U$1,2295,1365,0,2,1,0,0,POLYSYNC,POLYSYNC,0,,,,, +U1,575,845,90,1,1,173.62,267.72,MCP2551,SOIC8-6.0,1,,,,,MCP2551-I/SN +U2,1455,580,270,1,1,430,457,MCP2515,SOIC18,1,,,,,MCP2515-I/SO +U4,1144.84,1590,270,1,1,421.26,653.54,TL750M,TO-263,1,,,,,TL750M05CKTTR +U5,1125,1085,0,1,1,289.37,171.26,MCP4922T,TSSOP-14,1,,,,,MCP4922T-E/ST +X1,870,340,90,1,1,590,76,16MHz,HC49UP,1,,,,,ABLS-16.000MHZ-D-4-T diff --git a/hardware/boards/sensor_interface/polysync_sensor_v_1_1_0-1_BOM.csv b/hardware/boards/sensor_interface/polysync_sensor_v_1_1_0-1_BOM.csv new file mode 100644 index 00000000..b359be1a --- /dev/null +++ b/hardware/boards/sensor_interface/polysync_sensor_v_1_1_0-1_BOM.csv @@ -0,0 +1,33 @@ +Polysync Sensor BOM v1.1.0,,,,,,,, +,,,,,,,, +Quantity,Reference Designator,Description,Mfg,Mfg Part No.,Distributor,Distributor Part No.,Price,Total Price +1,R8,RES SMD 0.3 OHM 1% 1/6W 0402,Panasonic Electronic Components,ERJ-2BQFR30X,Digikey,P.30AKCT-ND,0.59,0.59 +5,"R3, R15, R16, R19, R20",RES SMD 0.0OHM JUMPER 1/10W 0402,Panasonic Electronic Components,ERJ-2GE0R00X,Digikey,P0.0JCT-ND,0.1,0.5 +6,"R2, R9, R11, R17, R18, R23",RES SMD 10K OHM 1% 1/10W 0402,Panasonic Electronic Components,ERJ-2RKF1002X,Digikey,P10.0KLCT-ND,0.1,0.6 +1,R13,RES SMD 120 OHM 1% 1/10W 0402,Panasonic Electronic Components,ERJ-2RKF1200X,Digikey,P120LCT-ND,0.1,0.1 +5,"R1, R4, R5, R6, R7",RES SMD 1K OHM 1% 1/10W 0402,Panasonic Electronic Components,ERJ-2RKF1001X,Digikey,P1.00KLCT-ND,0.1,0.5 +1,R14,RES SMD 47K OHM 1% 1/10W 0402,Panasonic Electronic Components,ERJ-2RKF4702X,Digikey,P47.0KLCT-ND,0.1,0.1 +4,"C1, C2, C6, C8",0.10µF ±10% 16V Ceramic Capacitor X7R 0402 (1005 Metric),Murata Electronics North America,GRM155R71C104KA88J,Digikey,490-6328-1-ND,0.1,0.4 +3,"C5, C9, C19",10µF ±10% 10V Ceramic Capacitor X7R 0805 (2012 Metric),Taiyo Yuden,LMK212B7106KG-TD,Digikey,587-2668-1-ND,0.28,0.84 +2,"C4, C7","22pF ±5% 50V Ceramic Capacitor C0G, NP0 0402 (1005 Metric)",Murata Electronics North America,GRM1555C1H220JA01J,Digikey,490-11382-1-ND,0.1,0.2 +1,C3,33µF ±10% Molded Tantalum Capacitors 10V 1206 (3216 Metric) 1.7 Ohm,AVX Corporation,TAJA336K010RNJ,Digikey,478-8882-1-ND,0.6,0.6 +1,D5,Blue 470nm LED Indication - Discrete 3.2V 0603 (1608 Metric),Wurth Electronics Inc,150060BS75000,Digikey,732-4966-1-ND,0.26,0.26 +2,"D1, D4",LED RED CLEAR 0603 SMD,Wurth Electronics Inc,150060RS75000,Digikey,732-4978-1-ND,0.24,0.48 +2,"D2, D3",LED GREEN CLEAR 0603 SMD,Wurth Electronics Inc,150060GS75000,Digikey,732-4971-1-ND,0.24,0.48 +1,X1,16MHz ±30ppm Crystal 18pF 40 Ohm -40°C ~ 85°C Surface Mount HC49/US,Abracon LLC,ABLS-16.000MHZ-D-4-T,Digikey,535-13436-1-ND,0.24,0.24 +1,Q1,MOSFET N-CH 20V 0.2A EMT3,Rohm Semiconductor,RE1C002UNTCL,Digikey,RE1C002UNTCLCT-ND,0.2,0.2 +1,U2,CAN Controller CAN 2.0 SPI Interface 18-SOIC,Microchip Technology,MCP2515-I/SO,Digikey,MCP2515-I/SO-ND,1.82,1.82 +1,U1,1/1 Transceiver Half CAN 8-SOIC,Microchip Technology,MCP2551-I/SN,Digikey,MCP2551-I/SN-ND,1.02,1.02 +1,U5,12 Bit Digital to Analog Converter 2 14-TSSOP,Microchip Technology,MCP4922T-E/ST,Digikey,MCP4922T-E/STCT-ND,2.62,2.62 +1,U4,Linear Voltage Regulator IC Positive Fixed 1 Output 5V 750mA DDPAK/TO-263-3,Texas Instruments,TL750M05CKTTR,Digikey,296-20776-1-ND,1.47,1.47 +1,U6,IC SWITCH BUS DUAL FET 8-SOIC,Texas Instruments,SN74CBT3306CDR,Digikey,296-19215-1-ND,0.6,0.6 +1,RELAY1,General Purpose Relay DPDT (2 Form C) Surface Mount,Kemet,EE2-5NU-L,Digikey,399-11017-1-ND,1.91,1.91 +1,JP1,"10 Positions Header, Unshrouded Connector 0.100"" (2.54mm) Through Hole Gold or Gold, GXT™",Amphenol FCI,68002-210HLF,Digikey,609-3301-ND,0.44,0.44 +2,"JP2, JP5","8 Positions Header, Unshrouded Connector 0.100"" (2.54mm) Through Hole Gold or Gold, GXT™",Amphenol FCI,68000-208HLF,Digikey,609-3257-ND,0.43,0.86 +1,JP3,"6 Position Receptacle Connector 0.100"" (2.54mm) Through Hole Gold",Amphenol FCI,68683-303LF,Digikey,609-3582-ND,1.61,1.61 +1,JP4,"6 Positions Header, Unshrouded Connector 0.100"" (2.54mm) Through Hole Gold or Gold, GXT™",Amphenol FCI,68000-206HLF,Digikey,609-3256-ND,0.32,0.32 +1,JP6,"2 Positions Header, Unshrouded Connector 0.100"" (2.54mm) Through Hole Gold or Gold, GXT™",Amphenol FCI,77311-118-02LF,Digikey,609-4434-ND,0.18,0.18 +2,"CON1, CON2","2 Position Wire to Board Terminal Block 45° (135°) Angle with Board 0.138"" (3.50mm) Through Hole",Phoenix Contact,1988956,Digikey,277-1779-ND,0.41,0.82 +2,"CON3, CON4","4 Position Wire to Board Terminal Block 45° (135°) Angle with Board 0.138"" (3.50mm) Through Hole",Phoenix Contact,1988972,Digikey,277-1781-ND,0.82,1.64 +1,For JP6,"2 (1 x 2) Position Shunt Connector White Open Top 0.100"" (2.54mm) Gold or Gold, GXT™",Amphenol FCI,68786-102LF,Digikey,609-3121-ND,0.19,0.19 +Total,,,,,,,,$21.59 diff --git a/hardware/boards/sensor_interface/polysync_sensor_v_1_1_0-1_MacrFab_XTRS_Data.csv b/hardware/boards/sensor_interface/polysync_sensor_v_1_1_0-1_MacrFab_XTRS_Data.csv new file mode 100644 index 00000000..b513eb94 --- /dev/null +++ b/hardware/boards/sensor_interface/polysync_sensor_v_1_1_0-1_MacrFab_XTRS_Data.csv @@ -0,0 +1,57 @@ +"# Generated by MacroFab for PCB 7n6gav, version 1.",,,,,,,,,,,,,,, +# DESIGNATOR,X_LOC,Y_LOC,ROTATION,SIDE,TYPE,X_SIZE,Y_SIZE,VALUE,FOOTPRINT,POPULATE,MPN,MPN1,MPN2,MPN3, +C1,780,1555,90,1,1,62.99,23.62,.1u,C0402,1,,,,, +C2,1040,1225,0,1,1,62.99,23.62,.1u,C0402,1,,,,, +C3,680,1530,90,1,1,149.61,62.99,33u,CP1206,1,,,,,TAJA336K010RNJ +C4,1005,405,270,1,1,62.99,23.62,22p,C0402,1,,,,, +C5,1065,1295,0,1,1,102.36,51.18,10u,C0805,1,,,,,LMK212B7106KG-TD +C6,745,850,270,1,1,62.99,23.62,.1u,C0402,1,,,,, +C7,1005,505,90,1,1,62.99,23.62,22p,C0402,1,,,,, +CON1,180,1686.1,270,1,2,192.91,55.12,CON2,PHOENIX_2_45,1,,,,,1988956 +CON2,180,536.1,270,1,2,192.91,55.12,CON2,PHOENIX_2_45,1,,,,,1988956 +CON3,2380,636.69,90,1,2,468.5,55.12,CON4,PHOENIX_4_45,1,,,,,1988972 +CON4,2380,1586.69,90,1,2,468.5,55.12,CON4,PHOENIX_4_45,1,,,,,1988972 +D1,2205,1180,270,1,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +D2,230,330,180,1,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +D3,230,255,180,1,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +D4,230,180,180,1,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +D5,230,105,180,1,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +JP1,1195,2005,0,2,2,935,35,ARDUINO_JP1,ARDUINO_JP1,1,,,,,68002-210HLF +JP2,2155,2005,0,2,2,735,35,ARDUINO_JP2,ARDUINO_JP2,1,,,,,68000-208HLF +JP3,2555,1105,0,2,2,135,235,ARDUINO_JP3,ARDUINO_JP3,1,,,,,68683-303LF +JP4,2255,105,0,2,2,535,35,ARDUINO_JP4,ARDUINO_JP4,1,,,,,68000-206HLF +JP5,1455,105,0,2,2,735,35,ARDUINO_JP5,ARDUINO_JP5,1,,,,,68000-208HLF +JP6,180,855,270,1,2,36,136,,JP1,1,,,,,77311-118-02LF +Q1,1660,1389.33,180,1,1,57.48,66.93,RE1C002UN,EMT3F,1,,,,,RE1C002UNTCL +R1,2205,1030,270,1,1,62.99,23.62,1k,R0402,1,,,,, +R10,1380,1140,180,1,1,62.99,23.62,DNP,R0402,0,,,,, +R11,1410,980,90,1,1,62.99,23.62,10k,R0402,1,,,,, +R12,1360,980,270,1,1,62.99,23.62,DNP,R0402,0,,,,, +R13,380,855,180,1,1,62.99,23.62,120,R0402,1,,,,,ERJ-2RKF1200X +R14,380,780,180,1,1,62.99,23.62,47k,R0402,1,,,,,ERJ-2RKF4702X +R15,1830,505,270,1,1,62.99,23.62,0,R0402,1,,,,, +R16,1880,505,270,1,1,62.99,23.62,0,R0402,1,,,,, +R17,1830,355,270,1,1,62.99,23.62,DNP,R0402,0,,,,, +R18,1880,355,270,1,1,62.99,23.62,DNP,R0402,0,,,,, +R19,1935,505,270,1,1,62.99,23.62,0,R0402,1,,,,, +R2,1725,755,270,1,1,62.99,23.62,10k,R0402,1,,,,, +R20,1985,505,270,1,1,62.99,23.62,0,R0402,1,,,,, +R21,1935,355,270,1,1,62.99,23.62,DNP,R0402,0,,,,, +R22,1985,355,270,1,1,62.99,23.62,DNP,R0402,0,,,,, +R3,1380,1190,180,1,1,62.99,23.62,0,R0402,1,,,,, +R4,105,330,180,1,1,62.99,23.62,1k,R0402,1,,,,, +R5,105,255,180,1,1,62.99,23.62,1k,R0402,1,,,,, +R6,105,180,180,1,1,62.99,23.62,1k,R0402,1,,,,, +R7,105,105,180,1,1,62.99,23.62,1k,R0402,1,,,,, +R8,780,1455,270,1,1,62.99,23.62,0.3,R0402,1,,,,,ERJ-2BQFR30X +R9,1310,980,270,1,1,62.99,23.62,10k,R0402,1,,,,, +RELAY1,1781.06,1115,0,1,1,443.31,405.12,RELAY_DPDT,KEMET_EE2,1,,,,,EE2-5NU-L +TP1,640,320,0,1,1,45,45,,TP_4545,0,,,,, +TP2,2355,1090,0,1,1,45,45,,TP_4545,0,,,,, +TP3,75,2040,0,1,1,45,45,,TP_4545,0,,,,, +U$1,2295,1365,0,2,1,0,0,POLYSYNC,POLYSYNC,0,,,,, +U1,575,845,90,1,1,173.62,267.72,MCP2551,SOIC8-6.0,1,,,,,MCP2551-I/SN +U2,1455,580,270,1,1,430,457,MCP2515,SOIC18,1,,,,,MCP2515-I/SO +U4,1144.84,1590,270,1,1,421.26,653.54,TL750M,TO-263,1,,,,,TL750M05CKTTR +U5,1125,1085,0,1,1,289.37,171.26,MCP4922T,TSSOP-14,1,,,,,MCP4922T-E/ST +X1,870,340,90,1,1,590,76,16MHz,HC49UP,1,,,,,ABLS-16.000MHZ-D-4-T diff --git a/hardware/boards/vehicle_control_module/polysync_vcm_v_0_1_0_BOM.csv b/hardware/boards/vehicle_control_module/polysync_vcm_v_0_1_0_BOM.csv new file mode 100644 index 00000000..ebc730fd --- /dev/null +++ b/hardware/boards/vehicle_control_module/polysync_vcm_v_0_1_0_BOM.csv @@ -0,0 +1,33 @@ +Polysync Vehicle Control Module v0.1.0,,,,,,,, +,,,,,,,, +Quantity,Reference Designator,Description,Mfg,Mfg Part No.,Distributor,Distributor Part No.,Price,Total Price +1,R8,RES SMD 0.3 OHM 1% 1/6W 0402,Panasonic Electronic Components,ERJ-2BQFR30X,Digikey,P.30AKCT-ND,0.59,0.59 +5,"R3, R15, R16, R19, R20",RES SMD 0.0OHM JUMPER 1/10W 0402,Panasonic Electronic Components,ERJ-2GE0R00X,Digikey,P0.0JCT-ND,0.1,0.5 +8,"R2, R9, R11, R17, R18, R23, R24, R25",RES SMD 10K OHM 1% 1/10W 0402,Panasonic Electronic Components,ERJ-2RKF1002X,Digikey,P10.0KLCT-ND,0.1,0.8 +1,R13,RES SMD 120 OHM 1% 1/10W 0402,Panasonic Electronic Components,ERJ-2RKF1200X,Digikey,P120LCT-ND,0.1,0.1 +6,"R1, R4, R5, R6, R7, R103",RES SMD 1K OHM 1% 1/10W 0402,Panasonic Electronic Components,ERJ-2RKF1001X,Digikey,P1.00KLCT-ND,0.1,0.6 +1,R14,RES SMD 47K OHM 1% 1/10W 0402,Panasonic Electronic Components,ERJ-2RKF4702X,Digikey,P47.0KLCT-ND,0.1,0.1 +4,"R10, R12, R21, R22",DNP,,,,,, +4,"C1, C2, C6, C8",0.10µF ±10% 16V Ceramic Capacitor X7R 0402 (1005 Metric),Murata Electronics North America,GRM155R71C104KA88J,Digikey,490-6328-1-ND,0.1,0.4 +3,"C5, C9, C10",10µF ±10% 10V Ceramic Capacitor X7R 0805 (2012 Metric),Taiyo Yuden,LMK212B7106KG-TD,Digikey,587-2668-1-ND,0.28,0.84 +2,"C4, C7","22pF ±5% 50V Ceramic Capacitor C0G, NP0 0402 (1005 Metric)",Murata Electronics North America,GRM1555C1H220JA01J,Digikey,490-11382-1-ND,0.1,0.2 +1,C3,33µF ±10% Molded Tantalum Capacitors 10V 1206 (3216 Metric) 1.7 Ohm,AVX Corporation,TAJA336K010RNJ,Digikey,478-8882-1-ND,0.6,0.6 +6,"D1, D2, D3, D4, D5, D17",Blue 470nm LED Indication - Discrete 3.2V 0603 (1608 Metric),Wurth Electronics Inc,150060BS75000,Digikey,732-4966-1-ND,0.26,1.56 +1,X1,16MHz ±30ppm Crystal 18pF 40 Ohm -40°C ~ 85°C Surface Mount HC49/US,Abracon LLC,ABLS-16.000MHZ-D-4-T,Digikey,535-13436-1-ND,0.24,0.24 +2,"Q1, Q10",MOSFET N-CH 20V 0.2A EMT3,Rohm Semiconductor,RE1C002UNTCL,Digikey,RE1C002UNTCLCT-ND,0.2,0.4 +1,U2,CAN Controller CAN 2.0 SPI Interface 18-SOIC,Microchip Technology,MCP2515-I/SO,Digikey,MCP2515-I/SO-ND,1.82,1.82 +1,U1,1/1 Transceiver Half CAN 8-SOIC,Microchip Technology,MCP2551-I/SN,Digikey,MCP2551-I/SN-ND,1.02,1.02 +1,U5,12 Bit Digital to Analog Converter 2 14-TSSOP,Microchip Technology,MCP4922T-E/ST,Digikey,MCP4922T-E/STCT-ND,2.62,2.62 +1,U4,Linear Voltage Regulator IC Positive Fixed 1 Output 5V 750mA DDPAK/TO-263-3,Texas Instruments,TL750M05CKTTR,Digikey,296-20776-1-ND,1.47,1.47 +1,U6,IC SWITCH BUS DUAL FET 8-SOIC,Texas Instruments,SN74CBT3306CDR,Digikey,296-19215-1-ND,0.6,0.6 +2,"RELAY1, RELAY2",General Purpose Relay DPDT (2 Form C) Surface Mount,Kemet,EE2-5NU-L,Digikey,399-11017-1-ND,1.91,3.82 +1,JP1,"10 Positions Header, Unshrouded Connector 0.100"" (2.54mm) Through Hole Gold or Gold, GXT™",Amphenol FCI,68002-210HLF,Digikey,609-3301-ND,0.44,0.44 +2,"JP2, JP5","8 Positions Header, Unshrouded Connector 0.100"" (2.54mm) Through Hole Gold or Gold, GXT™",Amphenol FCI,68000-208HLF,Digikey,609-3257-ND,0.43,0.86 +1,JP3,"6 Position Receptacle Connector 0.100"" (2.54mm) Through Hole Gold",Amphenol FCI,68683-303LF,Digikey,609-3582-ND,1.61,1.61 +1,JP4,"6 Positions Header, Unshrouded Connector 0.100"" (2.54mm) Through Hole Gold or Gold, GXT™",Amphenol FCI,68000-206HLF,Digikey,609-3256-ND,0.32,0.32 +1,JP6,"2 Positions Header, Unshrouded Connector 0.100"" (2.54mm) Through Hole Gold or Gold, GXT™",Amphenol FCI,77311-118-02LF,Digikey,609-4434-ND,0.18,0.18 +2,"CON1, CON2","2 Position Wire to Board Terminal Block 45° (135°) Angle with Board 0.138"" (3.50mm) Through Hole",Phoenix Contact,1988956,Digikey,277-1779-ND,0.41,0.82 +2,"CON3, CON4","4 Position Wire to Board Terminal Block 45° (135°) Angle with Board 0.138"" (3.50mm) Through Hole",Phoenix Contact,1988972,Digikey,277-1781-ND,0.82,1.64 +2,"CON9, CON10",CONN TERM BLOCK 45DEG 3POS 3.5MM,Phoenix Contact,1988969,Digikey,277-1780-ND,0.65,1.3 +1,For JP6,"2 (1 x 2) Position Shunt Connector White Open Top 0.100"" (2.54mm) Gold or Gold, GXT™",Amphenol FCI,68786-102LF,Digikey,609-3121-ND,0.19,0.19 +Total,,,,,,,,$25.64 diff --git a/hardware/boards/vehicle_control_module/polysync_vcm_v_0_1_0_MacroFab_XYRS_Data.csv b/hardware/boards/vehicle_control_module/polysync_vcm_v_0_1_0_MacroFab_XYRS_Data.csv new file mode 100644 index 00000000..b513eb94 --- /dev/null +++ b/hardware/boards/vehicle_control_module/polysync_vcm_v_0_1_0_MacroFab_XYRS_Data.csv @@ -0,0 +1,57 @@ +"# Generated by MacroFab for PCB 7n6gav, version 1.",,,,,,,,,,,,,,, +# DESIGNATOR,X_LOC,Y_LOC,ROTATION,SIDE,TYPE,X_SIZE,Y_SIZE,VALUE,FOOTPRINT,POPULATE,MPN,MPN1,MPN2,MPN3, +C1,780,1555,90,1,1,62.99,23.62,.1u,C0402,1,,,,, +C2,1040,1225,0,1,1,62.99,23.62,.1u,C0402,1,,,,, +C3,680,1530,90,1,1,149.61,62.99,33u,CP1206,1,,,,,TAJA336K010RNJ +C4,1005,405,270,1,1,62.99,23.62,22p,C0402,1,,,,, +C5,1065,1295,0,1,1,102.36,51.18,10u,C0805,1,,,,,LMK212B7106KG-TD +C6,745,850,270,1,1,62.99,23.62,.1u,C0402,1,,,,, +C7,1005,505,90,1,1,62.99,23.62,22p,C0402,1,,,,, +CON1,180,1686.1,270,1,2,192.91,55.12,CON2,PHOENIX_2_45,1,,,,,1988956 +CON2,180,536.1,270,1,2,192.91,55.12,CON2,PHOENIX_2_45,1,,,,,1988956 +CON3,2380,636.69,90,1,2,468.5,55.12,CON4,PHOENIX_4_45,1,,,,,1988972 +CON4,2380,1586.69,90,1,2,468.5,55.12,CON4,PHOENIX_4_45,1,,,,,1988972 +D1,2205,1180,270,1,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +D2,230,330,180,1,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +D3,230,255,180,1,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +D4,230,180,180,1,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +D5,230,105,180,1,1,90.55,31.5,,LED0603,1,,,,,150060BS75000 +JP1,1195,2005,0,2,2,935,35,ARDUINO_JP1,ARDUINO_JP1,1,,,,,68002-210HLF +JP2,2155,2005,0,2,2,735,35,ARDUINO_JP2,ARDUINO_JP2,1,,,,,68000-208HLF +JP3,2555,1105,0,2,2,135,235,ARDUINO_JP3,ARDUINO_JP3,1,,,,,68683-303LF +JP4,2255,105,0,2,2,535,35,ARDUINO_JP4,ARDUINO_JP4,1,,,,,68000-206HLF +JP5,1455,105,0,2,2,735,35,ARDUINO_JP5,ARDUINO_JP5,1,,,,,68000-208HLF +JP6,180,855,270,1,2,36,136,,JP1,1,,,,,77311-118-02LF +Q1,1660,1389.33,180,1,1,57.48,66.93,RE1C002UN,EMT3F,1,,,,,RE1C002UNTCL +R1,2205,1030,270,1,1,62.99,23.62,1k,R0402,1,,,,, +R10,1380,1140,180,1,1,62.99,23.62,DNP,R0402,0,,,,, +R11,1410,980,90,1,1,62.99,23.62,10k,R0402,1,,,,, +R12,1360,980,270,1,1,62.99,23.62,DNP,R0402,0,,,,, +R13,380,855,180,1,1,62.99,23.62,120,R0402,1,,,,,ERJ-2RKF1200X +R14,380,780,180,1,1,62.99,23.62,47k,R0402,1,,,,,ERJ-2RKF4702X +R15,1830,505,270,1,1,62.99,23.62,0,R0402,1,,,,, +R16,1880,505,270,1,1,62.99,23.62,0,R0402,1,,,,, +R17,1830,355,270,1,1,62.99,23.62,DNP,R0402,0,,,,, +R18,1880,355,270,1,1,62.99,23.62,DNP,R0402,0,,,,, +R19,1935,505,270,1,1,62.99,23.62,0,R0402,1,,,,, +R2,1725,755,270,1,1,62.99,23.62,10k,R0402,1,,,,, +R20,1985,505,270,1,1,62.99,23.62,0,R0402,1,,,,, +R21,1935,355,270,1,1,62.99,23.62,DNP,R0402,0,,,,, +R22,1985,355,270,1,1,62.99,23.62,DNP,R0402,0,,,,, +R3,1380,1190,180,1,1,62.99,23.62,0,R0402,1,,,,, +R4,105,330,180,1,1,62.99,23.62,1k,R0402,1,,,,, +R5,105,255,180,1,1,62.99,23.62,1k,R0402,1,,,,, +R6,105,180,180,1,1,62.99,23.62,1k,R0402,1,,,,, +R7,105,105,180,1,1,62.99,23.62,1k,R0402,1,,,,, +R8,780,1455,270,1,1,62.99,23.62,0.3,R0402,1,,,,,ERJ-2BQFR30X +R9,1310,980,270,1,1,62.99,23.62,10k,R0402,1,,,,, +RELAY1,1781.06,1115,0,1,1,443.31,405.12,RELAY_DPDT,KEMET_EE2,1,,,,,EE2-5NU-L +TP1,640,320,0,1,1,45,45,,TP_4545,0,,,,, +TP2,2355,1090,0,1,1,45,45,,TP_4545,0,,,,, +TP3,75,2040,0,1,1,45,45,,TP_4545,0,,,,, +U$1,2295,1365,0,2,1,0,0,POLYSYNC,POLYSYNC,0,,,,, +U1,575,845,90,1,1,173.62,267.72,MCP2551,SOIC8-6.0,1,,,,,MCP2551-I/SN +U2,1455,580,270,1,1,430,457,MCP2515,SOIC18,1,,,,,MCP2515-I/SO +U4,1144.84,1590,270,1,1,421.26,653.54,TL750M,TO-263,1,,,,,TL750M05CKTTR +U5,1125,1085,0,1,1,289.37,171.26,MCP4922T,TSSOP-14,1,,,,,MCP4922T-E/ST +X1,870,340,90,1,1,590,76,16MHz,HC49UP,1,,,,,ABLS-16.000MHZ-D-4-T From e3671cd2df5695c3a944012c8d3a45c10e765c99 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Wed, 7 Feb 2018 13:17:03 -0800 Subject: [PATCH 04/80] Update dbc to support float Prior to this commit the dbc file did not support the float leaving the user to determine how to interpret the 32 bits. The variable naming was also a mix of upper and lower case letters. This commit fixes that by setting the command messages to the standard IEEE float and making the message parameters all lower case. --- api/include/can_protocols/oscc.dbc | 109 +++++++++++++++++++++++++++++ api/include/vehicles/oscc.dbc | 106 ---------------------------- 2 files changed, 109 insertions(+), 106 deletions(-) create mode 100644 api/include/can_protocols/oscc.dbc delete mode 100644 api/include/vehicles/oscc.dbc diff --git a/api/include/can_protocols/oscc.dbc b/api/include/can_protocols/oscc.dbc new file mode 100644 index 00000000..61613101 --- /dev/null +++ b/api/include/can_protocols/oscc.dbc @@ -0,0 +1,109 @@ +VERSION "" + +NS_ : + BA_ + BA_DEF_ + BA_DEF_DEF_ + BA_DEF_DEF_REL_ + BA_DEF_REL_ + BA_DEF_SGTYPE_ + BA_REL_ + BA_SGTYPE_ + BO_TX_BU_ + BU_BO_REL_ + BU_EV_REL_ + BU_SG_REL_ + CAT_ + CAT_DEF_ + CM_ + ENVVAR_DATA_ + EV_DATA_ + FILTER + NS_DESC_ + SGTYPE_ + SGTYPE_VAL_ + SG_MUL_VAL_ + SIGTYPE_VALTYPE_ + SIG_GROUP_ + SIG_TYPE_REF_ + SIG_VALTYPE_ + VAL_ + VAL_TABLE_ + +BS_: + +BU_: BRAKE STEERING THROTTLE FAULT + +BO_ 112 BRAKE_ENABLE: 8 BRAKE + SG_ brake_enable_magic : 0|16@1+ (1,0) [0|0] "" BRAKE + SG_ brake_enable_reserved : 16|48@1+ (1,0) [0|0] "" BRAKE + +BO_ 113 BRAKE_DISABLE: 8 BRAKE + SG_ brake_disable_magic : 0|16@1+ (1,0) [0|0] "" BRAKE + SG_ brake_disable_reserved : 16|48@1+ (1,0) [0|0] "" BRAKE + +BO_ 114 BRAKE_COMMAND: 8 BRAKE + SG_ brake_command_magic : 0|16@1+ (1,0) [0|0] "" BRAKE + SG_ brake_command_pedal_request : 16|32@1+ (1,0) [0|1] "" BRAKE + SG_ brake_command_reserved : 48|16@1+ (1,0) [0|0] "" BRAKE + +BO_ 115 BRAKE_REPORT: 8 BRAKE + SG_ brake_report_magic : 0|16@1+ (1,0) [0|0] "" BRAKE + SG_ brake_report_enabled : 16|8@1+ (1,0) [0|0] "" BRAKE + SG_ brake_report_operator_override : 24|8@1+ (1,0) [0|0] "" BRAKE + SG_ brake_report_dtcs : 32|8@1+ (1,0) [0|0] "" BRAKE + SG_ brake_report_reserved : 40|24@1+ (1,0) [0|0] "" BRAKE + +BO_ 128 STEERING_ENABLE: 8 STEERING + SG_ steering_enable_magic : 0|16@1+ (1,0) [0|0] "" STEERING + SG_ steering_enable_reserved : 16|48@1+ (1,0) [0|0] "" STEERING + +BO_ 129 STEERING_DISABLE: 8 STEERING + SG_ steering_disable_magic : 0|16@1+ (1,0) [0|0] "" STEERING + SG_ steering_disable_reserved : 16|48@1+ (1,0) [0|0] "" STEERING + +BO_ 130 STEERING_COMMAND: 8 STEERING + SG_ steering_command_magic : 0|16@1+ (1,0) [0|0] "" STEERING + SG_ steering_command_torque_request : 16|32@1- (1,0) [-1|1] "" STEERING + SG_ steering_command_reserved : 48|16@1+ (1,0) [0|0] "" STEERING + +BO_ 131 STEERING_REPORT: 8 STEERING + SG_ steering_report_magic : 0|16@1+ (1,0) [0|0] "" STEERING + SG_ steering_report_enabled : 16|8@1+ (1,0) [0|0] "" STEERING + SG_ steering_report_operator_override : 24|8@1+ (1,0) [0|0] "" STEERING + SG_ steering_report_dtcs : 32|8@1+ (1,0) [0|0] "" STEERING + SG_ steering_report_reserved : 40|24@1+ (1,0) [0|0] "" STEERING + +BO_ 144 THROTTLE_ENABLE: 8 THROTTLE + SG_ throttle_enable_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE + SG_ throttle_enable_reserved : 16|48@1+ (1,0) [0|0] "" THROTTLE + +BO_ 145 THROTTLE_DISABLE: 8 THROTTLE + SG_ throttle_disable_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE + SG_ throttle_disable_reserved : 16|48@1+ (1,0) [0|0] "" THROTTLE + +BO_ 146 THROTTLE_COMMAND: 8 THROTTLE + SG_ throttle_command_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE + SG_ throttle_command_pedal_request : 16|32@1- (1,0) [0|1] "" THROTTLE + SG_ throttle_command_reserved : 48|16@1+ (1,0) [0|0] "" THROTTLE + +BO_ 147 THROTTLE_REPORT: 8 THROTTLE + SG_ throttle_report_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE + SG_ throttle_report_enabled : 16|8@1+ (1,0) [0|0] "" THROTTLE + SG_ throttle_report_operator_override : 24|8@1+ (1,0) [0|0] "" THROTTLE + SG_ throttle_report_dtcs : 32|8@1+ (1,0) [0|0] "" THROTTLE + SG_ throttle_report_reserved : 40|24@1+ (1,0) [0|0] "" THROTTLE + +BO_ 175 FAULT_REPORT: 8 FAULT + SG_ fault_report_magic : 0|16@1+ (1,0) [0|0] "" FAULT + SG_ fault_report_fault_origin_id : 16|32@1+ (1,0) [0|0] "" FAULT + SG_ fault_report_dtcs : 48|8@1+ (1,0) [0|0] "" FAULT + SG_ fault_report_reserved : 56|8@1+ (1,0) [0|0] "" FAULT + +CM_ BU_ BRAKE "The OSCC brake module"; +CM_ BU_ STEERING "The OSCC steering module"; +CM_ BU_ THROTTLE "The OSCC throttle module"; +CM_ BU_ FAULT "The OSCC fault report"; +SIG_VALTYPE_ 114 brake_command_pedal_request : 1; +SIG_VALTYPE_ 130 steering_command_torque_request : 1; +SIG_VALTYPE_ 146 throttle_command_pedal_request : 1; diff --git a/api/include/vehicles/oscc.dbc b/api/include/vehicles/oscc.dbc deleted file mode 100644 index b5e94403..00000000 --- a/api/include/vehicles/oscc.dbc +++ /dev/null @@ -1,106 +0,0 @@ -VERSION "" - -NS_ : - BA_ - BA_DEF_ - BA_DEF_DEF_ - BA_DEF_DEF_REL_ - BA_DEF_REL_ - BA_DEF_SGTYPE_ - BA_REL_ - BA_SGTYPE_ - BO_TX_BU_ - BU_BO_REL_ - BU_EV_REL_ - BU_SG_REL_ - CAT_ - CAT_DEF_ - CM_ - ENVVAR_DATA_ - EV_DATA_ - FILTER - NS_DESC_ - SGTYPE_ - SGTYPE_VAL_ - SG_MUL_VAL_ - SIGTYPE_VALTYPE_ - SIG_GROUP_ - SIG_TYPE_REF_ - SIG_VALTYPE_ - VAL_ - VAL_TABLE_ - -BS_: - -BU_: BRAKE STEERING THROTTLE FAULT - -BO_ 112 BRAKE_ENABLE: 8 BRAKE - SG_ BRAKE_ENABLE_magic : 0|16@1+ (1,0) [0|0] "" BRAKE - SG_ BRAKE_ENABLE_reserved : 16|48@1+ (1,0) [0|0] "" BRAKE - -BO_ 113 BRAKE_DISABLE: 8 BRAKE - SG_ BRAKE_DISABLE_magic : 0|16@1+ (1,0) [0|0] "" BRAKE - SG_ BRAKE_DISABLE_reserved : 16|48@1+ (1,0) [0|0] "" BRAKE - -BO_ 114 BRAKE_COMMAND: 8 BRAKE - SG_ BRAKE_COMMAND_magic : 0|16@1+ (1,0) [0|0] "" BRAKE - SG_ BRAKE_COMMAND_pedal_command : 16|32@1+ (1,0) [0|0] "" BRAKE - SG_ BRAKE_COMMAND_reserved : 48|16@1+ (1,0) [0|0] "" BRAKE - -BO_ 115 BRAKE_REPORT: 8 BRAKE - SG_ BRAKE_REPORT_magic : 0|16@1+ (1,0) [0|0] "" BRAKE - SG_ BRAKE_REPORT_enabled : 16|8@1+ (1,0) [0|0] "" BRAKE - SG_ BRAKE_REPORT_operator_override : 24|8@1+ (1,0) [0|0] "" BRAKE - SG_ BRAKE_REPORT_dtcs : 32|8@1+ (1,0) [0|0] "" BRAKE - SG_ BRAKE_REPORT_reserved : 40|24@1+ (1,0) [0|0] "" BRAKE - -BO_ 128 STEERING_ENABLE: 8 STEERING - SG_ STEERING_ENABLE_magic : 0|16@1+ (1,0) [0|0] "" STEERING - SG_ STEERING_ENABLE_reserved : 16|48@1+ (1,0) [0|0] "" STEERING - -BO_ 129 STEERING_DISABLE: 8 STEERING - SG_ STEERING_DISABLE_magic : 0|16@1+ (1,0) [0|0] "" STEERING - SG_ STEERING_DISABLE_reserved : 16|48@1+ (1,0) [0|0] "" STEERING - -BO_ 130 STEERING_COMMAND: 8 STEERING - SG_ STEERING_COMMAND_magic : 0|16@1+ (1,0) [0|0] "" STEERING - SG_ STEERING_COMMAND_pedal_command : 16|32@1+ (1,0) [0|0] "" STEERING - SG_ STEERING_COMMAND_reserved : 48|16@1+ (1,0) [0|0] "" STEERING - -BO_ 131 STEERING_REPORT: 8 STEERING - SG_ STEERING_REPORT_magic : 0|16@1+ (1,0) [0|0] "" STEERING - SG_ STEERING_REPORT_enabled : 16|8@1+ (1,0) [0|0] "" STEERING - SG_ STEERING_REPORT_operator_override : 24|8@1+ (1,0) [0|0] "" STEERING - SG_ STEERING_REPORT_dtcs : 32|8@1+ (1,0) [0|0] "" STEERING - SG_ STEERING_REPORT_reserved : 40|24@1+ (1,0) [0|0] "" STEERING - -BO_ 144 THROTTLE_ENABLE: 8 THROTTLE - SG_ THROTTLE_ENABLE_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE - SG_ THROTTLE_ENABLE_reserved : 16|48@1+ (1,0) [0|0] "" THROTTLE - -BO_ 145 THROTTLE_DISABLE: 8 THROTTLE - SG_ THROTTLE_DISABLE_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE - SG_ THROTTLE_DISABLE_reserved : 16|48@1+ (1,0) [0|0] "" THROTTLE - -BO_ 146 THROTTLE_COMMAND: 8 THROTTLE - SG_ THROTTLE_COMMAND_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE - SG_ THROTTLE_COMMAND_pedal_command : 16|32@1+ (1,0) [0|0] "" THROTTLE - SG_ THROTTLE_COMMAND_reserved : 48|16@1+ (1,0) [0|0] "" THROTTLE - -BO_ 147 THROTTLE_REPORT: 8 THROTTLE - SG_ THROTTLE_REPORT_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE - SG_ THROTTLE_REPORT_enabled : 16|8@1+ (1,0) [0|0] "" THROTTLE - SG_ THROTTLE_REPORT_operator_override : 24|8@1+ (1,0) [0|0] "" THROTTLE - SG_ THROTTLE_REPORT_dtcs : 32|8@1+ (1,0) [0|0] "" THROTTLE - SG_ THROTTLE_REPORT_reserved : 40|24@1+ (1,0) [0|0] "" THROTTLE - -BO_ 175 FAULT_REPORT: 8 FAULT - SG_ FAULT_REPORT_magic : 0|16@1+ (1,0) [0|0] "" FAULT - SG_ FAULT_REPORT_fault_origin_id : 16|32@1+ (1,0) [0|0] "" FAULT - SG_ FAULT_REPORT_dtcs : 48|8@1+ (1,0) [0|0] "" FAULT - SG_ FAULT_REPORT_reserved : 56|8@1+ (1,0) [0|0] "" FAULT - -CM_ BU_ BRAKE "The OSCC brake module"; -CM_ BU_ STEERING "The OSCC steering module"; -CM_ BU_ THROTTLE "The OSCC throttle module"; -CM_ BU_ FAULT "The OSCC fault report"; From 4eb9c692423d8d533b94c05d8384f235344450e1 Mon Sep 17 00:00:00 2001 From: Adrien Thebo Date: Mon, 12 Feb 2018 10:08:12 -0800 Subject: [PATCH 05/80] maint: fix typo in soul-petrol unit test project --- firmware/brake/kia_soul_petrol/tests/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/firmware/brake/kia_soul_petrol/tests/CMakeLists.txt b/firmware/brake/kia_soul_petrol/tests/CMakeLists.txt index 5da335ed..bf3d4458 100644 --- a/firmware/brake/kia_soul_petrol/tests/CMakeLists.txt +++ b/firmware/brake/kia_soul_petrol/tests/CMakeLists.txt @@ -1,4 +1,4 @@ -project(brake-tests) +project(brake-unit-tests) add_library( brake From e5ba276a6ecc31f5c2bb3c3496c03f07958cd639 Mon Sep 17 00:00:00 2001 From: Adrien Thebo Date: Mon, 12 Feb 2018 10:26:28 -0800 Subject: [PATCH 06/80] testing: prevent multiple inclusion of common test fixtures --- firmware/common/testing/step_definitions/common.cpp | 2 ++ firmware/common/testing/step_definitions/fault_checking.cpp | 2 ++ firmware/common/testing/step_definitions/vcm.cpp | 2 ++ 3 files changed, 6 insertions(+) diff --git a/firmware/common/testing/step_definitions/common.cpp b/firmware/common/testing/step_definitions/common.cpp index a0634456..ef7c3251 100644 --- a/firmware/common/testing/step_definitions/common.cpp +++ b/firmware/common/testing/step_definitions/common.cpp @@ -1,3 +1,5 @@ +#pragma once + #include #include #include diff --git a/firmware/common/testing/step_definitions/fault_checking.cpp b/firmware/common/testing/step_definitions/fault_checking.cpp index 484d534b..e4c10093 100644 --- a/firmware/common/testing/step_definitions/fault_checking.cpp +++ b/firmware/common/testing/step_definitions/fault_checking.cpp @@ -1,3 +1,5 @@ +#pragma once + // fault_checking.cpp WHEN("^a sensor is grounded for (\\d+) ms$") diff --git a/firmware/common/testing/step_definitions/vcm.cpp b/firmware/common/testing/step_definitions/vcm.cpp index a4c1c638..1a9fe8d5 100644 --- a/firmware/common/testing/step_definitions/vcm.cpp +++ b/firmware/common/testing/step_definitions/vcm.cpp @@ -1,3 +1,5 @@ +#pragma once + THEN("^control should be enabled$") { assert_that( From f5125db4aaa5b6925277ec4c25708c26aefad8d8 Mon Sep 17 00:00:00 2001 From: Adrien Thebo Date: Mon, 12 Feb 2018 10:53:51 -0800 Subject: [PATCH 07/80] testing: Reorganize test setup files to match best practices The module firmware `common.cpp` file layout was a bit mangled due to the test refactoring, which was confusing and a bit jarring. This commit cleans up the unit test setup files to use a more consistent layout and renames them to indicate that they are, in fact, just for setup. --- .../step_definitions/{common.cpp => setup.cpp} | 6 ++---- .../tests/features/step_definitions/test.cpp | 9 ++++++--- .../{common.cpp => actuator_control.cpp} | 14 +------------- .../tests/features/step_definitions/setup.cpp | 12 ++++++++++++ .../tests/features/step_definitions/test.cpp | 9 ++++++--- .../step_definitions/{common.cpp => setup.cpp} | 6 ++---- .../tests/features/step_definitions/test.cpp | 9 ++++++--- .../step_definitions/{common.cpp => setup.cpp} | 6 ++---- .../tests/features/step_definitions/test.cpp | 9 ++++++--- 9 files changed, 43 insertions(+), 37 deletions(-) rename firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/{common.cpp => setup.cpp} (69%) rename firmware/brake/kia_soul_petrol/tests/features/step_definitions/{common.cpp => actuator_control.cpp} (87%) create mode 100644 firmware/brake/kia_soul_petrol/tests/features/step_definitions/setup.cpp rename firmware/steering/tests/features/step_definitions/{common.cpp => setup.cpp} (70%) rename firmware/throttle/tests/features/step_definitions/{common.cpp => setup.cpp} (70%) diff --git a/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/common.cpp b/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/setup.cpp similarity index 69% rename from firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/common.cpp rename to firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/setup.cpp index 77539bfe..8ceafaf6 100644 --- a/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/common.cpp +++ b/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/setup.cpp @@ -3,9 +3,7 @@ #include "can_protocols/brake_can_protocol.h" #include "globals.h" -extern volatile brake_control_state_s g_brake_control_state; - #define FIRMWARE_NAME "brake" #define g_vcm_control_state g_brake_control_state -#include "../../common/testing/step_definitions/common.cpp" -#include "../../common/testing/step_definitions/vcm.cpp" + +extern volatile brake_control_state_s g_brake_control_state; diff --git a/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/test.cpp b/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/test.cpp index 990913dd..fc03bf18 100644 --- a/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/test.cpp +++ b/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/test.cpp @@ -1,7 +1,10 @@ // include source files to prevent step files from conflicting with each other -#include "common.cpp" +#include "setup.cpp" + +#include "../../common/testing/step_definitions/common.cpp" +#include "../../common/testing/step_definitions/vcm.cpp" +#include "../../common/testing/step_definitions/fault_checking.cpp" + #include "checking_faults.cpp" #include "receiving_messages.cpp" #include "sending_reports.cpp" - -#include "../../common/testing/step_definitions/fault_checking.cpp" diff --git a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/common.cpp b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/actuator_control.cpp similarity index 87% rename from firmware/brake/kia_soul_petrol/tests/features/step_definitions/common.cpp rename to firmware/brake/kia_soul_petrol/tests/features/step_definitions/actuator_control.cpp index c75d4873..fc1cc9d0 100644 --- a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/common.cpp +++ b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/actuator_control.cpp @@ -1,16 +1,4 @@ -#include "communications.h" -#include "brake_control.h" -#include "can_protocols/brake_can_protocol.h" -#include "vehicles.h" -#include "globals.h" - -extern volatile brake_control_state_s g_brake_control_state; - -#define FIRMWARE_NAME "brake" -#define g_vcm_control_state g_brake_control_state -#include "../../common/testing/step_definitions/common.cpp" - -#define check_for_faults() (check_for_sensor_faults()) +#pragma once THEN("^control should be enabled$") { diff --git a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/setup.cpp b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/setup.cpp new file mode 100644 index 00000000..21af4a00 --- /dev/null +++ b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/setup.cpp @@ -0,0 +1,12 @@ +#include "communications.h" +#include "brake_control.h" +#include "can_protocols/brake_can_protocol.h" +#include "vehicles.h" +#include "globals.h" + +extern volatile brake_control_state_s g_brake_control_state; + +#define FIRMWARE_NAME "brake" +#define g_vcm_control_state g_brake_control_state + +#define check_for_faults() (check_for_sensor_faults()) diff --git a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/test.cpp b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/test.cpp index 990913dd..7867f066 100644 --- a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/test.cpp +++ b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/test.cpp @@ -1,7 +1,10 @@ // include source files to prevent step files from conflicting with each other -#include "common.cpp" +#include "setup.cpp" + +#include "../../common/testing/step_definitions/common.cpp" +#include "../../common/testing/step_definitions/fault_checking.cpp" + #include "checking_faults.cpp" #include "receiving_messages.cpp" #include "sending_reports.cpp" - -#include "../../common/testing/step_definitions/fault_checking.cpp" +#include "actuator_control.cpp" diff --git a/firmware/steering/tests/features/step_definitions/common.cpp b/firmware/steering/tests/features/step_definitions/setup.cpp similarity index 70% rename from firmware/steering/tests/features/step_definitions/common.cpp rename to firmware/steering/tests/features/step_definitions/setup.cpp index 4c83c5b4..8cfbd715 100644 --- a/firmware/steering/tests/features/step_definitions/common.cpp +++ b/firmware/steering/tests/features/step_definitions/setup.cpp @@ -3,9 +3,7 @@ #include "can_protocols/steering_can_protocol.h" #include "globals.h" -extern volatile steering_control_state_s g_steering_control_state; - #define FIRMWARE_NAME "steering" #define g_vcm_control_state g_steering_control_state -#include "../../common/testing/step_definitions/common.cpp" -#include "../../common/testing/step_definitions/vcm.cpp" + +extern volatile steering_control_state_s g_steering_control_state; diff --git a/firmware/steering/tests/features/step_definitions/test.cpp b/firmware/steering/tests/features/step_definitions/test.cpp index 990913dd..fc03bf18 100644 --- a/firmware/steering/tests/features/step_definitions/test.cpp +++ b/firmware/steering/tests/features/step_definitions/test.cpp @@ -1,7 +1,10 @@ // include source files to prevent step files from conflicting with each other -#include "common.cpp" +#include "setup.cpp" + +#include "../../common/testing/step_definitions/common.cpp" +#include "../../common/testing/step_definitions/vcm.cpp" +#include "../../common/testing/step_definitions/fault_checking.cpp" + #include "checking_faults.cpp" #include "receiving_messages.cpp" #include "sending_reports.cpp" - -#include "../../common/testing/step_definitions/fault_checking.cpp" diff --git a/firmware/throttle/tests/features/step_definitions/common.cpp b/firmware/throttle/tests/features/step_definitions/setup.cpp similarity index 70% rename from firmware/throttle/tests/features/step_definitions/common.cpp rename to firmware/throttle/tests/features/step_definitions/setup.cpp index a2c2b963..5de38dcc 100644 --- a/firmware/throttle/tests/features/step_definitions/common.cpp +++ b/firmware/throttle/tests/features/step_definitions/setup.cpp @@ -3,9 +3,7 @@ #include "can_protocols/throttle_can_protocol.h" #include "globals.h" -extern volatile throttle_control_state_s g_throttle_control_state; - #define FIRMWARE_NAME "throttle" #define g_vcm_control_state g_throttle_control_state -#include "../../common/testing/step_definitions/common.cpp" -#include "../../common/testing/step_definitions/vcm.cpp" + +extern volatile throttle_control_state_s g_throttle_control_state; diff --git a/firmware/throttle/tests/features/step_definitions/test.cpp b/firmware/throttle/tests/features/step_definitions/test.cpp index 990913dd..fc03bf18 100644 --- a/firmware/throttle/tests/features/step_definitions/test.cpp +++ b/firmware/throttle/tests/features/step_definitions/test.cpp @@ -1,7 +1,10 @@ // include source files to prevent step files from conflicting with each other -#include "common.cpp" +#include "setup.cpp" + +#include "../../common/testing/step_definitions/common.cpp" +#include "../../common/testing/step_definitions/vcm.cpp" +#include "../../common/testing/step_definitions/fault_checking.cpp" + #include "checking_faults.cpp" #include "receiving_messages.cpp" #include "sending_reports.cpp" - -#include "../../common/testing/step_definitions/fault_checking.cpp" From da625e54395e43d03485f785b648b8e48bb66709 Mon Sep 17 00:00:00 2001 From: Adrien Thebo Date: Mon, 12 Feb 2018 11:40:34 -0800 Subject: [PATCH 08/80] testing: Don't expose fault origin id in fault checking tests --- .../tests/features/checking_faults.feature | 4 +-- .../tests/features/step_definitions/setup.cpp | 23 ++++++++++++ .../tests/features/checking_faults.feature | 4 +-- .../tests/features/step_definitions/setup.cpp | 35 ++++++++++++++++++- .../step_definitions/fault_checking.cpp | 8 ++--- .../tests/features/checking_faults.feature | 4 +-- .../tests/features/step_definitions/setup.cpp | 23 ++++++++++++ .../tests/features/checking_faults.feature | 4 +-- .../tests/features/step_definitions/setup.cpp | 23 ++++++++++++ 9 files changed, 113 insertions(+), 15 deletions(-) diff --git a/firmware/brake/kia_soul_ev_niro/tests/features/checking_faults.feature b/firmware/brake/kia_soul_ev_niro/tests/features/checking_faults.feature index 46a8a5f8..aa766aa7 100644 --- a/firmware/brake/kia_soul_ev_niro/tests/features/checking_faults.feature +++ b/firmware/brake/kia_soul_ev_niro/tests/features/checking_faults.feature @@ -12,7 +12,7 @@ Feature: Checking for faults When a sensor is grounded for 200 ms Then control should be disabled - And a fault report should be published with origin ID 0 + And a fault report should be published Scenario Outline: Operator override @@ -21,7 +21,7 @@ Feature: Checking for faults When the operator applies to the brake pedal for 200 ms Then control should be disabled - And a fault report should be published with origin ID 0 + And a fault report should be published Examples: | sensor_val | diff --git a/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/setup.cpp b/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/setup.cpp index 8ceafaf6..83b41502 100644 --- a/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/setup.cpp +++ b/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/setup.cpp @@ -1,9 +1,32 @@ #include "communications.h" #include "brake_control.h" #include "can_protocols/brake_can_protocol.h" +#include "can_protocols/fault_can_protocol.h" #include "globals.h" + +/** Define the module name under test + * + * In order to implement reusable test fixtures and steps, those fixtures + * need the name of the module under test defined. + * + * \sa firmware/common/testing/step_definitions/common.cpp + */ #define FIRMWARE_NAME "brake" + + +/** Define aliases to the brake control state + * + * \sa firmware/common/testing/step_definitions/fault_checking.cpp + */ #define g_vcm_control_state g_brake_control_state + extern volatile brake_control_state_s g_brake_control_state; + + +/** Define the origin ID that brake faults should be associated with + * + * \sa firmware/common/testing/step_definitions/fault_checking.cpp + */ +const int MODULE_FAULT_ORIGIN_ID = FAULT_ORIGIN_BRAKE; diff --git a/firmware/brake/kia_soul_petrol/tests/features/checking_faults.feature b/firmware/brake/kia_soul_petrol/tests/features/checking_faults.feature index f43e008a..3abe2197 100644 --- a/firmware/brake/kia_soul_petrol/tests/features/checking_faults.feature +++ b/firmware/brake/kia_soul_petrol/tests/features/checking_faults.feature @@ -21,7 +21,7 @@ Feature: Timeouts and overrides When a sensor is grounded for 200 ms Then control should be disabled - And a fault report should be published with origin ID 0 + And a fault report should be published Scenario Outline: Operator override @@ -30,7 +30,7 @@ Feature: Timeouts and overrides When the operator applies to the brake pedal for 200 ms Then control should be disabled - And a fault report should be published with origin ID 0 + And a fault report should be published Examples: | sensor_val | diff --git a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/setup.cpp b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/setup.cpp index 21af4a00..db248054 100644 --- a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/setup.cpp +++ b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/setup.cpp @@ -1,12 +1,45 @@ #include "communications.h" #include "brake_control.h" #include "can_protocols/brake_can_protocol.h" +#include "can_protocols/fault_can_protocol.h" #include "vehicles.h" #include "globals.h" -extern volatile brake_control_state_s g_brake_control_state; +/** Define the module name under test + * + * In order to implement reusable test fixtures and steps, those fixtures + * need the name of the module under test defined. + * + * \sa firmware/common/testing/step_definitions/common.cpp + */ #define FIRMWARE_NAME "brake" + + +/** Define aliases to the brake control state + * + * \sa firmware/common/testing/step_definitions/fault_checking.cpp + */ #define g_vcm_control_state g_brake_control_state + +/** Match the oscc module fault checking naming convention + * + * The other oscc modules define a `check_for_faults()` function, but the + * petrol brake module doesn't match that convention. In order to reuse the + * common testing step definitions we define this function-like macro to + * mask this variation. + * + * \sa firmware/common/testing/step_definitions/fault_checking.cpp + */ #define check_for_faults() (check_for_sensor_faults()) + + +extern volatile brake_control_state_s g_brake_control_state; + + +/** Define the origin ID that brake faults should be associated with + * + * \sa firmware/common/testing/step_definitions/fault_checking.cpp + */ +const int MODULE_FAULT_ORIGIN_ID = FAULT_ORIGIN_BRAKE; diff --git a/firmware/common/testing/step_definitions/fault_checking.cpp b/firmware/common/testing/step_definitions/fault_checking.cpp index e4c10093..88b029aa 100644 --- a/firmware/common/testing/step_definitions/fault_checking.cpp +++ b/firmware/common/testing/step_definitions/fault_checking.cpp @@ -1,7 +1,5 @@ #pragma once -// fault_checking.cpp - WHEN("^a sensor is grounded for (\\d+) ms$") { REGEX_PARAM(int, duration); @@ -16,10 +14,8 @@ WHEN("^a sensor is grounded for (\\d+) ms$") check_for_faults(); } -THEN("^a fault report should be published with origin ID (\\d+)$") +THEN("^a fault report should be published$") { - REGEX_PARAM(int, fault_origin_id); - assert_that(g_mock_mcp_can_send_msg_buf_id, is_equal_to(OSCC_FAULT_REPORT_CAN_ID)); assert_that(g_mock_mcp_can_send_msg_buf_ext, is_equal_to(CAN_STANDARD)); assert_that(g_mock_mcp_can_send_msg_buf_len, is_equal_to(OSCC_FAULT_REPORT_CAN_DLC)); @@ -37,5 +33,5 @@ THEN("^a fault report should be published with origin ID (\\d+)$") assert_that( fault_report->fault_origin_id, - is_equal_to(fault_origin_id)); + is_equal_to(MODULE_FAULT_ORIGIN_ID)); } diff --git a/firmware/steering/tests/features/checking_faults.feature b/firmware/steering/tests/features/checking_faults.feature index 0c364b3d..e435302a 100644 --- a/firmware/steering/tests/features/checking_faults.feature +++ b/firmware/steering/tests/features/checking_faults.feature @@ -12,7 +12,7 @@ Feature: Checking for faults When a sensor is grounded for 200 ms Then control should be disabled - And a fault report should be published with origin ID 1 + And a fault report should be published Scenario Outline: Operator override @@ -21,7 +21,7 @@ Feature: Checking for faults When the operator applies to the steering wheel Then control should be disabled - And a fault report should be published with origin ID 1 + And a fault report should be published Examples: | sensor_val | diff --git a/firmware/steering/tests/features/step_definitions/setup.cpp b/firmware/steering/tests/features/step_definitions/setup.cpp index 8cfbd715..00851938 100644 --- a/firmware/steering/tests/features/step_definitions/setup.cpp +++ b/firmware/steering/tests/features/step_definitions/setup.cpp @@ -1,9 +1,32 @@ #include "communications.h" #include "steering_control.h" #include "can_protocols/steering_can_protocol.h" +#include "can_protocols/fault_can_protocol.h" #include "globals.h" + +/** Define the module name under test + * + * In order to implement reusable test fixtures and steps, those fixtures + * need the name of the module under test defined. + * + * \sa firmware/common/testing/step_definitions/common.cpp + */ #define FIRMWARE_NAME "steering" + + +/** Define aliases to the steering control state + * + * \sa firmware/common/testing/step_definitions/fault_checking.cpp + */ #define g_vcm_control_state g_steering_control_state + extern volatile steering_control_state_s g_steering_control_state; + + +/** Define the origin ID that steering faults should be associated with + * + * \sa firmware/common/testing/step_definitions/fault_checking.cpp + */ +const int MODULE_FAULT_ORIGIN_ID = FAULT_ORIGIN_STEERING; diff --git a/firmware/throttle/tests/features/checking_faults.feature b/firmware/throttle/tests/features/checking_faults.feature index 912f275f..f710d43b 100644 --- a/firmware/throttle/tests/features/checking_faults.feature +++ b/firmware/throttle/tests/features/checking_faults.feature @@ -11,7 +11,7 @@ Feature: Checking for faults When a sensor is grounded for 200 ms Then control should be disabled - And a fault report should be published with origin ID 2 + And a fault report should be published Scenario Outline: Operator override @@ -20,7 +20,7 @@ Feature: Checking for faults When the operator applies to the accelerator for 200 ms Then control should be disabled - And a fault report should be published with origin ID 2 + And a fault report should be published Examples: | sensor_val | diff --git a/firmware/throttle/tests/features/step_definitions/setup.cpp b/firmware/throttle/tests/features/step_definitions/setup.cpp index 5de38dcc..a1827703 100644 --- a/firmware/throttle/tests/features/step_definitions/setup.cpp +++ b/firmware/throttle/tests/features/step_definitions/setup.cpp @@ -1,9 +1,32 @@ #include "communications.h" #include "throttle_control.h" #include "can_protocols/throttle_can_protocol.h" +#include "can_protocols/fault_can_protocol.h" #include "globals.h" + +/** Define the module name under test + * + * In order to implement reusable test fixtures and steps, those fixtures + * need the name of the module under test defined. + * + * \sa firmware/common/testing/step_definitions/common.cpp + */ #define FIRMWARE_NAME "throttle" + + +/** Define aliases to the throttle control state + * + * \sa firmware/common/testing/step_definitions/fault_checking.cpp + */ #define g_vcm_control_state g_throttle_control_state + extern volatile throttle_control_state_s g_throttle_control_state; + + +/** Define the origin ID that throttle faults should be associated with + * + * \sa firmware/common/testing/step_definitions/fault_checking.cpp + */ +const int MODULE_FAULT_ORIGIN_ID = FAULT_ORIGIN_THROTTLE; From 18581efe28ae136ccf296cd47db09fc10ee31e73 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Wed, 21 Feb 2018 11:27:33 -0800 Subject: [PATCH 09/80] Add auto detection Prior to this commit dual channel support did not include any form of auto detection requiring the user to determine which can channels belonged to OSCC and Vehicle CAN. This commit fixes that by adding auto detection for all CAN channels and for the already existing oscc_open for backwards compatibility. --- api/include/oscc.h | 14 +- api/src/internal/oscc.h | 65 ++++-- api/src/oscc.c | 456 ++++++++++++++++++++++------------------ 3 files changed, 293 insertions(+), 242 deletions(-) diff --git a/api/include/oscc.h b/api/include/oscc.h index 01a65e19..704a91b0 100644 --- a/api/include/oscc.h +++ b/api/include/oscc.h @@ -32,7 +32,7 @@ typedef enum * @return OSCC_ERROR or OSCC_OK * */ -oscc_result_t oscc_open(); +oscc_result_t oscc_init(); /** * @brief Use provided CAN channel to open communications to CAN bus connected @@ -46,18 +46,6 @@ oscc_result_t oscc_open(); */ oscc_result_t oscc_open( unsigned int channel ); -/** - * @brief Initializes connection to the specified CAN channels for OSCC control - * and vehicle CAN for feedback. - * - * @param [in] oscc_channel - CAN channel connected to OSCC modules. - * @param [in] vehicle_channel - CAN channel connected to OSCC modules. - * - * @return OSCC_ERROR or OSCC_OK - * - */ -oscc_result_t oscc_open( const char * const oscc_channel, - const char * const vehicle_channel ); /** * @brief Use provided CAN channel to close communications diff --git a/api/src/internal/oscc.h b/api/src/internal/oscc.h index c201f94e..b0668af4 100644 --- a/api/src/internal/oscc.h +++ b/api/src/internal/oscc.h @@ -8,9 +8,19 @@ #define _OSCC_INTERNAL_H #include +#include #define CONSTRAIN(amt, low, high) ((amt) < (low) ? (low) : ((amt) > (high) ? (high) : (amt))) +struct can_contains { + bool is_oscc; + bool has_vehicle; +}can_contains_s; + +struct device_name { + struct device_name *next, *prev; + char name[IFNAMSIZ]; +}; void (*brake_report_callback)( oscc_brake_report_s *report ); @@ -27,21 +37,11 @@ void (*fault_report_callback)( void (*obd_frame_callback)( struct can_frame *frame ); - -oscc_result_t oscc_init_can( - const char *can_channel ); - -oscc_result_t vehicle_init_can( - const char *can_channel ); - oscc_result_t oscc_can_write( long id, void *msg, unsigned int dlc ); -oscc_result_t oscc_async_enable( - int socket ); - oscc_result_t oscc_enable_brakes( void ); @@ -62,18 +62,45 @@ oscc_result_t oscc_disable_throttle( void oscc_update_status( ); -//These are all detection function for determining CAN signals -//Might be worth putting in their own location... +oscc_result_t register_can_signal(); -struct dev_name { - struct dev_name *next, *prev; - char name[IFNAMSIZ]; -}; +// Enables asynchronous callback to each socket should be started after all +// connections are made +oscc_result_t oscc_async_enable( + int socket ); + +// Runs a calback function through all available socketcan signals +oscc_result_t oscc_search_can( oscc_result_t(*search_callback)( const char * )); + +// Auto detects OSCC CAN and Vehicle CAN depending on OSCC CAN returned IDs +oscc_result_t auto_init_all_can( const char *can_channel ); + +// Auto detects Vehicle CAN based on vehicle header CAN IDs +oscc_result_t auto_init_vehicle_can( const char *can_channel ); + +// Initializes the OSCC CAN +oscc_result_t init_oscc_can( + const char *can_channel ); + +// Initializes the vehicle can with vehicle header CAN IDs +oscc_result_t init_vehicle_can( + const char *can_channel ); + +// Returns socket id after initiating a socketcan connection +int init_can_socket( const char *can_channel, + struct can_filter *filter ); + +// Determines if the CAN channel contains OSCC data and/or Vehicle CAN IDs +struct can_contains can_detection( const char *can_channel ); -char * get_dev_name(char *string); +// Constructs a list of all can and vcan devices +oscc_result_t construct_interfaces_list(struct device_name * const list_ptr); -oscc_result_t add_dev_name(const char * const name, struct dev_name * const list_ptr); +// Gets the device name from a line of /proc/net/dev data +char * get_device_name(char *string); -oscc_result_t construct_interfaces_list(struct dev_name * const list_ptr); +// Adds a device to a linked list of devices +oscc_result_t add_device_name(const char * const name, + struct device_name * const list_ptr); #endif /* _OSCC_INTERNAL_H */ diff --git a/api/src/oscc.c b/api/src/oscc.c index 00e09eba..77c1e6ce 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -19,39 +19,9 @@ static int oscc_can_socket = -1; static int vehicle_can_socket = -1; -static uint64_t dummy_counter = 0; -oscc_result_t oscc_open() -{ - oscc_result_t result = OSCC_ERROR; - - result = register_can_signal(); - - if( retsult != OSCC_ERROR ) - { - static struct dev_name *dev_list, temp_ptr; - dev_list = malloc(sizeof(struct dev_name)); - - ret = construct_interfaces_list(dev_list); - - temp_ptr = dev_list; - - do - { - if (strstr(temp_ptr->name,"can") != NULL) - { - printf("%s\n", temp_ptr->name); - //Check and assign if OSCC CAN - //Check and assign if Vehicle CAN - } - - temp_ptr = temp_ptr->next; - }while(temp_ptr != dev_list); - } - -} -oscc_result_t oscc_open( unsigned int channel ) +oscc_result_t oscc_init() { oscc_result_t result = OSCC_ERROR; @@ -59,52 +29,79 @@ oscc_result_t oscc_open( unsigned int channel ) if( result != OSCC_ERROR ) { - char can_string_buffer[16]; - - snprintf( can_string_buffer, 16, "can%u", channel ); + result = oscc_search_can( &auto_init_all_can ); + } - printf( "Opening CAN channel: %s\n", can_string_buffer ); + if ( oscc_can_socket > 0 ) + { + result = oscc_async_enable( oscc_can_socket ); + } + else + { + printf( "Error could not find OSCC CAN signal\n" ); + result = OSCC_ERROR; + } - result = oscc_init_can( can_string_buffer ); + if ( result == OSCC_OK && vehicle_can_socket > 0 ) + { + oscc_async_enable( vehicle_can_socket ); } - //If no vehicle CAN through OSCC add CAN detection here for second channel... - //Warn if no vehicle CAN is found. return result; } -oscc_result_t oscc_open( const char * const oscc_channel, - const char * const vehicle_channel ) +oscc_result_t oscc_open( unsigned int channel ) { oscc_result_t result = OSCC_ERROR; result = register_can_signal(); + struct can_contains channel_contents; + + char can_string_buffer[16]; + if( result != OSCC_ERROR ) { - char can_string_buffer[16]; + snprintf( can_string_buffer, 16, "can%u", channel ); - snprintf( can_string_buffer, 16, oscc_channel ); + channel_contents = can_detection( can_string_buffer ); + } + + if( result != OSCC_ERROR && !channel_contents.has_vehicle ) + { + int vehicle_ret = OSCC_ERROR; - printf( "Opening CAN channel: %s\n", can_string_buffer ); + vehicle_ret = oscc_search_can( &auto_init_vehicle_can ); - result = oscc_init_can( can_string_buffer ); + if( vehicle_ret != OSCC_OK ) + { + printf( "Warning Vehicle CAN not found.\n" ); + } } - if(result != OSCC_ERROR) + if( result != OSCC_ERROR) { - char veh_can_string_buffer[16]; - - snprintf( veh_can_string_buffer, 16, vehicle_can ); + result = init_oscc_can( can_string_buffer ); + } - printf( "Opening CAN channel: %s\n", veh_can_string_buffer ); + if ( result != OSCC_ERROR && oscc_can_socket >= 0 ) + { + result = oscc_async_enable( oscc_can_socket ); + } + else + { + printf( "Error could not find OSCC CAN signal.\n" ); + } - result = vehicle_init_can( veh_can_string_buffer ); + if ( result != OSCC_ERROR && vehicle_can_socket >= 0 ) + { + oscc_async_enable( vehicle_can_socket ); } return result; -}; +} + oscc_result_t oscc_close( unsigned int channel ) { @@ -554,6 +551,24 @@ oscc_result_t oscc_can_write( long id, void *msg, unsigned int dlc ) return result; } + +oscc_result_t register_can_signal() +{ + int result = OSCC_ERROR; + struct sigaction sig; + memset( &sig, 0, sizeof(sig) ); + sigemptyset( &sig.sa_mask ); + sig.sa_sigaction = oscc_update_status; + sig.sa_flags = SA_SIGINFO; + if( sigaction( SIGIO, &sig, NULL ) == 0 ) + { + result = OSCC_OK; + } + + return result; +} + + oscc_result_t oscc_async_enable( int socket ) { oscc_result_t result = OSCC_ERROR; @@ -587,157 +602,139 @@ oscc_result_t oscc_async_enable( int socket ) return result; } -oscc_result_t register_can_signal() + +oscc_result_t oscc_search_can( oscc_result_t(*search_callback)( const char * )) { - int result = OSCC_ERROR; - struct sigaction sig; - memset( &sig, 0, sizeof(sig) ); - sigemptyset( &sig.sa_mask ); - sig.sa_sigaction = oscc_update_status; - sig.sa_flags = SA_SIGINFO; - if( sigaction( SIGIO, &sig, NULL ) == 0 ) - { - result = OSCC_OK; - } + oscc_result_t result = OSCC_ERROR; - return result; -} + static struct device_name *dev_list, *temp_ptr; + dev_list = malloc(sizeof(struct device_name)); -oscc_result_t oscc_init_can( const char *can_channel ) -{ - int result = OSCC_ERROR; - int ret = -1; + result = construct_interfaces_list(dev_list); - int sock = socket( PF_CAN, SOCK_RAW, CAN_RAW ); + temp_ptr = dev_list; - if ( sock < 0 ) - { - printf( "Opening CAN socket failed: %s\n", strerror(errno) ); - } - else + do { - result = OSCC_OK; - } + if (strstr(temp_ptr->name,"can") != NULL) + { + search_callback( temp_ptr->name ); + } + temp_ptr = temp_ptr->next; + }while(temp_ptr != dev_list); - struct ifreq ifr; - memset( &ifr, 0, sizeof(ifr) ); + return result; +} - if ( result == OSCC_OK ) - { - strncpy( ifr.ifr_name, can_channel, IFNAMSIZ ); - ret = ioctl( sock, SIOCGIFINDEX, &ifr ); +oscc_result_t auto_init_all_can( const char *can_channel ) +{ + //Default to ok for the case of other CAN signals that are not OSCC related + int result = OSCC_OK; - if ( ret < 0 ) - { - printf( "Finding CAN index failed: %s\n", strerror(errno) ); + struct can_contains contents = can_detection( can_channel ); - result = OSCC_ERROR; - } - } + if( contents.is_oscc ) + { + printf( "Found an OSCC CAN...\n" ); + result = init_oscc_can( can_channel ); + } + else if( contents.has_vehicle ) + { + result = init_vehicle_can( can_channel ); + } + return result; +} - if ( result == OSCC_OK ) - { - struct sockaddr_can can_address; - memset( &can_address, 0, sizeof(can_address) ); - can_address.can_family = AF_CAN; - can_address.can_ifindex = ifr.ifr_ifindex; +oscc_result_t auto_init_vehicle_can( const char *can_channel ) +{ + //Default to ok for the case of other CAN signals that are not OSCC related + int result = OSCC_OK; - ret = bind( - sock, - (struct sockaddr *) &can_address, - sizeof(can_address) ); + struct can_contains contents = can_detection( can_channel ); - if ( ret < 0 ) - { - printf( "Socket binding failed: %s\n", strerror(errno) ); + if( contents.has_vehicle ) + { + result = init_vehicle_can( can_channel ); + } - result = OSCC_ERROR; - } - } + return result; +} - if ( result == OSCC_OK ) - { - ret = oscc_async_enable( sock ); +oscc_result_t init_oscc_can( const char *can_channel ) +{ + int result = OSCC_ERROR; - if ( ret != OSCC_OK ) - { - printf( "Enabling asynchronous socket I/O failed\n" ); + printf( "Assigning OSCC CAN Channel to: %s\n", can_channel ); - result = OSCC_ERROR; - } + oscc_can_socket = init_can_socket( can_channel, NULL ); + + if( oscc_can_socket >= 0 ) + { + result = OSCC_OK; } + return result; +} - if ( result == OSCC_OK ) - { - /* all prior checks will pass even if a valid interface has not been - set up - attempt to write an empty CAN frame to the interface to see - if it is valid */ - struct can_frame tx_frame; - memset( &tx_frame, 0, sizeof(tx_frame) ); - tx_frame.can_id = 0; - tx_frame.can_dlc = 8; +oscc_result_t init_vehicle_can( const char *can_channel ) +{ + int result = OSCC_ERROR; - int bytes_written = write( sock, &tx_frame, sizeof(tx_frame) ); + printf( "Assigning Vehicle CAN Channel to: %s\n", can_channel ); - if ( bytes_written < 0 ) - { - printf( "Failed to write test frame to %s: %s\n", can_channel, strerror(errno) ); + struct can_filter rfilter[4]; - result = OSCC_ERROR; - } - else - { - oscc_can_socket = sock; - } - } + rfilter[0].can_id = KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID; + rfilter[0].can_mask = CAN_SFF_MASK; + rfilter[1].can_id = KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID; + rfilter[1].can_mask = CAN_SFF_MASK; + rfilter[2].can_id = KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID; + rfilter[2].can_mask = CAN_SFF_MASK; + + vehicle_can_socket = init_can_socket( can_channel, rfilter ); + if(vehicle_can_socket >= 0) + { + result = OSCC_OK; + } return result; } -oscc_result_t vehicle_init_can( const char *can_channel ) + +int init_can_socket( const char *can_channel, + struct can_filter *filter ) { - int result = OSCC_ERROR; - int ret = -1; + int valid = -1; + int sock = -1; + struct ifreq ifr; + memset( &ifr, 0, sizeof(ifr) ); - int sock = socket( PF_CAN, SOCK_RAW, CAN_RAW ); + sock = socket( PF_CAN, SOCK_RAW, CAN_RAW ); if ( sock < 0 ) { printf( "Opening CAN socket failed: %s\n", strerror(errno) ); } else - { - result = OSCC_OK; - } - - - struct ifreq ifr; - memset( &ifr, 0, sizeof(ifr) ); - - if ( result == OSCC_OK ) { strncpy( ifr.ifr_name, can_channel, IFNAMSIZ ); - ret = ioctl( sock, SIOCGIFINDEX, &ifr ); + valid = ioctl( sock, SIOCGIFINDEX, &ifr ); - if ( ret < 0 ) + if ( valid < 0 ) { printf( "Finding CAN index failed: %s\n", strerror(errno) ); - - result = OSCC_ERROR; } } - - if ( result == OSCC_OK ) + if ( valid >= 0 ) { struct sockaddr_can can_address; @@ -745,63 +742,127 @@ oscc_result_t vehicle_init_can( const char *can_channel ) can_address.can_family = AF_CAN; can_address.can_ifindex = ifr.ifr_ifindex; - ret = bind( + valid = bind( sock, (struct sockaddr *) &can_address, sizeof(can_address) ); - if ( ret < 0 ) + if ( valid < 0 ) { printf( "Socket binding failed: %s\n", strerror(errno) ); - - result = OSCC_ERROR; } } - struct can_filter rfilter[4]; + if( (valid >= 0) && (filter != NULL) ) + { + setsockopt(sock, SOL_CAN_RAW, CAN_RAW_FILTER, &filter, sizeof(filter)); + } - rfilter[0].can_id = KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID; - rfilter[0].can_mask = CAN_SFF_MASK; - rfilter[1].can_id = KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID; - rfilter[1].can_mask = CAN_SFF_MASK; - rfilter[2].can_id = KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID; - rfilter[2].can_mask = CAN_SFF_MASK; - rfilter[2].can_id = KIA_SOUL_OBD_VEHICLE_SPEED_CAN_ID; - rfilter[2].can_mask = CAN_SFF_MASK; + // If it's invalid close the connection before bailing out... + if( valid < 0 ) + { + close( sock ); + sock = -1; + } + return sock; +} - setsockopt(sock, SOL_CAN_RAW, CAN_RAW_FILTER, &rfilter, sizeof(rfilter)); +struct can_contains can_detection( const char *can_channel ) +{ + int sock = init_can_socket(can_channel, NULL ); - if ( result == OSCC_OK ) + int i = 0; + struct can_contains detection = { - ret = oscc_async_enable( sock ); - - if ( ret != OSCC_OK ) - { - printf( "Enabling asynchronous socket I/O failed\n" ); + .is_oscc = false, + .has_vehicle = false + }; - result = OSCC_ERROR; - } + for(i=0; i < 10; i++) + { + struct can_frame rx_frame; + memset( &rx_frame, 0, sizeof(rx_frame) ); + int recv_bytes = 0; + fd_set read_set; + FD_ZERO(&read_set); + FD_SET(sock, &read_set); + + // Set timeout to 1.0 seconds + struct timeval timeout; + timeout.tv_sec = 0; + timeout.tv_usec = 500; + + setsockopt(sock, SOL_SOCKET, SO_RCVTIMEO, &timeout, sizeof(timeout)); + + recv_bytes = read(sock, &rx_frame, sizeof(rx_frame)); + + switch (recv_bytes) { + case CAN_MTU: + case CANFD_MTU: + if((rx_frame.can_id == OSCC_BRAKE_REPORT_CAN_ID || + rx_frame.can_id == OSCC_THROTTLE_REPORT_CAN_ID || + rx_frame.can_id == OSCC_STEERING_REPORT_CAN_ID) && + rx_frame.data[0] == OSCC_MAGIC_BYTE_0 && + rx_frame.data[1] == OSCC_MAGIC_BYTE_1 ) + { + detection.is_oscc = true; + } + if(rx_frame.can_id == KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID || + rx_frame.can_id == KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID || + rx_frame.can_id == KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID ) + { + detection.has_vehicle = true; + } + case -1: + if (EINTR == errno) + continue; + default: + continue; + } } + close(sock); - if ( result == OSCC_OK ) - { - vehicle_can_socket = sock; - } + return detection; +} - return result; +oscc_result_t construct_interfaces_list(struct device_name * const list_ptr) +{ + FILE *fh; + char buffer[512]; + oscc_result_t ret = OSCC_ERROR; + + fh = fopen("/proc/net/dev", "r"); + if (!fh) { + fprintf(stderr, + "Cannot read: /proc/net/dev (%s).\n", + strerror(errno)); + return -2; + } + + //Consume the first two lines since they are headers + fgets(buffer, sizeof buffer, fh); + fgets(buffer, sizeof buffer, fh); + + while (fgets(buffer, sizeof buffer, fh)) { + char *socket_name; + socket_name = get_device_name(buffer); + ret = add_device_name(socket_name, list_ptr); + } + + return ret; } -//Might want to put these CAN detection functions in their own library... -char * get_dev_name(char *string) +char * get_device_name(char *string) { size_t span = strcspn(string, ":"); static char temp_name[IFNAMSIZ]; strncpy(temp_name, string, span); + temp_name[span] = '\0'; size_t leading_spaces = strspn(temp_name, " "); if(leading_spaces == 0) @@ -813,10 +874,12 @@ char * get_dev_name(char *string) strncpy(new_name, temp_name + leading_spaces, span - leading_spaces + 1); + new_name[span - leading_spaces] = '\0'; + return new_name; } -oscc_result_t add_dev_name(const char * const name, struct dev_name * const list_ptr) +oscc_result_t add_device_name(const char * const name, struct device_name * const list_ptr) { if(list_ptr == NULL){ fprintf(stderr, @@ -827,8 +890,8 @@ oscc_result_t add_dev_name(const char * const name, struct dev_name * const list if(strlen(list_ptr->name) != 0) { - struct dev_name * old_tail; - struct dev_name * new_name = malloc(sizeof(struct dev_name)); + struct device_name * old_tail; + struct device_name * new_name = malloc(sizeof(struct device_name)); strncpy(new_name->name, name, IFNAMSIZ); if(list_ptr->next == list_ptr){ @@ -848,30 +911,3 @@ oscc_result_t add_dev_name(const char * const name, struct dev_name * const list return OSCC_OK; } - -oscc_result_t construct_interfaces_list(struct dev_name * const list_ptr) -{ - FILE *fh; - char buffer[512]; - oscc_result_t ret = OSCC_ERROR; - - fh = fopen("/proc/net/dev", "r"); - if (!fh) { - fprintf(stderr, - "Cannot read: /proc/net/dev (%s).\n", - strerror(errno)); - return -2; - } - - //Consume the first two lines since they are headers - fgets(buffer, sizeof buffer, fh); - fgets(buffer, sizeof buffer, fh); - - while (fgets(buffer, sizeof buffer, fh)) { - char *socket_name; - socket_name = get_dev_name(buffer); - ret = add_dev_name(socket_name, list_ptr); - } - - return ret; -} From 34742dbbafb2a2014b6d5f28f26c539bd17c833a Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Wed, 21 Feb 2018 12:12:30 -0800 Subject: [PATCH 10/80] Fix formatting Prior to this commit the white space did not follow the OSCC code style standards. This commit fixes that by making the added code in this branch follow the correct code style. --- api/src/internal/oscc.h | 16 ++- api/src/oscc.c | 214 +++++++++++++++++++++------------------- 2 files changed, 117 insertions(+), 113 deletions(-) diff --git a/api/src/internal/oscc.h b/api/src/internal/oscc.h index b0668af4..29f775dd 100644 --- a/api/src/internal/oscc.h +++ b/api/src/internal/oscc.h @@ -70,7 +70,7 @@ oscc_result_t oscc_async_enable( int socket ); // Runs a calback function through all available socketcan signals -oscc_result_t oscc_search_can( oscc_result_t(*search_callback)( const char * )); +oscc_result_t oscc_search_can( oscc_result_t(*search_callback)( const char * ) ); // Auto detects OSCC CAN and Vehicle CAN depending on OSCC CAN returned IDs oscc_result_t auto_init_all_can( const char *can_channel ); @@ -79,12 +79,10 @@ oscc_result_t auto_init_all_can( const char *can_channel ); oscc_result_t auto_init_vehicle_can( const char *can_channel ); // Initializes the OSCC CAN -oscc_result_t init_oscc_can( - const char *can_channel ); +oscc_result_t init_oscc_can( const char *can_channel ); // Initializes the vehicle can with vehicle header CAN IDs -oscc_result_t init_vehicle_can( - const char *can_channel ); +oscc_result_t init_vehicle_can( const char *can_channel ); // Returns socket id after initiating a socketcan connection int init_can_socket( const char *can_channel, @@ -94,13 +92,13 @@ int init_can_socket( const char *can_channel, struct can_contains can_detection( const char *can_channel ); // Constructs a list of all can and vcan devices -oscc_result_t construct_interfaces_list(struct device_name * const list_ptr); +oscc_result_t construct_interfaces_list( struct device_name * const list_ptr ); // Gets the device name from a line of /proc/net/dev data -char * get_device_name(char *string); +char * get_device_name( char *string ); // Adds a device to a linked list of devices -oscc_result_t add_device_name(const char * const name, - struct device_name * const list_ptr); +oscc_result_t add_device_name( const char * const name, + struct device_name * const list_ptr ); #endif /* _OSCC_INTERNAL_H */ diff --git a/api/src/oscc.c b/api/src/oscc.c index 77c1e6ce..0eeeddc3 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -47,7 +47,6 @@ oscc_result_t oscc_init() oscc_async_enable( vehicle_can_socket ); } - return result; } @@ -70,19 +69,19 @@ oscc_result_t oscc_open( unsigned int channel ) if( result != OSCC_ERROR && !channel_contents.has_vehicle ) { - int vehicle_ret = OSCC_ERROR; + int vehicle_ret = OSCC_ERROR; - vehicle_ret = oscc_search_can( &auto_init_vehicle_can ); + vehicle_ret = oscc_search_can( &auto_init_vehicle_can ); - if( vehicle_ret != OSCC_OK ) - { - printf( "Warning Vehicle CAN not found.\n" ); - } + if( vehicle_ret != OSCC_OK ) + { + printf( "Warning Vehicle CAN not found.\n" ); + } } if( result != OSCC_ERROR) { - result = init_oscc_can( can_string_buffer ); + result = init_oscc_can( can_string_buffer ); } if ( result != OSCC_ERROR && oscc_can_socket >= 0 ) @@ -603,26 +602,26 @@ oscc_result_t oscc_async_enable( int socket ) } -oscc_result_t oscc_search_can( oscc_result_t(*search_callback)( const char * )) +oscc_result_t oscc_search_can( oscc_result_t(*search_callback)( const char * ) ) { - oscc_result_t result = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; static struct device_name *dev_list, *temp_ptr; - dev_list = malloc(sizeof(struct device_name)); + dev_list = malloc( sizeof( struct device_name ) ); - result = construct_interfaces_list(dev_list); + result = construct_interfaces_list( dev_list ); temp_ptr = dev_list; do { - if (strstr(temp_ptr->name,"can") != NULL) + if ( strstr( temp_ptr->name,"can" ) != NULL ) { search_callback( temp_ptr->name ); } temp_ptr = temp_ptr->next; - }while(temp_ptr != dev_list); + }while( temp_ptr != dev_list ); return result; } @@ -714,13 +713,13 @@ int init_can_socket( const char *can_channel, int valid = -1; int sock = -1; struct ifreq ifr; - memset( &ifr, 0, sizeof(ifr) ); + memset( &ifr, 0, sizeof( ifr ) ); sock = socket( PF_CAN, SOCK_RAW, CAN_RAW ); if ( sock < 0 ) { - printf( "Opening CAN socket failed: %s\n", strerror(errno) ); + printf( "Opening CAN socket failed: %s\n", strerror( errno ) ); } else { @@ -730,7 +729,7 @@ int init_can_socket( const char *can_channel, if ( valid < 0 ) { - printf( "Finding CAN index failed: %s\n", strerror(errno) ); + printf( "Finding CAN index failed: %s\n", strerror( errno ) ); } } @@ -738,24 +737,28 @@ int init_can_socket( const char *can_channel, { struct sockaddr_can can_address; - memset( &can_address, 0, sizeof(can_address) ); + memset( &can_address, 0, sizeof( can_address ) ); can_address.can_family = AF_CAN; can_address.can_ifindex = ifr.ifr_ifindex; valid = bind( sock, (struct sockaddr *) &can_address, - sizeof(can_address) ); + sizeof( can_address ) ); if ( valid < 0 ) { - printf( "Socket binding failed: %s\n", strerror(errno) ); + printf( "Socket binding failed: %s\n", strerror( errno ) ); } } if( (valid >= 0) && (filter != NULL) ) { - setsockopt(sock, SOL_CAN_RAW, CAN_RAW_FILTER, &filter, sizeof(filter)); + setsockopt( sock, + SOL_CAN_RAW, + CAN_RAW_FILTER, + &filter, + sizeof( filter ) ); } // If it's invalid close the connection before bailing out... @@ -771,7 +774,7 @@ int init_can_socket( const char *can_channel, struct can_contains can_detection( const char *can_channel ) { - int sock = init_can_socket(can_channel, NULL ); + int sock = init_can_socket( can_channel, NULL ); int i = 0; struct can_contains detection = @@ -783,131 +786,134 @@ struct can_contains can_detection( const char *can_channel ) for(i=0; i < 10; i++) { struct can_frame rx_frame; - memset( &rx_frame, 0, sizeof(rx_frame) ); + memset( &rx_frame, 0, sizeof( rx_frame ) ); int recv_bytes = 0; fd_set read_set; - FD_ZERO(&read_set); - FD_SET(sock, &read_set); + FD_ZERO( &read_set ); + FD_SET( sock, &read_set ); // Set timeout to 1.0 seconds struct timeval timeout; timeout.tv_sec = 0; timeout.tv_usec = 500; - setsockopt(sock, SOL_SOCKET, SO_RCVTIMEO, &timeout, sizeof(timeout)); + setsockopt( sock, SOL_SOCKET, SO_RCVTIMEO, &timeout, sizeof( timeout ) ); - recv_bytes = read(sock, &rx_frame, sizeof(rx_frame)); + recv_bytes = read( sock, &rx_frame, sizeof( rx_frame ) ); switch (recv_bytes) { case CAN_MTU: case CANFD_MTU: - if((rx_frame.can_id == OSCC_BRAKE_REPORT_CAN_ID || - rx_frame.can_id == OSCC_THROTTLE_REPORT_CAN_ID || - rx_frame.can_id == OSCC_STEERING_REPORT_CAN_ID) && - rx_frame.data[0] == OSCC_MAGIC_BYTE_0 && - rx_frame.data[1] == OSCC_MAGIC_BYTE_1 ) - { - detection.is_oscc = true; - } - if(rx_frame.can_id == KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID || - rx_frame.can_id == KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID || - rx_frame.can_id == KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID ) - { - detection.has_vehicle = true; - } + if( ( rx_frame.can_id == OSCC_BRAKE_REPORT_CAN_ID || + rx_frame.can_id == OSCC_THROTTLE_REPORT_CAN_ID || + rx_frame.can_id == OSCC_STEERING_REPORT_CAN_ID ) && + rx_frame.data[0] == OSCC_MAGIC_BYTE_0 && + rx_frame.data[1] == OSCC_MAGIC_BYTE_1 ) + { + detection.is_oscc = true; + } + if( rx_frame.can_id == KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID || + rx_frame.can_id == KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID || + rx_frame.can_id == KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID ) + { + detection.has_vehicle = true; + } case -1: - if (EINTR == errno) + if( EINTR == errno ) continue; default: continue; } } - close(sock); + close( sock ); return detection; } -oscc_result_t construct_interfaces_list(struct device_name * const list_ptr) +oscc_result_t construct_interfaces_list( struct device_name * const list_ptr ) { - FILE *fh; - char buffer[512]; - oscc_result_t ret = OSCC_ERROR; + FILE *fh; + char buffer[512]; + oscc_result_t ret = OSCC_ERROR; - fh = fopen("/proc/net/dev", "r"); - if (!fh) { - fprintf(stderr, - "Cannot read: /proc/net/dev (%s).\n", - strerror(errno)); - return -2; - } + fh = fopen( "/proc/net/dev", "r" ); + if (!fh) { + fprintf( stderr, + "Cannot read: /proc/net/dev (%s).\n", + strerror( errno ) ); - //Consume the first two lines since they are headers - fgets(buffer, sizeof buffer, fh); - fgets(buffer, sizeof buffer, fh); + return -2; + } - while (fgets(buffer, sizeof buffer, fh)) { - char *socket_name; - socket_name = get_device_name(buffer); - ret = add_device_name(socket_name, list_ptr); - } + //Consume the first two lines since they are headers + fgets( buffer, sizeof buffer, fh ); + fgets( buffer, sizeof buffer, fh ); - return ret; + while ( fgets( buffer, sizeof buffer, fh ) ) { + char *socket_name; + socket_name = get_device_name( buffer ); + ret = add_device_name( socket_name, list_ptr ); + } + + return ret; } -char * get_device_name(char *string) +char * get_device_name( char *string ) { - size_t span = strcspn(string, ":"); - static char temp_name[IFNAMSIZ]; - strncpy(temp_name, string, span); - temp_name[span] = '\0'; - size_t leading_spaces = strspn(temp_name, " "); + size_t span = strcspn(string, ":"); + static char temp_name[IFNAMSIZ]; + strncpy(temp_name, string, span); + temp_name[span] = '\0'; + size_t leading_spaces = strspn(temp_name, " "); - if(leading_spaces == 0) - { - return temp_name; - } + if(leading_spaces == 0) + { + return temp_name; + } - static char new_name[IFNAMSIZ]; + static char new_name[IFNAMSIZ]; - strncpy(new_name, temp_name + leading_spaces, span - leading_spaces + 1); + strncpy(new_name, temp_name + leading_spaces, span - leading_spaces + 1); - new_name[span - leading_spaces] = '\0'; + new_name[span - leading_spaces] = '\0'; - return new_name; + return new_name; } -oscc_result_t add_device_name(const char * const name, struct device_name * const list_ptr) +oscc_result_t add_device_name( const char * const name, + struct device_name * const list_ptr ) { - if(list_ptr == NULL){ - fprintf(stderr, - "dev list is uninitialized (%s)\n", - strerror(errno)); - return -1; - } + if( list_ptr == NULL ) + { + fprintf( stderr, + "dev list is uninitialized (%s)\n", + strerror( errno ) ); + return -1; + } - if(strlen(list_ptr->name) != 0) - { - struct device_name * old_tail; - struct device_name * new_name = malloc(sizeof(struct device_name)); - strncpy(new_name->name, name, IFNAMSIZ); + if(strlen(list_ptr->name) != 0) + { + struct device_name * old_tail; + struct device_name * new_name = malloc( sizeof( struct device_name ) ); + strncpy( new_name->name, name, IFNAMSIZ ); - if(list_ptr->next == list_ptr){ - list_ptr->next = new_name; - } - old_tail = list_ptr->prev; - old_tail->next = new_name; - new_name->prev = old_tail; - new_name->next = list_ptr; - list_ptr->prev = new_name; - } - else{ - strncpy(list_ptr->name, name, IFNAMSIZ); - list_ptr->prev = list_ptr; - list_ptr->next = list_ptr; - } + if( list_ptr->next == list_ptr ){ + list_ptr->next = new_name; + } + old_tail = list_ptr->prev; + old_tail->next = new_name; + new_name->prev = old_tail; + new_name->next = list_ptr; + list_ptr->prev = new_name; + } + else{ + strncpy( list_ptr->name, name, IFNAMSIZ ); + list_ptr->prev = list_ptr; + list_ptr->next = list_ptr; + } - return OSCC_OK; + return OSCC_OK; } From 1df5e009fe68921878c86bd67c1701902e1d9623 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Mon, 26 Feb 2018 11:50:28 -0800 Subject: [PATCH 11/80] Remove can filtering in detection Prior to this commit there was CAN filtering in the detection portion of the code. For unknown reasons this caused intermittent behavior where zero CAN messages would be returned yielding nothing being detected and requiring the user to close and restart the program. This commit fixes that by removing the filtering during detection and relying more heavily on the for loop to check which CAN IDs are included in the messages. --- api/include/oscc.h | 11 ++ api/src/internal/oscc.h | 29 +++- api/src/oscc.c | 283 ++++++++++++++++++++++++---------------- 3 files changed, 201 insertions(+), 122 deletions(-) diff --git a/api/include/oscc.h b/api/include/oscc.h index 704a91b0..6ff8e58d 100644 --- a/api/include/oscc.h +++ b/api/include/oscc.h @@ -18,6 +18,17 @@ #include "vehicles.h" +/* + * @brief MAX_CAN_IDs is the maximum number unique CAN IDs on the CAN bus used + * for auto detection of CAN channels. Increasing this number increases the wait + * time for checking if a channel contains expected CAN IDs, reducing this + * number below number of CAN IDs broadcast could yield a false negative in auto + * detection. + * + */ +#define MAX_CAN_IDS ( 100 ) + + typedef enum { OSCC_OK, diff --git a/api/src/internal/oscc.h b/api/src/internal/oscc.h index 29f775dd..2e4afdb1 100644 --- a/api/src/internal/oscc.h +++ b/api/src/internal/oscc.h @@ -13,13 +13,25 @@ #define CONSTRAIN(amt, low, high) ((amt) < (low) ? (low) : ((amt) > (high) ? (high) : (amt))) struct can_contains { - bool is_oscc; - bool has_vehicle; + bool is_oscc; + bool has_vehicle; }can_contains_s; +struct vehicle_can_desc { + bool has_steering_angle; + bool has_brake_pressure; + bool has_wheel_speed; +}vehicle_can_desc_s; + +struct oscc_can_desc { + bool has_torqe_report; + bool has_steer_report; + bool has_brake_report; +}oscc_can_desc_s; + struct device_name { - struct device_name *next, *prev; - char name[IFNAMSIZ]; + struct device_name *next, *prev; + char name[IFNAMSIZ]; }; void (*brake_report_callback)( @@ -70,13 +82,15 @@ oscc_result_t oscc_async_enable( int socket ); // Runs a calback function through all available socketcan signals -oscc_result_t oscc_search_can( oscc_result_t(*search_callback)( const char * ) ); +oscc_result_t oscc_search_can( + struct can_contains(*search_callback)( const char * ), + bool search_oscc ); // Auto detects OSCC CAN and Vehicle CAN depending on OSCC CAN returned IDs -oscc_result_t auto_init_all_can( const char *can_channel ); +struct can_contains auto_init_all_can( const char *can_channel ); // Auto detects Vehicle CAN based on vehicle header CAN IDs -oscc_result_t auto_init_vehicle_can( const char *can_channel ); +struct can_contains auto_init_vehicle_can( const char *can_channel ); // Initializes the OSCC CAN oscc_result_t init_oscc_can( const char *can_channel ); @@ -86,6 +100,7 @@ oscc_result_t init_vehicle_can( const char *can_channel ); // Returns socket id after initiating a socketcan connection int init_can_socket( const char *can_channel, + struct timeval *tv, struct can_filter *filter ); // Determines if the CAN channel contains OSCC data and/or Vehicle CAN IDs diff --git a/api/src/oscc.c b/api/src/oscc.c index 0eeeddc3..67a3d5c4 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -5,6 +5,7 @@ #include #include #include +#include #include #include #include @@ -12,6 +13,7 @@ #include #include #include +#include #include "oscc.h" #include "internal/oscc.h" @@ -25,11 +27,11 @@ oscc_result_t oscc_init() { oscc_result_t result = OSCC_ERROR; - result = register_can_signal(); + result = oscc_search_can( &auto_init_all_can, true ); if( result != OSCC_ERROR ) { - result = oscc_search_can( &auto_init_all_can ); + result = register_can_signal(); } if ( oscc_can_socket > 0 ) @@ -54,28 +56,23 @@ oscc_result_t oscc_open( unsigned int channel ) { oscc_result_t result = OSCC_ERROR; - result = register_can_signal(); - struct can_contains channel_contents; char can_string_buffer[16]; - if( result != OSCC_ERROR ) - { - snprintf( can_string_buffer, 16, "can%u", channel ); + snprintf( can_string_buffer, 16, "can%u", channel ); - channel_contents = can_detection( can_string_buffer ); - } + channel_contents = can_detection( can_string_buffer ); if( result != OSCC_ERROR && !channel_contents.has_vehicle ) { int vehicle_ret = OSCC_ERROR; - vehicle_ret = oscc_search_can( &auto_init_vehicle_can ); + vehicle_ret = oscc_search_can( &auto_init_vehicle_can, false ); - if( vehicle_ret != OSCC_OK ) + if( (vehicle_can_socket < 0) || (vehicle_ret != OSCC_OK) ) { - printf( "Warning Vehicle CAN not found.\n" ); + printf( "Warning Vehicle CAN was not found.\n" ); } } @@ -84,6 +81,8 @@ oscc_result_t oscc_open( unsigned int channel ) result = init_oscc_can( can_string_buffer ); } + result = register_can_signal(); + if ( result != OSCC_ERROR && oscc_can_socket >= 0 ) { result = oscc_async_enable( oscc_can_socket ); @@ -542,7 +541,7 @@ oscc_result_t oscc_can_write( long id, void *msg, unsigned int dlc ) } else { - printf( "Could not write to socket: %s\n", strerror(errno) ); + perror( "Could not write to socket:" ); } } @@ -577,7 +576,7 @@ oscc_result_t oscc_async_enable( int socket ) if ( ret < 0 ) { - printf( "Setting owner process of socket failed: %s\n", strerror(errno) ); + perror( "Setting owner process of socket failed:" ); } else { @@ -591,7 +590,7 @@ oscc_result_t oscc_async_enable( int socket ) if ( ret < 0 ) { - printf( "Setting nonblocking asynchronous socket I/O failed: %s\n", strerror(errno) ); + perror( "Setting nonblocking asynchronous socket I/O failed:" ); result = OSCC_ERROR; } @@ -602,7 +601,8 @@ oscc_result_t oscc_async_enable( int socket ) } -oscc_result_t oscc_search_can( oscc_result_t(*search_callback)( const char * ) ) +oscc_result_t oscc_search_can( struct can_contains(*search_callback)( const char * ), + bool search_oscc ) { oscc_result_t result = OSCC_ERROR; @@ -611,56 +611,67 @@ oscc_result_t oscc_search_can( oscc_result_t(*search_callback)( const char * ) ) result = construct_interfaces_list( dev_list ); + //temp_contents is the temporary storage of the current CAN channel + //all_contents is the sum of all channels searched + struct can_contains temp_contents, all_contents; + + //Set the all_contents based search_oscc boolean in function call + all_contents.is_oscc = !search_oscc; + all_contents.has_vehicle = false; + temp_ptr = dev_list; do { - if ( strstr( temp_ptr->name,"can" ) != NULL ) - { - search_callback( temp_ptr->name ); - } + if ( strstr( temp_ptr->name, "can" ) != NULL ) + { + temp_contents = search_callback( temp_ptr->name ); + + all_contents.is_oscc |= temp_contents.is_oscc; + + all_contents.has_vehicle |= temp_contents.has_vehicle; - temp_ptr = temp_ptr->next; + //Leave the while loop if both requirements are met + if( all_contents.is_oscc && all_contents.has_vehicle ) + { + break; + } + } + + temp_ptr = temp_ptr->next; }while( temp_ptr != dev_list ); return result; } -oscc_result_t auto_init_all_can( const char *can_channel ) +struct can_contains auto_init_all_can( const char *can_channel ) { - //Default to ok for the case of other CAN signals that are not OSCC related - int result = OSCC_OK; - - struct can_contains contents = can_detection( can_channel ); + struct can_contains contents = can_detection( can_channel ); - if( contents.is_oscc ) - { - printf( "Found an OSCC CAN...\n" ); - result = init_oscc_can( can_channel ); - } - else if( contents.has_vehicle ) - { - result = init_vehicle_can( can_channel ); - } + if( contents.is_oscc ) + { + init_oscc_can( can_channel ); + } + else if( contents.has_vehicle ) + { + init_vehicle_can( can_channel ); + } - return result; + return contents; } -oscc_result_t auto_init_vehicle_can( const char *can_channel ) +struct can_contains auto_init_vehicle_can( const char *can_channel ) { - //Default to ok for the case of other CAN signals that are not OSCC related - int result = OSCC_OK; - - struct can_contains contents = can_detection( can_channel ); + struct can_contains contents = can_detection( can_channel ); - if( contents.has_vehicle ) - { - result = init_vehicle_can( can_channel ); - } + if( contents.has_vehicle ) + { + init_vehicle_can( can_channel ); + } - return result; + return contents; } @@ -670,11 +681,11 @@ oscc_result_t init_oscc_can( const char *can_channel ) printf( "Assigning OSCC CAN Channel to: %s\n", can_channel ); - oscc_can_socket = init_can_socket( can_channel, NULL ); + oscc_can_socket = init_can_socket( can_channel, NULL, NULL ); if( oscc_can_socket >= 0 ) { - result = OSCC_OK; + result = OSCC_OK; } return result; @@ -696,7 +707,7 @@ oscc_result_t init_vehicle_can( const char *can_channel ) rfilter[2].can_id = KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID; rfilter[2].can_mask = CAN_SFF_MASK; - vehicle_can_socket = init_can_socket( can_channel, rfilter ); + vehicle_can_socket = init_can_socket( can_channel, NULL, rfilter ); if(vehicle_can_socket >= 0) { @@ -708,6 +719,7 @@ oscc_result_t init_vehicle_can( const char *can_channel ) int init_can_socket( const char *can_channel, + struct timeval *tv, struct can_filter *filter ) { int valid = -1; @@ -719,7 +731,7 @@ int init_can_socket( const char *can_channel, if ( sock < 0 ) { - printf( "Opening CAN socket failed: %s\n", strerror( errno ) ); + perror( "Opening CAN socket failed:" ); } else { @@ -729,39 +741,60 @@ int init_can_socket( const char *can_channel, if ( valid < 0 ) { - printf( "Finding CAN index failed: %s\n", strerror( errno ) ); + perror( "Finding CAN index failed:" ); } } - if ( valid >= 0 ) + //If a timeout has been specified set one here since it should be set before + //the bind call + if( valid >= 0 && tv != NULL ) { - struct sockaddr_can can_address; - - memset( &can_address, 0, sizeof( can_address ) ); - can_address.can_family = AF_CAN; - can_address.can_ifindex = ifr.ifr_ifindex; - - valid = bind( - sock, - (struct sockaddr *) &can_address, - sizeof( can_address ) ); + valid = setsockopt( sock, + SOL_SOCKET, + SO_RCVTIMEO, + tv, + sizeof( struct timeval ) ); if ( valid < 0 ) { - printf( "Socket binding failed: %s\n", strerror( errno ) ); + perror( "Setting timeout failed:" ); } } + //If a filter has been specified set one here if( (valid >= 0) && (filter != NULL) ) { - setsockopt( sock, + int ret = setsockopt( sock, SOL_CAN_RAW, CAN_RAW_FILTER, &filter, sizeof( filter ) ); + + if ( valid < 0 ) + { + perror( "Setting filter failed:" ); + } } - // If it's invalid close the connection before bailing out... + if ( valid >= 0 ) + { + struct sockaddr_can can_address; + + memset( &can_address, 0, sizeof( can_address ) ); + can_address.can_family = AF_CAN; + can_address.can_ifindex = ifr.ifr_ifindex; + + valid = bind( sock, + (struct sockaddr *) &can_address, + sizeof( can_address ) ); + + if ( valid < 0 ) + { + perror( "Socket binding failed:" ); + } + } + + // Clean up resources and close the connection if it's invalid. if( valid < 0 ) { close( sock ); @@ -774,60 +807,84 @@ int init_can_socket( const char *can_channel, struct can_contains can_detection( const char *can_channel ) { - int sock = init_can_socket( can_channel, NULL ); + struct timeval timeout; + timeout.tv_sec = 0; + timeout.tv_usec = 75000; + + int sock = init_can_socket( can_channel, &timeout, NULL ); int i = 0; - struct can_contains detection = + + struct vehicle_can_desc vehicle_detection = { - .is_oscc = false, - .has_vehicle = false + .has_steering_angle = false, + .has_brake_pressure = false, + .has_wheel_speed = false }; - for(i=0; i < 10; i++) + struct oscc_can_desc oscc_detection = { - struct can_frame rx_frame; - memset( &rx_frame, 0, sizeof( rx_frame ) ); - int recv_bytes = 0; - fd_set read_set; - FD_ZERO( &read_set ); - FD_SET( sock, &read_set ); - - // Set timeout to 1.0 seconds - struct timeval timeout; - timeout.tv_sec = 0; - timeout.tv_usec = 500; - - setsockopt( sock, SOL_SOCKET, SO_RCVTIMEO, &timeout, sizeof( timeout ) ); - - recv_bytes = read( sock, &rx_frame, sizeof( rx_frame ) ); + .has_torqe_report = false, + .has_steer_report = false, + .has_brake_report = false + }; - switch (recv_bytes) { - case CAN_MTU: - case CANFD_MTU: - if( ( rx_frame.can_id == OSCC_BRAKE_REPORT_CAN_ID || - rx_frame.can_id == OSCC_THROTTLE_REPORT_CAN_ID || - rx_frame.can_id == OSCC_STEERING_REPORT_CAN_ID ) && - rx_frame.data[0] == OSCC_MAGIC_BYTE_0 && - rx_frame.data[1] == OSCC_MAGIC_BYTE_1 ) - { - detection.is_oscc = true; - } - if( rx_frame.can_id == KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID || - rx_frame.can_id == KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID || - rx_frame.can_id == KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID ) - { - detection.has_vehicle = true; - } - case -1: - if( EINTR == errno ) - continue; - default: - continue; - } + for( i = 0; i < MAX_CAN_IDS; i++ ) + { + struct can_frame rx_frame; + memset( &rx_frame, 0, sizeof( rx_frame ) ); + int recv_bytes = 0; + + recv_bytes = read( sock, &rx_frame, sizeof( rx_frame ) ); + + switch (recv_bytes) { + case CAN_MTU: + case CANFD_MTU: + oscc_detection.has_brake_report |= + ( (rx_frame.can_id == OSCC_BRAKE_REPORT_CAN_ID) && + (rx_frame.data[0] == OSCC_MAGIC_BYTE_0) && + (rx_frame.data[1] == OSCC_MAGIC_BYTE_1) ); + + oscc_detection.has_steer_report |= + ( (rx_frame.can_id == OSCC_STEERING_REPORT_CAN_ID) && + (rx_frame.data[0] == OSCC_MAGIC_BYTE_0) && + (rx_frame.data[1] == OSCC_MAGIC_BYTE_1) ); + + oscc_detection.has_torqe_report |= + ( (rx_frame.can_id == OSCC_THROTTLE_REPORT_CAN_ID) && + (rx_frame.data[0] == OSCC_MAGIC_BYTE_0) && + (rx_frame.data[1] == OSCC_MAGIC_BYTE_1) ); + + vehicle_detection.has_brake_pressure |= + ( rx_frame.can_id == KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID ); + + vehicle_detection.has_steering_angle |= + ( rx_frame.can_id == KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID ); + + vehicle_detection.has_wheel_speed |= + ( rx_frame.can_id == KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID ); + case -1: + if( EINTR == errno ) + { + continue; + } + default: + continue; + } } close( sock ); + struct can_contains detection = + { + .is_oscc = oscc_detection.has_brake_report && + oscc_detection.has_steer_report && + oscc_detection.has_torqe_report, + .has_vehicle = vehicle_detection.has_brake_pressure && + vehicle_detection.has_steering_angle && + vehicle_detection.has_wheel_speed + }; + return detection; } @@ -840,9 +897,7 @@ oscc_result_t construct_interfaces_list( struct device_name * const list_ptr ) fh = fopen( "/proc/net/dev", "r" ); if (!fh) { - fprintf( stderr, - "Cannot read: /proc/net/dev (%s).\n", - strerror( errno ) ); + perror( "Cannot read: /proc/net/dev" ); return -2; } @@ -888,13 +943,11 @@ oscc_result_t add_device_name( const char * const name, { if( list_ptr == NULL ) { - fprintf( stderr, - "dev list is uninitialized (%s)\n", - strerror( errno ) ); + perror( "list is uninitialized" ); return -1; } - if(strlen(list_ptr->name) != 0) + if( strlen( list_ptr->name ) != 0 ) { struct device_name * old_tail; struct device_name * new_name = malloc( sizeof( struct device_name ) ); From fe12e006e07bd249b1c3f7f8bce4ba5eedcfc35c Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Mon, 26 Feb 2018 12:24:35 -0800 Subject: [PATCH 12/80] Reduce wait time and total messages scanned Prior to this commit the detection took a while causing the user to wait long enough to wonder if the program hung. This commit fixes that by reducing the can message timeout and number of CAN IDs looked at to something more reasonable. The new timeout was calculated based on 500k baudrate at standard message sizes showing 6250 messages per second. The new CAN ID number was determined by number of messages on the CAN bus which was ~40 at a 40% bus load. --- api/include/oscc.h | 12 ++++++++++-- api/src/oscc.c | 29 ++++++++++++++--------------- 2 files changed, 24 insertions(+), 17 deletions(-) diff --git a/api/include/oscc.h b/api/include/oscc.h index 6ff8e58d..7cb50214 100644 --- a/api/include/oscc.h +++ b/api/include/oscc.h @@ -19,14 +19,22 @@ /* - * @brief MAX_CAN_IDs is the maximum number unique CAN IDs on the CAN bus used + * @brief MAX_CAN_IDS is the maximum number unique CAN IDs on the CAN bus used * for auto detection of CAN channels. Increasing this number increases the wait * time for checking if a channel contains expected CAN IDs, reducing this * number below number of CAN IDs broadcast could yield a false negative in auto * detection. * */ -#define MAX_CAN_IDS ( 100 ) +#define MAX_CAN_IDS ( 50 ) + + +/* + * @brief CAN_MESSAGE_TIMEOUT is the time to wait for a CAN message in + * miliseconds used for auto detection of can channels. + * + */ +#define CAN_MESSAGE_TIMEOUT ( 100 ) typedef enum diff --git a/api/src/oscc.c b/api/src/oscc.c index 67a3d5c4..14fbeac9 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -809,7 +809,7 @@ struct can_contains can_detection( const char *can_channel ) { struct timeval timeout; timeout.tv_sec = 0; - timeout.tv_usec = 75000; + timeout.tv_usec = CAN_MESSAGE_TIMEOUT; int sock = init_can_socket( can_channel, &timeout, NULL ); @@ -840,20 +840,19 @@ struct can_contains can_detection( const char *can_channel ) switch (recv_bytes) { case CAN_MTU: case CANFD_MTU: - oscc_detection.has_brake_report |= - ( (rx_frame.can_id == OSCC_BRAKE_REPORT_CAN_ID) && - (rx_frame.data[0] == OSCC_MAGIC_BYTE_0) && - (rx_frame.data[1] == OSCC_MAGIC_BYTE_1) ); - - oscc_detection.has_steer_report |= - ( (rx_frame.can_id == OSCC_STEERING_REPORT_CAN_ID) && - (rx_frame.data[0] == OSCC_MAGIC_BYTE_0) && - (rx_frame.data[1] == OSCC_MAGIC_BYTE_1) ); - - oscc_detection.has_torqe_report |= - ( (rx_frame.can_id == OSCC_THROTTLE_REPORT_CAN_ID) && - (rx_frame.data[0] == OSCC_MAGIC_BYTE_0) && - (rx_frame.data[1] == OSCC_MAGIC_BYTE_1) ); + if ( (rx_frame.can_id < 0x100) && + (rx_frame.data[0] == OSCC_MAGIC_BYTE_0) && + (rx_frame.data[1] == OSCC_MAGIC_BYTE_1) ) + { + oscc_detection.has_brake_report |= + ( (rx_frame.can_id == OSCC_BRAKE_REPORT_CAN_ID) ); + + oscc_detection.has_steer_report |= + ( (rx_frame.can_id == OSCC_STEERING_REPORT_CAN_ID) ); + + oscc_detection.has_torqe_report |= + ( (rx_frame.can_id == OSCC_THROTTLE_REPORT_CAN_ID) ); + } vehicle_detection.has_brake_pressure |= ( rx_frame.can_id == KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID ); From 3ce99596cd8ba88b65b54d70373bda9b9ad4ce3f Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Mon, 26 Feb 2018 17:24:48 -0800 Subject: [PATCH 13/80] Correct spelling and result conditionals Prior to this commit there was a misspelling in the comments and the result value was not always checked before continuing on in two places. This commit fixes that by checking the result variable and correcting the misspelling. --- api/include/oscc.h | 4 ++-- api/src/oscc.c | 17 ++++++++++------- 2 files changed, 12 insertions(+), 9 deletions(-) diff --git a/api/include/oscc.h b/api/include/oscc.h index 7cb50214..5117b30f 100644 --- a/api/include/oscc.h +++ b/api/include/oscc.h @@ -26,12 +26,12 @@ * detection. * */ -#define MAX_CAN_IDS ( 50 ) +#define MAX_CAN_IDS ( 70 ) /* * @brief CAN_MESSAGE_TIMEOUT is the time to wait for a CAN message in - * miliseconds used for auto detection of can channels. + * milliseconds used for auto detection of can channels. * */ #define CAN_MESSAGE_TIMEOUT ( 100 ) diff --git a/api/src/oscc.c b/api/src/oscc.c index 14fbeac9..489039e4 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -29,12 +29,12 @@ oscc_result_t oscc_init() result = oscc_search_can( &auto_init_all_can, true ); - if( result != OSCC_ERROR ) + if( result == OSCC_OK ) { result = register_can_signal(); } - if ( oscc_can_socket > 0 ) + if ( result == OSCC_OK && oscc_can_socket > 0 ) { result = oscc_async_enable( oscc_can_socket ); } @@ -64,7 +64,7 @@ oscc_result_t oscc_open( unsigned int channel ) channel_contents = can_detection( can_string_buffer ); - if( result != OSCC_ERROR && !channel_contents.has_vehicle ) + if( result == OSCC_OK && !channel_contents.has_vehicle ) { int vehicle_ret = OSCC_ERROR; @@ -76,14 +76,17 @@ oscc_result_t oscc_open( unsigned int channel ) } } - if( result != OSCC_ERROR) + if( result == OSCC_OK) { result = init_oscc_can( can_string_buffer ); } - result = register_can_signal(); + if( result == OSCC_OK) + { + result = register_can_signal(); + } - if ( result != OSCC_ERROR && oscc_can_socket >= 0 ) + if ( result == OSCC_OK && oscc_can_socket >= 0 ) { result = oscc_async_enable( oscc_can_socket ); } @@ -92,7 +95,7 @@ oscc_result_t oscc_open( unsigned int channel ) printf( "Error could not find OSCC CAN signal.\n" ); } - if ( result != OSCC_ERROR && vehicle_can_socket >= 0 ) + if ( result == OSCC_OK && vehicle_can_socket >= 0 ) { oscc_async_enable( vehicle_can_socket ); } From 0b6d5653c93fc2a4fa62f8c8261a99f42e1e6f14 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Wed, 28 Feb 2018 12:22:53 -0800 Subject: [PATCH 14/80] Remove Linked List and Fix Formatting Prior to this commit there were formatting errors, and the code utilized a linked list which was over engineered. This commit fixes the formatting and removes the linked list in favor of a dynamic array. --- api/include/oscc.h | 2 +- api/src/internal/oscc.h | 49 +++++---- api/src/oscc.c | 221 ++++++++++++++++++++-------------------- 3 files changed, 140 insertions(+), 132 deletions(-) diff --git a/api/include/oscc.h b/api/include/oscc.h index 5117b30f..515b90b3 100644 --- a/api/include/oscc.h +++ b/api/include/oscc.h @@ -45,7 +45,7 @@ typedef enum } oscc_result_t; /** - * @brief Looks for available CAN channels and automaticcaly detects which + * @brief Looks for available CAN channels and automatically detects which * channel is OSCC control and which channel is vehicle CAN for feedback. * * @return OSCC_ERROR or OSCC_OK diff --git a/api/src/internal/oscc.h b/api/src/internal/oscc.h index 2e4afdb1..6a3f348d 100644 --- a/api/src/internal/oscc.h +++ b/api/src/internal/oscc.h @@ -10,29 +10,39 @@ #include #include +#define UNINITIALIZED_SOCKET -1 + #define CONSTRAIN(amt, low, high) ((amt) < (low) ? (low) : ((amt) > (high) ? (high) : (amt))) -struct can_contains { +struct can_contains_s { bool is_oscc; bool has_vehicle; -}can_contains_s; +} can_contains_default = { false, false }; + +typedef struct can_contains_s can_contains; -struct vehicle_can_desc { +struct vehicle_can_desc_s { bool has_steering_angle; bool has_brake_pressure; bool has_wheel_speed; -}vehicle_can_desc_s; +} vehicle_can_desc_default = { false, false, false }; + +typedef struct vehicle_can_desc_s vehicle_can_desc; -struct oscc_can_desc { +struct oscc_can_desc_s { bool has_torqe_report; bool has_steer_report; bool has_brake_report; -}oscc_can_desc_s; +} oscc_can_desc_default = { false, false, false }; + +typedef struct oscc_can_desc_s oscc_can_desc; + +struct device_names_s{ + char **name; + size_t size; +} device_names_default = { NULL, 0 }; -struct device_name { - struct device_name *next, *prev; - char name[IFNAMSIZ]; -}; +typedef struct device_names_s device_names; void (*brake_report_callback)( oscc_brake_report_s *report ); @@ -76,21 +86,21 @@ void oscc_update_status( ); oscc_result_t register_can_signal(); -// Enables asynchronous callback to each socket should be started after all -// connections are made +// Enables asynchronous callback to each socket and should only be called after +// all connections are made to prevent interrupts while making new connections. oscc_result_t oscc_async_enable( int socket ); // Runs a calback function through all available socketcan signals oscc_result_t oscc_search_can( - struct can_contains(*search_callback)( const char * ), + can_contains(*search_callback)( const char * ), bool search_oscc ); // Auto detects OSCC CAN and Vehicle CAN depending on OSCC CAN returned IDs -struct can_contains auto_init_all_can( const char *can_channel ); +can_contains auto_init_all_can( const char *can_channel ); // Auto detects Vehicle CAN based on vehicle header CAN IDs -struct can_contains auto_init_vehicle_can( const char *can_channel ); +can_contains auto_init_vehicle_can( const char *can_channel ); // Initializes the OSCC CAN oscc_result_t init_oscc_can( const char *can_channel ); @@ -104,16 +114,15 @@ int init_can_socket( const char *can_channel, struct can_filter *filter ); // Determines if the CAN channel contains OSCC data and/or Vehicle CAN IDs -struct can_contains can_detection( const char *can_channel ); +can_contains can_detection( const char *can_channel ); // Constructs a list of all can and vcan devices -oscc_result_t construct_interfaces_list( struct device_name * const list_ptr ); +oscc_result_t construct_interfaces_list( + struct device_names_s * const list_ptr ); // Gets the device name from a line of /proc/net/dev data char * get_device_name( char *string ); -// Adds a device to a linked list of devices -oscc_result_t add_device_name( const char * const name, - struct device_name * const list_ptr ); +void clear_device_names( struct device_names_s * const names_ptr ); #endif /* _OSCC_INTERNAL_H */ diff --git a/api/src/oscc.c b/api/src/oscc.c index 489039e4..45814212 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -19,8 +19,8 @@ #include "internal/oscc.h" -static int oscc_can_socket = -1; -static int vehicle_can_socket = -1; +static int oscc_can_socket = UNINITIALIZED_SOCKET; +static int vehicle_can_socket = UNINITIALIZED_SOCKET; oscc_result_t oscc_init() @@ -40,7 +40,7 @@ oscc_result_t oscc_init() } else { - printf( "Error could not find OSCC CAN signal\n" ); + printf( "Error: Could not find OSCC CAN signal\n" ); result = OSCC_ERROR; } @@ -56,7 +56,7 @@ oscc_result_t oscc_open( unsigned int channel ) { oscc_result_t result = OSCC_ERROR; - struct can_contains channel_contents; + can_contains channel_contents = can_contains_default; char can_string_buffer[16]; @@ -72,7 +72,7 @@ oscc_result_t oscc_open( unsigned int channel ) if( (vehicle_can_socket < 0) || (vehicle_ret != OSCC_OK) ) { - printf( "Warning Vehicle CAN was not found.\n" ); + printf( "Warning: Vehicle CAN was not found.\n" ); } } @@ -92,7 +92,7 @@ oscc_result_t oscc_open( unsigned int channel ) } else { - printf( "Error could not find OSCC CAN signal.\n" ); + printf( "Error: Could not find OSCC CAN signal.\n" ); } if ( result == OSCC_OK && vehicle_can_socket >= 0 ) @@ -108,7 +108,7 @@ oscc_result_t oscc_close( unsigned int channel ) { oscc_result_t result = OSCC_ERROR; - if( oscc_can_socket != -1 ) + if( oscc_can_socket < 0 ) { int result = close( oscc_can_socket ); @@ -118,7 +118,7 @@ oscc_result_t oscc_close( unsigned int channel ) } } - if( vehicle_can_socket != -1 ) + if( vehicle_can_socket < 0 ) { int result = close( vehicle_can_socket ); @@ -444,11 +444,11 @@ void oscc_update_status( int sig, siginfo_t *siginfo, void *context ) struct can_frame rx_frame; memset( &rx_frame, 0, sizeof(rx_frame) ); - if ( oscc_can_socket != -1 ) + if ( oscc_can_socket >= 0 ) { - int ret = read( oscc_can_socket, &rx_frame, CAN_MTU ); + int oscc_can_bytes = read( oscc_can_socket, &rx_frame, CAN_MTU ); - while ( ret > 0 ) + while ( oscc_can_bytes > 0 ) { if ( (rx_frame.data[0] == OSCC_MAGIC_BYTE_0) && (rx_frame.data[1] == OSCC_MAGIC_BYTE_1) ) @@ -502,22 +502,22 @@ void oscc_update_status( int sig, siginfo_t *siginfo, void *context ) } } - ret = read( oscc_can_socket, &rx_frame, CAN_MTU ); + oscc_can_bytes = read( oscc_can_socket, &rx_frame, CAN_MTU ); } } - if ( vehicle_can_socket != -1 ) + if ( vehicle_can_socket >= 0 ) { - int veh_ret = read( vehicle_can_socket, &rx_frame, CAN_MTU ); + int vehicle_can_bytes = read( vehicle_can_socket, &rx_frame, CAN_MTU ); - while( veh_ret > 0 ) + while( vehicle_can_bytes > 0 ) { if ( obd_frame_callback != NULL ) { obd_frame_callback( &rx_frame ); } - veh_ret = read( vehicle_can_socket, &rx_frame, CAN_MTU ); + vehicle_can_bytes = read( vehicle_can_socket, &rx_frame, CAN_MTU ); } } } @@ -527,7 +527,7 @@ oscc_result_t oscc_can_write( long id, void *msg, unsigned int dlc ) oscc_result_t result = OSCC_ERROR; - if ( oscc_can_socket != -1 ) + if ( oscc_can_socket >= 0 ) { struct can_frame tx_frame; @@ -553,17 +553,22 @@ oscc_result_t oscc_can_write( long id, void *msg, unsigned int dlc ) } -oscc_result_t register_can_signal() +oscc_result_t register_can_signal( ) { - int result = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; + struct sigaction sig; memset( &sig, 0, sizeof(sig) ); + sigemptyset( &sig.sa_mask ); + sig.sa_sigaction = oscc_update_status; - sig.sa_flags = SA_SIGINFO; + + sig.sa_flags = SA_SIGINFO | SA_RESTART; + if( sigaction( SIGIO, &sig, NULL ) == 0 ) { - result = OSCC_OK; + result = OSCC_OK; } return result; @@ -604,31 +609,29 @@ oscc_result_t oscc_async_enable( int socket ) } -oscc_result_t oscc_search_can( struct can_contains(*search_callback)( const char * ), +oscc_result_t oscc_search_can( can_contains(*search_callback)( const char * ), bool search_oscc ) { oscc_result_t result = OSCC_ERROR; - static struct device_name *dev_list, *temp_ptr; - dev_list = malloc( sizeof( struct device_name ) ); - - result = construct_interfaces_list( dev_list ); + device_names dev_list = device_names_default; + result = construct_interfaces_list( &dev_list ); //temp_contents is the temporary storage of the current CAN channel //all_contents is the sum of all channels searched - struct can_contains temp_contents, all_contents; + can_contains temp_contents = can_contains_default; + can_contains all_contents = can_contains_default; //Set the all_contents based search_oscc boolean in function call all_contents.is_oscc = !search_oscc; - all_contents.has_vehicle = false; - temp_ptr = dev_list; + int i = 0; - do + for( i = 0; i < dev_list.size; i++ ) { - if ( strstr( temp_ptr->name, "can" ) != NULL ) + if ( strstr( dev_list.name[i], "can") != NULL ) { - temp_contents = search_callback( temp_ptr->name ); + temp_contents = search_callback( dev_list.name[i] ); all_contents.is_oscc |= temp_contents.is_oscc; @@ -640,17 +643,17 @@ oscc_result_t oscc_search_can( struct can_contains(*search_callback)( const char break; } } + } - temp_ptr = temp_ptr->next; - }while( temp_ptr != dev_list ); + clear_device_names( &dev_list ); return result; } -struct can_contains auto_init_all_can( const char *can_channel ) +can_contains auto_init_all_can( const char *can_channel ) { - struct can_contains contents = can_detection( can_channel ); + can_contains contents = can_detection( can_channel ); if( contents.is_oscc ) { @@ -665,9 +668,9 @@ struct can_contains auto_init_all_can( const char *can_channel ) } -struct can_contains auto_init_vehicle_can( const char *can_channel ) +can_contains auto_init_vehicle_can( const char *can_channel ) { - struct can_contains contents = can_detection( can_channel ); + can_contains contents = can_detection( can_channel ); if( contents.has_vehicle ) { @@ -701,7 +704,8 @@ oscc_result_t init_vehicle_can( const char *can_channel ) printf( "Assigning Vehicle CAN Channel to: %s\n", can_channel ); - struct can_filter rfilter[4]; + //TODO: Remove filters... + struct can_filter rfilter[3]; rfilter[0].can_id = KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID; rfilter[0].can_mask = CAN_SFF_MASK; @@ -725,8 +729,8 @@ int init_can_socket( const char *can_channel, struct timeval *tv, struct can_filter *filter ) { - int valid = -1; - int sock = -1; + int valid = UNINITIALIZED_SOCKET; + int sock = UNINITIALIZED_SOCKET; struct ifreq ifr; memset( &ifr, 0, sizeof( ifr ) ); @@ -801,14 +805,14 @@ int init_can_socket( const char *can_channel, if( valid < 0 ) { close( sock ); - sock = -1; + sock = UNINITIALIZED_SOCKET; } return sock; } -struct can_contains can_detection( const char *can_channel ) +can_contains can_detection( const char *can_channel ) { struct timeval timeout; timeout.tv_sec = 0; @@ -816,21 +820,11 @@ struct can_contains can_detection( const char *can_channel ) int sock = init_can_socket( can_channel, &timeout, NULL ); - int i = 0; + vehicle_can_desc vehicle_detection = vehicle_can_desc_default; - struct vehicle_can_desc vehicle_detection = - { - .has_steering_angle = false, - .has_brake_pressure = false, - .has_wheel_speed = false - }; + oscc_can_desc oscc_detection = oscc_can_desc_default; - struct oscc_can_desc oscc_detection = - { - .has_torqe_report = false, - .has_steer_report = false, - .has_brake_report = false - }; + int i = 0; for( i = 0; i < MAX_CAN_IDS; i++ ) { @@ -865,19 +859,12 @@ struct can_contains can_detection( const char *can_channel ) vehicle_detection.has_wheel_speed |= ( rx_frame.can_id == KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID ); - case -1: - if( EINTR == errno ) - { - continue; - } - default: - continue; } } close( sock ); - struct can_contains detection = + can_contains detection = { .is_oscc = oscc_detection.has_brake_report && oscc_detection.has_steer_report && @@ -891,39 +878,84 @@ struct can_contains can_detection( const char *can_channel ) } -oscc_result_t construct_interfaces_list( struct device_name * const list_ptr ) +oscc_result_t construct_interfaces_list( struct device_names_s * const names_ptr ) { - FILE *fh; + FILE *file_handler; char buffer[512]; - oscc_result_t ret = OSCC_ERROR; - fh = fopen( "/proc/net/dev", "r" ); - if (!fh) { + file_handler = fopen( "/proc/net/dev", "r" ); + if (!file_handler) { perror( "Cannot read: /proc/net/dev" ); - return -2; + return OSCC_ERROR; + } + + int lines = 0; + + while ( fgets( buffer, sizeof( buffer ), file_handler ) ) { + ++lines; + } + + names_ptr->name = (char**) malloc(lines * sizeof(char*)); + + int i; + + for ( i = 0; i < lines; i++ ) + { + names_ptr->name[i] = (char*) malloc(IFNAMSIZ * sizeof(char)); } + rewind( file_handler ); + //Consume the first two lines since they are headers - fgets( buffer, sizeof buffer, fh ); - fgets( buffer, sizeof buffer, fh ); + fgets( buffer, sizeof( buffer ), file_handler ); + fgets( buffer, sizeof( buffer ), file_handler ); + + int size = 0; - while ( fgets( buffer, sizeof buffer, fh ) ) { + while ( fgets( buffer, sizeof( buffer ), file_handler ) ) { char *socket_name; + socket_name = get_device_name( buffer ); - ret = add_device_name( socket_name, list_ptr ); + + strncpy( names_ptr->name[size], socket_name, IFNAMSIZ ); + + size++; } - return ret; + names_ptr->size = size; + + close( file_handler ); + + return OSCC_OK; +} + +void clear_device_names( struct device_names_s * const names_ptr ) +{ + int i; + + for ( i = 0; i < names_ptr->size; i++ ) + { + free( names_ptr->name[i] ); + } + + free( names_ptr->name ); } char * get_device_name( char *string ) { size_t span = strcspn(string, ":"); - static char temp_name[IFNAMSIZ]; + + char temp_name[IFNAMSIZ]; + strncpy(temp_name, string, span); - temp_name[span] = '\0'; + + if( span <= IFNAMSIZ ) + { + temp_name[span] = '\0'; + } + size_t leading_spaces = strspn(temp_name, " "); if(leading_spaces == 0) @@ -931,7 +963,7 @@ char * get_device_name( char *string ) return temp_name; } - static char new_name[IFNAMSIZ]; + char new_name[IFNAMSIZ]; strncpy(new_name, temp_name + leading_spaces, span - leading_spaces + 1); @@ -939,36 +971,3 @@ char * get_device_name( char *string ) return new_name; } - -oscc_result_t add_device_name( const char * const name, - struct device_name * const list_ptr ) -{ - if( list_ptr == NULL ) - { - perror( "list is uninitialized" ); - return -1; - } - - if( strlen( list_ptr->name ) != 0 ) - { - struct device_name * old_tail; - struct device_name * new_name = malloc( sizeof( struct device_name ) ); - strncpy( new_name->name, name, IFNAMSIZ ); - - if( list_ptr->next == list_ptr ){ - list_ptr->next = new_name; - } - old_tail = list_ptr->prev; - old_tail->next = new_name; - new_name->prev = old_tail; - new_name->next = list_ptr; - list_ptr->prev = new_name; - } - else{ - strncpy( list_ptr->name, name, IFNAMSIZ ); - list_ptr->prev = list_ptr; - list_ptr->next = list_ptr; - } - - return OSCC_OK; -} From b3a45a79615441c5293b5f53b291d5eb45eceada Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Wed, 28 Feb 2018 12:34:59 -0800 Subject: [PATCH 15/80] Remove CAN Filter and Fix Return Pointer Prior to this commit the code had CAN filters which are intermittently filtering out everything. Also the get_device_name function was returning a char* which is not adviced in C since that is the function's memory space. This commit fixes these issues by removing CAN filtering and passing in a pointer for the get_device_name function to modify. --- api/src/internal/oscc.h | 5 ++-- api/src/oscc.c | 63 +++++++++++++---------------------------- 2 files changed, 22 insertions(+), 46 deletions(-) diff --git a/api/src/internal/oscc.h b/api/src/internal/oscc.h index 6a3f348d..9493854a 100644 --- a/api/src/internal/oscc.h +++ b/api/src/internal/oscc.h @@ -110,8 +110,7 @@ oscc_result_t init_vehicle_can( const char *can_channel ); // Returns socket id after initiating a socketcan connection int init_can_socket( const char *can_channel, - struct timeval *tv, - struct can_filter *filter ); + struct timeval *tv ); // Determines if the CAN channel contains OSCC data and/or Vehicle CAN IDs can_contains can_detection( const char *can_channel ); @@ -121,7 +120,7 @@ oscc_result_t construct_interfaces_list( struct device_names_s * const list_ptr ); // Gets the device name from a line of /proc/net/dev data -char * get_device_name( char *string ); +void get_device_name( char *string, char *name ); void clear_device_names( struct device_names_s * const names_ptr ); diff --git a/api/src/oscc.c b/api/src/oscc.c index 45814212..a7252d51 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -512,7 +512,10 @@ void oscc_update_status( int sig, siginfo_t *siginfo, void *context ) while( vehicle_can_bytes > 0 ) { - if ( obd_frame_callback != NULL ) + if ( obd_frame_callback != NULL && + ( rx_frame.can_id == KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID || + rx_frame.can_id == KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID || + rx_frame.can_id == KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID ) ) { obd_frame_callback( &rx_frame ); } @@ -687,7 +690,7 @@ oscc_result_t init_oscc_can( const char *can_channel ) printf( "Assigning OSCC CAN Channel to: %s\n", can_channel ); - oscc_can_socket = init_can_socket( can_channel, NULL, NULL ); + oscc_can_socket = init_can_socket( can_channel, NULL ); if( oscc_can_socket >= 0 ) { @@ -704,17 +707,7 @@ oscc_result_t init_vehicle_can( const char *can_channel ) printf( "Assigning Vehicle CAN Channel to: %s\n", can_channel ); - //TODO: Remove filters... - struct can_filter rfilter[3]; - - rfilter[0].can_id = KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID; - rfilter[0].can_mask = CAN_SFF_MASK; - rfilter[1].can_id = KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID; - rfilter[1].can_mask = CAN_SFF_MASK; - rfilter[2].can_id = KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID; - rfilter[2].can_mask = CAN_SFF_MASK; - - vehicle_can_socket = init_can_socket( can_channel, NULL, rfilter ); + vehicle_can_socket = init_can_socket( can_channel, NULL ); if(vehicle_can_socket >= 0) { @@ -726,8 +719,7 @@ oscc_result_t init_vehicle_can( const char *can_channel ) int init_can_socket( const char *can_channel, - struct timeval *tv, - struct can_filter *filter ) + struct timeval *tv ) { int valid = UNINITIALIZED_SOCKET; int sock = UNINITIALIZED_SOCKET; @@ -768,21 +760,6 @@ int init_can_socket( const char *can_channel, } } - //If a filter has been specified set one here - if( (valid >= 0) && (filter != NULL) ) - { - int ret = setsockopt( sock, - SOL_CAN_RAW, - CAN_RAW_FILTER, - &filter, - sizeof( filter ) ); - - if ( valid < 0 ) - { - perror( "Setting filter failed:" ); - } - } - if ( valid >= 0 ) { struct sockaddr_can can_address; @@ -818,7 +795,7 @@ can_contains can_detection( const char *can_channel ) timeout.tv_sec = 0; timeout.tv_usec = CAN_MESSAGE_TIMEOUT; - int sock = init_can_socket( can_channel, &timeout, NULL ); + int sock = init_can_socket( can_channel, &timeout ); vehicle_can_desc vehicle_detection = vehicle_can_desc_default; @@ -916,7 +893,7 @@ oscc_result_t construct_interfaces_list( struct device_names_s * const names_ptr while ( fgets( buffer, sizeof( buffer ), file_handler ) ) { char *socket_name; - socket_name = get_device_name( buffer ); + get_device_name( buffer, socket_name ); strncpy( names_ptr->name[size], socket_name, IFNAMSIZ ); @@ -925,7 +902,7 @@ oscc_result_t construct_interfaces_list( struct device_names_s * const names_ptr names_ptr->size = size; - close( file_handler ); + fclose( file_handler ); return OSCC_OK; } @@ -943,7 +920,7 @@ void clear_device_names( struct device_names_s * const names_ptr ) } -char * get_device_name( char *string ) +void get_device_name( char *string, char *name ) { size_t span = strcspn(string, ":"); @@ -958,16 +935,16 @@ char * get_device_name( char *string ) size_t leading_spaces = strspn(temp_name, " "); - if(leading_spaces == 0) + if(leading_spaces != 0) { - return temp_name; - } - - char new_name[IFNAMSIZ]; - - strncpy(new_name, temp_name + leading_spaces, span - leading_spaces + 1); + char new_name[IFNAMSIZ]; - new_name[span - leading_spaces] = '\0'; + strncpy(name, temp_name + leading_spaces, span - leading_spaces + 1); - return new_name; + new_name[span - leading_spaces] = '\0'; + } + else + { + strncpy(name, temp_name, span); + } } From 44db25193976fcc40de9a7d39ad48e76ee1d2dce Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Thu, 1 Mar 2018 10:01:05 -0800 Subject: [PATCH 16/80] Clean up structs and fix string initialization Prior to this commit the code had a struct typedef with unused naming and the struct default value was a global variable which could be changed. The code also had a missing variable initialization for a string copy. This commit fixes that by moving the struct initiailzation to the variable decleraction and using calloc rather than malloc for the string intialization. --- api/src/internal/oscc.h | 48 ++++++++----------- api/src/oscc.c | 100 ++++++++++++++++++++++++++-------------- 2 files changed, 85 insertions(+), 63 deletions(-) diff --git a/api/src/internal/oscc.h b/api/src/internal/oscc.h index 9493854a..52a4d7ce 100644 --- a/api/src/internal/oscc.h +++ b/api/src/internal/oscc.h @@ -14,35 +14,27 @@ #define CONSTRAIN(amt, low, high) ((amt) < (low) ? (low) : ((amt) > (high) ? (high) : (amt))) -struct can_contains_s { +typedef struct { bool is_oscc; bool has_vehicle; -} can_contains_default = { false, false }; +} can_contains_s; -typedef struct can_contains_s can_contains; - -struct vehicle_can_desc_s { +typedef struct { bool has_steering_angle; bool has_brake_pressure; bool has_wheel_speed; -} vehicle_can_desc_default = { false, false, false }; - -typedef struct vehicle_can_desc_s vehicle_can_desc; +} vehicle_can_desc_s; -struct oscc_can_desc_s { - bool has_torqe_report; +typedef struct { + bool has_accel_report; bool has_steer_report; bool has_brake_report; -} oscc_can_desc_default = { false, false, false }; +} oscc_can_desc_s; -typedef struct oscc_can_desc_s oscc_can_desc; - -struct device_names_s{ +typedef struct { char **name; size_t size; -} device_names_default = { NULL, 0 }; - -typedef struct device_names_s device_names; +} device_names_s; void (*brake_report_callback)( oscc_brake_report_s *report ); @@ -93,35 +85,35 @@ oscc_result_t oscc_async_enable( // Runs a calback function through all available socketcan signals oscc_result_t oscc_search_can( - can_contains(*search_callback)( const char * ), + can_contains_s(*search_callback)( const char * ), bool search_oscc ); // Auto detects OSCC CAN and Vehicle CAN depending on OSCC CAN returned IDs -can_contains auto_init_all_can( const char *can_channel ); +can_contains_s auto_init_all_can( const char * can_channel ); // Auto detects Vehicle CAN based on vehicle header CAN IDs -can_contains auto_init_vehicle_can( const char *can_channel ); +can_contains_s auto_init_vehicle_can( const char * can_channel ); // Initializes the OSCC CAN -oscc_result_t init_oscc_can( const char *can_channel ); +oscc_result_t init_oscc_can( const char * can_channel ); // Initializes the vehicle can with vehicle header CAN IDs -oscc_result_t init_vehicle_can( const char *can_channel ); +oscc_result_t init_vehicle_can( const char * can_channel ); // Returns socket id after initiating a socketcan connection -int init_can_socket( const char *can_channel, - struct timeval *tv ); +int init_can_socket( const char * can_channel, + struct timeval * tv ); // Determines if the CAN channel contains OSCC data and/or Vehicle CAN IDs -can_contains can_detection( const char *can_channel ); +can_contains_s can_detection( const char * can_channel ); // Constructs a list of all can and vcan devices oscc_result_t construct_interfaces_list( - struct device_names_s * const list_ptr ); + device_names_s * const list_ptr ); // Gets the device name from a line of /proc/net/dev data -void get_device_name( char *string, char *name ); +void get_device_name( char * string, char * const name ); -void clear_device_names( struct device_names_s * const names_ptr ); +void clear_device_names( device_names_s * const names_ptr ); #endif /* _OSCC_INTERNAL_H */ diff --git a/api/src/oscc.c b/api/src/oscc.c index a7252d51..8110c160 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -56,7 +56,11 @@ oscc_result_t oscc_open( unsigned int channel ) { oscc_result_t result = OSCC_ERROR; - can_contains channel_contents = can_contains_default; + can_contains_s channel_contents = + { + .is_oscc = false, + .has_vehicle = false + }; char can_string_buffer[16]; @@ -612,21 +616,26 @@ oscc_result_t oscc_async_enable( int socket ) } -oscc_result_t oscc_search_can( can_contains(*search_callback)( const char * ), +oscc_result_t oscc_search_can( can_contains_s(*search_callback)( const char * ), bool search_oscc ) { oscc_result_t result = OSCC_ERROR; - device_names dev_list = device_names_default; + device_names_s dev_list = + { + .name = NULL, + .size = 0 + }; result = construct_interfaces_list( &dev_list ); //temp_contents is the temporary storage of the current CAN channel //all_contents is the sum of all channels searched - can_contains temp_contents = can_contains_default; - can_contains all_contents = can_contains_default; - - //Set the all_contents based search_oscc boolean in function call - all_contents.is_oscc = !search_oscc; + can_contains_s temp_contents; + can_contains_s all_contents = + { + .is_oscc = !search_oscc, + .has_vehicle = false + }; int i = 0; @@ -654,9 +663,9 @@ oscc_result_t oscc_search_can( can_contains(*search_callback)( const char * ), } -can_contains auto_init_all_can( const char *can_channel ) +can_contains_s auto_init_all_can( const char *can_channel ) { - can_contains contents = can_detection( can_channel ); + can_contains_s contents = can_detection( can_channel ); if( contents.is_oscc ) { @@ -671,9 +680,9 @@ can_contains auto_init_all_can( const char *can_channel ) } -can_contains auto_init_vehicle_can( const char *can_channel ) +can_contains_s auto_init_vehicle_can( const char *can_channel ) { - can_contains contents = can_detection( can_channel ); + can_contains_s contents = can_detection( can_channel ); if( contents.has_vehicle ) { @@ -789,7 +798,7 @@ int init_can_socket( const char *can_channel, } -can_contains can_detection( const char *can_channel ) +can_contains_s can_detection( const char *can_channel ) { struct timeval timeout; timeout.tv_sec = 0; @@ -797,9 +806,19 @@ can_contains can_detection( const char *can_channel ) int sock = init_can_socket( can_channel, &timeout ); - vehicle_can_desc vehicle_detection = vehicle_can_desc_default; + vehicle_can_desc_s vehicle_detection = + { + .has_steering_angle = false, + .has_brake_pressure = false, + .has_wheel_speed = false + }; - oscc_can_desc oscc_detection = oscc_can_desc_default; + oscc_can_desc_s oscc_detection = + { + .has_accel_report = false, + .has_steer_report = false, + .has_brake_report = false + }; int i = 0; @@ -824,7 +843,7 @@ can_contains can_detection( const char *can_channel ) oscc_detection.has_steer_report |= ( (rx_frame.can_id == OSCC_STEERING_REPORT_CAN_ID) ); - oscc_detection.has_torqe_report |= + oscc_detection.has_accel_report |= ( (rx_frame.can_id == OSCC_THROTTLE_REPORT_CAN_ID) ); } @@ -841,11 +860,11 @@ can_contains can_detection( const char *can_channel ) close( sock ); - can_contains detection = + can_contains_s detection = { .is_oscc = oscc_detection.has_brake_report && oscc_detection.has_steer_report && - oscc_detection.has_torqe_report, + oscc_detection.has_accel_report, .has_vehicle = vehicle_detection.has_brake_pressure && vehicle_detection.has_steering_angle && vehicle_detection.has_wheel_speed @@ -855,10 +874,11 @@ can_contains can_detection( const char *can_channel ) } -oscc_result_t construct_interfaces_list( struct device_names_s * const names_ptr ) +oscc_result_t construct_interfaces_list( device_names_s * const names_ptr ) { FILE *file_handler; char buffer[512]; + oscc_result_t result = OSCC_OK; file_handler = fopen( "/proc/net/dev", "r" ); if (!file_handler) { @@ -890,24 +910,34 @@ oscc_result_t construct_interfaces_list( struct device_names_s * const names_ptr int size = 0; - while ( fgets( buffer, sizeof( buffer ), file_handler ) ) { - char *socket_name; + char* socket_name = calloc( IFNAMSIZ, sizeof(char) ); - get_device_name( buffer, socket_name ); + if( !socket_name ) + { + result = OSCC_ERROR; + } + else + { + while ( size < lines && fgets( buffer, sizeof( buffer ), file_handler ) ) { - strncpy( names_ptr->name[size], socket_name, IFNAMSIZ ); + get_device_name( buffer, socket_name ); - size++; - } + strncpy( names_ptr->name[size], socket_name, IFNAMSIZ ); - names_ptr->size = size; + size++; + } + + free( socket_name ); + + names_ptr->size = size; + } fclose( file_handler ); - return OSCC_OK; + return result; } -void clear_device_names( struct device_names_s * const names_ptr ) +void clear_device_names( device_names_s * const names_ptr ) { int i; @@ -920,31 +950,31 @@ void clear_device_names( struct device_names_s * const names_ptr ) } -void get_device_name( char *string, char *name ) +void get_device_name( char * string, char * const name ) { size_t span = strcspn(string, ":"); char temp_name[IFNAMSIZ]; - strncpy(temp_name, string, span); + strncpy( temp_name, string, span ); if( span <= IFNAMSIZ ) { - temp_name[span] = '\0'; + temp_name[span] = '\0'; } - size_t leading_spaces = strspn(temp_name, " "); + size_t leading_spaces = strspn( temp_name, " " ); - if(leading_spaces != 0) + if( leading_spaces != 0 ) { char new_name[IFNAMSIZ]; - strncpy(name, temp_name + leading_spaces, span - leading_spaces + 1); + strncpy( name, temp_name + leading_spaces, span - leading_spaces + 1 ); new_name[span - leading_spaces] = '\0'; } else { - strncpy(name, temp_name, span); + strncpy( name, temp_name, span ); } } From e038abc6ffd336292e5c8d8d66b9ebab228e41b6 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Thu, 1 Mar 2018 10:10:47 -0800 Subject: [PATCH 17/80] Fix Whitespace Prior to this commit there were double space indentation while the code style uses four space indentation. This commit commit fixes that by adding two more spaces to the double space indentation. --- api/src/oscc.c | 62 +++++++++++++++++++++++++------------------------- 1 file changed, 31 insertions(+), 31 deletions(-) diff --git a/api/src/oscc.c b/api/src/oscc.c index 8110c160..b457948f 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -512,20 +512,20 @@ void oscc_update_status( int sig, siginfo_t *siginfo, void *context ) if ( vehicle_can_socket >= 0 ) { - int vehicle_can_bytes = read( vehicle_can_socket, &rx_frame, CAN_MTU ); + int vehicle_can_bytes = read( vehicle_can_socket, &rx_frame, CAN_MTU ); - while( vehicle_can_bytes > 0 ) - { - if ( obd_frame_callback != NULL && - ( rx_frame.can_id == KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID || - rx_frame.can_id == KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID || - rx_frame.can_id == KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID ) ) - { - obd_frame_callback( &rx_frame ); - } + while( vehicle_can_bytes > 0 ) + { + if ( obd_frame_callback != NULL && + ( rx_frame.can_id == KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID || + rx_frame.can_id == KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID || + rx_frame.can_id == KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID ) ) + { + obd_frame_callback( &rx_frame ); + } - vehicle_can_bytes = read( vehicle_can_socket, &rx_frame, CAN_MTU ); - } + vehicle_can_bytes = read( vehicle_can_socket, &rx_frame, CAN_MTU ); + } } } @@ -562,23 +562,23 @@ oscc_result_t oscc_can_write( long id, void *msg, unsigned int dlc ) oscc_result_t register_can_signal( ) { - oscc_result_t result = OSCC_ERROR; + oscc_result_t result = OSCC_ERROR; - struct sigaction sig; - memset( &sig, 0, sizeof(sig) ); + struct sigaction sig; + memset( &sig, 0, sizeof(sig) ); - sigemptyset( &sig.sa_mask ); + sigemptyset( &sig.sa_mask ); - sig.sa_sigaction = oscc_update_status; + sig.sa_sigaction = oscc_update_status; - sig.sa_flags = SA_SIGINFO | SA_RESTART; + sig.sa_flags = SA_SIGINFO | SA_RESTART; - if( sigaction( SIGIO, &sig, NULL ) == 0 ) - { - result = OSCC_OK; - } + if( sigaction( SIGIO, &sig, NULL ) == 0 ) + { + result = OSCC_OK; + } - return result; + return result; } @@ -790,8 +790,8 @@ int init_can_socket( const char *can_channel, // Clean up resources and close the connection if it's invalid. if( valid < 0 ) { - close( sock ); - sock = UNINITIALIZED_SOCKET; + close( sock ); + sock = UNINITIALIZED_SOCKET; } return sock; @@ -862,12 +862,12 @@ can_contains_s can_detection( const char *can_channel ) can_contains_s detection = { - .is_oscc = oscc_detection.has_brake_report && - oscc_detection.has_steer_report && - oscc_detection.has_accel_report, - .has_vehicle = vehicle_detection.has_brake_pressure && - vehicle_detection.has_steering_angle && - vehicle_detection.has_wheel_speed + .is_oscc = oscc_detection.has_brake_report && + oscc_detection.has_steer_report && + oscc_detection.has_accel_report, + .has_vehicle = vehicle_detection.has_brake_pressure && + vehicle_detection.has_steering_angle && + vehicle_detection.has_wheel_speed }; return detection; From 38d18bb7b93b250adbac9e310e717d5ac23f6770 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Thu, 1 Mar 2018 13:18:38 -0800 Subject: [PATCH 18/80] Add parenthesis to #define and pid to fcntl Prior to this commit a #define did not have parenthesis and fcntl had a gettid for returning a thread id rather than a process id. This commit changes that by adding the parenthesis and going back to getpid. --- api/src/internal/oscc.h | 2 +- api/src/oscc.c | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/api/src/internal/oscc.h b/api/src/internal/oscc.h index 52a4d7ce..e2ef74a0 100644 --- a/api/src/internal/oscc.h +++ b/api/src/internal/oscc.h @@ -10,7 +10,7 @@ #include #include -#define UNINITIALIZED_SOCKET -1 +#define UNINITIALIZED_SOCKET (-1) #define CONSTRAIN(amt, low, high) ((amt) < (low) ? (low) : ((amt) > (high) ? (high) : (amt))) diff --git a/api/src/oscc.c b/api/src/oscc.c index b457948f..02e37b03 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -587,7 +587,7 @@ oscc_result_t oscc_async_enable( int socket ) oscc_result_t result = OSCC_ERROR; - int ret = fcntl( socket, F_SETOWN, (pid_t) syscall (SYS_gettid) ); + int ret = fcntl( socket, F_SETOWN, getpid( ) ); if ( ret < 0 ) { From 63febc7aaf18bea81115c72358c8814e117ecf4f Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Thu, 1 Mar 2018 13:50:39 -0800 Subject: [PATCH 19/80] Add null pointer checking Prior to this commit functions did not check if the pointer passed in was NULL. This commit fixes that by adding NULL pointer checking and returning status if there was a void in that function. --- api/src/internal/oscc.h | 4 +- api/src/oscc.c | 202 +++++++++++++++++++++++++++++----------- 2 files changed, 148 insertions(+), 58 deletions(-) diff --git a/api/src/internal/oscc.h b/api/src/internal/oscc.h index e2ef74a0..b9ca2576 100644 --- a/api/src/internal/oscc.h +++ b/api/src/internal/oscc.h @@ -112,8 +112,8 @@ oscc_result_t construct_interfaces_list( device_names_s * const list_ptr ); // Gets the device name from a line of /proc/net/dev data -void get_device_name( char * string, char * const name ); +oscc_result_t get_device_name( char * string, char * const name ); -void clear_device_names( device_names_s * const names_ptr ); +oscc_result_t clear_device_names( device_names_s * const names_ptr ); #endif /* _OSCC_INTERNAL_H */ diff --git a/api/src/oscc.c b/api/src/oscc.c index 02e37b03..50beb3b1 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -586,7 +586,6 @@ oscc_result_t oscc_async_enable( int socket ) { oscc_result_t result = OSCC_ERROR; - int ret = fcntl( socket, F_SETOWN, getpid( ) ); if ( ret < 0 ) @@ -619,7 +618,12 @@ oscc_result_t oscc_async_enable( int socket ) oscc_result_t oscc_search_can( can_contains_s(*search_callback)( const char * ), bool search_oscc ) { - oscc_result_t result = OSCC_ERROR; + oscc_result_t result = OSCC_OK; + + if( search_callback == NULL ) + { + result = OSCC_ERROR; + } device_names_s dev_list = { @@ -627,7 +631,11 @@ oscc_result_t oscc_search_can( can_contains_s(*search_callback)( const char * ), .size = 0 }; - result = construct_interfaces_list( &dev_list ); + if( result == OSCC_OK ) + { + result = construct_interfaces_list( &dev_list ); + } + //temp_contents is the temporary storage of the current CAN channel //all_contents is the sum of all channels searched can_contains_s temp_contents; @@ -637,11 +645,11 @@ oscc_result_t oscc_search_can( can_contains_s(*search_callback)( const char * ), .has_vehicle = false }; - int i = 0; + uint i; for( i = 0; i < dev_list.size; i++ ) { - if ( strstr( dev_list.name[i], "can") != NULL ) + if ( strstr( dev_list.name[i], "can") != NULL && result == OSCC_OK ) { temp_contents = search_callback( dev_list.name[i] ); @@ -657,7 +665,10 @@ oscc_result_t oscc_search_can( can_contains_s(*search_callback)( const char * ), } } - clear_device_names( &dev_list ); + if( dev_list.name != NULL ) + { + result = clear_device_names( &dev_list ); + } return result; } @@ -665,6 +676,17 @@ oscc_result_t oscc_search_can( can_contains_s(*search_callback)( const char * ), can_contains_s auto_init_all_can( const char *can_channel ) { + if ( can_channel == NULL ) + { + can_contains_s contents = + { + .is_oscc = false, + .has_vehicle = false + }; + + return contents; + } + can_contains_s contents = can_detection( can_channel ); if( contents.is_oscc ) @@ -682,6 +704,17 @@ can_contains_s auto_init_all_can( const char *can_channel ) can_contains_s auto_init_vehicle_can( const char *can_channel ) { + if ( can_channel == NULL ) + { + can_contains_s contents = + { + .is_oscc = false, + .has_vehicle = false + }; + + return contents; + } + can_contains_s contents = can_detection( can_channel ); if( contents.has_vehicle ) @@ -697,11 +730,14 @@ oscc_result_t init_oscc_can( const char *can_channel ) { int result = OSCC_ERROR; - printf( "Assigning OSCC CAN Channel to: %s\n", can_channel ); + if( can_channel != NULL ) + { + printf( "Assigning OSCC CAN Channel to: %s\n", can_channel ); - oscc_can_socket = init_can_socket( can_channel, NULL ); + oscc_can_socket = init_can_socket( can_channel, NULL ); + } - if( oscc_can_socket >= 0 ) + if( can_channel != NULL && oscc_can_socket >= 0 ) { result = OSCC_OK; } @@ -714,11 +750,14 @@ oscc_result_t init_vehicle_can( const char *can_channel ) { int result = OSCC_ERROR; - printf( "Assigning Vehicle CAN Channel to: %s\n", can_channel ); + if( can_channel != NULL ) + { + printf( "Assigning Vehicle CAN Channel to: %s\n", can_channel ); - vehicle_can_socket = init_can_socket( can_channel, NULL ); + vehicle_can_socket = init_can_socket( can_channel, NULL ); + } - if(vehicle_can_socket >= 0) + if( can_channel != NULL && vehicle_can_socket >= 0 ) { result = OSCC_OK; } @@ -730,6 +769,11 @@ oscc_result_t init_vehicle_can( const char *can_channel ) int init_can_socket( const char *can_channel, struct timeval *tv ) { + if( can_channel == NULL ) + { + return UNINITIALIZED_SOCKET; + } + int valid = UNINITIALIZED_SOCKET; int sock = UNINITIALIZED_SOCKET; struct ifreq ifr; @@ -800,6 +844,17 @@ int init_can_socket( const char *can_channel, can_contains_s can_detection( const char *can_channel ) { + if( can_channel == NULL ) + { + can_contains_s detection = + { + .is_oscc = false, + .has_vehicle = false + }; + + return detection; + } + struct timeval timeout; timeout.tv_sec = 0; timeout.tv_usec = CAN_MESSAGE_TIMEOUT; @@ -820,7 +875,7 @@ can_contains_s can_detection( const char *can_channel ) .has_brake_report = false }; - int i = 0; + uint i = 0; for( i = 0; i < MAX_CAN_IDS; i++ ) { @@ -884,31 +939,37 @@ oscc_result_t construct_interfaces_list( device_names_s * const names_ptr ) if (!file_handler) { perror( "Cannot read: /proc/net/dev" ); - return OSCC_ERROR; + result = OSCC_ERROR; } - int lines = 0; - - while ( fgets( buffer, sizeof( buffer ), file_handler ) ) { - ++lines; + if( result == OSCC_OK && names_ptr == NULL ) + { + result = OSCC_ERROR; } - names_ptr->name = (char**) malloc(lines * sizeof(char*)); - - int i; + int lines = 0; - for ( i = 0; i < lines; i++ ) + if( result == OSCC_OK ) { - names_ptr->name[i] = (char*) malloc(IFNAMSIZ * sizeof(char)); - } + while ( fgets( buffer, sizeof( buffer ), file_handler ) ) { + ++lines; + } - rewind( file_handler ); + names_ptr->name = (char**) malloc(lines * sizeof(char*)); + + uint i; + + for ( i = 0; i < lines; i++ ) + { + names_ptr->name[i] = (char*) malloc(IFNAMSIZ * sizeof(char)); + } - //Consume the first two lines since they are headers - fgets( buffer, sizeof( buffer ), file_handler ); - fgets( buffer, sizeof( buffer ), file_handler ); + rewind( file_handler ); - int size = 0; + //Consume the first two lines since they are headers + fgets( buffer, sizeof( buffer ), file_handler ); + fgets( buffer, sizeof( buffer ), file_handler ); + } char* socket_name = calloc( IFNAMSIZ, sizeof(char) ); @@ -916,15 +977,21 @@ oscc_result_t construct_interfaces_list( device_names_s * const names_ptr ) { result = OSCC_ERROR; } - else + + if( result == OSCC_OK ) { + uint size = 0; + while ( size < lines && fgets( buffer, sizeof( buffer ), file_handler ) ) { - get_device_name( buffer, socket_name ); + result = get_device_name( buffer, socket_name ); - strncpy( names_ptr->name[size], socket_name, IFNAMSIZ ); + if( result == OSCC_OK ) + { + strncpy( names_ptr->name[size], socket_name, IFNAMSIZ ); - size++; + size++; + } } free( socket_name ); @@ -937,44 +1004,67 @@ oscc_result_t construct_interfaces_list( device_names_s * const names_ptr ) return result; } -void clear_device_names( device_names_s * const names_ptr ) +oscc_result_t clear_device_names( device_names_s * const names_ptr ) { - int i; + oscc_result_t result = OSCC_OK; - for ( i = 0; i < names_ptr->size; i++ ) + if( names_ptr == NULL ) { - free( names_ptr->name[i] ); + result = OSCC_ERROR; } + else + { + uint i; - free( names_ptr->name ); -} + for ( i = 0; i < names_ptr->size; i++ ) + { + free( names_ptr->name[i] ); + } + free( names_ptr->name ); + } -void get_device_name( char * string, char * const name ) -{ - size_t span = strcspn(string, ":"); + return result; +} - char temp_name[IFNAMSIZ]; - strncpy( temp_name, string, span ); +oscc_result_t get_device_name( char * string, char * const name ) +{ + oscc_result_t result = OSCC_OK; - if( span <= IFNAMSIZ ) + if( name == NULL || string == NULL ) { - temp_name[span] = '\0'; + result = OSCC_ERROR; } - size_t leading_spaces = strspn( temp_name, " " ); - - if( leading_spaces != 0 ) + if( result == OSCC_OK ) { - char new_name[IFNAMSIZ]; + size_t span = strcspn(string, ":"); - strncpy( name, temp_name + leading_spaces, span - leading_spaces + 1 ); + char temp_name[IFNAMSIZ]; - new_name[span - leading_spaces] = '\0'; - } - else - { - strncpy( name, temp_name, span ); + strncpy( temp_name, string, span ); + + if( span <= IFNAMSIZ ) + { + temp_name[span] = '\0'; + } + + size_t leading_spaces = strspn( temp_name, " " ); + + if( leading_spaces != 0 ) + { + char new_name[IFNAMSIZ]; + + strncpy( name, temp_name + leading_spaces, span - leading_spaces + 1 ); + + new_name[span - leading_spaces] = '\0'; + } + else + { + strncpy( name, temp_name, span ); + } } + + return result; } From 088f516ea4d1e5ea710d4fc79bb6d11b8e76a3b7 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Thu, 1 Mar 2018 15:20:09 -0800 Subject: [PATCH 20/80] Remove switch case Prior to this commit a switch case statment was bing used for something that didn't have multiple cases. This commit replaces the case statement with an if block for simplicity. --- api/src/oscc.c | 49 ++++++++++++++++++++++++------------------------- 1 file changed, 24 insertions(+), 25 deletions(-) diff --git a/api/src/oscc.c b/api/src/oscc.c index 50beb3b1..d2d88be1 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -885,31 +885,30 @@ can_contains_s can_detection( const char *can_channel ) recv_bytes = read( sock, &rx_frame, sizeof( rx_frame ) ); - switch (recv_bytes) { - case CAN_MTU: - case CANFD_MTU: - if ( (rx_frame.can_id < 0x100) && - (rx_frame.data[0] == OSCC_MAGIC_BYTE_0) && - (rx_frame.data[1] == OSCC_MAGIC_BYTE_1) ) - { - oscc_detection.has_brake_report |= - ( (rx_frame.can_id == OSCC_BRAKE_REPORT_CAN_ID) ); - - oscc_detection.has_steer_report |= - ( (rx_frame.can_id == OSCC_STEERING_REPORT_CAN_ID) ); - - oscc_detection.has_accel_report |= - ( (rx_frame.can_id == OSCC_THROTTLE_REPORT_CAN_ID) ); - } - - vehicle_detection.has_brake_pressure |= - ( rx_frame.can_id == KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID ); - - vehicle_detection.has_steering_angle |= - ( rx_frame.can_id == KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID ); - - vehicle_detection.has_wheel_speed |= - ( rx_frame.can_id == KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID ); + if( recv_bytes == CAN_MTU || recv_bytes == CANFD_MTU ) + { + if ( (rx_frame.can_id < 0x100) && + (rx_frame.data[0] == OSCC_MAGIC_BYTE_0) && + (rx_frame.data[1] == OSCC_MAGIC_BYTE_1) ) + { + oscc_detection.has_brake_report |= + ( (rx_frame.can_id == OSCC_BRAKE_REPORT_CAN_ID) ); + + oscc_detection.has_steer_report |= + ( (rx_frame.can_id == OSCC_STEERING_REPORT_CAN_ID) ); + + oscc_detection.has_accel_report |= + ( (rx_frame.can_id == OSCC_THROTTLE_REPORT_CAN_ID) ); + } + + vehicle_detection.has_brake_pressure |= + ( rx_frame.can_id == KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID ); + + vehicle_detection.has_steering_angle |= + ( rx_frame.can_id == KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID ); + + vehicle_detection.has_wheel_speed |= + ( rx_frame.can_id == KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID ); } } From 0cb31661c807f21fe4ef84bccb234ed1ea7a0bd9 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Thu, 1 Mar 2018 15:22:59 -0800 Subject: [PATCH 21/80] Make static global variables SCREAMING_SNAKE_CASE Prior to this commit static globals weren't any different from local variables leaving it hard to tell which ones were global. This commit fixes that by changing them to SCREAMING_SNAKE_CASE. --- api/src/oscc.c | 56 +++++++++++++++++++++++++------------------------- 1 file changed, 28 insertions(+), 28 deletions(-) diff --git a/api/src/oscc.c b/api/src/oscc.c index d2d88be1..529656dc 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -19,8 +19,8 @@ #include "internal/oscc.h" -static int oscc_can_socket = UNINITIALIZED_SOCKET; -static int vehicle_can_socket = UNINITIALIZED_SOCKET; +static int OSCC_CAN_SOCKET = UNINITIALIZED_SOCKET; +static int VEHICLE_CAN_SOCKET = UNINITIALIZED_SOCKET; oscc_result_t oscc_init() @@ -34,9 +34,9 @@ oscc_result_t oscc_init() result = register_can_signal(); } - if ( result == OSCC_OK && oscc_can_socket > 0 ) + if ( result == OSCC_OK && OSCC_CAN_SOCKET > 0 ) { - result = oscc_async_enable( oscc_can_socket ); + result = oscc_async_enable( OSCC_CAN_SOCKET ); } else { @@ -44,9 +44,9 @@ oscc_result_t oscc_init() result = OSCC_ERROR; } - if ( result == OSCC_OK && vehicle_can_socket > 0 ) + if ( result == OSCC_OK && VEHICLE_CAN_SOCKET > 0 ) { - oscc_async_enable( vehicle_can_socket ); + oscc_async_enable( VEHICLE_CAN_SOCKET ); } return result; @@ -74,7 +74,7 @@ oscc_result_t oscc_open( unsigned int channel ) vehicle_ret = oscc_search_can( &auto_init_vehicle_can, false ); - if( (vehicle_can_socket < 0) || (vehicle_ret != OSCC_OK) ) + if( (VEHICLE_CAN_SOCKET < 0) || (vehicle_ret != OSCC_OK) ) { printf( "Warning: Vehicle CAN was not found.\n" ); } @@ -90,18 +90,18 @@ oscc_result_t oscc_open( unsigned int channel ) result = register_can_signal(); } - if ( result == OSCC_OK && oscc_can_socket >= 0 ) + if ( result == OSCC_OK && OSCC_CAN_SOCKET >= 0 ) { - result = oscc_async_enable( oscc_can_socket ); + result = oscc_async_enable( OSCC_CAN_SOCKET ); } else { printf( "Error: Could not find OSCC CAN signal.\n" ); } - if ( result == OSCC_OK && vehicle_can_socket >= 0 ) + if ( result == OSCC_OK && VEHICLE_CAN_SOCKET >= 0 ) { - oscc_async_enable( vehicle_can_socket ); + oscc_async_enable( VEHICLE_CAN_SOCKET ); } return result; @@ -112,9 +112,9 @@ oscc_result_t oscc_close( unsigned int channel ) { oscc_result_t result = OSCC_ERROR; - if( oscc_can_socket < 0 ) + if( OSCC_CAN_SOCKET < 0 ) { - int result = close( oscc_can_socket ); + int result = close( OSCC_CAN_SOCKET ); if ( result > 0 ) { @@ -122,9 +122,9 @@ oscc_result_t oscc_close( unsigned int channel ) } } - if( vehicle_can_socket < 0 ) + if( VEHICLE_CAN_SOCKET < 0 ) { - int result = close( vehicle_can_socket ); + int result = close( VEHICLE_CAN_SOCKET ); if ( result > 0 ) { @@ -448,9 +448,9 @@ void oscc_update_status( int sig, siginfo_t *siginfo, void *context ) struct can_frame rx_frame; memset( &rx_frame, 0, sizeof(rx_frame) ); - if ( oscc_can_socket >= 0 ) + if ( OSCC_CAN_SOCKET >= 0 ) { - int oscc_can_bytes = read( oscc_can_socket, &rx_frame, CAN_MTU ); + int oscc_can_bytes = read( OSCC_CAN_SOCKET, &rx_frame, CAN_MTU ); while ( oscc_can_bytes > 0 ) { @@ -500,19 +500,19 @@ void oscc_update_status( int sig, siginfo_t *siginfo, void *context ) } else { - if ( obd_frame_callback != NULL && vehicle_can_socket < 0 ) + if ( obd_frame_callback != NULL && VEHICLE_CAN_SOCKET < 0 ) { obd_frame_callback( &rx_frame ); } } - oscc_can_bytes = read( oscc_can_socket, &rx_frame, CAN_MTU ); + oscc_can_bytes = read( OSCC_CAN_SOCKET, &rx_frame, CAN_MTU ); } } - if ( vehicle_can_socket >= 0 ) + if ( VEHICLE_CAN_SOCKET >= 0 ) { - int vehicle_can_bytes = read( vehicle_can_socket, &rx_frame, CAN_MTU ); + int vehicle_can_bytes = read( VEHICLE_CAN_SOCKET, &rx_frame, CAN_MTU ); while( vehicle_can_bytes > 0 ) { @@ -524,7 +524,7 @@ void oscc_update_status( int sig, siginfo_t *siginfo, void *context ) obd_frame_callback( &rx_frame ); } - vehicle_can_bytes = read( vehicle_can_socket, &rx_frame, CAN_MTU ); + vehicle_can_bytes = read( VEHICLE_CAN_SOCKET, &rx_frame, CAN_MTU ); } } } @@ -534,7 +534,7 @@ oscc_result_t oscc_can_write( long id, void *msg, unsigned int dlc ) oscc_result_t result = OSCC_ERROR; - if ( oscc_can_socket >= 0 ) + if ( OSCC_CAN_SOCKET >= 0 ) { struct can_frame tx_frame; @@ -543,7 +543,7 @@ oscc_result_t oscc_can_write( long id, void *msg, unsigned int dlc ) tx_frame.can_dlc = dlc; memcpy( tx_frame.data, msg, dlc ); - int ret = write( oscc_can_socket, &tx_frame, sizeof(tx_frame) ); + int ret = write( OSCC_CAN_SOCKET, &tx_frame, sizeof(tx_frame) ); if ( ret > 0 ) { @@ -734,10 +734,10 @@ oscc_result_t init_oscc_can( const char *can_channel ) { printf( "Assigning OSCC CAN Channel to: %s\n", can_channel ); - oscc_can_socket = init_can_socket( can_channel, NULL ); + OSCC_CAN_SOCKET = init_can_socket( can_channel, NULL ); } - if( can_channel != NULL && oscc_can_socket >= 0 ) + if( can_channel != NULL && OSCC_CAN_SOCKET >= 0 ) { result = OSCC_OK; } @@ -754,10 +754,10 @@ oscc_result_t init_vehicle_can( const char *can_channel ) { printf( "Assigning Vehicle CAN Channel to: %s\n", can_channel ); - vehicle_can_socket = init_can_socket( can_channel, NULL ); + VEHICLE_CAN_SOCKET = init_can_socket( can_channel, NULL ); } - if( can_channel != NULL && vehicle_can_socket >= 0 ) + if( can_channel != NULL && VEHICLE_CAN_SOCKET >= 0 ) { result = OSCC_OK; } From 05d3e5f02db2f01aa598bd58916066c328425a26 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Thu, 1 Mar 2018 15:31:00 -0800 Subject: [PATCH 22/80] Switch globals from SCREAMING_SNAKE_CASE to prefix Prior to this commit the SCREAMING_SNAKE_CASE made globals no different from defined constants making it confusing when things were assigned to them. This commit fixes that by changing from SCREAMING_SNAKE_CASE to a prefix of global_. --- api/src/oscc.c | 56 +++++++++++++++++++++++++------------------------- 1 file changed, 28 insertions(+), 28 deletions(-) diff --git a/api/src/oscc.c b/api/src/oscc.c index 529656dc..2828da0c 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -19,8 +19,8 @@ #include "internal/oscc.h" -static int OSCC_CAN_SOCKET = UNINITIALIZED_SOCKET; -static int VEHICLE_CAN_SOCKET = UNINITIALIZED_SOCKET; +static int global_oscc_can_socket = UNINITIALIZED_SOCKET; +static int global_vehicle_can_socket = UNINITIALIZED_SOCKET; oscc_result_t oscc_init() @@ -34,9 +34,9 @@ oscc_result_t oscc_init() result = register_can_signal(); } - if ( result == OSCC_OK && OSCC_CAN_SOCKET > 0 ) + if ( result == OSCC_OK && global_oscc_can_socket > 0 ) { - result = oscc_async_enable( OSCC_CAN_SOCKET ); + result = oscc_async_enable( global_oscc_can_socket ); } else { @@ -44,9 +44,9 @@ oscc_result_t oscc_init() result = OSCC_ERROR; } - if ( result == OSCC_OK && VEHICLE_CAN_SOCKET > 0 ) + if ( result == OSCC_OK && global_vehicle_can_socket > 0 ) { - oscc_async_enable( VEHICLE_CAN_SOCKET ); + oscc_async_enable( global_vehicle_can_socket ); } return result; @@ -74,7 +74,7 @@ oscc_result_t oscc_open( unsigned int channel ) vehicle_ret = oscc_search_can( &auto_init_vehicle_can, false ); - if( (VEHICLE_CAN_SOCKET < 0) || (vehicle_ret != OSCC_OK) ) + if( (global_vehicle_can_socket < 0) || (vehicle_ret != OSCC_OK) ) { printf( "Warning: Vehicle CAN was not found.\n" ); } @@ -90,18 +90,18 @@ oscc_result_t oscc_open( unsigned int channel ) result = register_can_signal(); } - if ( result == OSCC_OK && OSCC_CAN_SOCKET >= 0 ) + if ( result == OSCC_OK && global_oscc_can_socket >= 0 ) { - result = oscc_async_enable( OSCC_CAN_SOCKET ); + result = oscc_async_enable( global_oscc_can_socket ); } else { printf( "Error: Could not find OSCC CAN signal.\n" ); } - if ( result == OSCC_OK && VEHICLE_CAN_SOCKET >= 0 ) + if ( result == OSCC_OK && global_vehicle_can_socket >= 0 ) { - oscc_async_enable( VEHICLE_CAN_SOCKET ); + oscc_async_enable( global_vehicle_can_socket ); } return result; @@ -112,9 +112,9 @@ oscc_result_t oscc_close( unsigned int channel ) { oscc_result_t result = OSCC_ERROR; - if( OSCC_CAN_SOCKET < 0 ) + if( global_oscc_can_socket < 0 ) { - int result = close( OSCC_CAN_SOCKET ); + int result = close( global_oscc_can_socket ); if ( result > 0 ) { @@ -122,9 +122,9 @@ oscc_result_t oscc_close( unsigned int channel ) } } - if( VEHICLE_CAN_SOCKET < 0 ) + if( global_vehicle_can_socket < 0 ) { - int result = close( VEHICLE_CAN_SOCKET ); + int result = close( global_vehicle_can_socket ); if ( result > 0 ) { @@ -448,9 +448,9 @@ void oscc_update_status( int sig, siginfo_t *siginfo, void *context ) struct can_frame rx_frame; memset( &rx_frame, 0, sizeof(rx_frame) ); - if ( OSCC_CAN_SOCKET >= 0 ) + if ( global_oscc_can_socket >= 0 ) { - int oscc_can_bytes = read( OSCC_CAN_SOCKET, &rx_frame, CAN_MTU ); + int oscc_can_bytes = read( global_oscc_can_socket, &rx_frame, CAN_MTU ); while ( oscc_can_bytes > 0 ) { @@ -500,19 +500,19 @@ void oscc_update_status( int sig, siginfo_t *siginfo, void *context ) } else { - if ( obd_frame_callback != NULL && VEHICLE_CAN_SOCKET < 0 ) + if ( obd_frame_callback != NULL && global_vehicle_can_socket < 0 ) { obd_frame_callback( &rx_frame ); } } - oscc_can_bytes = read( OSCC_CAN_SOCKET, &rx_frame, CAN_MTU ); + oscc_can_bytes = read( global_oscc_can_socket, &rx_frame, CAN_MTU ); } } - if ( VEHICLE_CAN_SOCKET >= 0 ) + if ( global_vehicle_can_socket >= 0 ) { - int vehicle_can_bytes = read( VEHICLE_CAN_SOCKET, &rx_frame, CAN_MTU ); + int vehicle_can_bytes = read( global_vehicle_can_socket, &rx_frame, CAN_MTU ); while( vehicle_can_bytes > 0 ) { @@ -524,7 +524,7 @@ void oscc_update_status( int sig, siginfo_t *siginfo, void *context ) obd_frame_callback( &rx_frame ); } - vehicle_can_bytes = read( VEHICLE_CAN_SOCKET, &rx_frame, CAN_MTU ); + vehicle_can_bytes = read( global_vehicle_can_socket, &rx_frame, CAN_MTU ); } } } @@ -534,7 +534,7 @@ oscc_result_t oscc_can_write( long id, void *msg, unsigned int dlc ) oscc_result_t result = OSCC_ERROR; - if ( OSCC_CAN_SOCKET >= 0 ) + if ( global_oscc_can_socket >= 0 ) { struct can_frame tx_frame; @@ -543,7 +543,7 @@ oscc_result_t oscc_can_write( long id, void *msg, unsigned int dlc ) tx_frame.can_dlc = dlc; memcpy( tx_frame.data, msg, dlc ); - int ret = write( OSCC_CAN_SOCKET, &tx_frame, sizeof(tx_frame) ); + int ret = write( global_oscc_can_socket, &tx_frame, sizeof(tx_frame) ); if ( ret > 0 ) { @@ -734,10 +734,10 @@ oscc_result_t init_oscc_can( const char *can_channel ) { printf( "Assigning OSCC CAN Channel to: %s\n", can_channel ); - OSCC_CAN_SOCKET = init_can_socket( can_channel, NULL ); + global_oscc_can_socket = init_can_socket( can_channel, NULL ); } - if( can_channel != NULL && OSCC_CAN_SOCKET >= 0 ) + if( can_channel != NULL && global_oscc_can_socket >= 0 ) { result = OSCC_OK; } @@ -754,10 +754,10 @@ oscc_result_t init_vehicle_can( const char *can_channel ) { printf( "Assigning Vehicle CAN Channel to: %s\n", can_channel ); - VEHICLE_CAN_SOCKET = init_can_socket( can_channel, NULL ); + global_vehicle_can_socket = init_can_socket( can_channel, NULL ); } - if( can_channel != NULL && VEHICLE_CAN_SOCKET >= 0 ) + if( can_channel != NULL && global_vehicle_can_socket >= 0 ) { result = OSCC_OK; } From 347947ce69050cbba7c09bc7360132047d3dd924 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Thu, 1 Mar 2018 17:07:02 -0800 Subject: [PATCH 23/80] Fix error state Prior to this commit oscc_open would fail because it checked for OSCC_OK before any funciton set result. This comit fixes that by removing the first if condition so that result is assigned before checking it. --- api/src/oscc.c | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/api/src/oscc.c b/api/src/oscc.c index 2828da0c..6780ce80 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -68,7 +68,7 @@ oscc_result_t oscc_open( unsigned int channel ) channel_contents = can_detection( can_string_buffer ); - if( result == OSCC_OK && !channel_contents.has_vehicle ) + if( !channel_contents.has_vehicle ) { int vehicle_ret = OSCC_ERROR; @@ -80,10 +80,7 @@ oscc_result_t oscc_open( unsigned int channel ) } } - if( result == OSCC_OK) - { - result = init_oscc_can( can_string_buffer ); - } + result = init_oscc_can( can_string_buffer ); if( result == OSCC_OK) { From 8605ccfb3edce904d1ac6db30e0c29232c3ad420 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Thu, 1 Mar 2018 17:16:27 -0800 Subject: [PATCH 24/80] Check and set freed memory to NULL Prior to this commit the free was run without checking if the pointer was NULL. This commit fixes that by checking if the pointer is equal to NULL and then after memory is free'd setting it equal to NULL. --- api/src/oscc.c | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/api/src/oscc.c b/api/src/oscc.c index 6780ce80..bbe34cba 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -1014,10 +1014,20 @@ oscc_result_t clear_device_names( device_names_s * const names_ptr ) for ( i = 0; i < names_ptr->size; i++ ) { - free( names_ptr->name[i] ); + if( names_ptr->name[i] != NULL ) + { + free( names_ptr->name[i] ); + } + + names_ptr->name[i] = NULL; + } + + if( names_ptr->name != NULL ) + { + free( names_ptr->name ); } - free( names_ptr->name ); + names_ptr->name = NULL; } return result; From fbaaddf2e5ff3e309856023ee5c6f5738940c84a Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Thu, 1 Mar 2018 17:23:13 -0800 Subject: [PATCH 25/80] Move assign into if block Prior to this commit a NULL assign was outside of an if block that checked for NULL. This commit moves the assign into the if block to save an assign in the case that the NULL already exists. --- api/src/oscc.c | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/api/src/oscc.c b/api/src/oscc.c index bbe34cba..05f5034f 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -1017,17 +1017,19 @@ oscc_result_t clear_device_names( device_names_s * const names_ptr ) if( names_ptr->name[i] != NULL ) { free( names_ptr->name[i] ); + + names_ptr->name[i] = NULL; } - names_ptr->name[i] = NULL; } if( names_ptr->name != NULL ) { free( names_ptr->name ); + + names_ptr->name = NULL; } - names_ptr->name = NULL; } return result; From 316e6d865bc3f592bca3667edd8d863d30a71e16 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Fri, 30 Mar 2018 13:40:07 -0700 Subject: [PATCH 26/80] Update CMake Calls for portability Prior to this commit the CMakeLists.txt in the firmware directory assumed the files would be built in that directory. This commit makes some changes to CMakeLists.txt files to remove that assumption so that the firmware directory can be used and built elsewhere by providing an include .cmake file and using a root firmware directory instead of CMAKE_SOURCE_DIR. --- firmware/CMakeLists.txt | 53 ++----------------- firmware/brake/CMakeLists.txt | 2 +- .../brake/kia_soul_ev_niro/CMakeLists.txt | 36 ++++++------- firmware/brake/kia_soul_petrol/CMakeLists.txt | 32 +++++------ firmware/can_gateway/CMakeLists.txt | 32 +++++------ firmware/cmake/OsccFirmware.cmake | 53 +++++++++++++++++++ firmware/steering/CMakeLists.txt | 40 +++++++------- firmware/throttle/CMakeLists.txt | 36 ++++++------- 8 files changed, 145 insertions(+), 139 deletions(-) create mode 100644 firmware/cmake/OsccFirmware.cmake diff --git a/firmware/CMakeLists.txt b/firmware/CMakeLists.txt index 6fbab699..4893729b 100644 --- a/firmware/CMakeLists.txt +++ b/firmware/CMakeLists.txt @@ -1,6 +1,6 @@ -if(TESTS) - cmake_minimum_required(VERSION 2.8) +cmake_minimum_required(VERSION 2.8) +if(TESTS) project(tests) if(TESTS) @@ -57,57 +57,10 @@ if(TESTS) else() set(CMAKE_TOOLCHAIN_FILE common/toolchain/ArduinoToolchain.cmake) - cmake_minimum_required(VERSION 2.8) + include(cmake/OsccFirmware.cmake) project(firmware) - set(CMAKE_CFLAGS "-std=gnu11 -Os") - set(CMAKE_CXX_FLAGS "-std=gnu++11 -Os") - - option(DEBUG "Enable debug mode" OFF) - option(KIA_SOUL "Build firmware for the petrol Kia Soul" OFF) - option(KIA_SOUL_EV "Build firmware for the Kia Soul EV" OFF) - option(KIA_NIRO "Build firmware for the Kia Niro" OFF) - option(BRAKE_STARTUP_TEST "Enable brake startup sensor tests" ON) - option(STEERING_OVERRIDE "Enable steering override" ON) - - set(SERIAL_PORT_BRAKE "/dev/ttyACM0" CACHE STRING "Serial port of the brake module") - set(SERIAL_BAUD_BRAKE "115200" CACHE STRING "Serial baud rate of the brake module") - - set(SERIAL_PORT_CAN_GATEWAY "/dev/ttyACM0" CACHE STRING "Serial port of the CAN gateway module") - set(SERIAL_BAUD_CAN_GATEWAY "115200" CACHE STRING "Serial baud rate of the CAN gateway module") - - set(SERIAL_PORT_STEERING "/dev/ttyACM0" CACHE STRING "Serial port of the steering module") - set(SERIAL_BAUD_STEERING "115200" CACHE STRING "Serial baud rate of the steering module") - - set(SERIAL_PORT_THROTTLE "/dev/ttyACM0" CACHE STRING "Serial port of the throttle module") - set(SERIAL_BAUD_THROTTLE "115200" CACHE STRING "Serial baud rate of the throttle module") - - if(DEBUG) - add_definitions(-DDEBUG) - endif() - - if(KIA_SOUL) - add_definitions(-DKIA_SOUL) - elseif(KIA_SOUL_EV) - add_definitions(-DKIA_SOUL_EV) - elseif(KIA_NIRO) - add_definitions(-DKIA_NIRO) - else() - message(FATAL_ERROR "No platform selected - no firmware will be built") - endif() - - if(KIA_SOUL AND BRAKE_STARTUP_TEST) - add_definitions(-DBRAKE_STARTUP_TEST) - elseif(KIA_SOUL AND NOT BRAKE_STARTUP_TEST) - message(WARNING "Brake sensor startup tests disabled") - endif() - - if(STEERING_OVERRIDE) - add_definitions(-DSTEERING_OVERRIDE) - message(WARNING "Steering override is enabled. This is an experimental feature! Attempting to grab the steering wheel while the system is active could result in serious injury. The preferred method of operator override for steering is to utilize the brake pedal or E-stop button.") - endif() - add_subdirectory(brake) add_subdirectory(can_gateway) add_subdirectory(steering) diff --git a/firmware/brake/CMakeLists.txt b/firmware/brake/CMakeLists.txt index 9b0aa0d3..e28759ba 100644 --- a/firmware/brake/CMakeLists.txt +++ b/firmware/brake/CMakeLists.txt @@ -1,6 +1,6 @@ project(brake) -SET(ARDUINO_DEFAULT_PORT ${SERIAL_PORT_BRAKE}) +set(ARDUINO_DEFAULT_PORT ${SERIAL_PORT_BRAKE}) set(ARDUINO_DEFAULT_BAUDRATE ${SERIAL_BAUD_BRAKE}) add_definitions(-DSERIAL_BAUD=${ARDUINO_DEFAULT_BAUDRATE}) diff --git a/firmware/brake/kia_soul_ev_niro/CMakeLists.txt b/firmware/brake/kia_soul_ev_niro/CMakeLists.txt index 891758d9..0a0b5a46 100644 --- a/firmware/brake/kia_soul_ev_niro/CMakeLists.txt +++ b/firmware/brake/kia_soul_ev_niro/CMakeLists.txt @@ -3,14 +3,14 @@ set(ARDUINO_DEFAULT_BOARD uno) generate_arduino_firmware( brake SRCS - ${CMAKE_SOURCE_DIR}/common/libs/arduino_init/arduino_init.cpp - ${CMAKE_SOURCE_DIR}/common/libs/DAC_MCP49xx/DAC_MCP49xx.cpp - ${CMAKE_SOURCE_DIR}/common/libs/fault_check/oscc_check.cpp - ${CMAKE_SOURCE_DIR}/common/libs/mcp_can/mcp_can.cpp - ${CMAKE_SOURCE_DIR}/common/libs/serial/oscc_serial.cpp - ${CMAKE_SOURCE_DIR}/common/libs/can/oscc_can.cpp - ${CMAKE_SOURCE_DIR}/common/libs/dac/oscc_dac.cpp - ${CMAKE_SOURCE_DIR}/common/libs/timer/oscc_timer.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/arduino_init/arduino_init.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/DAC_MCP49xx/DAC_MCP49xx.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/fault_check/oscc_check.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/mcp_can/mcp_can.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/serial/oscc_serial.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/can/oscc_can.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/dac/oscc_dac.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/timer/oscc_timer.cpp src/main.cpp src/globals.cpp src/brake_control.cpp @@ -21,13 +21,13 @@ target_include_directories( brake PRIVATE include - ${CMAKE_SOURCE_DIR}/common/include - ${CMAKE_SOURCE_DIR}/common/libs/arduino_init - ${CMAKE_SOURCE_DIR}/common/libs/DAC_MCP49xx - ${CMAKE_SOURCE_DIR}/common/libs/fault_check - ${CMAKE_SOURCE_DIR}/common/libs/mcp_can - ${CMAKE_SOURCE_DIR}/common/libs/serial - ${CMAKE_SOURCE_DIR}/common/libs/can - ${CMAKE_SOURCE_DIR}/common/libs/dac - ${CMAKE_SOURCE_DIR}/common/libs/timer - ${CMAKE_SOURCE_DIR}/../api/include) + ${OSCC_FIRMWARE_ROOT}/common/include + ${OSCC_FIRMWARE_ROOT}/common/libs/arduino_init + ${OSCC_FIRMWARE_ROOT}/common/libs/DAC_MCP49xx + ${OSCC_FIRMWARE_ROOT}/common/libs/fault_check + ${OSCC_FIRMWARE_ROOT}/common/libs/mcp_can + ${OSCC_FIRMWARE_ROOT}/common/libs/serial + ${OSCC_FIRMWARE_ROOT}/common/libs/can + ${OSCC_FIRMWARE_ROOT}/common/libs/dac + ${OSCC_FIRMWARE_ROOT}/common/libs/timer + ${OSCC_FIRMWARE_ROOT}/../api/include) diff --git a/firmware/brake/kia_soul_petrol/CMakeLists.txt b/firmware/brake/kia_soul_petrol/CMakeLists.txt index b854ddc9..a5f34426 100644 --- a/firmware/brake/kia_soul_petrol/CMakeLists.txt +++ b/firmware/brake/kia_soul_petrol/CMakeLists.txt @@ -3,13 +3,13 @@ set(ARDUINO_DEFAULT_BOARD mega2560) generate_arduino_firmware( brake SRCS - ${CMAKE_SOURCE_DIR}/common/libs/arduino_init/arduino_init.cpp - ${CMAKE_SOURCE_DIR}/common/libs/mcp_can/mcp_can.cpp - ${CMAKE_SOURCE_DIR}/common/libs/pid/oscc_pid.cpp - ${CMAKE_SOURCE_DIR}/common/libs/serial/oscc_serial.cpp - ${CMAKE_SOURCE_DIR}/common/libs/can/oscc_can.cpp - ${CMAKE_SOURCE_DIR}/common/libs/timer/oscc_timer.cpp - ${CMAKE_SOURCE_DIR}/common/libs/fault_check/oscc_check.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/arduino_init/arduino_init.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/mcp_can/mcp_can.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/pid/oscc_pid.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/serial/oscc_serial.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/can/oscc_can.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/timer/oscc_timer.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/fault_check/oscc_check.cpp src/main.cpp src/globals.cpp src/accumulator.cpp @@ -24,14 +24,14 @@ target_include_directories( brake PRIVATE include - ${CMAKE_SOURCE_DIR}/common/include - ${CMAKE_SOURCE_DIR}/common/libs/arduino_init - ${CMAKE_SOURCE_DIR}/common/libs/mcp_can - ${CMAKE_SOURCE_DIR}/common/libs/pid - ${CMAKE_SOURCE_DIR}/common/libs/serial - ${CMAKE_SOURCE_DIR}/common/libs/can - ${CMAKE_SOURCE_DIR}/common/libs/timer - ${CMAKE_SOURCE_DIR}/common/libs/fault_check - ${CMAKE_SOURCE_DIR}/../api/include) + ${OSCC_FIRMWARE_ROOT}/common/include + ${OSCC_FIRMWARE_ROOT}/common/libs/arduino_init + ${OSCC_FIRMWARE_ROOT}/common/libs/mcp_can + ${OSCC_FIRMWARE_ROOT}/common/libs/pid + ${OSCC_FIRMWARE_ROOT}/common/libs/serial + ${OSCC_FIRMWARE_ROOT}/common/libs/can + ${OSCC_FIRMWARE_ROOT}/common/libs/timer + ${OSCC_FIRMWARE_ROOT}/common/libs/fault_check + ${OSCC_FIRMWARE_ROOT}/../api/include) add_subdirectory(utils) diff --git a/firmware/can_gateway/CMakeLists.txt b/firmware/can_gateway/CMakeLists.txt index b5a76658..ccea737d 100644 --- a/firmware/can_gateway/CMakeLists.txt +++ b/firmware/can_gateway/CMakeLists.txt @@ -17,13 +17,13 @@ add_custom_target( generate_arduino_firmware( can-gateway SRCS - ${CMAKE_SOURCE_DIR}/common/libs/arduino_init/arduino_init.cpp - ${CMAKE_SOURCE_DIR}/common/libs/mcp_can/mcp_can.cpp - ${CMAKE_SOURCE_DIR}/common/libs/serial/oscc_serial.cpp - ${CMAKE_SOURCE_DIR}/common/libs/can/oscc_can.cpp - ${CMAKE_SOURCE_DIR}/common/libs/timer/oscc_timer.cpp - ${CMAKE_SOURCE_DIR}/common/libs/ssd1325/ssd1325.cpp - ${CMAKE_SOURCE_DIR}/common/libs/ssd1325/gfx/gfx.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/arduino_init/arduino_init.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/mcp_can/mcp_can.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/serial/oscc_serial.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/can/oscc_can.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/timer/oscc_timer.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/ssd1325/ssd1325.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/ssd1325/gfx/gfx.cpp src/main.cpp src/globals.cpp src/init.cpp @@ -35,12 +35,12 @@ target_include_directories( can-gateway PRIVATE include - ${CMAKE_SOURCE_DIR}/common/include - ${CMAKE_SOURCE_DIR}/common/libs/arduino_init - ${CMAKE_SOURCE_DIR}/common/libs/mcp_can - ${CMAKE_SOURCE_DIR}/common/libs/serial - ${CMAKE_SOURCE_DIR}/common/libs/can - ${CMAKE_SOURCE_DIR}/common/libs/timer - ${CMAKE_SOURCE_DIR}/common/libs/ssd1325 - ${CMAKE_SOURCE_DIR}/common/libs/ssd1325/gfx - ${CMAKE_SOURCE_DIR}/../api/include) + ${OSCC_FIRMWARE_ROOT}/common/include + ${OSCC_FIRMWARE_ROOT}/common/libs/arduino_init + ${OSCC_FIRMWARE_ROOT}/common/libs/mcp_can + ${OSCC_FIRMWARE_ROOT}/common/libs/serial + ${OSCC_FIRMWARE_ROOT}/common/libs/can + ${OSCC_FIRMWARE_ROOT}/common/libs/timer + ${OSCC_FIRMWARE_ROOT}/common/libs/ssd1325 + ${OSCC_FIRMWARE_ROOT}/common/libs/ssd1325/gfx + ${OSCC_FIRMWARE_ROOT}/../api/include) diff --git a/firmware/cmake/OsccFirmware.cmake b/firmware/cmake/OsccFirmware.cmake new file mode 100644 index 00000000..eb918abf --- /dev/null +++ b/firmware/cmake/OsccFirmware.cmake @@ -0,0 +1,53 @@ +cmake_minimum_required(VERSION 2.8) + +set(OSCC_FIRMWARE_ROOT ${CMAKE_CURRENT_LIST_DIR}/..) + +#Required by Arduino? +#set(CMAKE_CFLAGS "-std=gnu11 -Os") +#set(CMAKE_CXX_FLAGS "-std=gnu++11 -Os") + +#can use set instead of option like below? +option(DEBUG "Enable debug mode" OFF) +option(KIA_SOUL "Build firmware for the petrol Kia Soul" OFF) +option(KIA_SOUL_EV "Build firmware for the Kia Soul EV" OFF) +option(KIA_NIRO "Build firmware for the Kia Niro" OFF) +option(BRAKE_STARTUP_TEST "Enable brake startup sensor tests" ON) +option(STEERING_OVERRIDE "Enable steering override" ON) + +set(SERIAL_PORT_BRAKE "/dev/ttyACM0" CACHE STRING "Serial port of the brake module") +set(SERIAL_BAUD_BRAKE "115200" CACHE STRING "Serial baud rate of the brake module") + +set(SERIAL_PORT_CAN_GATEWAY "/dev/ttyACM0" CACHE STRING "Serial port of the CAN gateway module") +set(SERIAL_BAUD_CAN_GATEWAY "115200" CACHE STRING "Serial baud rate of the CAN gateway module") + +set(SERIAL_PORT_STEERING "/dev/ttyACM0" CACHE STRING "Serial port of the steering module") +set(SERIAL_BAUD_STEERING "115200" CACHE STRING "Serial baud rate of the steering module") + +set(SERIAL_PORT_THROTTLE "/dev/ttyACM0" CACHE STRING "Serial port of the throttle module") +set(SERIAL_BAUD_THROTTLE "115200" CACHE STRING "Serial baud rate of the throttle module") + +#target_compile_options (or something) for setting locally rather than globally +if(DEBUG) + add_definitions(-DDEBUG) +endif() + +if(KIA_SOUL) + add_definitions(-DKIA_SOUL) +elseif(KIA_SOUL_EV) + add_definitions(-DKIA_SOUL_EV) +elseif(KIA_NIRO) + add_definitions(-DKIA_NIRO) +else() + message(FATAL_ERROR "No platform selected - no firmware will be built") +endif() + +if(KIA_SOUL AND BRAKE_STARTUP_TEST) + add_definitions(-DBRAKE_STARTUP_TEST) +elseif(KIA_SOUL AND NOT BRAKE_STARTUP_TEST) + message(WARNING "Brake sensor startup tests disabled") +endif() + +if(STEERING_OVERRIDE) + add_definitions(-DSTEERING_OVERRIDE) + message(WARNING "Steering override is enabled. This is an experimental feature! Attempting to grab the steering wheel while the system is active could result in serious injury. The preferred method of operator override for steering is to utilize the brake pedal or E-stop button.") +endif() diff --git a/firmware/steering/CMakeLists.txt b/firmware/steering/CMakeLists.txt index cc8ad953..09361af6 100644 --- a/firmware/steering/CMakeLists.txt +++ b/firmware/steering/CMakeLists.txt @@ -17,15 +17,15 @@ add_custom_target( generate_arduino_firmware( steering SRCS - ${CMAKE_SOURCE_DIR}/common/libs/arduino_init/arduino_init.cpp - ${CMAKE_SOURCE_DIR}/common/libs/DAC_MCP49xx/DAC_MCP49xx.cpp - ${CMAKE_SOURCE_DIR}/common/libs/fault_check/oscc_check.cpp - ${CMAKE_SOURCE_DIR}/common/libs/mcp_can/mcp_can.cpp - ${CMAKE_SOURCE_DIR}/common/libs/pid/oscc_pid.cpp - ${CMAKE_SOURCE_DIR}/common/libs/serial/oscc_serial.cpp - ${CMAKE_SOURCE_DIR}/common/libs/can/oscc_can.cpp - ${CMAKE_SOURCE_DIR}/common/libs/dac/oscc_dac.cpp - ${CMAKE_SOURCE_DIR}/common/libs/timer/oscc_timer.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/arduino_init/arduino_init.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/DAC_MCP49xx/DAC_MCP49xx.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/fault_check/oscc_check.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/mcp_can/mcp_can.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/pid/oscc_pid.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/serial/oscc_serial.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/can/oscc_can.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/dac/oscc_dac.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/timer/oscc_timer.cpp src/main.cpp src/globals.cpp src/init.cpp @@ -36,14 +36,14 @@ target_include_directories( steering PRIVATE include - ${CMAKE_SOURCE_DIR}/common/include - ${CMAKE_SOURCE_DIR}/common/libs/arduino_init - ${CMAKE_SOURCE_DIR}/common/libs/DAC_MCP49xx - ${CMAKE_SOURCE_DIR}/common/libs/fault_check - ${CMAKE_SOURCE_DIR}/common/libs/mcp_can - ${CMAKE_SOURCE_DIR}/common/libs/pid - ${CMAKE_SOURCE_DIR}/common/libs/serial - ${CMAKE_SOURCE_DIR}/common/libs/can - ${CMAKE_SOURCE_DIR}/common/libs/dac - ${CMAKE_SOURCE_DIR}/common/libs/timer - ${CMAKE_SOURCE_DIR}/../api/include) + ${OSCC_FIRMWARE_ROOT}/common/include + ${OSCC_FIRMWARE_ROOT}/common/libs/arduino_init + ${OSCC_FIRMWARE_ROOT}/common/libs/DAC_MCP49xx + ${OSCC_FIRMWARE_ROOT}/common/libs/fault_check + ${OSCC_FIRMWARE_ROOT}/common/libs/mcp_can + ${OSCC_FIRMWARE_ROOT}/common/libs/pid + ${OSCC_FIRMWARE_ROOT}/common/libs/serial + ${OSCC_FIRMWARE_ROOT}/common/libs/can + ${OSCC_FIRMWARE_ROOT}/common/libs/dac + ${OSCC_FIRMWARE_ROOT}/common/libs/timer + ${OSCC_FIRMWARE_ROOT}/../api/include) diff --git a/firmware/throttle/CMakeLists.txt b/firmware/throttle/CMakeLists.txt index 36b0ba12..2e798a08 100644 --- a/firmware/throttle/CMakeLists.txt +++ b/firmware/throttle/CMakeLists.txt @@ -17,14 +17,14 @@ add_custom_target( generate_arduino_firmware( throttle SRCS - ${CMAKE_SOURCE_DIR}/common/libs/arduino_init/arduino_init.cpp - ${CMAKE_SOURCE_DIR}/common/libs/DAC_MCP49xx/DAC_MCP49xx.cpp - ${CMAKE_SOURCE_DIR}/common/libs/fault_check/oscc_check.cpp - ${CMAKE_SOURCE_DIR}/common/libs/mcp_can/mcp_can.cpp - ${CMAKE_SOURCE_DIR}/common/libs/serial/oscc_serial.cpp - ${CMAKE_SOURCE_DIR}/common/libs/can/oscc_can.cpp - ${CMAKE_SOURCE_DIR}/common/libs/dac/oscc_dac.cpp - ${CMAKE_SOURCE_DIR}/common/libs/timer/oscc_timer.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/arduino_init/arduino_init.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/DAC_MCP49xx/DAC_MCP49xx.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/fault_check/oscc_check.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/mcp_can/mcp_can.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/serial/oscc_serial.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/can/oscc_can.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/dac/oscc_dac.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/timer/oscc_timer.cpp src/main.cpp src/globals.cpp src/init.cpp @@ -35,13 +35,13 @@ target_include_directories( throttle PRIVATE include - ${CMAKE_SOURCE_DIR}/common/include - ${CMAKE_SOURCE_DIR}/common/libs/arduino_init - ${CMAKE_SOURCE_DIR}/common/libs/DAC_MCP49xx - ${CMAKE_SOURCE_DIR}/common/libs/fault_check - ${CMAKE_SOURCE_DIR}/common/libs/mcp_can - ${CMAKE_SOURCE_DIR}/common/libs/serial - ${CMAKE_SOURCE_DIR}/common/libs/can - ${CMAKE_SOURCE_DIR}/common/libs/dac - ${CMAKE_SOURCE_DIR}/common/libs/timer - ${CMAKE_SOURCE_DIR}/../api/include) + ${OSCC_FIRMWARE_ROOT}/common/include + ${OSCC_FIRMWARE_ROOT}/common/libs/arduino_init + ${OSCC_FIRMWARE_ROOT}/common/libs/DAC_MCP49xx + ${OSCC_FIRMWARE_ROOT}/common/libs/fault_check + ${OSCC_FIRMWARE_ROOT}/common/libs/mcp_can + ${OSCC_FIRMWARE_ROOT}/common/libs/serial + ${OSCC_FIRMWARE_ROOT}/common/libs/can + ${OSCC_FIRMWARE_ROOT}/common/libs/dac + ${OSCC_FIRMWARE_ROOT}/common/libs/timer + ${OSCC_FIRMWARE_ROOT}/../api/include) From f701d1172531d9cb33d2fdde8833eed9e8fbd196 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Fri, 30 Mar 2018 15:39:06 -0700 Subject: [PATCH 27/80] Commonize OsccConfig.cmake Prior to this commit there were multiple if blocks for the same thin in the API and firmware directories. This commit fixes that by placing the if block in the firmware directory and pointing the API OsccConfig.cmake to the one in the firmware. --- api/OsccConfig.cmake | 10 +--------- firmware/cmake/OsccConfig.cmake | 9 +++++++++ firmware/cmake/OsccFirmware.cmake | 11 +---------- 3 files changed, 11 insertions(+), 19 deletions(-) create mode 100644 firmware/cmake/OsccConfig.cmake diff --git a/api/OsccConfig.cmake b/api/OsccConfig.cmake index 5fc0cc72..cf219507 100644 --- a/api/OsccConfig.cmake +++ b/api/OsccConfig.cmake @@ -1,9 +1 @@ -if(KIA_SOUL) - add_definitions(-DKIA_SOUL) -elseif(KIA_SOUL_EV) - add_definitions(-DKIA_SOUL_EV) -elseif(KIA_NIRO) - add_definitions(-DKIA_NIRO) -else() - message(FATAL_ERROR "No platform selected") -endif() +include(${CMAKE_SOURCE_DIR}/../firmware/cmake/OsccConfig.cmake) diff --git a/firmware/cmake/OsccConfig.cmake b/firmware/cmake/OsccConfig.cmake new file mode 100644 index 00000000..5fc0cc72 --- /dev/null +++ b/firmware/cmake/OsccConfig.cmake @@ -0,0 +1,9 @@ +if(KIA_SOUL) + add_definitions(-DKIA_SOUL) +elseif(KIA_SOUL_EV) + add_definitions(-DKIA_SOUL_EV) +elseif(KIA_NIRO) + add_definitions(-DKIA_NIRO) +else() + message(FATAL_ERROR "No platform selected") +endif() diff --git a/firmware/cmake/OsccFirmware.cmake b/firmware/cmake/OsccFirmware.cmake index eb918abf..f8b3fc40 100644 --- a/firmware/cmake/OsccFirmware.cmake +++ b/firmware/cmake/OsccFirmware.cmake @@ -1,5 +1,6 @@ cmake_minimum_required(VERSION 2.8) +include(OsccConfig.cmake) set(OSCC_FIRMWARE_ROOT ${CMAKE_CURRENT_LIST_DIR}/..) #Required by Arduino? @@ -31,16 +32,6 @@ if(DEBUG) add_definitions(-DDEBUG) endif() -if(KIA_SOUL) - add_definitions(-DKIA_SOUL) -elseif(KIA_SOUL_EV) - add_definitions(-DKIA_SOUL_EV) -elseif(KIA_NIRO) - add_definitions(-DKIA_NIRO) -else() - message(FATAL_ERROR "No platform selected - no firmware will be built") -endif() - if(KIA_SOUL AND BRAKE_STARTUP_TEST) add_definitions(-DBRAKE_STARTUP_TEST) elseif(KIA_SOUL AND NOT BRAKE_STARTUP_TEST) From adde0828f41a05a6f4365c7e6658a49ebdab3b71 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Fri, 30 Mar 2018 15:41:59 -0700 Subject: [PATCH 28/80] Remove dead code and clean up options Prior to this commit there were a mix of set and option calls making for clarity all of these have been changed to use the set cmake function. --- firmware/cmake/OsccFirmware.cmake | 18 ++++++------------ 1 file changed, 6 insertions(+), 12 deletions(-) diff --git a/firmware/cmake/OsccFirmware.cmake b/firmware/cmake/OsccFirmware.cmake index f8b3fc40..c55d04a8 100644 --- a/firmware/cmake/OsccFirmware.cmake +++ b/firmware/cmake/OsccFirmware.cmake @@ -3,17 +3,12 @@ cmake_minimum_required(VERSION 2.8) include(OsccConfig.cmake) set(OSCC_FIRMWARE_ROOT ${CMAKE_CURRENT_LIST_DIR}/..) -#Required by Arduino? -#set(CMAKE_CFLAGS "-std=gnu11 -Os") -#set(CMAKE_CXX_FLAGS "-std=gnu++11 -Os") - -#can use set instead of option like below? -option(DEBUG "Enable debug mode" OFF) -option(KIA_SOUL "Build firmware for the petrol Kia Soul" OFF) -option(KIA_SOUL_EV "Build firmware for the Kia Soul EV" OFF) -option(KIA_NIRO "Build firmware for the Kia Niro" OFF) -option(BRAKE_STARTUP_TEST "Enable brake startup sensor tests" ON) -option(STEERING_OVERRIDE "Enable steering override" ON) +set(DEBUG OFF CACHE BOOL "Enable debug mode") +set(KIA_SOUL OFF CACHE BOOL "Build firmware for the petrol Kia Soul") +set(KIA_SOUL_EV OFF CACHE BOOL "Build firmware for the Kia Soul EV") +set(KIA_NIRO OFF CACHE BOOL "Build firmware for the Kia Niro") +set(BRAKE_STARTUP_TEST ON CACHE BOOL "Enable brake startup sensor tests) +set(STEERING_OVERRIDE ON CACHE BOOL "Enable steering override) set(SERIAL_PORT_BRAKE "/dev/ttyACM0" CACHE STRING "Serial port of the brake module") set(SERIAL_BAUD_BRAKE "115200" CACHE STRING "Serial baud rate of the brake module") @@ -27,7 +22,6 @@ set(SERIAL_BAUD_STEERING "115200" CACHE STRING "Serial baud rate of the steering set(SERIAL_PORT_THROTTLE "/dev/ttyACM0" CACHE STRING "Serial port of the throttle module") set(SERIAL_BAUD_THROTTLE "115200" CACHE STRING "Serial baud rate of the throttle module") -#target_compile_options (or something) for setting locally rather than globally if(DEBUG) add_definitions(-DDEBUG) endif() From 6f4caad5187351d6ded52a31ba86bac2878be82a Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Fri, 30 Mar 2018 15:51:05 -0700 Subject: [PATCH 29/80] Fix missing qoutes Prior to this commit some quotes were unintentionally removed from the set variables. This commit fixes that by putting them back in. --- firmware/cmake/OsccFirmware.cmake | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/firmware/cmake/OsccFirmware.cmake b/firmware/cmake/OsccFirmware.cmake index c55d04a8..e94a5fed 100644 --- a/firmware/cmake/OsccFirmware.cmake +++ b/firmware/cmake/OsccFirmware.cmake @@ -1,14 +1,14 @@ cmake_minimum_required(VERSION 2.8) -include(OsccConfig.cmake) +include(${CMAKE_CURRENT_LIST_DIR}/OsccConfig.cmake) set(OSCC_FIRMWARE_ROOT ${CMAKE_CURRENT_LIST_DIR}/..) set(DEBUG OFF CACHE BOOL "Enable debug mode") set(KIA_SOUL OFF CACHE BOOL "Build firmware for the petrol Kia Soul") set(KIA_SOUL_EV OFF CACHE BOOL "Build firmware for the Kia Soul EV") set(KIA_NIRO OFF CACHE BOOL "Build firmware for the Kia Niro") -set(BRAKE_STARTUP_TEST ON CACHE BOOL "Enable brake startup sensor tests) -set(STEERING_OVERRIDE ON CACHE BOOL "Enable steering override) +set(BRAKE_STARTUP_TEST ON CACHE BOOL "Enable brake startup sensor tests") +set(STEERING_OVERRIDE ON CACHE BOOL "Enable steering override") set(SERIAL_PORT_BRAKE "/dev/ttyACM0" CACHE STRING "Serial port of the brake module") set(SERIAL_BAUD_BRAKE "115200" CACHE STRING "Serial baud rate of the brake module") From fc8914667dfb2315667b69fc3095e36bb42948de Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Fri, 30 Mar 2018 15:57:17 -0700 Subject: [PATCH 30/80] Move default Arduino to main CMake file Prior to this commit the Arduino type was set at the level of the firmware rather than having it in a global place making it specific to the build. This commit makes it more flexible by setting that variable in a more global place where it can be changed. --- firmware/CMakeLists.txt | 2 ++ firmware/brake/kia_soul_ev_niro/CMakeLists.txt | 2 -- firmware/can_gateway/CMakeLists.txt | 1 - firmware/throttle/CMakeLists.txt | 1 - 4 files changed, 2 insertions(+), 4 deletions(-) diff --git a/firmware/CMakeLists.txt b/firmware/CMakeLists.txt index 4893729b..80e896d4 100644 --- a/firmware/CMakeLists.txt +++ b/firmware/CMakeLists.txt @@ -1,5 +1,7 @@ cmake_minimum_required(VERSION 2.8) +set(ARDUINO_DEFAULT_BOARD uno) + if(TESTS) project(tests) diff --git a/firmware/brake/kia_soul_ev_niro/CMakeLists.txt b/firmware/brake/kia_soul_ev_niro/CMakeLists.txt index 0a0b5a46..adf356b7 100644 --- a/firmware/brake/kia_soul_ev_niro/CMakeLists.txt +++ b/firmware/brake/kia_soul_ev_niro/CMakeLists.txt @@ -1,5 +1,3 @@ -set(ARDUINO_DEFAULT_BOARD uno) - generate_arduino_firmware( brake SRCS diff --git a/firmware/can_gateway/CMakeLists.txt b/firmware/can_gateway/CMakeLists.txt index ccea737d..5d52c4b2 100644 --- a/firmware/can_gateway/CMakeLists.txt +++ b/firmware/can_gateway/CMakeLists.txt @@ -1,6 +1,5 @@ project(can-gateway) -set(ARDUINO_DEFAULT_BOARD uno) SET(ARDUINO_DEFAULT_PORT ${SERIAL_PORT_CAN_GATEWAY}) set(ARDUINO_DEFAULT_BAUDRATE ${SERIAL_BAUD_CAN_GATEWAY}) diff --git a/firmware/throttle/CMakeLists.txt b/firmware/throttle/CMakeLists.txt index 2e798a08..ba04a705 100644 --- a/firmware/throttle/CMakeLists.txt +++ b/firmware/throttle/CMakeLists.txt @@ -1,6 +1,5 @@ project(throttle) -set(ARDUINO_DEFAULT_BOARD uno) SET(ARDUINO_DEFAULT_PORT ${SERIAL_PORT_THROTTLE}) set(ARDUINO_DEFAULT_BAUDRATE ${SERIAL_BAUD_THROTTLE}) From 5a333538fe48a7586ad8f850bc2e46c35b65f2f9 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Mon, 2 Apr 2018 10:07:44 -0700 Subject: [PATCH 31/80] Update Jenkins for easier platform support Prior to this commit the Jenkinsfile required more code to be added when including a new platform. This commit fixes that by utilizing a list at the top of the file and iterating through that loop so that all platforms in the list are built and tested. --- Jenkinsfile | 70 ++++++++++++++++++++--------------------------------- 1 file changed, 26 insertions(+), 44 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 265ffe2a..255df6d4 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -1,51 +1,33 @@ #!groovy -node('arduino') { - try { - stage('Checkout') { - checkout([ - $class: 'GitSCM', - branches: scm.branches, - extensions: scm.extensions + [[$class: 'CleanBeforeCheckout']], - userRemoteConfigs: scm.userRemoteConfigs - ]) - } - stage('Build') { - parallel 'kia soul petrol firmware': { - sh 'cd firmware && mkdir build_kia_soul_petrol && cd build_kia_soul_petrol && cmake .. -DKIA_SOUL=ON -DCMAKE_BUILD_TYPE=Release && make' - }, 'kia soul EV firmware': { - sh 'cd firmware && mkdir build_kia_soul_ev && cd build_kia_soul_ev && cmake .. -DKIA_SOUL_EV=ON -DCMAKE_BUILD_TYPE=Release && make' + +def platforms = ['kia_soul_petrol', 'kia_soul_ev', 'kia_niro'] + +for(int j=0; j Date: Mon, 2 Apr 2018 10:11:59 -0700 Subject: [PATCH 32/80] Add finally block Prior to this commit the finally block in the try statement was dropped off. This commit fixes that by putting the finally block back in. --- Jenkinsfile | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Jenkinsfile b/Jenkinsfile index 255df6d4..fb49f665 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -29,5 +29,8 @@ for(int j=0; j Date: Mon, 2 Apr 2018 10:26:03 -0700 Subject: [PATCH 33/80] Fix build indexing Prior to this commit the same node that constructed the multiple builds also called the build function before the array had been constructed causing the variables to be unpopulated at build time. This commit fixes that by having a worker node construct the array of parallel builds and then call the builds after the list exists. --- Jenkinsfile | 66 +++++++++++++++++++++++++++++++---------------------- 1 file changed, 39 insertions(+), 27 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index fb49f665..98780a84 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -2,35 +2,47 @@ def platforms = ['kia_soul_petrol', 'kia_soul_ev', 'kia_niro'] -for(int j=0; j Date: Mon, 2 Apr 2018 10:30:12 -0700 Subject: [PATCH 34/80] Move finally block to correct section Prior to this commit the finally block was in the wrong set of close brackets. This commit fixes that by moving the finally block up one set of close brackets. --- Jenkinsfile | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 98780a84..74f7a86b 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -31,9 +31,9 @@ node('worker'){ echo '${platform}: Property-Based Tests Complete!' } } - } - finally { - deleteDir() + finally { + deleteDir() + } } } } From 0d1caa8de606dc0e74f9d9237c7067fb18f36516 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Mon, 2 Apr 2018 16:10:00 -0700 Subject: [PATCH 35/80] Update Jenkinsfile to use cmake variable Prior to this commit the platform variable did not work because the strings were encapsulated in single quotes rather than double. Also the platform variable was populated inside the jenkins file rather than some other location where the available vehicles to build are located. This commit fixes that by encapsulating strings in double quotes so the variable is evaluated and uses cmake to determine how many platforms to build for. --- Jenkinsfile | 34 +++++++++++++++++------------ firmware/brake/CMakeLists.txt | 4 ++-- firmware/cmake/OsccConfig.cmake | 36 ++++++++++++++++++++++++++----- firmware/cmake/OsccFirmware.cmake | 3 --- firmware/steering/CMakeLists.txt | 1 - 5 files changed, 53 insertions(+), 25 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 74f7a86b..7b1887fa 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -1,33 +1,39 @@ #!groovy -def platforms = ['kia_soul_petrol', 'kia_soul_ev', 'kia_niro'] +def cleanCheckout() { + checkout([ + $class: 'GitSCM', + branches: scm.branches, + extensions: scm.extensions + [[$class: 'CleanBeforeCheckout']], + userRemoteConfigs: scm.userRemoteConfigs + ]) +} node('worker'){ def builds = [:] + cleanCheckout() + def output = sh returnStdout: true, script: 'cmake -LA .. | grep 'VEHICLE_VALUES' | cut -d'=' -f 2 > vehicles.txt' + def platforms = output.tokenize(';') + for(int j=0; j Date: Mon, 2 Apr 2018 16:13:11 -0700 Subject: [PATCH 36/80] Fix quotes for shell call Prior to this commit the shell call was encapsulated in single quotes and the call it self used single quotes causing an incomplete shell call. This commit fixes that by encapsulating the whole call in double quotes. --- Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index 7b1887fa..7bdf28bc 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -12,7 +12,7 @@ def cleanCheckout() { node('worker'){ def builds = [:] cleanCheckout() - def output = sh returnStdout: true, script: 'cmake -LA .. | grep 'VEHICLE_VALUES' | cut -d'=' -f 2 > vehicles.txt' + def output = sh returnStdout: true, script: "cmake -LA .. | grep 'VEHICLE_VALUES' | cut -d'=' -f 2 > vehicles.txt" def platforms = output.tokenize(';') for(int j=0; j Date: Mon, 2 Apr 2018 16:16:53 -0700 Subject: [PATCH 37/80] Remove output to text file Prior to this commit the shell call dumped the standard out to file which is not needed since the call is wrapped in an output to variable. This commit fixes that by removing pipe to file. --- Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index 7bdf28bc..f63cc34e 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -12,7 +12,7 @@ def cleanCheckout() { node('worker'){ def builds = [:] cleanCheckout() - def output = sh returnStdout: true, script: "cmake -LA .. | grep 'VEHICLE_VALUES' | cut -d'=' -f 2 > vehicles.txt" + def output = sh returnStdout: true, script: "cmake -LA .. |& grep 'VEHICLE_VALUES' | cut -d'=' -f 2" def platforms = output.tokenize(';') for(int j=0; j Date: Mon, 2 Apr 2018 16:23:42 -0700 Subject: [PATCH 38/80] Fix cmake directory Prior to this commit the cmake call assumed the current directory was in the firmware directory when it was not. This commit fixes that by pointing cmake to the firmware directory. --- Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index f63cc34e..34170d90 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -12,7 +12,7 @@ def cleanCheckout() { node('worker'){ def builds = [:] cleanCheckout() - def output = sh returnStdout: true, script: "cmake -LA .. |& grep 'VEHICLE_VALUES' | cut -d'=' -f 2" + def output = sh returnStdout: true, script: "cmake -LA ./firmware | grep 'VEHICLE_VALUES' | cut -d'=' -f 2" def platforms = output.tokenize(';') for(int j=0; j Date: Mon, 2 Apr 2018 16:42:58 -0700 Subject: [PATCH 39/80] Update Jenkins CMake calls and CMakeFile test Prior to this commit the cmake tests did not work because the test condition had not been updated to use the VEHICLE variable and Jenkins was using the old -D=ON method. This commit fixes those by updating the main CMakeLists.txt and Jenkinsfile accordingly. --- Jenkinsfile | 6 +++--- firmware/CMakeLists.txt | 13 ++++--------- 2 files changed, 7 insertions(+), 12 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 34170d90..4cb868c2 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -25,15 +25,15 @@ node('worker'){ cleanCheckout() } stage("Build ${platform}") { - sh("cd firmware && mkdir build_${platform} && cd build_${platform} && cmake -D${platform.toUpperCase()}=ON -DCMAKE_BUILD_TYPE=Release .. && make") + sh("cd firmware && mkdir build_${platform} && cd build_${platform} && cmake -DVEHICLE=${platform} -DCMAKE_BUILD_TYPE=Release .. && make") echo '${platform}: Build Complete!' } stage("Test ${platform} unit tests") { - sh("cd firmware && mkdir build_${platform}_unit_tests && cd build_${platform}_unit_tests && cmake -D${platform.toUpperCase()} -DCMAKE_BUILD_TYPE=Release .. && make run-unit-tests") + sh("cd firmware && mkdir build_${platform}_unit_tests && cd build_${platform}_unit_tests && cmake -DVEHICLE=${platform} -DCMAKE_BUILD_TYPE=Release .. && make run-unit-tests") echo '${platform}: Unit Tests Complete!' } stage("Test ${platform} property-based tests") { - sh("cd firmware && mkdir build_${platform}_property_tests && cd build_${platform}_property_tests && cmake -D${platform.toUpperCase()}=ON -DTESTS=ON -DCMAKE_BUILD_TYPE=Release .. && make run-property-tests") + sh("cd firmware && mkdir build_${platform}_property_tests && cd build_${platform}_property_tests && cmake -DVEHICLE=${platform} -DTESTS=ON -DCMAKE_BUILD_TYPE=Release .. && make run-property-tests") echo '${platform}: Property-Based Tests Complete!' } } diff --git a/firmware/CMakeLists.txt b/firmware/CMakeLists.txt index 80e896d4..52151f07 100644 --- a/firmware/CMakeLists.txt +++ b/firmware/CMakeLists.txt @@ -3,6 +3,8 @@ cmake_minimum_required(VERSION 2.8) set(ARDUINO_DEFAULT_BOARD uno) if(TESTS) + include(cmake/OsccConfig.cmake) + project(tests) if(TESTS) @@ -13,17 +15,10 @@ if(TESTS) add_definitions(-DDEBUG) endif() - if(KIA_SOUL) - add_definitions(-DKIA_SOUL) + if(VEHICLE STREQUAL "kia_soul") add_subdirectory(brake/kia_soul_petrol/tests) - elseif(KIA_SOUL_EV) - add_definitions(-DKIA_SOUL_EV) - add_subdirectory(brake/kia_soul_ev_niro/tests) - elseif(KIA_NIRO) - add_definitions(-DKIA_NIRO) - add_subdirectory(brake/kia_soul_ev_niro/tests) else() - message(FATAL_ERROR "No platform selected - no firmware will be tested") + add_subdirectory(brake/kia_soul_ev_niro/tests) endif() add_subdirectory(can_gateway/tests) From bb1400971f9994d797e450592442587383fbc314 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Mon, 2 Apr 2018 16:48:19 -0700 Subject: [PATCH 40/80] Remove function brackets from sh Prior to this commit the Jenkins build would fail because the sh function was called which does not expect multiple shell calls. This commit fixes that by removing the brackets so that the regular shell call occurs and multiple shell commands can be used at once. --- Jenkinsfile | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 4cb868c2..3b4c07fc 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -25,15 +25,15 @@ node('worker'){ cleanCheckout() } stage("Build ${platform}") { - sh("cd firmware && mkdir build_${platform} && cd build_${platform} && cmake -DVEHICLE=${platform} -DCMAKE_BUILD_TYPE=Release .. && make") + sh "cd firmware && mkdir build_${platform} && cd build_${platform} && cmake -DVEHICLE=${platform} -DCMAKE_BUILD_TYPE=Release .. && make" echo '${platform}: Build Complete!' } stage("Test ${platform} unit tests") { - sh("cd firmware && mkdir build_${platform}_unit_tests && cd build_${platform}_unit_tests && cmake -DVEHICLE=${platform} -DCMAKE_BUILD_TYPE=Release .. && make run-unit-tests") + sh "cd firmware && mkdir build_${platform}_unit_tests && cd build_${platform}_unit_tests && cmake -DVEHICLE=${platform} -DCMAKE_BUILD_TYPE=Release .. && make run-unit-tests" echo '${platform}: Unit Tests Complete!' } stage("Test ${platform} property-based tests") { - sh("cd firmware && mkdir build_${platform}_property_tests && cd build_${platform}_property_tests && cmake -DVEHICLE=${platform} -DTESTS=ON -DCMAKE_BUILD_TYPE=Release .. && make run-property-tests") + sh "cd firmware && mkdir build_${platform}_property_tests && cd build_${platform}_property_tests && cmake -DVEHICLE=${platform} -DTESTS=ON -DCMAKE_BUILD_TYPE=Release .. && make run-property-tests" echo '${platform}: Property-Based Tests Complete!' } } From f00c52e15277d3f041b895893ae3f882260b556e Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Mon, 2 Apr 2018 17:19:26 -0700 Subject: [PATCH 41/80] Update Jenkins Tests Prior to this commit the unit tests was missing the TESTS flag and the property tests were building their own cmake directory which was not nessisary. This commit fixes that by adding the TESTS flag and using the same test directory for both the unit tests and the property tests. --- Jenkinsfile | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 3b4c07fc..bc2fec2d 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -29,11 +29,11 @@ node('worker'){ echo '${platform}: Build Complete!' } stage("Test ${platform} unit tests") { - sh "cd firmware && mkdir build_${platform}_unit_tests && cd build_${platform}_unit_tests && cmake -DVEHICLE=${platform} -DCMAKE_BUILD_TYPE=Release .. && make run-unit-tests" + sh "cd firmware && mkdir build_${platform}_tests && cd build_${platform}_tests && cmake -DVEHICLE=${platform} -DTESTS=ON -DCMAKE_BUILD_TYPE=Release .. && make run-unit-tests" echo '${platform}: Unit Tests Complete!' } stage("Test ${platform} property-based tests") { - sh "cd firmware && mkdir build_${platform}_property_tests && cd build_${platform}_property_tests && cmake -DVEHICLE=${platform} -DTESTS=ON -DCMAKE_BUILD_TYPE=Release .. && make run-property-tests" + sh "cd firmware/build_${platform}_tests && make run-property-tests" echo '${platform}: Property-Based Tests Complete!' } } From d9e0aa14bd94d6299a71572b758c88005dd2d0b9 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Mon, 2 Apr 2018 18:02:14 -0700 Subject: [PATCH 42/80] Fix cucumber port clash and property tests Prior to this commit the unit tests failed on parallel builds due to port number clash and the property tests build due to cmake directory build process missing. This commit fixes these by setting a port based on the jenkins executor and the platform index to ensure a unique port used per test. --- Jenkinsfile | 4 ++-- firmware/CMakeLists.txt | 2 ++ firmware/brake/kia_soul_ev_niro/tests/CMakeLists.txt | 6 +++++- .../tests/features/step_definitions/cucumber.wire | 2 -- firmware/brake/kia_soul_petrol/tests/CMakeLists.txt | 6 +++++- .../tests/features/step_definitions/cucumber.wire | 2 -- firmware/steering/tests/CMakeLists.txt | 6 +++++- .../steering/tests/features/step_definitions/cucumber.wire | 2 -- firmware/throttle/tests/CMakeLists.txt | 7 ++++++- .../throttle/tests/features/step_definitions/cucumber.wire | 2 -- 10 files changed, 25 insertions(+), 14 deletions(-) delete mode 100644 firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/cucumber.wire delete mode 100644 firmware/brake/kia_soul_petrol/tests/features/step_definitions/cucumber.wire delete mode 100644 firmware/steering/tests/features/step_definitions/cucumber.wire delete mode 100644 firmware/throttle/tests/features/step_definitions/cucumber.wire diff --git a/Jenkinsfile b/Jenkinsfile index bc2fec2d..b50e1d90 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -29,11 +29,11 @@ node('worker'){ echo '${platform}: Build Complete!' } stage("Test ${platform} unit tests") { - sh "cd firmware && mkdir build_${platform}_tests && cd build_${platform}_tests && cmake -DVEHICLE=${platform} -DTESTS=ON -DCMAKE_BUILD_TYPE=Release .. && make run-unit-tests" + sh "cd firmware && mkdir build_${platform}_unit_tests && cd build_${platform}_unit_tests && cmake -DPORT_SUFFIX=${EXECUTOR_NUMBER}${platform_idx} -DVEHICLE=${platform} -DTESTS=ON -DCMAKE_BUILD_TYPE=Release .. && make run-unit-tests" echo '${platform}: Unit Tests Complete!' } stage("Test ${platform} property-based tests") { - sh "cd firmware/build_${platform}_tests && make run-property-tests" + sh "cd firmware && mkdir build_${platform}_property_tests && cd build_${platform}_property_tests && cmake -DVEHICLE=${platform} -DTESTS=ON -DCMAKE_BUILD_TYPE=Release .. && make run-property-tests" echo '${platform}: Property-Based Tests Complete!' } } diff --git a/firmware/CMakeLists.txt b/firmware/CMakeLists.txt index 52151f07..90eefdfb 100644 --- a/firmware/CMakeLists.txt +++ b/firmware/CMakeLists.txt @@ -7,6 +7,8 @@ if(TESTS) project(tests) + set(PORT_SUFFIX "02" CACHE STRING "Local host server port to use for cucumber tests") + if(TESTS) add_definitions(-DTESTS) endif() diff --git a/firmware/brake/kia_soul_ev_niro/tests/CMakeLists.txt b/firmware/brake/kia_soul_ev_niro/tests/CMakeLists.txt index ead50d80..5bcc4f2a 100644 --- a/firmware/brake/kia_soul_ev_niro/tests/CMakeLists.txt +++ b/firmware/brake/kia_soul_ev_niro/tests/CMakeLists.txt @@ -1,5 +1,7 @@ project(brake-unit-tests) +set(CUCUMBER_PORT_BRAKE "39${PORT_SUFFIX}") + add_library( brake SHARED @@ -49,12 +51,14 @@ target_include_directories( ${CMAKE_SOURCE_DIR}/common/testing/framework/cgreen/include ${CMAKE_SOURCE_DIR}/../api/include) +file(WRITE ${CMAKE_CURRENT_LIST_DIR}/features/step_definitions/cucumber.wire "host: localhost\nport: ${CUCUMBER_PORT_BRAKE}") + add_custom_target( run-brake-unit-tests DEPENDS brake-unit-test COMMAND - brake-unit-test --port=3902 >/dev/null & cucumber _2.0.0_ ${CMAKE_CURRENT_SOURCE_DIR}/features ) + brake-unit-test --port=${CUCUMBER_PORT_BRAKE} >/dev/null & cucumber _2.0.0_ ${CMAKE_CURRENT_SOURCE_DIR}/features ) add_custom_target( run-brake-property-tests diff --git a/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/cucumber.wire b/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/cucumber.wire deleted file mode 100644 index da2da560..00000000 --- a/firmware/brake/kia_soul_ev_niro/tests/features/step_definitions/cucumber.wire +++ /dev/null @@ -1,2 +0,0 @@ -host: localhost -port: 3902 diff --git a/firmware/brake/kia_soul_petrol/tests/CMakeLists.txt b/firmware/brake/kia_soul_petrol/tests/CMakeLists.txt index 5da335ed..1378b774 100644 --- a/firmware/brake/kia_soul_petrol/tests/CMakeLists.txt +++ b/firmware/brake/kia_soul_petrol/tests/CMakeLists.txt @@ -1,5 +1,7 @@ project(brake-tests) +set(CUCUMBER_PORT_BRAKE "39${PORT_SUFFIX}") + add_library( brake SHARED @@ -51,12 +53,14 @@ target_include_directories( ${CMAKE_SOURCE_DIR}/common/testing/framework/cgreen/include ${CMAKE_SOURCE_DIR}/../api/include) +file(WRITE ${CMAKE_CURRENT_LIST_DIR}/features/step_definitions/cucumber.wire "host: localhost\nport: ${CUCUMBER_PORT_BRAKE}") + add_custom_target( run-brake-unit-tests DEPENDS brake-unit-test COMMAND - brake-unit-test --port=3902 >/dev/null & cucumber _2.0.0_ ${CMAKE_CURRENT_SOURCE_DIR}/features ) + brake-unit-test --port=${CUCUMBER_PORT_BRAKE} >/dev/null & cucumber _2.0.0_ ${CMAKE_CURRENT_SOURCE_DIR}/features ) add_custom_target( run-brake-property-tests diff --git a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/cucumber.wire b/firmware/brake/kia_soul_petrol/tests/features/step_definitions/cucumber.wire deleted file mode 100644 index da2da560..00000000 --- a/firmware/brake/kia_soul_petrol/tests/features/step_definitions/cucumber.wire +++ /dev/null @@ -1,2 +0,0 @@ -host: localhost -port: 3902 diff --git a/firmware/steering/tests/CMakeLists.txt b/firmware/steering/tests/CMakeLists.txt index 12701b6e..1e3a29b3 100644 --- a/firmware/steering/tests/CMakeLists.txt +++ b/firmware/steering/tests/CMakeLists.txt @@ -1,5 +1,7 @@ project(steering-unit-tests) +set(CUCUMBER_PORT_STEERING "39${PORT_SUFFIX}") + add_library( steering SHARED @@ -52,12 +54,14 @@ target_include_directories( ${CMAKE_SOURCE_DIR}/common/testing/framework/cgreen/include ${CMAKE_SOURCE_DIR}/../api/include) +file(WRITE ${CMAKE_CURRENT_LIST_DIR}/features/step_definitions/cucumber.wire "host: localhost\nport: ${CUCUMBER_PORT_STEERING}") + add_custom_target( run-steering-unit-tests DEPENDS steering-unit-test COMMAND - steering-unit-test --port=3902 >/dev/null & cucumber _2.0.0_ ${CMAKE_CURRENT_SOURCE_DIR}/features ) + steering-unit-test --port=${CUCUMBER_PORT_STEERING} >/dev/null & cucumber _2.0.0_ ${CMAKE_CURRENT_SOURCE_DIR}/features ) add_custom_target( run-steering-property-tests diff --git a/firmware/steering/tests/features/step_definitions/cucumber.wire b/firmware/steering/tests/features/step_definitions/cucumber.wire deleted file mode 100644 index da2da560..00000000 --- a/firmware/steering/tests/features/step_definitions/cucumber.wire +++ /dev/null @@ -1,2 +0,0 @@ -host: localhost -port: 3902 diff --git a/firmware/throttle/tests/CMakeLists.txt b/firmware/throttle/tests/CMakeLists.txt index 145f91ab..0a02f886 100644 --- a/firmware/throttle/tests/CMakeLists.txt +++ b/firmware/throttle/tests/CMakeLists.txt @@ -1,5 +1,7 @@ project(throttle-unit-tests) +set(CUCUMBER_PORT_THROTTLE "39${PORT_SUFFIX}") + add_library( throttle SHARED @@ -49,12 +51,15 @@ target_include_directories( ${CMAKE_SOURCE_DIR}/common/testing/framework/cgreen/include ${CMAKE_SOURCE_DIR}/../api/include) +file(WRITE ${CMAKE_CURRENT_LIST_DIR}/features/step_definitions/cucumber.wire "host: localhost\nport: ${CUCUMBER_PORT_THROTTLE}") + + add_custom_target( run-throttle-unit-tests DEPENDS throttle-unit-test COMMAND - throttle-unit-test --port=3902 >/dev/null & cucumber _2.0.0_ ${CMAKE_CURRENT_SOURCE_DIR}/features ) + throttle-unit-test --port=${CUCUMBER_PORT_THROTTLE} >/dev/null & cucumber _2.0.0_ ${CMAKE_CURRENT_SOURCE_DIR}/features ) add_custom_target( run-throttle-property-tests diff --git a/firmware/throttle/tests/features/step_definitions/cucumber.wire b/firmware/throttle/tests/features/step_definitions/cucumber.wire deleted file mode 100644 index da2da560..00000000 --- a/firmware/throttle/tests/features/step_definitions/cucumber.wire +++ /dev/null @@ -1,2 +0,0 @@ -host: localhost -port: 3902 From 200cd91f17a865e11a4a48f3e5bb51c33849fa74 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Mon, 2 Apr 2018 18:21:15 -0700 Subject: [PATCH 43/80] Include cargo environment Prior to this commit the property tests failed because they could not find cargo this commit fixes that by supplying the cargo environment in the Jenkinsfile. --- Jenkinsfile | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index b50e1d90..6aeeece9 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -29,12 +29,14 @@ node('worker'){ echo '${platform}: Build Complete!' } stage("Test ${platform} unit tests") { - sh "cd firmware && mkdir build_${platform}_unit_tests && cd build_${platform}_unit_tests && cmake -DPORT_SUFFIX=${EXECUTOR_NUMBER}${platform_idx} -DVEHICLE=${platform} -DTESTS=ON -DCMAKE_BUILD_TYPE=Release .. && make run-unit-tests" + sh "cd firmware && mkdir build_${platform}_tests && cd build_${platform}_tests && cmake -DPORT_SUFFIX=${EXECUTOR_NUMBER}${platform_idx} -DVEHICLE=${platform} -DTESTS=ON -DCMAKE_BUILD_TYPE=Release .. && make run-unit-tests" echo '${platform}: Unit Tests Complete!' } stage("Test ${platform} property-based tests") { - sh "cd firmware && mkdir build_${platform}_property_tests && cd build_${platform}_property_tests && cmake -DVEHICLE=${platform} -DTESTS=ON -DCMAKE_BUILD_TYPE=Release .. && make run-property-tests" + withEnv(["PATH+CARGO=$HOME/.cargo/bin"]) { + sh "cd firmware/build_${platform}_tests && make run-property-tests" echo '${platform}: Property-Based Tests Complete!' + } } } finally { From 986a39fb2c65e8bfb8a00f030da3cc229b21ec76 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Mon, 2 Apr 2018 18:29:53 -0700 Subject: [PATCH 44/80] Clean up newline from shell call Prior to this commit the new line in the shell output would be included in the jenkins platform list causing the builds to fail for the last platform. This commit fixes that by adding trim which cleans up whitespace and newlines before tokenizing the string into a list. --- Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index 6aeeece9..8c023fe3 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -13,7 +13,7 @@ node('worker'){ def builds = [:] cleanCheckout() def output = sh returnStdout: true, script: "cmake -LA ./firmware | grep 'VEHICLE_VALUES' | cut -d'=' -f 2" - def platforms = output.tokenize(';') + def platforms = output.trim().tokenize(';') for(int j=0; j Date: Mon, 2 Apr 2018 18:33:07 -0700 Subject: [PATCH 45/80] Clean up echo and 80 character limit Prior to this commit the shell calls would run past 80 characters and the echo call wouldn't evaluate the platform variable. This commit fixes that by using the continued line command and puts double quotes around echo so the variables are evaluated before being echoed. --- Jenkinsfile | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/Jenkinsfile b/Jenkinsfile index 8c023fe3..5b6866dc 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -25,17 +25,21 @@ node('worker'){ cleanCheckout() } stage("Build ${platform}") { - sh "cd firmware && mkdir build_${platform} && cd build_${platform} && cmake -DVEHICLE=${platform} -DCMAKE_BUILD_TYPE=Release .. && make" - echo '${platform}: Build Complete!' + sh "cd firmware && mkdir build_${platform} && cd build_${platform} \ + && cmake -DVEHICLE=${platform} -DCMAKE_BUILD_TYPE=Release .. && make" + echo "${platform}: Build Complete!" } stage("Test ${platform} unit tests") { - sh "cd firmware && mkdir build_${platform}_tests && cd build_${platform}_tests && cmake -DPORT_SUFFIX=${EXECUTOR_NUMBER}${platform_idx} -DVEHICLE=${platform} -DTESTS=ON -DCMAKE_BUILD_TYPE=Release .. && make run-unit-tests" - echo '${platform}: Unit Tests Complete!' + sh "cd firmware && mkdir build_${platform}_tests && \ + cd build_${platform}_tests && cmake -DVEHICLE=${platform} \ + -DTESTS=ON -DPORT_SUFFIX=${EXECUTOR_NUMBER}${platform_idx} \ + -DCMAKE_BUILD_TYPE=Release .. && make run-unit-tests" + echo "${platform}: Unit Tests Complete!" } stage("Test ${platform} property-based tests") { withEnv(["PATH+CARGO=$HOME/.cargo/bin"]) { sh "cd firmware/build_${platform}_tests && make run-property-tests" - echo '${platform}: Property-Based Tests Complete!' + echo "${platform}: Property-Based Tests Complete!" } } } From eebab397bbf7d568d42c5d66b7031f8ca85e9964 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Wed, 4 Apr 2018 11:18:11 -0700 Subject: [PATCH 46/80] Update tests to use vehicle specific defines Prior to this commit the test features had variables in the gherkin examples which coupled the test to a specific vehicle. This commit fixes that by using the define so that the tests are decoupled from the specific vehicle and the same tests can be run against different vehicles. --- .../tests/features/receiving_messages.feature | 20 +++++------- .../testing/step_definitions/common.cpp | 32 +++++++++++++++++++ .../common/testing/step_definitions/vcm.cpp | 9 +++--- .../tests/features/receiving_messages.feature | 19 +++++------ .../step_definitions/checking_faults.cpp | 2 +- .../tests/features/receiving_messages.feature | 21 +++++------- 6 files changed, 62 insertions(+), 41 deletions(-) diff --git a/firmware/brake/kia_soul_ev_niro/tests/features/receiving_messages.feature b/firmware/brake/kia_soul_ev_niro/tests/features/receiving_messages.feature index 098b2a1b..f6c9f69f 100644 --- a/firmware/brake/kia_soul_ev_niro/tests/features/receiving_messages.feature +++ b/firmware/brake/kia_soul_ev_niro/tests/features/receiving_messages.feature @@ -38,13 +38,9 @@ Feature: Receiving commands And should be sent to DAC B Examples: - | value | high | low | - | 1 | 1875 | 917 | - | 0.942 | 1800 | 880 | - | 0.712 | 1500 | 731 | - | 0.329 | 1000 | 484 | - | 0.137 | 750 | 361 | - | 0 | 572 | 273 | + | value | high | low | + | 1 | BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MAX | BRAKE_SPOOF_LOW_SIGNAL_RANGE_MAX | + | 0 | BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MIN | BRAKE_SPOOF_LOW_SIGNAL_RANGE_MIN | Scenario Outline: Spoof value sent from application outside valid range @@ -56,8 +52,8 @@ Feature: Receiving commands And should be sent to DAC B Examples: - | value | high_clamped | low_clamped | - | 5 | 1875 | 917 | - | 2 | 1875 | 917 | - | -1 | 572 | 273 | - | -2 | 572 | 273 | + | value | high_clamped | low_clamped | + | 5 | BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MAX | BRAKE_SPOOF_LOW_SIGNAL_RANGE_MAX | + | 1.1 | BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MAX | BRAKE_SPOOF_LOW_SIGNAL_RANGE_MAX | + | -0.1 | BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MIN | BRAKE_SPOOF_LOW_SIGNAL_RANGE_MIN | + | -5 | BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MIN | BRAKE_SPOOF_LOW_SIGNAL_RANGE_MIN | diff --git a/firmware/common/testing/step_definitions/common.cpp b/firmware/common/testing/step_definitions/common.cpp index ef7c3251..4d3d1439 100644 --- a/firmware/common/testing/step_definitions/common.cpp +++ b/firmware/common/testing/step_definitions/common.cpp @@ -1,5 +1,7 @@ #pragma once +#include +#include #include #include #include @@ -35,6 +37,10 @@ extern unsigned short g_mock_dac_output_b; extern volatile unsigned long g_mock_arduino_millis_return; extern volatile unsigned long g_mock_arduino_micros_return; +std::map vehicle_defines; +const unsigned long Hysteresis_Time = FAULT_HYSTERESIS; + + // return to known state before every scenario BEFORE() { @@ -65,6 +71,32 @@ BEFORE() // A small amount of time elapsed after boot g_mock_arduino_millis_return = 1; + + //Make sure dictionary for looking up vehicle specific defines is correct + vehicle_defines["STEERING_SPOOF_LOW_SIGNAL_RANGE_MIN"] = + STEERING_SPOOF_LOW_SIGNAL_RANGE_MIN; + vehicle_defines["STEERING_SPOOF_LOW_SIGNAL_RANGE_MAX"] = + STEERING_SPOOF_LOW_SIGNAL_RANGE_MAX; + vehicle_defines["STEERING_SPOOF_HIGH_SIGNAL_RANGE_MIN"] = + STEERING_SPOOF_HIGH_SIGNAL_RANGE_MIN; + vehicle_defines["STEERING_SPOOF_HIGH_SIGNAL_RANGE_MAX"] = + STEERING_SPOOF_HIGH_SIGNAL_RANGE_MAX; + vehicle_defines["BRAKE_SPOOF_LOW_SIGNAL_RANGE_MIN"] = + BRAKE_SPOOF_LOW_SIGNAL_RANGE_MIN; + vehicle_defines["BRAKE_SPOOF_LOW_SIGNAL_RANGE_MAX"] = + BRAKE_SPOOF_LOW_SIGNAL_RANGE_MAX; + vehicle_defines["BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MIN"] = + BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MIN; + vehicle_defines["BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MAX"] = + BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MAX; + vehicle_defines["THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MIN"] = + THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MIN; + vehicle_defines["THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MAX"] = + THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MAX; + vehicle_defines["THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MIN"] = + THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MIN; + vehicle_defines["THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX"] = + THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX; } GIVEN("^(\\w+) control is enabled$") diff --git a/firmware/common/testing/step_definitions/vcm.cpp b/firmware/common/testing/step_definitions/vcm.cpp index 1a9fe8d5..5da4f215 100644 --- a/firmware/common/testing/step_definitions/vcm.cpp +++ b/firmware/common/testing/step_definitions/vcm.cpp @@ -1,5 +1,6 @@ #pragma once + THEN("^control should be enabled$") { assert_that( @@ -33,19 +34,19 @@ THEN("^control should be disabled$") THEN("^(.*) should be sent to DAC A$") { - REGEX_PARAM(int, dac_output_a); + REGEX_PARAM(std::string, dac_output_a); assert_that( g_mock_dac_output_a, - is_equal_to(dac_output_a)); + is_equal_to(vehicle_defines[dac_output_a])); } THEN("^(.*) should be sent to DAC B$") { - REGEX_PARAM(int, dac_output_b); + REGEX_PARAM(std::string, dac_output_b); assert_that( g_mock_dac_output_b, - is_equal_to(dac_output_b)); + is_equal_to(vehicle_defines[dac_output_b])); } diff --git a/firmware/steering/tests/features/receiving_messages.feature b/firmware/steering/tests/features/receiving_messages.feature index 71c55f05..a18aaf6c 100644 --- a/firmware/steering/tests/features/receiving_messages.feature +++ b/firmware/steering/tests/features/receiving_messages.feature @@ -38,12 +38,9 @@ Feature: Receiving commands And should be sent to DAC B Examples: - | value | high | low | - | -1 | 3440 | 656 | - | -0.3435 | 2500 | 1475 | - | 0 | 1982 | 1957 | - | 0.3435 | 1464 | 2440 | - | 1 | 738 | 3358 | + | value | high | low | + | -1 | STEERING_SPOOF_HIGH_SIGNAL_RANGE_MAX | STEERING_SPOOF_LOW_SIGNAL_RANGE_MIN | + | 1 | STEERING_SPOOF_HIGH_SIGNAL_RANGE_MIN | STEERING_SPOOF_LOW_SIGNAL_RANGE_MAX | Scenario Outline: Spoof value sent from application outside valid range @@ -55,8 +52,8 @@ Feature: Receiving commands And should be sent to DAC B Examples: - | value | high_clamped | low_clamped | - | -15 | 3440 | 656 | - | -1.1 | 3440 | 656 | - | 1.1 | 738 | 3358 | - | 15 | 738 | 3358 | + | value | high_clamped | low_clamped | + | -15 | STEERING_SPOOF_HIGH_SIGNAL_RANGE_MAX | STEERING_SPOOF_LOW_SIGNAL_RANGE_MIN | + | -1.1 | STEERING_SPOOF_HIGH_SIGNAL_RANGE_MAX | STEERING_SPOOF_LOW_SIGNAL_RANGE_MIN | + | 1.1 | STEERING_SPOOF_HIGH_SIGNAL_RANGE_MIN | STEERING_SPOOF_LOW_SIGNAL_RANGE_MAX | + | 15 | STEERING_SPOOF_HIGH_SIGNAL_RANGE_MIN | STEERING_SPOOF_LOW_SIGNAL_RANGE_MAX | diff --git a/firmware/steering/tests/features/step_definitions/checking_faults.cpp b/firmware/steering/tests/features/step_definitions/checking_faults.cpp index b221c18f..40f78e76 100644 --- a/firmware/steering/tests/features/step_definitions/checking_faults.cpp +++ b/firmware/steering/tests/features/step_definitions/checking_faults.cpp @@ -14,7 +14,7 @@ WHEN("^the operator applies (.*) to the steering wheel$") // set an elapsed time to account for hystoresis compensation - g_mock_arduino_millis_return = 105; + g_mock_arduino_millis_return = Hysteresis_Time + 5; check_for_faults(); } diff --git a/firmware/throttle/tests/features/receiving_messages.feature b/firmware/throttle/tests/features/receiving_messages.feature index ed16a435..a43de5b3 100644 --- a/firmware/throttle/tests/features/receiving_messages.feature +++ b/firmware/throttle/tests/features/receiving_messages.feature @@ -38,14 +38,9 @@ Feature: Receiving commands And should be sent to DAC B Examples: - | value | high | low | - | 1 | 3358 | 1638 | - | 0.8 | 2801 | 1359 | - | 0.6 | 2244 | 1081 | - | 0.5 | 1966 | 942 | - | 0.4 | 1687 | 802 | - | 0.2 | 1130 | 524 | - | 0 | 573 | 245 | + | value | high | low | + | 1 | THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX | THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MAX | + | 0 | THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MIN | THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MIN | Scenario Outline: Spoof value sent from application outside valid range @@ -57,8 +52,8 @@ Feature: Receiving commands And should be sent to DAC B Examples: - | value | high_clamped | low_clamped | - | 5 | 3358 | 1638 | - | 1.1 | 3358 | 1638 | - | -0.1 | 573 | 245 | - | -5 | 573 | 245 | + | value | high_clamped | low_clamped | + | 5 | THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX | THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MAX | + | 1.1 | THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX | THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MAX | + | -0.1 | THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MIN | THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MIN | + | -5 | THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MIN | THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MIN | From 6eebb3e4761281c4b03be435452cc4332f66e0f8 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Wed, 4 Apr 2018 11:19:40 -0700 Subject: [PATCH 47/80] Fix voltage spoof ranges Prior to this commit some of the voltage spoof ranges did not calculate to the correct value when multiplying and dividing by the STEPS_PER_VOLT against the the x_SPOOF_y_SIGNAL_VOLTAGE_z values. This commit fixes that by setting the x_SPOOF_y_SIGNAL_RANGE_z to something that calculates correctly. --- api/include/vehicles/kia_niro.h | 2 +- api/include/vehicles/kia_soul_ev.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/api/include/vehicles/kia_niro.h b/api/include/vehicles/kia_niro.h index 39ed27b2..e2975ae6 100644 --- a/api/include/vehicles/kia_niro.h +++ b/api/include/vehicles/kia_niro.h @@ -417,7 +417,7 @@ typedef struct * * Equal to \ref THROTTLE_SPOOF_LOW_SIGNAL_VOLTAGE_MAX * \ref STEPS_PER_VOLT. */ -#define THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MAX ( 1724 ) +#define THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MAX ( 1723 ) /* * @brief Minimum allowed value for the low spoof signal value. [steps] diff --git a/api/include/vehicles/kia_soul_ev.h b/api/include/vehicles/kia_soul_ev.h index 3a1cc774..405f9f3a 100644 --- a/api/include/vehicles/kia_soul_ev.h +++ b/api/include/vehicles/kia_soul_ev.h @@ -181,7 +181,7 @@ typedef struct * * Equal to \ref BRAKE_SPOOF_HIGH_SIGNAL_VOLTAGE_MAX * \ref STEPS_PER_VOLT. */ -#define BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MAX ( 1876 ) +#define BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MAX ( 1875 ) /* * @brief Calculation to convert a brake position to a low spoof voltage. From 21cffd6195d6e95e725f06d3393d226dc6efbcc1 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Wed, 4 Apr 2018 11:33:26 -0700 Subject: [PATCH 48/80] Add ifdef around brake values Prior to this commit the Kia Soul Petrol would fail becuase the brake spoof values are not the same pre-processor defines but the code for the map is in the common location. This commit fixes that by wrapping the brake defines in an ifdef. --- .../common/testing/step_definitions/common.cpp | 18 ++++++++++-------- 1 file changed, 10 insertions(+), 8 deletions(-) diff --git a/firmware/common/testing/step_definitions/common.cpp b/firmware/common/testing/step_definitions/common.cpp index 4d3d1439..8be53507 100644 --- a/firmware/common/testing/step_definitions/common.cpp +++ b/firmware/common/testing/step_definitions/common.cpp @@ -81,14 +81,6 @@ BEFORE() STEERING_SPOOF_HIGH_SIGNAL_RANGE_MIN; vehicle_defines["STEERING_SPOOF_HIGH_SIGNAL_RANGE_MAX"] = STEERING_SPOOF_HIGH_SIGNAL_RANGE_MAX; - vehicle_defines["BRAKE_SPOOF_LOW_SIGNAL_RANGE_MIN"] = - BRAKE_SPOOF_LOW_SIGNAL_RANGE_MIN; - vehicle_defines["BRAKE_SPOOF_LOW_SIGNAL_RANGE_MAX"] = - BRAKE_SPOOF_LOW_SIGNAL_RANGE_MAX; - vehicle_defines["BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MIN"] = - BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MIN; - vehicle_defines["BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MAX"] = - BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MAX; vehicle_defines["THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MIN"] = THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MIN; vehicle_defines["THROTTLE_SPOOF_LOW_SIGNAL_RANGE_MAX"] = @@ -97,6 +89,16 @@ BEFORE() THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MIN; vehicle_defines["THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX"] = THROTTLE_SPOOF_HIGH_SIGNAL_RANGE_MAX; +#ifndef KIA_SOUL + vehicle_defines["BRAKE_SPOOF_LOW_SIGNAL_RANGE_MIN"] = + BRAKE_SPOOF_LOW_SIGNAL_RANGE_MIN; + vehicle_defines["BRAKE_SPOOF_LOW_SIGNAL_RANGE_MAX"] = + BRAKE_SPOOF_LOW_SIGNAL_RANGE_MAX; + vehicle_defines["BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MIN"] = + BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MIN; + vehicle_defines["BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MAX"] = + BRAKE_SPOOF_HIGH_SIGNAL_RANGE_MAX; +#endif } GIVEN("^(\\w+) control is enabled$") From 50515934a3cef5a457b06459a84c31c795616d9e Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Wed, 4 Apr 2018 10:55:28 -0700 Subject: [PATCH 49/80] Add NULL firmware implementation Prior to this commit there was no clear firmware solution for disabling one or a subset of OSCC modules. This commit represents the addition of a NULL firmware implementation such that any combination of modules can be essentially ignored by OSCC. The NULL implementation is build by default and uploaded to any module with the command `make null-upload`. --- firmware/CMakeLists.txt | 2 ++ firmware/cmake/OsccFirmware.cmake | 3 +++ firmware/null/CMakeLists.txt | 10 ++++++++++ firmware/null/main.cpp | 8 ++++++++ 4 files changed, 23 insertions(+) create mode 100644 firmware/null/CMakeLists.txt create mode 100644 firmware/null/main.cpp diff --git a/firmware/CMakeLists.txt b/firmware/CMakeLists.txt index 80e896d4..66dd0fed 100644 --- a/firmware/CMakeLists.txt +++ b/firmware/CMakeLists.txt @@ -65,6 +65,7 @@ else() add_subdirectory(brake) add_subdirectory(can_gateway) + add_subdirectory(null) add_subdirectory(steering) add_subdirectory(throttle) @@ -73,6 +74,7 @@ else() DEPENDS brake-upload can-gateway-upload + null steering-upload throttle-upload) endif() diff --git a/firmware/cmake/OsccFirmware.cmake b/firmware/cmake/OsccFirmware.cmake index e94a5fed..faa618ec 100644 --- a/firmware/cmake/OsccFirmware.cmake +++ b/firmware/cmake/OsccFirmware.cmake @@ -22,6 +22,9 @@ set(SERIAL_BAUD_STEERING "115200" CACHE STRING "Serial baud rate of the steering set(SERIAL_PORT_THROTTLE "/dev/ttyACM0" CACHE STRING "Serial port of the throttle module") set(SERIAL_BAUD_THROTTLE "115200" CACHE STRING "Serial baud rate of the throttle module") +set(SERIAL_PORT_NULL "/dev/ttyACM0" CACHE STRING "Serial port of the NULL module") +set(SERIAL_BAUD_NULL "115200" CACHE STRING "Serial baud rate of the NULL module") + if(DEBUG) add_definitions(-DDEBUG) endif() diff --git a/firmware/null/CMakeLists.txt b/firmware/null/CMakeLists.txt new file mode 100644 index 00000000..fad5d981 --- /dev/null +++ b/firmware/null/CMakeLists.txt @@ -0,0 +1,10 @@ +project(null) + +set(ARDUINO_DEFAULT_BOARD uno) +SET(ARDUINO_DEFAULT_PORT ${SERIAL_PORT_NULL}) +set(ARDUINO_DEFAULT_BAUDRATE ${SERIAL_BAUD_NULL}) + +generate_arduino_firmware( + null + SRCS + main.cpp) diff --git a/firmware/null/main.cpp b/firmware/null/main.cpp new file mode 100644 index 00000000..1660cfd9 --- /dev/null +++ b/firmware/null/main.cpp @@ -0,0 +1,8 @@ +/** + * @file main.cpp + * NULL Implementation + */ +int main( void ) +{ + while( true ) { } +} From a936c1bb50873072cc63d273b3375f26fd9cf254 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Thu, 5 Apr 2018 09:55:50 -0700 Subject: [PATCH 50/80] Clarify Deprecation Warning Prior to this commit it was confusing what was being deprecated. This commit fixes that by specifically calling out the command to be deprecated in the warning message. --- firmware/cmake/OsccConfig.cmake | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/firmware/cmake/OsccConfig.cmake b/firmware/cmake/OsccConfig.cmake index c36f060e..2dddd024 100644 --- a/firmware/cmake/OsccConfig.cmake +++ b/firmware/cmake/OsccConfig.cmake @@ -21,15 +21,15 @@ if (";${VEHICLE_VALUES};" MATCHES ";${VEHICLE};") elseif(KIA_SOUL) add_definitions(-DKIA_SOUL) set(VEHICLE kia_soul) - message(WARNING "KIA_SOUL is being deprecated for VEHICLE string assign '-DVEHICLE=kia_soul'") + message(WARNING "-DKIA_SOUL=ON is being deprecated for VEHICLE string assign '-DVEHICLE=kia_soul'") elseif(KIA_SOUL_EV) add_definitions(-DKIA_SOUL_EV) set(VEHICLE kia_soul_ev) - message(WARNING "KIA_SOUL_EV is being deprecated for VEHICLE string assign '-DVEHICLE=kia_soul_ev'") + message(WARNING "-DKIA_SOUL_EV=ON is being deprecated for VEHICLE string assign '-DVEHICLE=kia_soul_ev'") elseif(KIA_NIRO) add_definitions(-DKIA_NIRO) set(VEHICLE kia_niro) - message(WARNING "KIA_NIRO is being deprecated for VEHICLE string assign '-DVEHICLE=kia_niro'") + message(WARNING "-DKIA_NIRO=ON is being deprecated for VEHICLE string assign '-DVEHICLE=kia_niro'") else() message(FATAL_ERROR "No platform selected, available platforms are: ${VEHICLE_VALUES}") endif() From 9ef6436a98deae40944fdc7461d361bc09cc329e Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Thu, 5 Apr 2018 13:38:25 -0700 Subject: [PATCH 51/80] Add ifndef for ATmega32U4 support Prior to this commit a build would fail if building for ATmega32U4 chips like the leonardo arduino. This commit fixes that by wrapping timer2 around an ifndef for the ATmega32U4. --- firmware/common/libs/timer/oscc_timer.cpp | 7 ++++++- firmware/common/libs/timer/oscc_timer.h | 2 ++ 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/firmware/common/libs/timer/oscc_timer.cpp b/firmware/common/libs/timer/oscc_timer.cpp index 4efc6325..87870300 100644 --- a/firmware/common/libs/timer/oscc_timer.cpp +++ b/firmware/common/libs/timer/oscc_timer.cpp @@ -10,7 +10,9 @@ static void (*timer_1_isr)(void); +#ifndef __AVR_ATmega32U4__ static void (*timer_2_isr)(void); +#endif // timer1 interrupt service routine @@ -19,11 +21,13 @@ ISR(TIMER1_COMPA_vect) timer_1_isr( ); } +#ifndef __AVR_ATmega32U4__ // timer2 interrupt service routine ISR(TIMER2_COMPA_vect) { timer_2_isr( ); } +#endif void timer1_init( float frequency, void (*isr)(void) ) @@ -101,7 +105,7 @@ void timer1_init( float frequency, void (*isr)(void) ) sei(); } - +#ifndef __AVR_ATmega32U4__ void timer2_init( float frequency, void (*isr)(void) ) { // disable interrupts temporarily @@ -188,3 +192,4 @@ void timer2_init( float frequency, void (*isr)(void) ) // re-enable interrupts sei(); } +#endif diff --git a/firmware/common/libs/timer/oscc_timer.h b/firmware/common/libs/timer/oscc_timer.h index 014826a2..6e368f96 100644 --- a/firmware/common/libs/timer/oscc_timer.h +++ b/firmware/common/libs/timer/oscc_timer.h @@ -113,6 +113,7 @@ void timer1_init( float frequency, void (*isr)(void) ); +#ifndef __AVR_ATmega32U4__ // **************************************************************************** // Function: timer2_init // @@ -131,6 +132,7 @@ void timer1_init( void timer2_init( float frequency, void (*isr)(void) ); +#endif #endif /* _OSCC_TIMER_H_ */ From 9a59c7c83c7e0172f626ab74e3fb08615661a323 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Mon, 9 Apr 2018 11:47:56 -0700 Subject: [PATCH 52/80] Fix oscc firmware root directory Prior to this commit the serial actuator built against the cmake source dir which is no longer the pratice for using the oscc firmware root directory. This commit fixes that by updating the variable used to oscc firmware root directory instead. --- .../utils/serial_actuator/CMakeLists.txt | 32 +++++++++---------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/firmware/brake/kia_soul_petrol/utils/serial_actuator/CMakeLists.txt b/firmware/brake/kia_soul_petrol/utils/serial_actuator/CMakeLists.txt index 4627e237..b1c8a33f 100644 --- a/firmware/brake/kia_soul_petrol/utils/serial_actuator/CMakeLists.txt +++ b/firmware/brake/kia_soul_petrol/utils/serial_actuator/CMakeLists.txt @@ -3,13 +3,13 @@ project(brake-utils-serial-actuator) generate_arduino_firmware( brake-utils-serial-actuator SRCS - ${CMAKE_SOURCE_DIR}/common/libs/arduino_init/arduino_init.cpp - ${CMAKE_SOURCE_DIR}/common/libs/mcp_can/mcp_can.cpp - ${CMAKE_SOURCE_DIR}/common/libs/pid/oscc_pid.cpp - ${CMAKE_SOURCE_DIR}/common/libs/serial/oscc_serial.cpp - ${CMAKE_SOURCE_DIR}/common/libs/can/oscc_can.cpp - ${CMAKE_SOURCE_DIR}/common/libs/timer/oscc_timer.cpp - ${CMAKE_SOURCE_DIR}/common/libs/fault_check/oscc_check.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/arduino_init/arduino_init.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/mcp_can/mcp_can.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/pid/oscc_pid.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/serial/oscc_serial.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/can/oscc_can.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/timer/oscc_timer.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/fault_check/oscc_check.cpp ../../src/globals.cpp ../../src/accumulator.cpp ../../src/helper.cpp @@ -23,12 +23,12 @@ target_include_directories( brake-utils-serial-actuator PRIVATE ../../include - ${CMAKE_SOURCE_DIR}/common/include - ${CMAKE_SOURCE_DIR}/common/libs/arduino_init - ${CMAKE_SOURCE_DIR}/common/libs/mcp_can - ${CMAKE_SOURCE_DIR}/common/libs/pid - ${CMAKE_SOURCE_DIR}/common/libs/serial - ${CMAKE_SOURCE_DIR}/common/libs/can - ${CMAKE_SOURCE_DIR}/common/libs/timer - ${CMAKE_SOURCE_DIR}/common/libs/fault_check - ${CMAKE_SOURCE_DIR}/../api/include) + ${OSCC_FIRMWARE_ROOT}/common/include + ${OSCC_FIRMWARE_ROOT}/common/libs/arduino_init + ${OSCC_FIRMWARE_ROOT}/common/libs/mcp_can + ${OSCC_FIRMWARE_ROOT}/common/libs/pid + ${OSCC_FIRMWARE_ROOT}/common/libs/serial + ${OSCC_FIRMWARE_ROOT}/common/libs/can + ${OSCC_FIRMWARE_ROOT}/common/libs/timer + ${OSCC_FIRMWARE_ROOT}/common/libs/fault_check + ${OSCC_FIRMWARE_ROOT}/../api/include) From 5e5d4a7054b68df85ab5ceee97f2ce4a4984a6d1 Mon Sep 17 00:00:00 2001 From: Adrien Thebo Date: Tue, 10 Apr 2018 11:25:21 -0700 Subject: [PATCH 53/80] Correct return code check for oscc_close() In oscc_close() when we were checking if the file descriptors could be closed the sign check was reversed, and when the socket(s) were closed the return code assumed that `close()` would return >0 when it returns 0 on success and -1 on error. In addition the variable naming introduced variable shadowing of the function return code; setting the result inside of close would instead set the shadowing variable whose value would be discarded. This commit resolve these issues by 1) correcting the sign check to close opened file descriptors 2) correcting the return code check of close() 3) removing the variable shadowing to properly return closed values. Test coverage of this is defined in the HIL property tests. --- api/src/oscc.c | 22 ++++++++++++++-------- 1 file changed, 14 insertions(+), 8 deletions(-) diff --git a/api/src/oscc.c b/api/src/oscc.c index 05f5034f..5e2a7fb0 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -107,29 +107,35 @@ oscc_result_t oscc_open( unsigned int channel ) oscc_result_t oscc_close( unsigned int channel ) { - oscc_result_t result = OSCC_ERROR; + oscc_result_t ret = OSCC_ERROR; - if( global_oscc_can_socket < 0 ) + if( global_oscc_can_socket >= 0 ) { int result = close( global_oscc_can_socket ); - if ( result > 0 ) + if ( result == 0 ) { - result = OSCC_OK; + ret = OSCC_OK; } } - if( global_vehicle_can_socket < 0 ) + if( global_vehicle_can_socket >= 0 ) { int result = close( global_vehicle_can_socket ); - if ( result > 0 ) + if ( result == 0 && ret == OSCC_OK ) { - result = OSCC_OK; + ret = OSCC_OK; + } + else + { + // If we were able to close the OSCC CAN socket but failed to close + // the OSCC socket, overwrite the return code with an error. + ret = OSCC_ERROR; } } - return result; + return ret; } oscc_result_t oscc_enable( void ) From 9f135c96910a8fa78d90f338c04a3634b1e53cce Mon Sep 17 00:00:00 2001 From: Adrien Thebo Date: Tue, 10 Apr 2018 12:51:16 -0700 Subject: [PATCH 54/80] Clarify return code behavior for oscc_close() The previous commit cleaned up the return code generation for `oscc_close()` but did not resolve some of the uncertain semantics around the return code of that function. This commit changes the return code for `oscc_close()` to only return `OSCC_OK` if one or more channels closed, and no errors were encountered while closing channels. --- api/src/oscc.c | 26 ++++++++++++++++++-------- 1 file changed, 18 insertions(+), 8 deletions(-) diff --git a/api/src/oscc.c b/api/src/oscc.c index 5e2a7fb0..8940b4c0 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -107,7 +107,8 @@ oscc_result_t oscc_open( unsigned int channel ) oscc_result_t oscc_close( unsigned int channel ) { - oscc_result_t ret = OSCC_ERROR; + bool closed_channel = false; + bool close_errored = false; if( global_oscc_can_socket >= 0 ) { @@ -115,7 +116,11 @@ oscc_result_t oscc_close( unsigned int channel ) if ( result == 0 ) { - ret = OSCC_OK; + closed_channel = true; + } + else + { + close_errored = true; } } @@ -123,19 +128,24 @@ oscc_result_t oscc_close( unsigned int channel ) { int result = close( global_vehicle_can_socket ); - if ( result == 0 && ret == OSCC_OK ) + if ( result == 0 ) { - ret = OSCC_OK; + closed_channel = true; } else { - // If we were able to close the OSCC CAN socket but failed to close - // the OSCC socket, overwrite the return code with an error. - ret = OSCC_ERROR; + close_errored = true; } } - return ret; + if ( closed_channel == true && close_errored == false ) + { + return OSCC_OK; + } + else + { + return OSCC_ERROR; + } } oscc_result_t oscc_enable( void ) From a8a22799c01c0bc53267b8f8623513c2d45b00c3 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Tue, 10 Apr 2018 16:21:27 -0700 Subject: [PATCH 55/80] Remove Null default Prior to this commit null had the default uno setting locally which would build uno regardless of the higher level CMake Arduino default board. This commit fixes that by removing the local one so that if the global setting is changed the null implementation is built on the global setting. --- firmware/CMakeLists.txt | 1 - firmware/null/CMakeLists.txt | 1 - 2 files changed, 2 deletions(-) diff --git a/firmware/CMakeLists.txt b/firmware/CMakeLists.txt index e81d05bd..d0518418 100644 --- a/firmware/CMakeLists.txt +++ b/firmware/CMakeLists.txt @@ -71,7 +71,6 @@ else() DEPENDS brake-upload can-gateway-upload - null steering-upload throttle-upload) endif() diff --git a/firmware/null/CMakeLists.txt b/firmware/null/CMakeLists.txt index fad5d981..1c1da30e 100644 --- a/firmware/null/CMakeLists.txt +++ b/firmware/null/CMakeLists.txt @@ -1,6 +1,5 @@ project(null) -set(ARDUINO_DEFAULT_BOARD uno) SET(ARDUINO_DEFAULT_PORT ${SERIAL_PORT_NULL}) set(ARDUINO_DEFAULT_BAUDRATE ${SERIAL_BAUD_NULL}) From d45b4c28ca80cf058d521b76e04a8353f0ad1d90 Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Tue, 17 Apr 2018 16:50:12 -0700 Subject: [PATCH 56/80] Add "getter" functions to unpack OBD-II CAN data Prior to this commit the expected method for getting relevant data from the DriveKit OBD-II messages was to cast the CAN frame data as a C struct. The C structs defined by the API did not reflect the CAN data in most cases which has the potential to mislead users and developers who want to use the unpacked CAN data. This commit represents the addition of "getter" functions that take as a parameter, the CAN frame read and the value to set. Each functoin unpacks its respective value from the CAN frame reported by the vehicle and scales it according to it's unit of measurement (degrees, bar, kph). Additionally, comments indicating that the old C structs are deprecated were added to the documentation as removing them completely would represent a breaking change. --- api/include/oscc.h | 113 +++++++++++++++++++++++++ api/include/vehicles/kia_niro.h | 12 ++- api/include/vehicles/kia_soul_ev.h | 12 ++- api/include/vehicles/kia_soul_petrol.h | 12 ++- api/src/oscc.c | 81 ++++++++++++++++++ 5 files changed, 221 insertions(+), 9 deletions(-) diff --git a/api/include/oscc.h b/api/include/oscc.h index 515b90b3..2d56f9ac 100644 --- a/api/include/oscc.h +++ b/api/include/oscc.h @@ -204,4 +204,117 @@ oscc_result_t oscc_subscribe_to_fault_reports( void( *callback )( oscc_fault_rep oscc_result_t oscc_subscribe_to_obd_messages( void( *callback )( struct can_frame *frame ) ); +/** + * @brief Set vehicle right rear wheel speed in kph from CAN frame. (kph) + * + * @param [in] frame - A pointer to \ref struct can_frame that contains the raw CAN data associated + * with wheel speed (CAN ID: \ref KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) + * + * @param [out] wheel_speed_right_rear - A pointer to double. Set to the unpacked and scaled rear + * right wheel speed reported by the vehicle (kph). + * + * @return: + * \li \ref OSCC_OK on successful unpacking. + * \li \ref OSCC_ERROR if a parameter is NULL or the CAN frame ID is not + * \ref KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID + */ +oscc_result_t get_wheel_speed_right_rear( + struct can_frame const * const frame, + double * wheel_speed_right_rear); + +/** + * @brief Get vehicle left rear wheel speed in kph from CAN frame. (kph) + * + * @param [in] frame - A pointer to \ref struct can_frame that contains the raw CAN data associated + * with wheel speed (CAN ID: \ref KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) + * + * @param [out] wheel_speed_left_rear - A pointer to double. Set to the unpacked and scaled front + * left wheel speed reported by the vehicle (kph). + * + * @return: + * \li \ref OSCC_OK on successful unpacking. + * \li \ref OSCC_ERROR if a parameter is NULL or the CAN frame ID is not + * \ref KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID + */ +oscc_result_t get_wheel_speed_left_rear( + struct can_frame const * const frame, + double * wheel_speed_left_rear); + + +/** + * @brief Get vehicle right front wheel speed in kph from CAN frame. (kph) + * + * @param [in] frame - A pointer to \ref struct can_frame that contains the raw CAN data associated + * with wheel speed (CAN ID: \ref KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) + * + * @param [out] wheel_speed_right_front - A pointer to double. Set to the unpacked and scaled front + * right wheel speed reported by the vehicle (kph). + * + * @return: + * \li \ref OSCC_OK on successful unpacking. + * \li \ref OSCC_ERROR if a parameter is NULL or the CAN frame ID is not + * \ref KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID + */ +oscc_result_t get_wheel_speed_right_front( + struct can_frame const * const frame, + double * wheel_speed_right_front); + + +/** + * @brief Get vehicle left front wheel speed in kph from CAN frame. (kph) + * + * @param [in] frame - A pointer to \ref struct can_frame that contains the raw CAN data associated + * with wheel speed (CAN ID: \ref KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) + * + * @param [out] wheel_speed_left_front - A pointer to double. Set to the unpacked and scaled rear + * left wheel speed reported by the vehicle (kph). + * + * @return: + * \li \ref OSCC_OK on successful unpacking. + * \li \ref OSCC_ERROR if a parameter is NULL or the CAN frame ID is not + * \ref KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID + */ +oscc_result_t get_wheel_speed_left_front( + struct can_frame const * const frame, + double * wheel_speed_left_front); + + +/** + * @brief Get vehicle steering wheel angle from CAN frame. (degrees) + * + * @param [in] frame - A pointer to \ref struct can_frame that contains the raw CAN data associated + * with steering wheel angle (CAN ID: \ref KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID) + * + * @param [out] steering_wheel_angle - A pointer to double. Value is set to the unpacked and scaled + * steering wheel angle reported by the vehicle (degrees). + * + * @return: + * \li \ref OSCC_OK on successful unpacking. + * \li \ref OSCC_ERROR if a parameter is NULL or the CAN frame ID is not + * \ref KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID + */ +oscc_result_t get_steering_wheel_angle( + struct can_frame const * const frame, + double * steering_wheel_angle); + + +/** + * @brief Get vehicle brake pressure from CAN frame. (bar) + * + * @param [in] frame - A pointer to \ref struct can_frame that contains the raw CAN data associated + * with brake pressure (CAN ID: \ref KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID) + * + * @param [out] brake_pressure - A pointer to double. Set to the unpacked and scaled brake pressure + * reported by the vehicle (bar). + * + * @return: + * \li \ref OSCC_OK on successful unpacking. + * \li \ref OSCC_ERROR if a parameter is NULL or the CAN frame ID is not + * \ref KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID + */ +oscc_result_t get_brake_pressure( + struct can_frame const * const frame, + double * brake_pressure); + + #endif /* _OSCC_H */ diff --git a/api/include/vehicles/kia_niro.h b/api/include/vehicles/kia_niro.h index e2975ae6..74b58310 100644 --- a/api/include/vehicles/kia_niro.h +++ b/api/include/vehicles/kia_niro.h @@ -63,7 +63,7 @@ /** * @brief Steering wheel angle message data. - * + * @warn Deprecated. Use \ref get_steering_wheel_angle instead. */ typedef struct { @@ -74,7 +74,12 @@ typedef struct /** * @brief Wheel speed message data. - * + * @warn Deprecated. + * @warn Does not reflect CAN message data. Use the following functions instead: + * \li \ref get_wheel_speed_right_rear + * \li \ref get_wheel_speed_left_rear + * \li \ref get_wheel_speed_right_front + * \li \ref get_wheel_speed_left_front */ typedef struct { @@ -97,7 +102,8 @@ typedef struct /** * @brief Brake pressure message data. - * + * @warn Deprecated. + * @warn Does not reflect CAN message data. Use \ref get_wheel_brake_pressure instead. */ typedef struct { diff --git a/api/include/vehicles/kia_soul_ev.h b/api/include/vehicles/kia_soul_ev.h index 405f9f3a..7af5d5f8 100644 --- a/api/include/vehicles/kia_soul_ev.h +++ b/api/include/vehicles/kia_soul_ev.h @@ -57,7 +57,7 @@ /** * @brief Steering wheel angle message data. - * + * @warn Deprecated. Use \ref get_steering_wheel_angle instead. */ typedef struct { @@ -68,7 +68,12 @@ typedef struct /** * @brief Wheel speed message data. - * + * @warn Deprecated. + * @warn Does not reflect CAN message data. Use the following functions instead: + * \li \ref get_wheel_speed_right_rear + * \li \ref get_wheel_speed_left_rear + * \li \ref get_wheel_speed_right_front + * \li \ref get_wheel_speed_left_front */ typedef struct { @@ -83,7 +88,8 @@ typedef struct /** * @brief Brake pressure message data. - * + * @warn Deprecated. + * @warn Does not reflect CAN message data. Use \ref get_wheel_brake_pressure instead. */ typedef struct { diff --git a/api/include/vehicles/kia_soul_petrol.h b/api/include/vehicles/kia_soul_petrol.h index 5a411b58..3bffdc17 100644 --- a/api/include/vehicles/kia_soul_petrol.h +++ b/api/include/vehicles/kia_soul_petrol.h @@ -57,7 +57,7 @@ /** * @brief Steering wheel angle message data. - * + * @warn Deprecated. Use \ref get_steering_wheel_angle instead. */ typedef struct { @@ -68,7 +68,12 @@ typedef struct /** * @brief Wheel speed message data. - * + * @warn Deprecated. + * @warn Does not reflect CAN message data. Use the following functions instead: + * \li \ref get_wheel_speed_right_rear + * \li \ref get_wheel_speed_left_rear + * \li \ref get_wheel_speed_right_front + * \li \ref get_wheel_speed_left_front */ typedef struct { @@ -83,7 +88,8 @@ typedef struct /** * @brief Brake pressure message data. - * + * @warn Deprecated. + * @warn Does not reflect CAN message data. Use \ref get_wheel_brake_pressure instead. */ typedef struct { diff --git a/api/src/oscc.c b/api/src/oscc.c index 8940b4c0..f463a24d 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -1092,3 +1092,84 @@ oscc_result_t get_device_name( char * string, char * const name ) return result; } + +oscc_result_t get_wheel_speed_right_rear( + struct can_frame const * const frame, + double * wheel_speed_right_rear) +{ + if((frame == NULL) || (wheel_speed_right_rear == NULL)) { return OSCC_ERROR; } + if(frame->can_id != KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) { return OSCC_ERROR; } + uint16_t raw = ((frame->data[7] & 0x0F) << 8) | frame->data[6]; + // 10^-1 precision, raw / 32.0 + *wheel_speed_right_rear = (double)((int)((double)raw / 3.2) / 10.0); + return OSCC_OK; +} + + +oscc_result_t get_wheel_speed_left_rear( + struct can_frame const * const frame, + double * wheel_speed_left_rear) +{ + if((frame == NULL) || (wheel_speed_left_rear == NULL)) { return OSCC_ERROR; } + if(frame->can_id != KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) { return OSCC_ERROR; } + uint16_t raw = ((frame->data[5] & 0x0F) << 8) | frame->data[4]; + // 10^-1 precision, raw / 32.0 + *wheel_speed_left_rear = (double)((int)((double)raw / 3.2) / 10.0); + return OSCC_OK; +} + + +oscc_result_t get_wheel_speed_right_front( + struct can_frame const * const frame, + double * wheel_speed_right_front) +{ + if((frame == NULL) || (wheel_speed_right_front == NULL)) { return OSCC_ERROR; } + if(frame->can_id != KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) { return OSCC_ERROR; } + uint16_t raw = ((frame->data[3] & 0x0F) << 8) | frame->data[2]; + // 10^-1 precision, raw / 32.0 + *wheel_speed_right_front = (double)((int)((double)raw / 3.2) / 10.0); + return OSCC_OK; +} + + +oscc_result_t get_wheel_speed_left_front( + struct can_frame const * const frame, + double * wheel_speed_left_front) +{ + if((frame == NULL) || (wheel_speed_left_front == NULL)) { return OSCC_ERROR; } + if(frame->can_id != KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) { return OSCC_ERROR; } + uint16_t raw = ((frame->data[1] & 0x0F) << 8) | frame->data[0]; + // 10^-1 precision, raw / 32.0 + *wheel_speed_left_front = (double)((int)((double)raw / 3.2) / 10.0); + return OSCC_OK; +} + + +oscc_result_t get_steering_wheel_angle( + struct can_frame const * const frame, + double * steering_wheel_angle) +{ + if((frame == NULL) || (steering_wheel_angle == NULL)) { return OSCC_ERROR; } + if(frame->can_id != KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID) { return OSCC_ERROR; } + int16_t raw = (frame->data[1] << 8) | frame->data[0]; + *steering_wheel_angle = -((double)raw / 10.0); + return OSCC_OK; +} + + +oscc_result_t get_brake_pressure( + struct can_frame const * const frame, + double * brake_pressure) +{ + if((frame == NULL) || (brake_pressure == NULL)) { return OSCC_ERROR; } + if(frame->can_id != KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID) { return OSCC_ERROR; } +#ifdef KIA_NIRO + double scale = 40.0; + uint16_t raw = ((frame->data[4] & 0x0F) << 8) | frame->data[3]; +#else + double scale = 10.0; + uint16_t raw = ((frame->data[5] & 0x0F) << 8) | frame->data[4]; +#endif + *brake_pressure = (double)raw / scale; + return OSCC_OK; +} From 3ceee997360d2956331b896d65f0da3bdd0e01d0 Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Wed, 25 Apr 2018 10:36:42 -0700 Subject: [PATCH 57/80] Incorportate predefined steering angle scalar Prior to this commit the "unpacking getter" logic added in the previous commit did not incorporate the pre-defined `KIA_SOUL_OBD_STEERING_ANGLE_SCALAR`. This resulted in the potential for stale code. After this commit the steering wheel angle "unpacking getter" employs the pre-defined scalar. --- api/src/oscc.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/api/src/oscc.c b/api/src/oscc.c index f463a24d..248a1f4c 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -1152,7 +1152,7 @@ oscc_result_t get_steering_wheel_angle( if((frame == NULL) || (steering_wheel_angle == NULL)) { return OSCC_ERROR; } if(frame->can_id != KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID) { return OSCC_ERROR; } int16_t raw = (frame->data[1] << 8) | frame->data[0]; - *steering_wheel_angle = -((double)raw / 10.0); + *steering_wheel_angle = -((double)raw * KIA_SOUL_OBD_STEERING_ANGLE_SCALAR); return OSCC_OK; } From 7e7307c25bcf0bed5614560d2a42ac28648a35ba Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Wed, 25 Apr 2018 10:39:35 -0700 Subject: [PATCH 58/80] Meet style convention Prior to this commit the code formatting in previous commits was not consistent with the rest of the OSCC code base. This commit represents formatting that should be consistent with the rest of the codebase. --- api/src/oscc.c | 84 ++++++++++++++++++++++++++++++++++++++++++-------- 1 file changed, 72 insertions(+), 12 deletions(-) diff --git a/api/src/oscc.c b/api/src/oscc.c index 248a1f4c..9bb535ff 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -1097,11 +1097,21 @@ oscc_result_t get_wheel_speed_right_rear( struct can_frame const * const frame, double * wheel_speed_right_rear) { - if((frame == NULL) || (wheel_speed_right_rear == NULL)) { return OSCC_ERROR; } - if(frame->can_id != KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) { return OSCC_ERROR; } + if((frame == NULL) || (wheel_speed_right_rear == NULL)) + { + return OSCC_ERROR; + } + + if(frame->can_id != KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) + { + return OSCC_ERROR; + } + uint16_t raw = ((frame->data[7] & 0x0F) << 8) | frame->data[6]; + // 10^-1 precision, raw / 32.0 *wheel_speed_right_rear = (double)((int)((double)raw / 3.2) / 10.0); + return OSCC_OK; } @@ -1110,11 +1120,21 @@ oscc_result_t get_wheel_speed_left_rear( struct can_frame const * const frame, double * wheel_speed_left_rear) { - if((frame == NULL) || (wheel_speed_left_rear == NULL)) { return OSCC_ERROR; } - if(frame->can_id != KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) { return OSCC_ERROR; } + if((frame == NULL) || (wheel_speed_left_rear == NULL)) + { + return OSCC_ERROR; + } + + if(frame->can_id != KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) + { + return OSCC_ERROR; + } + uint16_t raw = ((frame->data[5] & 0x0F) << 8) | frame->data[4]; + // 10^-1 precision, raw / 32.0 *wheel_speed_left_rear = (double)((int)((double)raw / 3.2) / 10.0); + return OSCC_OK; } @@ -1123,11 +1143,21 @@ oscc_result_t get_wheel_speed_right_front( struct can_frame const * const frame, double * wheel_speed_right_front) { - if((frame == NULL) || (wheel_speed_right_front == NULL)) { return OSCC_ERROR; } - if(frame->can_id != KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) { return OSCC_ERROR; } + if((frame == NULL) || (wheel_speed_right_front == NULL)) + { + return OSCC_ERROR; + } + + if(frame->can_id != KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) + { + return OSCC_ERROR; + } + uint16_t raw = ((frame->data[3] & 0x0F) << 8) | frame->data[2]; + // 10^-1 precision, raw / 32.0 *wheel_speed_right_front = (double)((int)((double)raw / 3.2) / 10.0); + return OSCC_OK; } @@ -1136,11 +1166,21 @@ oscc_result_t get_wheel_speed_left_front( struct can_frame const * const frame, double * wheel_speed_left_front) { - if((frame == NULL) || (wheel_speed_left_front == NULL)) { return OSCC_ERROR; } - if(frame->can_id != KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) { return OSCC_ERROR; } + if((frame == NULL) || (wheel_speed_left_front == NULL)) + { + return OSCC_ERROR; + } + + if(frame->can_id != KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) + { + return OSCC_ERROR; + } + uint16_t raw = ((frame->data[1] & 0x0F) << 8) | frame->data[0]; + // 10^-1 precision, raw / 32.0 *wheel_speed_left_front = (double)((int)((double)raw / 3.2) / 10.0); + return OSCC_OK; } @@ -1149,10 +1189,20 @@ oscc_result_t get_steering_wheel_angle( struct can_frame const * const frame, double * steering_wheel_angle) { - if((frame == NULL) || (steering_wheel_angle == NULL)) { return OSCC_ERROR; } - if(frame->can_id != KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID) { return OSCC_ERROR; } + if((frame == NULL) || (steering_wheel_angle == NULL)) + { + return OSCC_ERROR; + } + + if(frame->can_id != KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID) + { + return OSCC_ERROR; + } + int16_t raw = (frame->data[1] << 8) | frame->data[0]; + *steering_wheel_angle = -((double)raw * KIA_SOUL_OBD_STEERING_ANGLE_SCALAR); + return OSCC_OK; } @@ -1161,8 +1211,16 @@ oscc_result_t get_brake_pressure( struct can_frame const * const frame, double * brake_pressure) { - if((frame == NULL) || (brake_pressure == NULL)) { return OSCC_ERROR; } - if(frame->can_id != KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID) { return OSCC_ERROR; } + if((frame == NULL) || (brake_pressure == NULL)) + { + return OSCC_ERROR; + } + + if(frame->can_id != KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID) + { + return OSCC_ERROR; + } + #ifdef KIA_NIRO double scale = 40.0; uint16_t raw = ((frame->data[4] & 0x0F) << 8) | frame->data[3]; @@ -1170,6 +1228,8 @@ oscc_result_t get_brake_pressure( double scale = 10.0; uint16_t raw = ((frame->data[5] & 0x0F) << 8) | frame->data[4]; #endif + *brake_pressure = (double)raw / scale; + return OSCC_OK; } From 209b8d472e1e4eadfab249f68a496f5a3cd1a916 Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Wed, 25 Apr 2018 10:52:52 -0700 Subject: [PATCH 59/80] Isolated duplicate code for wheel speed Prior to this commit the logic to unpack the wheel speed reported by the vehicle contained duplicate code. This resulted in the need to make one change in 4 places and the potential for difficult to spot bugs. After this commit the duplicate code has been isolated to its own function. --- api/src/oscc.c | 73 ++++++++++++++++++-------------------------------- 1 file changed, 26 insertions(+), 47 deletions(-) diff --git a/api/src/oscc.c b/api/src/oscc.c index 9bb535ff..237d8ca7 100644 --- a/api/src/oscc.c +++ b/api/src/oscc.c @@ -1093,11 +1093,12 @@ oscc_result_t get_device_name( char * string, char * const name ) return result; } -oscc_result_t get_wheel_speed_right_rear( +static oscc_result_t get_wheel_speed( struct can_frame const * const frame, - double * wheel_speed_right_rear) + double * wheel_speed, + const size_t offset) { - if((frame == NULL) || (wheel_speed_right_rear == NULL)) + if((frame == NULL) || (wheel_speed == NULL)) { return OSCC_ERROR; } @@ -1107,35 +1108,35 @@ oscc_result_t get_wheel_speed_right_rear( return OSCC_ERROR; } - uint16_t raw = ((frame->data[7] & 0x0F) << 8) | frame->data[6]; + uint16_t raw = ((frame->data[offset + 1] & 0x0F) << 8) | frame->data[offset]; // 10^-1 precision, raw / 32.0 - *wheel_speed_right_rear = (double)((int)((double)raw / 3.2) / 10.0); + *wheel_speed = (double)((int)((double)raw / 3.2) / 10.0); return OSCC_OK; } +oscc_result_t get_wheel_speed_right_rear( + struct can_frame const * const frame, + double * wheel_speed_right_rear) +{ + size_t offset = 6; + + oscc_result_t ret = get_wheel_speed(frame, wheel_speed_right_rear, offset); + + return ret; +} + oscc_result_t get_wheel_speed_left_rear( struct can_frame const * const frame, double * wheel_speed_left_rear) { - if((frame == NULL) || (wheel_speed_left_rear == NULL)) - { - return OSCC_ERROR; - } + size_t offset = 4; - if(frame->can_id != KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) - { - return OSCC_ERROR; - } + oscc_result_t ret = get_wheel_speed(frame, wheel_speed_left_rear, offset); - uint16_t raw = ((frame->data[5] & 0x0F) << 8) | frame->data[4]; - - // 10^-1 precision, raw / 32.0 - *wheel_speed_left_rear = (double)((int)((double)raw / 3.2) / 10.0); - - return OSCC_OK; + return ret; } @@ -1143,22 +1144,11 @@ oscc_result_t get_wheel_speed_right_front( struct can_frame const * const frame, double * wheel_speed_right_front) { - if((frame == NULL) || (wheel_speed_right_front == NULL)) - { - return OSCC_ERROR; - } + size_t offset = 2; - if(frame->can_id != KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) - { - return OSCC_ERROR; - } - - uint16_t raw = ((frame->data[3] & 0x0F) << 8) | frame->data[2]; + oscc_result_t ret = get_wheel_speed(frame, wheel_speed_right_front, offset); - // 10^-1 precision, raw / 32.0 - *wheel_speed_right_front = (double)((int)((double)raw / 3.2) / 10.0); - - return OSCC_OK; + return ret; } @@ -1166,22 +1156,11 @@ oscc_result_t get_wheel_speed_left_front( struct can_frame const * const frame, double * wheel_speed_left_front) { - if((frame == NULL) || (wheel_speed_left_front == NULL)) - { - return OSCC_ERROR; - } + size_t offset = 0; - if(frame->can_id != KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID) - { - return OSCC_ERROR; - } - - uint16_t raw = ((frame->data[1] & 0x0F) << 8) | frame->data[0]; + oscc_result_t ret = get_wheel_speed(frame, wheel_speed_left_front, offset); - // 10^-1 precision, raw / 32.0 - *wheel_speed_left_front = (double)((int)((double)raw / 3.2) / 10.0); - - return OSCC_OK; + return ret; } From 0d347e08aa2b201e98933ee53c586752c88e08ff Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Fri, 27 Apr 2018 10:51:34 -0700 Subject: [PATCH 60/80] Add vehicle + OSCC consensus checking tool Prior to this commit there was no easy way to verify that OSCC and the vehicle were on the same page after an install. Usually validation after install required the joystick commander application but that provides no indication as to whether the vehicle reports what we expect it to after sending commands. After this commit the OSCC repo will have the `consensus.py` program to verify tat OSCC and the vehicle are on the same page or report otherwise. Ideally this program will be the first step taken after installing OSCC. It will also help pinpoint issues if the vehicle provides unexpected or error results if OSCC expected different information. --- utils/consensus/.gitignore | 101 +++++++ utils/consensus/README.md | 47 +++ utils/consensus/consensus.py | 440 ++++++++++++++++++++++++++++ utils/consensus/oscccan/__init__.py | 30 ++ utils/consensus/oscccan/canbus.py | 307 +++++++++++++++++++ 5 files changed, 925 insertions(+) create mode 100644 utils/consensus/.gitignore create mode 100644 utils/consensus/README.md create mode 100755 utils/consensus/consensus.py create mode 100644 utils/consensus/oscccan/__init__.py create mode 100644 utils/consensus/oscccan/canbus.py diff --git a/utils/consensus/.gitignore b/utils/consensus/.gitignore new file mode 100644 index 00000000..7bbc71c0 --- /dev/null +++ b/utils/consensus/.gitignore @@ -0,0 +1,101 @@ +# Byte-compiled / optimized / DLL files +__pycache__/ +*.py[cod] +*$py.class + +# C extensions +*.so + +# Distribution / packaging +.Python +env/ +build/ +develop-eggs/ +dist/ +downloads/ +eggs/ +.eggs/ +lib/ +lib64/ +parts/ +sdist/ +var/ +wheels/ +*.egg-info/ +.installed.cfg +*.egg + +# PyInstaller +# Usually these files are written by a python script from a template +# before PyInstaller builds the exe, so as to inject date/other infos into it. +*.manifest +*.spec + +# Installer logs +pip-log.txt +pip-delete-this-directory.txt + +# Unit test / coverage reports +htmlcov/ +.tox/ +.coverage +.coverage.* +.cache +nosetests.xml +coverage.xml +*.cover +.hypothesis/ + +# Translations +*.mo +*.pot + +# Django stuff: +*.log +local_settings.py + +# Flask stuff: +instance/ +.webassets-cache + +# Scrapy stuff: +.scrapy + +# Sphinx documentation +docs/_build/ + +# PyBuilder +target/ + +# Jupyter Notebook +.ipynb_checkpoints + +# pyenv +.python-version + +# celery beat schedule file +celerybeat-schedule + +# SageMath parsed files +*.sage.py + +# dotenv +.env + +# virtualenv +.venv +venv/ +ENV/ + +# Spyder project settings +.spyderproject +.spyproject + +# Rope project settings +.ropeproject + +# mkdocs documentation +/site + +# mypy +.mypy_cache/ diff --git a/utils/consensus/README.md b/utils/consensus/README.md new file mode 100644 index 00000000..77049c46 --- /dev/null +++ b/utils/consensus/README.md @@ -0,0 +1,47 @@ +# Consensus + +The purpose of this Python 3 program is to provide basic validation that there is the vehicle and +OSCC can reach a consensus. Ideally it's a method to quickly verify whether your vehicle is in a +good state. By sending control commands on the CAN gateway then polling for an expected result +there, we should be able to tell whether OSCC is functioning properly or diagnose +any issues more readily. + +While this program was designed to be run as a stand alone executable it may be imported as a module +should a use-case arise. + +Prerequisites for success: + +- A vehicle with OSCC installed +- That vehicle powered on (motor on) +- OSCC powered +- A socketcan connection to OSCC's CAN bus from your computer + +But what does it do? + +1. Enable each OSCC module (brake, steering, throttle). +1. Send commands to increase and decrease brake pressure. +1. Verify that brake pressure reported by vehicle increased or decreased accordingly. +1. Send commands to apply positive or negative torque to steering wheel. +1. Verify that the steering wheel angle increased or decreased accordingly. +1. Send commands to increase or decrease throttle pressure. +1. Verify just that the wheel position is reported. (This one's unique in that we don't require the + wheel positions to expect as a success condition. They shouldn't if the car's in park!. +1. Disable each OSCC module. + +## Dependencies + +- `python3` +- `pip` +- `python-can` (run `pip install python-can`) +- `docopt` (run `pip install docopt`) + +## Usage + +Connect your computer to OSCC's CAN bus and bring up your socketcan interface + +```bash +sudo ip link set can0 type can bitrate 125000 +sudo ip link set up can0 +``` + +Run `diagnostics.py --help` for more info. diff --git a/utils/consensus/consensus.py b/utils/consensus/consensus.py new file mode 100755 index 00000000..c388cacc --- /dev/null +++ b/utils/consensus/consensus.py @@ -0,0 +1,440 @@ +#!/usr/bin/python3 +"""Usage: consensus.py [-hdel] [-c ] [-v ] + +Options: + -h --help Display this information + -d --disable Disable modules only, no consensus checks (overrides enable) + -e --enable Enable modules only, no consensus checks + -l --loop Repeat consensus checks, run continuously + -c , --channel Specify CAN channel, defaults to 'can0' + -v , --vehicle Specify your vehcile, defaults to 'kia_soul_ev' + (kia_soul_ev / kia_soul_petrol / kia_niro) +""" + +# This module lets us sleep intermittently. We're not in a hurry and want to see how the car behaves +# when commands are spaced out a bit. +import time + +# This module makes it easier to print colored text to stdout +# `Fore`` is used to set the color and `Style`` is used to reset to default. +import colorama +from colorama import Fore, Style + +# This is a requirement for this tool's command line argument handling. +from docopt import docopt + +# These are the local modules you would import if you wanted to use this tool as a library rather +# than an executable. +from oscccan.canbus import CanBus +from oscccan.canbus import Report +from oscccan import OsccModule + +class DebugModules(object): + """ + The 'DebugModules' class contains references to each of the OsccModules, + brake, steering, and throttle. It is used to manage a majority of the stdout reporting this + tool relies on. + """ + def __init__(self, bus, brake, steering, throttle): + """ + Initialize references to modules and CAN bus as well as the 'last_measurement' variable + that allows this class to track whether expected increases and decreases occurred. + """ + self.bus = bus + self.brake = brake + self.steering = steering + self.throttle = throttle + self.last_measurement = None + + def reading_sleep(self, duration=1.0): + end = time.time() + duration + + while time.time() < end: + self.bus.recv_report() + + def enable(self): + """ + Enable all OSCC modules. + """ + + while True: + + success = self.enable_module(self.brake) + + if not success: + continue + + success = self.enable_module(self.steering) + + if not success: + continue + + success = self.enable_module(self.throttle) + + if not success: + continue + + break + + def disable(self): + """ + Disable all OSCC modules. + """ + self.disable_module(self.brake) + self.disable_module(self.steering) + self.disable_module(self.throttle) + + def enable_module(self, module): + """ + Enable a single OSCC modules. Print status, success and failure reports. + """ + + print( + Fore.MAGENTA + ' status: ', + Style.RESET_ALL, + 'attempting to enable', + module.module_name, + 'module') + + # Attempt to enable the module parameter. Under the hood, this sends the enable brakes CAN + # frame to OSCC/DriveKit over its CAN gateway. + self.bus.enable_module(module) + + # Verify the module parameter is enabled by listening to the OSCC/DriveKit CAN gateway for + # a status message that confirms it. Set the `success` flag so we can report and handle + # failure + success = self.bus.check_module_enabled_status( + module, + expect=True) + + if success: + print(Fore.GREEN + ' success:', Style.RESET_ALL, module.module_name, 'module enabled') + else: + print( + Fore.RED + + ' error: ', + Style.RESET_ALL, + module.module_name, + 'module could not be enabled') + + self.reading_sleep() + + return success + + def disable_module(self, module): + """ + Disable a single OSCC modules. Print status, success and failure reports. + """ + + print( + Fore.MAGENTA + ' status: ', + Style.RESET_ALL, + 'attempting to disable', + module.module_name, + 'module') + + # Attempt to enable the module parameter. Under the hood, this sends the enable brakes CAN + # frame to OSCC/DriveKit over its CAN gateway. + self.bus.enable_module(module) + + # Verify the module parameter is enabled by listening to the OSCC/DriveKit CAN gateway for + # a status message that confirms it. Set the `success` flag so we can report and handle + # failure + success = self.bus.check_module_enabled_status( + module, + expect=False) + + if success: + print(Fore.GREEN + ' success:', Style.RESET_ALL, module.module_name, 'module disabled') + return True + else: + print( + Fore.RED + ' error: ', + Style.RESET_ALL, + module.module_name, + 'module could not be disabled') + return False + + def command_brake_module(self, cmd_value, expect=None): + """ + Command OSCC brake module and verify resulting behavior. Print status, success and + failure reports. + """ + + if expect is not None: + print( + Fore.MAGENTA + ' status: ', + Style.RESET_ALL, + 'attempting to', + expect, + 'brake pressure from', + self.last_measurement, 'bar') + + print( + Fore.MAGENTA + ' status: ', + Style.RESET_ALL, + 'sending command value', + cmd_value, + 'to brake module') + self.bus.send_command(self.brake, cmd_value, timeout=1.0) + + print(Fore.MAGENTA + ' status: ', Style.RESET_ALL, 'measuring brake pressure') + + if expect == 'increase': + report = self.bus.check_brake_pressure(timeout=1.0, increase_from=self.last_measurement) + elif expect == 'decrease': + report = self.bus.check_brake_pressure(timeout=1.0, decrease_from=self.last_measurement) + else: + report = self.bus.check_brake_pressure(timeout=1.0) + + if report.success is True: + print( + Fore.GREEN + ' success:', + Style.RESET_ALL, + 'brake pressure measured at', + report.value, + 'bar') + else: + if report.value is not None and expect is not None: + print( + Fore.YELLOW + ' unexpected:', + Style.RESET_ALL, + 'brake pressure measured at', + report.value, + '(did not measure', + expect, + 'from last measurement', + self.last_measurement, + ')') + else: + print(Fore.RED + ' error: ', Style.RESET_ALL, 'failed to read brake pressure') + + self.last_measurement = report.value + + + self.reading_sleep() + + def command_steering_module(self, cmd_value, expect=None): + """ + Command OSCC steering module and verify resulting behavior. Print status, success and + failure reports. + """ + + if expect is not None: + direction = 'positive' if expect == 'increase' else 'negative' + print( + Fore.MAGENTA + ' status: ', + Style.RESET_ALL, + direction, + 'torque applied to steering wheel') + + print( + Fore.MAGENTA + ' status: ', + Style.RESET_ALL, + 'sending command value', + cmd_value, + 'to steering module') + self.bus.send_command(self.steering, cmd_value, timeout=1.0) + + self.reading_sleep(1) + + print(Fore.MAGENTA + ' status: ', Style.RESET_ALL, 'measuring steering wheel angle') + + report = Report() + report.success = False + if expect == 'increase': + report = self.bus.check_steering_wheel_angle( + timeout=1.0, + increase_from=self.last_measurement) + elif expect == 'decrease': + report = self.bus.check_steering_wheel_angle( + timeout=1.0, + decrease_from=self.last_measurement) + else: + report = self.bus.check_steering_wheel_angle(timeout=1.0) + + if report.success is True: + print( + Fore.GREEN + ' success:', + Style.RESET_ALL, + 'steering wheel angle measured at', + str(report.value) + '°') + else: + if report.value is not None and expect is not None: + print( + Fore.YELLOW + ' unexpected:', + Style.RESET_ALL, + 'steering wheel angle measured at', + report.value, + '(did not measure', expect, + 'from last measurement', + str(self.last_measurement) + '°)') + else: + print( + Fore.RED + ' error: ', + Style.RESET_ALL, + 'failed to read steering wheel angle') + + self.last_measurement = report.value + + self.reading_sleep() + + def command_throttle_module(self, cmd_value, expect=None): + """ + Command OSCC throttle module and verify resulting behavior. Print status, success and + failure reports. + """ + + if expect is not None: + print( + Fore.RED + ' unexpected:', + Style.RESET_ALL, + 'no logic to measure', + expect, + 'in wheel speed') + + print( + Fore.MAGENTA + ' status: ', + Style.RESET_ALL, + 'sending command value', + cmd_value, + 'to throttle module') + + self.bus.send_command(self.throttle, cmd_value, timeout=1.0) + + print(Fore.MAGENTA + ' status:', Style.RESET_ALL, ' measuring wheel speed') + + report = self.bus.check_wheel_speed(timeout=1.0) + + if report.success is True and report.value is not None: + print( + Fore.GREEN + ' success:', Style.RESET_ALL, + 'wheel speeds measured at lf', str(report.value[0]) + + ', rf', str(report.value[1]) + + ', lr', str(report.value[2]) + + ', rr', str(report.value[3])) + else: + print(Fore.RED + ' error:', Style.RESET_ALL, ' failed to read wheel speeds') + + self.last_measurement = report.value + + self.reading_sleep() + +def check_vehicle_arg(arg): + """ + Sanity check the optional vehicle argument. + """ + + vehicles = ['kia_soul_ev', 'kia_soul_petrol', 'kia_niro', None] + if arg not in vehicles: + raise ValueError('Unable to target vehicle', arg + '. Options are', vehicles) + +def main(args): + check_vehicle_arg(args['--vehicle']) + + channel = 'can0' if args['--channel'] is None else str(args['--channel']) + + bus = CanBus(channel=channel, vehicle=args['--vehicle']) + + brakes = OsccModule(base_arbitration_id=0x70, module_name='brake') + steering = OsccModule(base_arbitration_id=0x80, module_name='steering') + throttle = OsccModule(base_arbitration_id=0x90, module_name='throttle') + + modules = DebugModules(bus, brakes, steering, throttle) + + # Initialize module for printing colored text to stdout + colorama.init() + + if args['--disable']: + modules.disable() + return + elif args['--enable']: + modules.enable() + return + + # Each section or step of the following loop is distinguished from the next by this separator. + # The output begins with this separator for visually consistent output. + print("|Enable Modules -----------------------------------------------------------------|") + + # This `while` loop repeats the same basic steps on each iteration, they are as follows: + # 1. Enable each OSCC module. + # 2. Send commands to increase and decrease brake pressure. + # 3. Verify that brake pressure reported by vehicle increased or decreased accordingly. + # 4. Send commands to apply positive or negative torque to steering wheel. + # 5. Verify that the steering wheel angle increased or decreased accordingly. + # 6. Send commands to increase or decrease throttle application. + # 7. Verify that the wheel position is reported. (This one's unique in that we don't require the + # wheel positions to expect as a success condition. They shouldn't if the car's in park!. + # 8. Disable each OSCC module. + while True: + + modules.enable() + + # Visually distinguish enable steps from the following brake validation + print("|Brake Test --------------------------------------------------------------------|") + + pressure_cmd = 0.0 + modules.command_brake_module(pressure_cmd, expect=None) + + pressure_cmd = 0.5 + modules.command_brake_module(pressure_cmd, expect='increase') + + pressure_cmd = 0.0 + modules.command_brake_module(pressure_cmd, expect='decrease') + + pressure_cmd = 0.3 + modules.command_brake_module(pressure_cmd, expect='increase') + + pressure_cmd = 0.0 + modules.command_brake_module(pressure_cmd, expect='decrease') + + # Visually distinguish brake validation from the following steering wheel validation + print("|Steering Test ------------------------------------------------------------------|") + + torque_cmd = -0.1 + modules.command_steering_module(torque_cmd, expect=None) + + torque_cmd = 0.1 + modules.command_steering_module(torque_cmd, expect=None) + + torque_cmd = 0.2 + modules.command_steering_module(torque_cmd, expect='increase') + + torque_cmd = -0.2 + modules.command_steering_module(torque_cmd, expect='decrease') + + # Visually distinguish steering validation from the following throttle validation + print("|Throttle Test ------------------------------------------------------------------|") + + pressure_cmd = 0.0 + modules.command_throttle_module(pressure_cmd, expect=None) + + pressure_cmd = 0.05 + modules.command_throttle_module(pressure_cmd, expect=None) + + pressure_cmd = 0.1 + modules.command_throttle_module(pressure_cmd, expect=None) + + pressure_cmd = 0.05 + modules.command_throttle_module(pressure_cmd, expect=None) + + pressure_cmd = 0.0 + modules.command_throttle_module(pressure_cmd, expect=None) + + # Visually distinguish throttle validation from the following disable steps + print("|Disable Modules ----------------------------------------------------------------|") + + modules.disable() + + if not args['--loop']: + break + + # Visually distinguish disable steps from the following enable steps + print("|Enable Modules -----------------------------------------------------------------|") + +if __name__ == "__main__": + """ + The program's entry point if run as an executable. + """ + + main(docopt(__doc__)) diff --git a/utils/consensus/oscccan/__init__.py b/utils/consensus/oscccan/__init__.py new file mode 100644 index 00000000..8f1c9f4a --- /dev/null +++ b/utils/consensus/oscccan/__init__.py @@ -0,0 +1,30 @@ +""" +Import as 'oscccan' +""" + +__all__ = [ + 'canbus', + ] + +class OsccModule(object): + """ + Wrapper to CAN data specific to an OSCC module. Used with CanBus class to + communicate on the OSCC CAN bus. + """ + def __init__(self, base_arbitration_id, module_name=None): + """ + Initialize CAN data specific to OSCC module. + """ + try: + int(base_arbitration_id) + except: + raise ValueError( + 'unable to represent given base_arbitration_id as an integer: ', + base_arbitration_id) + + self.magic_word = [0x05, 0xCC] + self.enable_arbitration_id = base_arbitration_id + self.disable_arbitration_id = base_arbitration_id + 1 + self.command_arbitration_id = base_arbitration_id + 2 + self.report_arbitration_id = base_arbitration_id + 3 + self.module_name = module_name diff --git a/utils/consensus/oscccan/canbus.py b/utils/consensus/oscccan/canbus.py new file mode 100644 index 00000000..f1fa66e2 --- /dev/null +++ b/utils/consensus/oscccan/canbus.py @@ -0,0 +1,307 @@ +""" +Import as 'canbus' from 'oscc'. Contains 'CanBus' class used for communicating on the OSCC CAN bus +as well as the 'Report' class that the CanBus class's command methods return. +""" + +# This is the module required for everything CAN bus. It is not default on most systems though +# and needs to be installed with something like `pip install python-can` +import can +# The `struct` module is really helpful for packing bytes into messages for transmission on the CAN +# bus as well as unpacking bytes into an object for this program's consumption. +import struct +# This module lets us sleep intermittently. We're not in a hurry and want to see how the car behaves +# when commands are spaced out a bit. +import time + +from oscccan import OsccModule + +class Report(object): + """ + Class returned by the command methods of the 'CanBus' class. + """ + def __init__(self, success=None, value=None): + self.success = success + self.value = value + +class CanBus(object): + """ + CanBus class for to connecting to a CAN bus and communicating with OSCC modules. + """ + def __init__( + self, + bustype='socketcan_native', + channel='can0', + bitrate=500000, + vehicle='kia_soul_ev'): + """ + Connect to CAN bus. + """ + + try: + self.bus = can.interface.Bus( + bustype=bustype, + channel=channel, + bitrate=bitrate) + except: + raise Exception( + 'unable to connect to CAN bus, check that hardware ' + 'is connected and that socketcan is active') + + self.brake_pressure_arbitration_ids = [0x220] + self.steering_wheel_angle_arbitration_ids = [0x2B0] + self.wheel_speed_arbitration_ids = [0x4B0, 0x386] + self.vehicle = vehicle + + def bus_send_msg(self, arbitration_id, data=None, timeout=1.0): + """ + Send a frame on OSCC CAN bus. + """ + + msg = can.Message( + arbitration_id=arbitration_id, + data=data) + self.bus.send(msg, timeout=timeout) + + def enable_module(self, module, timeout=None): + """ + Send enable command specific to the module parameter. + """ + if not isinstance(module, OsccModule): + raise TypeError('cannot enable', module) + + self.bus_send_msg( + arbitration_id=module.enable_arbitration_id, + data=module.magic_word + [0, 0, 0, 0, 0, 0], + timeout=timeout + ) + + def disable_module(self, module, timeout=None): + """ + Send disable command specific to the module parameter. + """ + if not isinstance(module, OsccModule): + raise TypeError('cannot disable', module) + + self.bus_send_msg( + arbitration_id=module.disable_arbitration_id, + data=module.magic_word + [0, 0, 0, 0, 0, 0], + timeout=timeout + ) + + def check_module_enabled_status( + self, + module, + timeout=1.0, + expect=False): + """ + Check if OSCC module is enabled/disabled. + """ + if not isinstance(module, OsccModule): + raise TypeError('cannot check status for', module) + + status = False + wait = time.time() + timeout + + while True: + if time.time() > wait: + break + + msg = self.recv_report(module=module, timeout=timeout) + + if msg is not None: + byte_lst = list(msg.data) + if byte_lst[2] != 0 and expect is True: + status = True + break + + if byte_lst[2] == 0 and expect is False: + status = False + break + + if byte_lst[2] != 0: + status = True + else: + status = False + + return status + + def send_command( + self, + module, + value, + timeout=None): + """ + Send control command specifed by floating point value to the OsccModule parameter. + """ + if not isinstance(module, OsccModule): + raise TypeError('cannot send command to', module) + + try: + float(value) + except: + raise ValueError('invalid command', value) + + byte_list = list(bytearray(struct.pack("f", value))) + + self.bus_send_msg( + arbitration_id=module.command_arbitration_id, + data=module.magic_word + byte_list + [0, 0], + timeout=timeout + ) + + def recv_report( + self, + module=None, + can_ids=None, + timeout=1.0): + """ + If OsccModule parameter is valid, return its report message. + If OsccModule invalid and can_id is valid, return message with that ID. + If both OsccModule and can_id are invalid, return first message received. + """ + msg_ids = [] + if can_ids is not None: + if not isinstance(can_ids, list): + msg_ids.append(can_ids) + else: + msg_ids.extend(can_ids) + + # throw away can_id if module parameter is valid + if module is not None: + if not isinstance(module, OsccModule): + raise TypeError('cannot find CAN ID in', module) + msg_ids.append(module.report_arbitration_id) + + wait = time.time() + timeout + + while True: + msg = self.bus.recv(timeout) + if msg is not None: + if msg.arbitration_id in msg_ids: + return msg + elif can_ids is None and module is None: + return msg + else: + return None + + if wait > time.time(): + return None + + def check_brake_pressure( + self, + increase_from=None, + decrease_from=None, + timeout=2.0,): + """ + Check brake pressure report from vehicle. If the increase_from or decrease_from parameters + are populated, verify the reported value did increase or decrease. + """ + value = None + wait = time.time() + timeout + + while True: + if time.time() > wait: + if increase_from is None and decrease_from is None: + value = None + return Report(success=False, value=value) + + msg = self.recv_report(can_ids=self.brake_pressure_arbitration_ids, timeout=timeout) + + if msg is None: + continue + + if self.vehicle == 'kia_niro': + # Niro + byte1 = (msg.data[4] & 0x0F) << 8 + byte0 = msg.data[3] + value = int(str(byte1|byte0), 10) + value /= 40 + else: + # Soul EV and Petrol + byte1 = (msg.data[5] & 0x0F) << 8 + byte0 = msg.data[4] + value = int(str(byte1|byte0), 10) + value /= 10 + + if increase_from is not None: + if value > increase_from: + return Report(success=True, value=value) + elif decrease_from is not None: + if value < decrease_from: + return Report(success=True, value=value) + else: + return Report(success=True, value=value) + + def check_steering_wheel_angle( + self, + increase_from=None, + decrease_from=None, + timeout=2.0): + """ + Check steering wheel angle report from vehicle. If the increase_from or decrease_from + parameters are populated, verify the reported value did increase or decrease. + """ + value = None + wait = time.time() + timeout + + while True: + if time.time() > wait: + if increase_from is None and decrease_from is None: + value = None + return Report(success=False, value=value) + + msg = self.recv_report( + can_ids=self.steering_wheel_angle_arbitration_ids, + timeout=timeout) + + if msg is None: + continue + + value = -float(struct.unpack("h", msg.data[:2])[0]) / 10.0 + + if increase_from is not None: + if value > increase_from: + return Report(success=True, value=value) + elif decrease_from is not None: + if value < decrease_from: + return Report(success=True, value=value) + else: + return Report(success=True, value=value) + + def get_wheel_speed(self, data, offset): + """ + Wheel speed unpacking logic generic across offsets. + """ + byte1 = (data[offset + 1] & 0x0F) << 8 + byte0 = data[offset] + value = int(str(byte1|byte0), 10) + + return float(value) / 10.0 + + def check_wheel_speed( + self, + timeout=2.0): + """ + Check wheel speed report from vehicle. + """ + + wait = time.time() + timeout + + while True: + if time.time() > wait: + return Report(success=False, value=None) + + msg = self.recv_report(can_ids=self.wheel_speed_arbitration_ids, timeout=timeout) + + if msg is not None: + left_front = None + right_front = None + left_rear = None + right_rear = None + + left_front = self.get_wheel_speed(msg.data, 0) + right_front = self.get_wheel_speed(msg.data, 2) + left_rear = self.get_wheel_speed(msg.data, 4) + right_rear = self.get_wheel_speed(msg.data, 6) + + return Report(success=True, value=[left_front, right_front, left_rear, right_rear]) From fe83b574946719dfac9b00a3652d56f94c121c5c Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Fri, 27 Apr 2018 11:18:51 -0700 Subject: [PATCH 61/80] The program's name in Usage section of README was incorrect. This commit fixes that. --- utils/consensus/README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/utils/consensus/README.md b/utils/consensus/README.md index 77049c46..a2260e49 100644 --- a/utils/consensus/README.md +++ b/utils/consensus/README.md @@ -3,8 +3,8 @@ The purpose of this Python 3 program is to provide basic validation that there is the vehicle and OSCC can reach a consensus. Ideally it's a method to quickly verify whether your vehicle is in a good state. By sending control commands on the CAN gateway then polling for an expected result -there, we should be able to tell whether OSCC is functioning properly or diagnose -any issues more readily. +there, we should be able to tell whether OSCC is functioning properly or diagnose any issues more +readily. While this program was designed to be run as a stand alone executable it may be imported as a module should a use-case arise. @@ -44,4 +44,4 @@ sudo ip link set can0 type can bitrate 125000 sudo ip link set up can0 ``` -Run `diagnostics.py --help` for more info. +Run `consensus.py --help` for more info. From 4a772c3669223c1c0f794473bccab2fcae2ea37e Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Fri, 27 Apr 2018 11:26:24 -0700 Subject: [PATCH 62/80] Usage section referenced the wrong bitrate for communication with OSCC. This commit addresses that by updating the referenced bitrate to 500000 --- utils/consensus/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/utils/consensus/README.md b/utils/consensus/README.md index a2260e49..065093cf 100644 --- a/utils/consensus/README.md +++ b/utils/consensus/README.md @@ -40,7 +40,7 @@ But what does it do? Connect your computer to OSCC's CAN bus and bring up your socketcan interface ```bash -sudo ip link set can0 type can bitrate 125000 +sudo ip link set can0 type can bitrate 500000 sudo ip link set up can0 ``` From 7afe649aec2f0af081ad213958e3a6ba71ec7e17 Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Fri, 27 Apr 2018 13:21:42 -0700 Subject: [PATCH 63/80] add documentation to 'reading_sleep' method of the 'DebugModules' class --- utils/consensus/consensus.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/utils/consensus/consensus.py b/utils/consensus/consensus.py index c388cacc..67bf7f1d 100755 --- a/utils/consensus/consensus.py +++ b/utils/consensus/consensus.py @@ -47,6 +47,12 @@ def __init__(self, bus, brake, steering, throttle): self.last_measurement = None def reading_sleep(self, duration=1.0): + """ + Used in place of `time.sleep()`. Enables "waiting" for some interval while maintaining + confidence that once we start unpacking at the car's reports again that data hasn't gone + stale. + """ + end = time.time() + duration while time.time() < end: From 7a41a6e3c3182c1ad0bd7b63942d9ebfd9cad4d8 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Fri, 27 Apr 2018 13:46:52 -0700 Subject: [PATCH 64/80] Update the CMake include path Prior to this commit the CMake API include used a variable assuming the sub-directory would be within the api which does not work if the oscc repo is used as a submodule. This commit fixes that by using a current directory variable instead so that the include file still works as a submodule. --- api/OsccConfig.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/api/OsccConfig.cmake b/api/OsccConfig.cmake index cf219507..c4b45ed1 100644 --- a/api/OsccConfig.cmake +++ b/api/OsccConfig.cmake @@ -1 +1 @@ -include(${CMAKE_SOURCE_DIR}/../firmware/cmake/OsccConfig.cmake) +include(${CMAKE_CURRENT_LIST_DIR}/../firmware/cmake/OsccConfig.cmake) From 04ebade181e75a9323184a9c0eb93aa80ac66ef6 Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Fri, 27 Apr 2018 14:38:40 -0700 Subject: [PATCH 65/80] oscccan/canbus.py docstring typo in parent module name. This commit changes the docs to direct users to import 'oscccan' rather than importing 'oscc' --- utils/consensus/oscccan/canbus.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/utils/consensus/oscccan/canbus.py b/utils/consensus/oscccan/canbus.py index f1fa66e2..9d2eeacc 100644 --- a/utils/consensus/oscccan/canbus.py +++ b/utils/consensus/oscccan/canbus.py @@ -1,5 +1,5 @@ """ -Import as 'canbus' from 'oscc'. Contains 'CanBus' class used for communicating on the OSCC CAN bus +Import as 'canbus' from 'oscccan'. Contains 'CanBus' class used for communicating on the OSCC CAN bus as well as the 'Report' class that the CanBus class's command methods return. """ From a36a4d051b52736f8e51b5de081ce2de278984b3 Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Fri, 27 Apr 2018 16:50:37 -0700 Subject: [PATCH 66/80] Update Dependencies section of consensus.py README to specify pip3 and include python-can, and colorama. Also added install steps for linux --- utils/consensus/README.md | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/utils/consensus/README.md b/utils/consensus/README.md index 065093cf..f562eaae 100644 --- a/utils/consensus/README.md +++ b/utils/consensus/README.md @@ -30,10 +30,12 @@ But what does it do? ## Dependencies -- `python3` -- `pip` -- `python-can` (run `pip install python-can`) -- `docopt` (run `pip install docopt`) +- `python3` (`sudo apt install python3`) +- `pip3` (`sudo apt install python3-pip`) +- `python-can` (`pip3 install python-can`) +- `colorama` (`pip3 install python-can`) +- `docopt` (`pip3 install docopt`) +- `python-can` (`pip3 install python-can`) ## Usage From 0c0da98e1f39062bbc34d0bcb7e307965c01beff Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Fri, 27 Apr 2018 16:52:44 -0700 Subject: [PATCH 67/80] typo in colorama dependency install step in consensus.py README.md --- utils/consensus/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/utils/consensus/README.md b/utils/consensus/README.md index f562eaae..1cd0c4aa 100644 --- a/utils/consensus/README.md +++ b/utils/consensus/README.md @@ -33,7 +33,7 @@ But what does it do? - `python3` (`sudo apt install python3`) - `pip3` (`sudo apt install python3-pip`) - `python-can` (`pip3 install python-can`) -- `colorama` (`pip3 install python-can`) +- `colorama` (`pip3 install colorama`) - `docopt` (`pip3 install docopt`) - `python-can` (`pip3 install python-can`) From 60b80337daa60b0e47ea544cdfd7df0e89d63937 Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Fri, 27 Apr 2018 16:54:21 -0700 Subject: [PATCH 68/80] removed duplicate python-can dependency in consensus.py README.md --- utils/consensus/README.md | 1 - 1 file changed, 1 deletion(-) diff --git a/utils/consensus/README.md b/utils/consensus/README.md index 1cd0c4aa..374453e1 100644 --- a/utils/consensus/README.md +++ b/utils/consensus/README.md @@ -32,7 +32,6 @@ But what does it do? - `python3` (`sudo apt install python3`) - `pip3` (`sudo apt install python3-pip`) -- `python-can` (`pip3 install python-can`) - `colorama` (`pip3 install colorama`) - `docopt` (`pip3 install docopt`) - `python-can` (`pip3 install python-can`) From 2e4e851175089fd0e204eef50e630ca577bcea6f Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Mon, 30 Apr 2018 10:49:46 -0700 Subject: [PATCH 69/80] Prior to this commit the function to disable modules in consensus.py was calling 'enable' and was not sleeping between commands. This commit addresses those issues by adding a sleep and calling disable --- utils/consensus/consensus.py | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/utils/consensus/consensus.py b/utils/consensus/consensus.py index 67bf7f1d..d4180221 100755 --- a/utils/consensus/consensus.py +++ b/utils/consensus/consensus.py @@ -139,11 +139,11 @@ def disable_module(self, module): module.module_name, 'module') - # Attempt to enable the module parameter. Under the hood, this sends the enable brakes CAN + # Attempt to disable the module parameter. Under the hood, this sends the disable brakes CAN # frame to OSCC/DriveKit over its CAN gateway. - self.bus.enable_module(module) + self.bus.disable_module(module) - # Verify the module parameter is enabled by listening to the OSCC/DriveKit CAN gateway for + # Verify the module parameter is disabled by listening to the OSCC/DriveKit CAN gateway for # a status message that confirms it. Set the `success` flag so we can report and handle # failure success = self.bus.check_module_enabled_status( @@ -161,6 +161,8 @@ def disable_module(self, module): 'module could not be disabled') return False + time.sleep(1) + def command_brake_module(self, cmd_value, expect=None): """ Command OSCC brake module and verify resulting behavior. Print status, success and From 2fdac8d6e4a50beb1b9c8c83df0e7e9b3e2beb09 Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Mon, 30 Apr 2018 11:03:57 -0700 Subject: [PATCH 70/80] The previous commit didn't catch a boolean logic bug that prevented the disabled status to succeed and failed to actually sleep between between disable commands and validation that the disable succeeded --- utils/consensus/consensus.py | 4 ++-- utils/consensus/oscccan/canbus.py | 7 +------ 2 files changed, 3 insertions(+), 8 deletions(-) diff --git a/utils/consensus/consensus.py b/utils/consensus/consensus.py index d4180221..6de13452 100755 --- a/utils/consensus/consensus.py +++ b/utils/consensus/consensus.py @@ -143,6 +143,8 @@ def disable_module(self, module): # frame to OSCC/DriveKit over its CAN gateway. self.bus.disable_module(module) + time.sleep(1) + # Verify the module parameter is disabled by listening to the OSCC/DriveKit CAN gateway for # a status message that confirms it. Set the `success` flag so we can report and handle # failure @@ -161,8 +163,6 @@ def disable_module(self, module): 'module could not be disabled') return False - time.sleep(1) - def command_brake_module(self, cmd_value, expect=None): """ Command OSCC brake module and verify resulting behavior. Print status, success and diff --git a/utils/consensus/oscccan/canbus.py b/utils/consensus/oscccan/canbus.py index 9d2eeacc..ac62812c 100644 --- a/utils/consensus/oscccan/canbus.py +++ b/utils/consensus/oscccan/canbus.py @@ -115,14 +115,9 @@ def check_module_enabled_status( break if byte_lst[2] == 0 and expect is False: - status = False + status = True break - if byte_lst[2] != 0: - status = True - else: - status = False - return status def send_command( From 2e8b62dc91274c137a8efc870a6324da2c9d4943 Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Mon, 30 Apr 2018 11:40:52 -0700 Subject: [PATCH 71/80] Prior to this commit the first sentence of the README had some 'extra words'. This commit revises that sentence so that is says something sensical. --- utils/consensus/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/utils/consensus/README.md b/utils/consensus/README.md index 374453e1..142c3df1 100644 --- a/utils/consensus/README.md +++ b/utils/consensus/README.md @@ -1,6 +1,6 @@ # Consensus -The purpose of this Python 3 program is to provide basic validation that there is the vehicle and +The purpose of this Python 3 program is to provide basic validation that the vehicle and OSCC can reach a consensus. Ideally it's a method to quickly verify whether your vehicle is in a good state. By sending control commands on the CAN gateway then polling for an expected result there, we should be able to tell whether OSCC is functioning properly or diagnose any issues more From b1fb2234ab2c79cffa7357df93974b22819fe6dc Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Mon, 30 Apr 2018 12:37:23 -0700 Subject: [PATCH 72/80] Add compatibility note in consensus README.md --- utils/consensus/README.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/utils/consensus/README.md b/utils/consensus/README.md index 142c3df1..4f73d696 100644 --- a/utils/consensus/README.md +++ b/utils/consensus/README.md @@ -36,6 +36,10 @@ But what does it do? - `docopt` (`pip3 install docopt`) - `python-can` (`pip3 install python-can`) +## Compatibility + +Works with OSCC `v1.2.1` and up. + ## Usage Connect your computer to OSCC's CAN bus and bring up your socketcan interface From ad5ee3509287cc12a387e902e09da5ab2620c465 Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Mon, 30 Apr 2018 13:29:19 -0700 Subject: [PATCH 73/80] Turned down max torque requests used for consensus tool. When the front wheels were on plates the 0.2 torque command was enough to hit the rack and disable OSCC --- utils/consensus/consensus.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/utils/consensus/consensus.py b/utils/consensus/consensus.py index 6de13452..ea93ad5c 100755 --- a/utils/consensus/consensus.py +++ b/utils/consensus/consensus.py @@ -405,10 +405,10 @@ def main(args): torque_cmd = 0.1 modules.command_steering_module(torque_cmd, expect=None) - torque_cmd = 0.2 + torque_cmd = 0.15 modules.command_steering_module(torque_cmd, expect='increase') - torque_cmd = -0.2 + torque_cmd = -0.15 modules.command_steering_module(torque_cmd, expect='decrease') # Visually distinguish steering validation from the following throttle validation From c9387514419c0abfc05193b56a60b597a0ea44f4 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Mon, 30 Apr 2018 16:17:05 -0700 Subject: [PATCH 74/80] Add arduino init to null implementation Prior to this commit the null implementation did not initialize the Arduino code in the firmware. This commit fixes that by adding arduino_init to the null firmware. --- firmware/null/CMakeLists.txt | 9 ++++++++- firmware/null/main.cpp | 5 +++++ 2 files changed, 13 insertions(+), 1 deletion(-) diff --git a/firmware/null/CMakeLists.txt b/firmware/null/CMakeLists.txt index 1c1da30e..5798a7cd 100644 --- a/firmware/null/CMakeLists.txt +++ b/firmware/null/CMakeLists.txt @@ -6,4 +6,11 @@ set(ARDUINO_DEFAULT_BAUDRATE ${SERIAL_BAUD_NULL}) generate_arduino_firmware( null SRCS - main.cpp) + main.cpp + ${OSCC_FIRMWARE_ROOT}/common/libs/arduino_init/arduino_init.cpp) + +target_include_directories( + null + PRIVATE + ${OSCC_FIRMWARE_ROOT}/common/libs/arduino_init +) diff --git a/firmware/null/main.cpp b/firmware/null/main.cpp index 1660cfd9..e7e46117 100644 --- a/firmware/null/main.cpp +++ b/firmware/null/main.cpp @@ -2,7 +2,12 @@ * @file main.cpp * NULL Implementation */ + +#include "arduino_init.h" + int main( void ) { + init_arduino( ); + while( true ) { } } From 0223139b3b4acadb44488aff38940c93bcd7a243 Mon Sep 17 00:00:00 2001 From: Shea Newton Date: Tue, 1 May 2018 13:29:57 -0700 Subject: [PATCH 75/80] Remove consensus utility Prior to this commit this repo contained a utility called consensus. We've decided to move that utility to its own repository and rebrand as consensus may misrepresnt the tool's purpose. --- utils/consensus/.gitignore | 101 ---- utils/consensus/README.md | 52 -- utils/consensus/consensus.py | 448 ------------------ utils/consensus/oscccan/__init__.py | 30 -- .../__pycache__/__init__.cpython-35.pyc | Bin 0 -> 1080 bytes .../oscccan/__pycache__/canbus.cpython-35.pyc | Bin 0 -> 7552 bytes utils/consensus/oscccan/canbus.py | 302 ------------ 7 files changed, 933 deletions(-) delete mode 100644 utils/consensus/.gitignore delete mode 100644 utils/consensus/README.md delete mode 100755 utils/consensus/consensus.py delete mode 100644 utils/consensus/oscccan/__init__.py create mode 100644 utils/consensus/oscccan/__pycache__/__init__.cpython-35.pyc create mode 100644 utils/consensus/oscccan/__pycache__/canbus.cpython-35.pyc delete mode 100644 utils/consensus/oscccan/canbus.py diff --git a/utils/consensus/.gitignore b/utils/consensus/.gitignore deleted file mode 100644 index 7bbc71c0..00000000 --- a/utils/consensus/.gitignore +++ /dev/null @@ -1,101 +0,0 @@ -# Byte-compiled / optimized / DLL files -__pycache__/ -*.py[cod] -*$py.class - -# C extensions -*.so - -# Distribution / packaging -.Python -env/ -build/ -develop-eggs/ -dist/ -downloads/ -eggs/ -.eggs/ -lib/ -lib64/ -parts/ -sdist/ -var/ -wheels/ -*.egg-info/ -.installed.cfg -*.egg - -# PyInstaller -# Usually these files are written by a python script from a template -# before PyInstaller builds the exe, so as to inject date/other infos into it. -*.manifest -*.spec - -# Installer logs -pip-log.txt -pip-delete-this-directory.txt - -# Unit test / coverage reports -htmlcov/ -.tox/ -.coverage -.coverage.* -.cache -nosetests.xml -coverage.xml -*.cover -.hypothesis/ - -# Translations -*.mo -*.pot - -# Django stuff: -*.log -local_settings.py - -# Flask stuff: -instance/ -.webassets-cache - -# Scrapy stuff: -.scrapy - -# Sphinx documentation -docs/_build/ - -# PyBuilder -target/ - -# Jupyter Notebook -.ipynb_checkpoints - -# pyenv -.python-version - -# celery beat schedule file -celerybeat-schedule - -# SageMath parsed files -*.sage.py - -# dotenv -.env - -# virtualenv -.venv -venv/ -ENV/ - -# Spyder project settings -.spyderproject -.spyproject - -# Rope project settings -.ropeproject - -# mkdocs documentation -/site - -# mypy -.mypy_cache/ diff --git a/utils/consensus/README.md b/utils/consensus/README.md deleted file mode 100644 index 4f73d696..00000000 --- a/utils/consensus/README.md +++ /dev/null @@ -1,52 +0,0 @@ -# Consensus - -The purpose of this Python 3 program is to provide basic validation that the vehicle and -OSCC can reach a consensus. Ideally it's a method to quickly verify whether your vehicle is in a -good state. By sending control commands on the CAN gateway then polling for an expected result -there, we should be able to tell whether OSCC is functioning properly or diagnose any issues more -readily. - -While this program was designed to be run as a stand alone executable it may be imported as a module -should a use-case arise. - -Prerequisites for success: - -- A vehicle with OSCC installed -- That vehicle powered on (motor on) -- OSCC powered -- A socketcan connection to OSCC's CAN bus from your computer - -But what does it do? - -1. Enable each OSCC module (brake, steering, throttle). -1. Send commands to increase and decrease brake pressure. -1. Verify that brake pressure reported by vehicle increased or decreased accordingly. -1. Send commands to apply positive or negative torque to steering wheel. -1. Verify that the steering wheel angle increased or decreased accordingly. -1. Send commands to increase or decrease throttle pressure. -1. Verify just that the wheel position is reported. (This one's unique in that we don't require the - wheel positions to expect as a success condition. They shouldn't if the car's in park!. -1. Disable each OSCC module. - -## Dependencies - -- `python3` (`sudo apt install python3`) -- `pip3` (`sudo apt install python3-pip`) -- `colorama` (`pip3 install colorama`) -- `docopt` (`pip3 install docopt`) -- `python-can` (`pip3 install python-can`) - -## Compatibility - -Works with OSCC `v1.2.1` and up. - -## Usage - -Connect your computer to OSCC's CAN bus and bring up your socketcan interface - -```bash -sudo ip link set can0 type can bitrate 500000 -sudo ip link set up can0 -``` - -Run `consensus.py --help` for more info. diff --git a/utils/consensus/consensus.py b/utils/consensus/consensus.py deleted file mode 100755 index ea93ad5c..00000000 --- a/utils/consensus/consensus.py +++ /dev/null @@ -1,448 +0,0 @@ -#!/usr/bin/python3 -"""Usage: consensus.py [-hdel] [-c ] [-v ] - -Options: - -h --help Display this information - -d --disable Disable modules only, no consensus checks (overrides enable) - -e --enable Enable modules only, no consensus checks - -l --loop Repeat consensus checks, run continuously - -c , --channel Specify CAN channel, defaults to 'can0' - -v , --vehicle Specify your vehcile, defaults to 'kia_soul_ev' - (kia_soul_ev / kia_soul_petrol / kia_niro) -""" - -# This module lets us sleep intermittently. We're not in a hurry and want to see how the car behaves -# when commands are spaced out a bit. -import time - -# This module makes it easier to print colored text to stdout -# `Fore`` is used to set the color and `Style`` is used to reset to default. -import colorama -from colorama import Fore, Style - -# This is a requirement for this tool's command line argument handling. -from docopt import docopt - -# These are the local modules you would import if you wanted to use this tool as a library rather -# than an executable. -from oscccan.canbus import CanBus -from oscccan.canbus import Report -from oscccan import OsccModule - -class DebugModules(object): - """ - The 'DebugModules' class contains references to each of the OsccModules, - brake, steering, and throttle. It is used to manage a majority of the stdout reporting this - tool relies on. - """ - def __init__(self, bus, brake, steering, throttle): - """ - Initialize references to modules and CAN bus as well as the 'last_measurement' variable - that allows this class to track whether expected increases and decreases occurred. - """ - self.bus = bus - self.brake = brake - self.steering = steering - self.throttle = throttle - self.last_measurement = None - - def reading_sleep(self, duration=1.0): - """ - Used in place of `time.sleep()`. Enables "waiting" for some interval while maintaining - confidence that once we start unpacking at the car's reports again that data hasn't gone - stale. - """ - - end = time.time() + duration - - while time.time() < end: - self.bus.recv_report() - - def enable(self): - """ - Enable all OSCC modules. - """ - - while True: - - success = self.enable_module(self.brake) - - if not success: - continue - - success = self.enable_module(self.steering) - - if not success: - continue - - success = self.enable_module(self.throttle) - - if not success: - continue - - break - - def disable(self): - """ - Disable all OSCC modules. - """ - self.disable_module(self.brake) - self.disable_module(self.steering) - self.disable_module(self.throttle) - - def enable_module(self, module): - """ - Enable a single OSCC modules. Print status, success and failure reports. - """ - - print( - Fore.MAGENTA + ' status: ', - Style.RESET_ALL, - 'attempting to enable', - module.module_name, - 'module') - - # Attempt to enable the module parameter. Under the hood, this sends the enable brakes CAN - # frame to OSCC/DriveKit over its CAN gateway. - self.bus.enable_module(module) - - # Verify the module parameter is enabled by listening to the OSCC/DriveKit CAN gateway for - # a status message that confirms it. Set the `success` flag so we can report and handle - # failure - success = self.bus.check_module_enabled_status( - module, - expect=True) - - if success: - print(Fore.GREEN + ' success:', Style.RESET_ALL, module.module_name, 'module enabled') - else: - print( - Fore.RED + - ' error: ', - Style.RESET_ALL, - module.module_name, - 'module could not be enabled') - - self.reading_sleep() - - return success - - def disable_module(self, module): - """ - Disable a single OSCC modules. Print status, success and failure reports. - """ - - print( - Fore.MAGENTA + ' status: ', - Style.RESET_ALL, - 'attempting to disable', - module.module_name, - 'module') - - # Attempt to disable the module parameter. Under the hood, this sends the disable brakes CAN - # frame to OSCC/DriveKit over its CAN gateway. - self.bus.disable_module(module) - - time.sleep(1) - - # Verify the module parameter is disabled by listening to the OSCC/DriveKit CAN gateway for - # a status message that confirms it. Set the `success` flag so we can report and handle - # failure - success = self.bus.check_module_enabled_status( - module, - expect=False) - - if success: - print(Fore.GREEN + ' success:', Style.RESET_ALL, module.module_name, 'module disabled') - return True - else: - print( - Fore.RED + ' error: ', - Style.RESET_ALL, - module.module_name, - 'module could not be disabled') - return False - - def command_brake_module(self, cmd_value, expect=None): - """ - Command OSCC brake module and verify resulting behavior. Print status, success and - failure reports. - """ - - if expect is not None: - print( - Fore.MAGENTA + ' status: ', - Style.RESET_ALL, - 'attempting to', - expect, - 'brake pressure from', - self.last_measurement, 'bar') - - print( - Fore.MAGENTA + ' status: ', - Style.RESET_ALL, - 'sending command value', - cmd_value, - 'to brake module') - self.bus.send_command(self.brake, cmd_value, timeout=1.0) - - print(Fore.MAGENTA + ' status: ', Style.RESET_ALL, 'measuring brake pressure') - - if expect == 'increase': - report = self.bus.check_brake_pressure(timeout=1.0, increase_from=self.last_measurement) - elif expect == 'decrease': - report = self.bus.check_brake_pressure(timeout=1.0, decrease_from=self.last_measurement) - else: - report = self.bus.check_brake_pressure(timeout=1.0) - - if report.success is True: - print( - Fore.GREEN + ' success:', - Style.RESET_ALL, - 'brake pressure measured at', - report.value, - 'bar') - else: - if report.value is not None and expect is not None: - print( - Fore.YELLOW + ' unexpected:', - Style.RESET_ALL, - 'brake pressure measured at', - report.value, - '(did not measure', - expect, - 'from last measurement', - self.last_measurement, - ')') - else: - print(Fore.RED + ' error: ', Style.RESET_ALL, 'failed to read brake pressure') - - self.last_measurement = report.value - - - self.reading_sleep() - - def command_steering_module(self, cmd_value, expect=None): - """ - Command OSCC steering module and verify resulting behavior. Print status, success and - failure reports. - """ - - if expect is not None: - direction = 'positive' if expect == 'increase' else 'negative' - print( - Fore.MAGENTA + ' status: ', - Style.RESET_ALL, - direction, - 'torque applied to steering wheel') - - print( - Fore.MAGENTA + ' status: ', - Style.RESET_ALL, - 'sending command value', - cmd_value, - 'to steering module') - self.bus.send_command(self.steering, cmd_value, timeout=1.0) - - self.reading_sleep(1) - - print(Fore.MAGENTA + ' status: ', Style.RESET_ALL, 'measuring steering wheel angle') - - report = Report() - report.success = False - if expect == 'increase': - report = self.bus.check_steering_wheel_angle( - timeout=1.0, - increase_from=self.last_measurement) - elif expect == 'decrease': - report = self.bus.check_steering_wheel_angle( - timeout=1.0, - decrease_from=self.last_measurement) - else: - report = self.bus.check_steering_wheel_angle(timeout=1.0) - - if report.success is True: - print( - Fore.GREEN + ' success:', - Style.RESET_ALL, - 'steering wheel angle measured at', - str(report.value) + '°') - else: - if report.value is not None and expect is not None: - print( - Fore.YELLOW + ' unexpected:', - Style.RESET_ALL, - 'steering wheel angle measured at', - report.value, - '(did not measure', expect, - 'from last measurement', - str(self.last_measurement) + '°)') - else: - print( - Fore.RED + ' error: ', - Style.RESET_ALL, - 'failed to read steering wheel angle') - - self.last_measurement = report.value - - self.reading_sleep() - - def command_throttle_module(self, cmd_value, expect=None): - """ - Command OSCC throttle module and verify resulting behavior. Print status, success and - failure reports. - """ - - if expect is not None: - print( - Fore.RED + ' unexpected:', - Style.RESET_ALL, - 'no logic to measure', - expect, - 'in wheel speed') - - print( - Fore.MAGENTA + ' status: ', - Style.RESET_ALL, - 'sending command value', - cmd_value, - 'to throttle module') - - self.bus.send_command(self.throttle, cmd_value, timeout=1.0) - - print(Fore.MAGENTA + ' status:', Style.RESET_ALL, ' measuring wheel speed') - - report = self.bus.check_wheel_speed(timeout=1.0) - - if report.success is True and report.value is not None: - print( - Fore.GREEN + ' success:', Style.RESET_ALL, - 'wheel speeds measured at lf', str(report.value[0]) + - ', rf', str(report.value[1]) + - ', lr', str(report.value[2]) + - ', rr', str(report.value[3])) - else: - print(Fore.RED + ' error:', Style.RESET_ALL, ' failed to read wheel speeds') - - self.last_measurement = report.value - - self.reading_sleep() - -def check_vehicle_arg(arg): - """ - Sanity check the optional vehicle argument. - """ - - vehicles = ['kia_soul_ev', 'kia_soul_petrol', 'kia_niro', None] - if arg not in vehicles: - raise ValueError('Unable to target vehicle', arg + '. Options are', vehicles) - -def main(args): - check_vehicle_arg(args['--vehicle']) - - channel = 'can0' if args['--channel'] is None else str(args['--channel']) - - bus = CanBus(channel=channel, vehicle=args['--vehicle']) - - brakes = OsccModule(base_arbitration_id=0x70, module_name='brake') - steering = OsccModule(base_arbitration_id=0x80, module_name='steering') - throttle = OsccModule(base_arbitration_id=0x90, module_name='throttle') - - modules = DebugModules(bus, brakes, steering, throttle) - - # Initialize module for printing colored text to stdout - colorama.init() - - if args['--disable']: - modules.disable() - return - elif args['--enable']: - modules.enable() - return - - # Each section or step of the following loop is distinguished from the next by this separator. - # The output begins with this separator for visually consistent output. - print("|Enable Modules -----------------------------------------------------------------|") - - # This `while` loop repeats the same basic steps on each iteration, they are as follows: - # 1. Enable each OSCC module. - # 2. Send commands to increase and decrease brake pressure. - # 3. Verify that brake pressure reported by vehicle increased or decreased accordingly. - # 4. Send commands to apply positive or negative torque to steering wheel. - # 5. Verify that the steering wheel angle increased or decreased accordingly. - # 6. Send commands to increase or decrease throttle application. - # 7. Verify that the wheel position is reported. (This one's unique in that we don't require the - # wheel positions to expect as a success condition. They shouldn't if the car's in park!. - # 8. Disable each OSCC module. - while True: - - modules.enable() - - # Visually distinguish enable steps from the following brake validation - print("|Brake Test --------------------------------------------------------------------|") - - pressure_cmd = 0.0 - modules.command_brake_module(pressure_cmd, expect=None) - - pressure_cmd = 0.5 - modules.command_brake_module(pressure_cmd, expect='increase') - - pressure_cmd = 0.0 - modules.command_brake_module(pressure_cmd, expect='decrease') - - pressure_cmd = 0.3 - modules.command_brake_module(pressure_cmd, expect='increase') - - pressure_cmd = 0.0 - modules.command_brake_module(pressure_cmd, expect='decrease') - - # Visually distinguish brake validation from the following steering wheel validation - print("|Steering Test ------------------------------------------------------------------|") - - torque_cmd = -0.1 - modules.command_steering_module(torque_cmd, expect=None) - - torque_cmd = 0.1 - modules.command_steering_module(torque_cmd, expect=None) - - torque_cmd = 0.15 - modules.command_steering_module(torque_cmd, expect='increase') - - torque_cmd = -0.15 - modules.command_steering_module(torque_cmd, expect='decrease') - - # Visually distinguish steering validation from the following throttle validation - print("|Throttle Test ------------------------------------------------------------------|") - - pressure_cmd = 0.0 - modules.command_throttle_module(pressure_cmd, expect=None) - - pressure_cmd = 0.05 - modules.command_throttle_module(pressure_cmd, expect=None) - - pressure_cmd = 0.1 - modules.command_throttle_module(pressure_cmd, expect=None) - - pressure_cmd = 0.05 - modules.command_throttle_module(pressure_cmd, expect=None) - - pressure_cmd = 0.0 - modules.command_throttle_module(pressure_cmd, expect=None) - - # Visually distinguish throttle validation from the following disable steps - print("|Disable Modules ----------------------------------------------------------------|") - - modules.disable() - - if not args['--loop']: - break - - # Visually distinguish disable steps from the following enable steps - print("|Enable Modules -----------------------------------------------------------------|") - -if __name__ == "__main__": - """ - The program's entry point if run as an executable. - """ - - main(docopt(__doc__)) diff --git a/utils/consensus/oscccan/__init__.py b/utils/consensus/oscccan/__init__.py deleted file mode 100644 index 8f1c9f4a..00000000 --- a/utils/consensus/oscccan/__init__.py +++ /dev/null @@ -1,30 +0,0 @@ -""" -Import as 'oscccan' -""" - -__all__ = [ - 'canbus', - ] - -class OsccModule(object): - """ - Wrapper to CAN data specific to an OSCC module. Used with CanBus class to - communicate on the OSCC CAN bus. - """ - def __init__(self, base_arbitration_id, module_name=None): - """ - Initialize CAN data specific to OSCC module. - """ - try: - int(base_arbitration_id) - except: - raise ValueError( - 'unable to represent given base_arbitration_id as an integer: ', - base_arbitration_id) - - self.magic_word = [0x05, 0xCC] - self.enable_arbitration_id = base_arbitration_id - self.disable_arbitration_id = base_arbitration_id + 1 - self.command_arbitration_id = base_arbitration_id + 2 - self.report_arbitration_id = base_arbitration_id + 3 - self.module_name = module_name diff --git a/utils/consensus/oscccan/__pycache__/__init__.cpython-35.pyc b/utils/consensus/oscccan/__pycache__/__init__.cpython-35.pyc new file mode 100644 index 0000000000000000000000000000000000000000..ffba6607ceaf213c14345685e43284543fa30b28 GIT binary patch literal 1080 zcmZuw!A=`75FKYXA#6!16#+f^QlVV3chsV`QB`qhkctZJUM$CJf~$=;*xphi)I;HC z`Y-*0y>j9gdg|BEowB9JY(j3A33kKtg@UTh?Lvw3M8<(6)jRtUlMc9L~)nN(IF+WkPEjgJ?& zk?4a2PY8}~5HNT_*eg_HuOfb(>?7ufGOr4`_?}Q4M~2Vm(ok2@(VH>Nx#QH%rBKI8 zcq7+z|6nwtv+!t0KUta6Gv!X`i0ikNrJ~^0;?002%Gs>aN^mD>si`}W&1(;h2@J!f zvGB3`;n!81Bb?TuIPU{47X&T|kR!bXgb;^`kzi}VPXb>wfzM5L(-vF+FqC+Xo5*i4 zA*$va0T)eq@}yq4RLuo_Ox<}7iu9Nr(>Cm`$vmcmFAN|dcKUD z8)>C>bgI5dO()z+#?3@I!<{NMQ@JlL(yFwRQ)zbSO&c@6`RxVqqUD9BW<2QD5nij4 zLta$!oiU}!k{O>W!OlvPXB#s3eSn{B=F0kb{%zfKh8-XhFxFIfYymtqrax~7H9wf literal 0 HcmV?d00001 diff --git a/utils/consensus/oscccan/__pycache__/canbus.cpython-35.pyc b/utils/consensus/oscccan/__pycache__/canbus.cpython-35.pyc new file mode 100644 index 0000000000000000000000000000000000000000..1bafe888573786e927dde81faa7380d3f7c9f774 GIT binary patch literal 7552 zcmc&(-)|gO6}~gGzrE{q6aR?oG?|u^WNBo#2q~2cX<9c)T`6uR|YBhfG;a|Hyds&D-i^8Xb`VAb>4hmO@E=oRCyZnJiPt6R)+jh+D%DysxIbyqZ z;F^10ydAocDZO|ggXP8v+$7dJTGDtQgS->EgTCibTlUEvdIc>W910JjWcQKdP{BVc zCGiAqh11B(93VZ66#(cBP2G$)T9T9!&I972) z^C*rraV&&|ip~`t;6_JV@90T28aR#@MM?Re{fa-hVl}3YVZ~VDEXBl{74Ck6n#=)3P26?0$NsYFTdRSeC5A4iBwR)ToW#{|pX( zRMV(v+~S}m|5Q-Bfg}1oiqq$eCk)t55nbY$1D5N;Z3uUY=Mq=Z(iCn>JOO)veVk4U zx6P+j?mQ#h=Y)HP`{OG9&kA>zJHV7`L1j+3^Wq6e1mmi4LAd9HyU2}Gg~sQFyTpxn z?s?(9Ky2%_gp2+cgnN-KV+=Kb%uFf@DZ{P;8B;1{6p<+of%_ov93~Ua?2JVw!ET&u zhkm@Rn5L#CQo!rZM4_|m#h7r+UhE%uNeT5=ee)+(kxcFSwiShgzU3V_geUsYcMAt2 zG(zR*iim~S(ZmkZ27m=gfL74v*bt9}LHISq{a{vTnihjYCGl7j-_gW}fhN9zY1&d4 z=lM$O9E#wFErt53I4&{#;odr&(-^+YPGR;bCy+nVD5Bntt|e9AI6m6>D__K*}+!->0V3fVzlph?o%eJ2i~^t^u1155}o98 zR1ojvSt_2Vf+B}1n3+V`3pk>4C`7~1npy>aGn#?FX`_krHUh&c!!!>J>s!=Yh|k`1 zIC!8+0HT8d^kq~OdLUjobRG-+5zjXuwF4LdGYU)q5YU4NJY31=f5XE>*bpN`AJUYf zo)nNUJ?_S&FRAYb73kUIfrzB@FmTvV9yl!uKat>z{PXjk|(h^$ac`9C@YsOx* zHQ}VBiK(>c9t#(*p;tt{6XiNQg|K-x^-i(ZSm>WZXZ8z}o%{li#F}`li|B%gGkW0^ zST8loDQryPU|IK%`imRl9E0G5H0AftwuxY4N&Z;$)WQ(VY23#f7Yp6?JNNQYI> zF!yb8GQd0X>#zk#2Vra~3v%Qn4X?nSTJKbnh94m@i0#1fBq+p{Xo(OG3UU z?h;Khc7PO20{u}%97AEysV?L-5rZ5Rv4ccd6OSM@5dVr;L@vB*2>D}DF(}b)jq0f2 z(RT}7bh1EQbnbF3>+;~5xR1cK(WwvL$Y*(#MaAzGrI=JhVbNVl9po1HwUAD%(j!nP z9z>K(-x|%y`Uz1=65;N3suOdZlqkd{Q_^z|EXnC~QtJCr%%QAPQv#6BZ&L9dg8Xr} zq8^o$4s8hLMcD4vHjiS@>f_dNZAg}Qa9P%uzKo>|e1tnA0-LB2385Iep`Fn*{hUsU zaUPLT)2S@$!E)N2pUR~kno{`Sc_~Az(Hk-6l#Hz%?c$f3qX#_d^FDF>O(gN0E-oJh**aG zeA%L+ty($s`k`7K?T1JcOit{xC_GxkoEnMeQ>2jozy7Rnv>8e z^JtRB*J*j7g7sB+I;j&7Y$@%d1Tc{UCr(QHwzHeYlQevt8c))MgYiaF$U&vc1}#SA z1hks0rm4km;Raq6DJ&uHK<+WCU*OQbFw)oJJvm^=uz`d1^&hApHK8eGS*1X5ogt)W ziu)SPDiV+sGeL{ba|~hPk+RTz4>RZ?uZ2=?Q#?_+oGP_41E6q((Fj~s4qS%dz!k8V z*ThbpaRa2O_@vB#%E75YPv5Nw`5QXjNJovB^hbgqjYQRPEkL}}&;>}&o{NR@F=T8Etqb zjh%%!4}kOMM$Q3B;)!+4fgeFI00oj#h@>bY@>m-+DJlJC0cL9%X#lyk%mgp{5HTq@ zf(Sz2An66U5F=Hp3Q&_?XX>jU`>}Yi$Q=M$2rkt04~%zEs0IzLiyK(7UnfV0lE` zb>4uw#XC^)4WNyIpVVkKA@F5*LMy?OHWifkolsCdX;49cKOubHLtetXqH9bDxj;2u zn4U*1F`$l#0rBb7)v}gQ=7+uQXej*3_ZHjT5v26oYgMd+P112Ix2L5Z}ySi8e^T5+Z&~OS|T_P6Zni8)+5hGL1d?DiucEp&e z6ePwtGgIKqvwEkTnXsWa(;WUb2ejf$wpC*CZV2{luvPLOFekS@VvzaYXO6ZlJAecy z_-RbPbmJ6?(9Vo}jS9kOQW*rClo4MtLApg(Z&SgGxp78Ja^QJ|)Xay)?WVuLgwm%8 zCeR|g&TLp7NB@gs=s(S7z6K}!Q;c8^&|m=|6<8M*5p!=qWv)L$BF3$YO1}ULs0+Zx za=@7w)`ZwIK^jB?Q5H)ZoyzcLK7;pZ@66=wF;h8;ev{~j*lsYlya4gf!DgNe@%u&C z>qTCiZkf`y;t4IakT0TmlZv-c^E=ddlM0%RPDLdH9JeaUn0%M6u2I2rP^B6d z6cUs6mKUe)<`FjVK(&=rn%5fIqCT8Y-8s?Gp_L$g$P69q!@r?25_An&r!F3TT4;hy zLDXKS)R%Y-LbH%RL&dQp1r>+4xf7+p*cLC5{89;#Mu|v)62XGk-{?u=jjUIxbg{9< zjVen(SWrFd+=z^!*t5Zn)ohdq0X*ZFVT2?k16wNZcyJaeF0H(q!`JiaR^dQJ0X6Aq z9y_L=dG~^Zt&cQ}8K}7UHMsPIfO-$pJ0VqzXqI=WVCtnyY$jZ;KHWy&>&2v1LEN2^ z{?>MOQs)bhZ`p0AcB)Tu^Et)M!Y1!5VT5*QMO7t;N|tDo7JrZ?{?mu&#)w!j&}mCj zVM&{ilD5qxt*_N@H73=*NW~Q@R;Zx;O{LB6QSA;D{MH{(ZG`9?)^ZvbNWvq^wDIeX zL3_uB)}B4nXt&xksG03~Zn?zeD_ok*Cf^CA=K;-$HI+wXdq}s_PVHc)zMrY8v=MZarW7C$9F43jhEB literal 0 HcmV?d00001 diff --git a/utils/consensus/oscccan/canbus.py b/utils/consensus/oscccan/canbus.py deleted file mode 100644 index ac62812c..00000000 --- a/utils/consensus/oscccan/canbus.py +++ /dev/null @@ -1,302 +0,0 @@ -""" -Import as 'canbus' from 'oscccan'. Contains 'CanBus' class used for communicating on the OSCC CAN bus -as well as the 'Report' class that the CanBus class's command methods return. -""" - -# This is the module required for everything CAN bus. It is not default on most systems though -# and needs to be installed with something like `pip install python-can` -import can -# The `struct` module is really helpful for packing bytes into messages for transmission on the CAN -# bus as well as unpacking bytes into an object for this program's consumption. -import struct -# This module lets us sleep intermittently. We're not in a hurry and want to see how the car behaves -# when commands are spaced out a bit. -import time - -from oscccan import OsccModule - -class Report(object): - """ - Class returned by the command methods of the 'CanBus' class. - """ - def __init__(self, success=None, value=None): - self.success = success - self.value = value - -class CanBus(object): - """ - CanBus class for to connecting to a CAN bus and communicating with OSCC modules. - """ - def __init__( - self, - bustype='socketcan_native', - channel='can0', - bitrate=500000, - vehicle='kia_soul_ev'): - """ - Connect to CAN bus. - """ - - try: - self.bus = can.interface.Bus( - bustype=bustype, - channel=channel, - bitrate=bitrate) - except: - raise Exception( - 'unable to connect to CAN bus, check that hardware ' - 'is connected and that socketcan is active') - - self.brake_pressure_arbitration_ids = [0x220] - self.steering_wheel_angle_arbitration_ids = [0x2B0] - self.wheel_speed_arbitration_ids = [0x4B0, 0x386] - self.vehicle = vehicle - - def bus_send_msg(self, arbitration_id, data=None, timeout=1.0): - """ - Send a frame on OSCC CAN bus. - """ - - msg = can.Message( - arbitration_id=arbitration_id, - data=data) - self.bus.send(msg, timeout=timeout) - - def enable_module(self, module, timeout=None): - """ - Send enable command specific to the module parameter. - """ - if not isinstance(module, OsccModule): - raise TypeError('cannot enable', module) - - self.bus_send_msg( - arbitration_id=module.enable_arbitration_id, - data=module.magic_word + [0, 0, 0, 0, 0, 0], - timeout=timeout - ) - - def disable_module(self, module, timeout=None): - """ - Send disable command specific to the module parameter. - """ - if not isinstance(module, OsccModule): - raise TypeError('cannot disable', module) - - self.bus_send_msg( - arbitration_id=module.disable_arbitration_id, - data=module.magic_word + [0, 0, 0, 0, 0, 0], - timeout=timeout - ) - - def check_module_enabled_status( - self, - module, - timeout=1.0, - expect=False): - """ - Check if OSCC module is enabled/disabled. - """ - if not isinstance(module, OsccModule): - raise TypeError('cannot check status for', module) - - status = False - wait = time.time() + timeout - - while True: - if time.time() > wait: - break - - msg = self.recv_report(module=module, timeout=timeout) - - if msg is not None: - byte_lst = list(msg.data) - if byte_lst[2] != 0 and expect is True: - status = True - break - - if byte_lst[2] == 0 and expect is False: - status = True - break - - return status - - def send_command( - self, - module, - value, - timeout=None): - """ - Send control command specifed by floating point value to the OsccModule parameter. - """ - if not isinstance(module, OsccModule): - raise TypeError('cannot send command to', module) - - try: - float(value) - except: - raise ValueError('invalid command', value) - - byte_list = list(bytearray(struct.pack("f", value))) - - self.bus_send_msg( - arbitration_id=module.command_arbitration_id, - data=module.magic_word + byte_list + [0, 0], - timeout=timeout - ) - - def recv_report( - self, - module=None, - can_ids=None, - timeout=1.0): - """ - If OsccModule parameter is valid, return its report message. - If OsccModule invalid and can_id is valid, return message with that ID. - If both OsccModule and can_id are invalid, return first message received. - """ - msg_ids = [] - if can_ids is not None: - if not isinstance(can_ids, list): - msg_ids.append(can_ids) - else: - msg_ids.extend(can_ids) - - # throw away can_id if module parameter is valid - if module is not None: - if not isinstance(module, OsccModule): - raise TypeError('cannot find CAN ID in', module) - msg_ids.append(module.report_arbitration_id) - - wait = time.time() + timeout - - while True: - msg = self.bus.recv(timeout) - if msg is not None: - if msg.arbitration_id in msg_ids: - return msg - elif can_ids is None and module is None: - return msg - else: - return None - - if wait > time.time(): - return None - - def check_brake_pressure( - self, - increase_from=None, - decrease_from=None, - timeout=2.0,): - """ - Check brake pressure report from vehicle. If the increase_from or decrease_from parameters - are populated, verify the reported value did increase or decrease. - """ - value = None - wait = time.time() + timeout - - while True: - if time.time() > wait: - if increase_from is None and decrease_from is None: - value = None - return Report(success=False, value=value) - - msg = self.recv_report(can_ids=self.brake_pressure_arbitration_ids, timeout=timeout) - - if msg is None: - continue - - if self.vehicle == 'kia_niro': - # Niro - byte1 = (msg.data[4] & 0x0F) << 8 - byte0 = msg.data[3] - value = int(str(byte1|byte0), 10) - value /= 40 - else: - # Soul EV and Petrol - byte1 = (msg.data[5] & 0x0F) << 8 - byte0 = msg.data[4] - value = int(str(byte1|byte0), 10) - value /= 10 - - if increase_from is not None: - if value > increase_from: - return Report(success=True, value=value) - elif decrease_from is not None: - if value < decrease_from: - return Report(success=True, value=value) - else: - return Report(success=True, value=value) - - def check_steering_wheel_angle( - self, - increase_from=None, - decrease_from=None, - timeout=2.0): - """ - Check steering wheel angle report from vehicle. If the increase_from or decrease_from - parameters are populated, verify the reported value did increase or decrease. - """ - value = None - wait = time.time() + timeout - - while True: - if time.time() > wait: - if increase_from is None and decrease_from is None: - value = None - return Report(success=False, value=value) - - msg = self.recv_report( - can_ids=self.steering_wheel_angle_arbitration_ids, - timeout=timeout) - - if msg is None: - continue - - value = -float(struct.unpack("h", msg.data[:2])[0]) / 10.0 - - if increase_from is not None: - if value > increase_from: - return Report(success=True, value=value) - elif decrease_from is not None: - if value < decrease_from: - return Report(success=True, value=value) - else: - return Report(success=True, value=value) - - def get_wheel_speed(self, data, offset): - """ - Wheel speed unpacking logic generic across offsets. - """ - byte1 = (data[offset + 1] & 0x0F) << 8 - byte0 = data[offset] - value = int(str(byte1|byte0), 10) - - return float(value) / 10.0 - - def check_wheel_speed( - self, - timeout=2.0): - """ - Check wheel speed report from vehicle. - """ - - wait = time.time() + timeout - - while True: - if time.time() > wait: - return Report(success=False, value=None) - - msg = self.recv_report(can_ids=self.wheel_speed_arbitration_ids, timeout=timeout) - - if msg is not None: - left_front = None - right_front = None - left_rear = None - right_rear = None - - left_front = self.get_wheel_speed(msg.data, 0) - right_front = self.get_wheel_speed(msg.data, 2) - left_rear = self.get_wheel_speed(msg.data, 4) - right_rear = self.get_wheel_speed(msg.data, 6) - - return Report(success=True, value=[left_front, right_front, left_rear, right_rear]) From 5c7cef344d7314da6fe77fba1869ee2e146f8129 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Tue, 1 May 2018 15:51:48 -0700 Subject: [PATCH 76/80] Add port suffix to can-gateway Prior to this commit the can-gateway would fail tests because the port suffix was missing causing network port selection collision. This commit fixes that by adding the port suffix so that the Jenkins port is assigned on a per worker basis rather than a fixed number. --- firmware/can_gateway/tests/CMakeLists.txt | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/firmware/can_gateway/tests/CMakeLists.txt b/firmware/can_gateway/tests/CMakeLists.txt index 1fc99d69..d7acc6f2 100644 --- a/firmware/can_gateway/tests/CMakeLists.txt +++ b/firmware/can_gateway/tests/CMakeLists.txt @@ -1,5 +1,7 @@ project(can-gateway-unit-tests) +set(CUCUMBER_PORT_GATEWAY "39${PORT_SUFFIX}") + add_library( can-gateway SHARED @@ -45,4 +47,4 @@ add_custom_target( DEPENDS can-gateway-unit-test COMMAND - can-gateway-unit-test --port=3902 >/dev/null & cucumber _2.0.0_ ${CMAKE_CURRENT_SOURCE_DIR}/features ) + can-gateway-unit-test --port=${CUCUMBER_PORT_GATEWAY} >/dev/null & cucumber _2.0.0_ ${CMAKE_CURRENT_SOURCE_DIR}/features ) From 08e4230683f7978f532b2f1c6e59748119c02609 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Tue, 1 May 2018 15:59:18 -0700 Subject: [PATCH 77/80] Add dynamic cucumber wire file Prior to this the can gateway was missing the dynamic configuration of the cucumber wire file causing the tests to fail if the port was different from the file configured port number. This commit fixes that by removing the file and dynamically constructing it during the cmake process. --- firmware/can_gateway/tests/CMakeLists.txt | 2 ++ .../can_gateway/tests/features/step_definitions/cucumber.wire | 2 -- 2 files changed, 2 insertions(+), 2 deletions(-) delete mode 100644 firmware/can_gateway/tests/features/step_definitions/cucumber.wire diff --git a/firmware/can_gateway/tests/CMakeLists.txt b/firmware/can_gateway/tests/CMakeLists.txt index d7acc6f2..cbf47380 100644 --- a/firmware/can_gateway/tests/CMakeLists.txt +++ b/firmware/can_gateway/tests/CMakeLists.txt @@ -42,6 +42,8 @@ target_include_directories( ${CMAKE_SOURCE_DIR}/common/testing/framework/cgreen/include ${CMAKE_SOURCE_DIR}/../api/include) +file(WRITE ${CMAKE_CURRENT_LIST_DIR}/features/step_definitions/cucumber.wire "host: localhost\nport: ${CUCUMBER_PORT_GATEWAY}") + add_custom_target( run-can-gateway-unit-tests DEPENDS diff --git a/firmware/can_gateway/tests/features/step_definitions/cucumber.wire b/firmware/can_gateway/tests/features/step_definitions/cucumber.wire deleted file mode 100644 index da2da560..00000000 --- a/firmware/can_gateway/tests/features/step_definitions/cucumber.wire +++ /dev/null @@ -1,2 +0,0 @@ -host: localhost -port: 3902 From aa020b115d9512f21741a49d9a0f9838417f958f Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Mon, 21 May 2018 11:10:42 -0700 Subject: [PATCH 78/80] Power RX LED after boot Prior to this commit the RX LED did nothing during OSCC usage on leonardo boards. This commit powers the RX LED in the main loop so that it's known if the module is running. --- firmware/brake/kia_soul_ev_niro/src/main.cpp | 3 +++ firmware/steering/src/main.cpp | 3 +++ firmware/throttle/src/main.cpp | 3 +++ 3 files changed, 9 insertions(+) diff --git a/firmware/brake/kia_soul_ev_niro/src/main.cpp b/firmware/brake/kia_soul_ev_niro/src/main.cpp index da440eb8..ab792277 100644 --- a/firmware/brake/kia_soul_ev_niro/src/main.cpp +++ b/firmware/brake/kia_soul_ev_niro/src/main.cpp @@ -27,6 +27,9 @@ int main( void ) while( true ) { +#ifdef __AVR_ATmega32U4__ + RXLED1; +#endif check_for_incoming_message( ); check_for_faults( ); diff --git a/firmware/steering/src/main.cpp b/firmware/steering/src/main.cpp index 97cc6dec..6d5814c9 100644 --- a/firmware/steering/src/main.cpp +++ b/firmware/steering/src/main.cpp @@ -27,6 +27,9 @@ int main( void ) while( true ) { +#ifdef __AVR_ATmega32U4__ + RXLED1; +#endif check_for_incoming_message( ); check_for_faults( ); diff --git a/firmware/throttle/src/main.cpp b/firmware/throttle/src/main.cpp index 8f754fcf..9381fd13 100644 --- a/firmware/throttle/src/main.cpp +++ b/firmware/throttle/src/main.cpp @@ -28,6 +28,9 @@ int main( void ) while( true ) { +#ifdef __AVR_ATmega32U4__ + RXLED1; +#endif check_for_incoming_message( ); check_for_faults( ); From 8f0d547b451911a21e905c4741daca45ce761724 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Thu, 24 May 2018 09:53:46 -0700 Subject: [PATCH 79/80] Update Arduino CMake Prior to this commit oscc used a no longer supported Arduino CMake based toolchain. This commit fixes that by updating the toolchain to use the arduino-cmake files. --- .gitignore | 3 + .../common/toolchain/ArduinoToolchain.cmake | 101 +- .../common/toolchain/Platform/Arduino.cmake | 2279 +---------------- .../Core/BoardFlags/CompilerFlagsSetter.cmake | 36 + .../Core/BoardFlags/FlagsSetter.cmake | 103 + .../Core/BoardFlags/LinkerFlagsSetter.cmake | 8 + .../Platform/Core/BoardPropertiesReader.cmake | 89 + .../Core/Examples/ArduinoExampleFactory.cmake | 70 + .../ArduinoLibraryExampleFactory.cmake | 35 + .../Libraries/ArduinoLibraryFactory.cmake | 112 + .../BlacklistedLibrariesRemover.cmake | 34 + .../Core/Libraries/CoreLibraryFactory.cmake | 31 + .../Platform/Core/LibraryFinder.cmake | 128 + .../Core/Sketch/ArduinoSketchFactory.cmake | 50 + .../Sketch/ArduinoSketchToCppConverter.cmake | 109 + .../Platform/Core/SourceFinder.cmake | 36 + .../ArduinoBootloaderArgumentsBuilder.cmake | 47 + .../ArduinoBootloaderBurnTargetCreator.cmake | 82 + ...ArduinoBootloaderUploadTargetCreator.cmake | 48 + .../ArduinoFirmwareTargetCreator.cmake | 73 + .../ArduinoProgrammerArgumentsBuilder.cmake | 55 + .../ArduinoProgrammerBurnTargetCreator.cmake | 41 + .../Targets/ArduinoSerialTargetCreator.cmake | 17 + .../Targets/ArduinoUploadTargetCreator.cmake | 26 + .../Platform/Core/VariableValidator.cmake | 37 + .../Extras/CalculateFirmwareSize.cmake | 71 + .../Platform/Extras/DebugOptions.cmake | 40 + .../Extras/GeneratorSettingsLoader.cmake | 32 + .../toolchain/Platform/Extras/Macros.cmake | 58 + .../toolchain/Platform/Extras/Printer.cmake | 125 + .../Generation/ArduinoExampleGenerator.cmake | 63 + .../Generation/ArduinoFirmwareGenerator.cmake | 80 + .../ArduinoLibraryExampleGenerator.cmake | 65 + .../Generation/ArduinoLibraryGenerator.cmake | 52 + .../Generation/AvrFirmwareGenerator.cmake | 53 + .../Generation/AvrLibraryGenerator.cmake | 44 + .../DefineAdvancedVariables.cmake | 14 + .../Initialization/DetectVersion.cmake | 67 + .../Initialization/FindPrograms.cmake | 58 + .../Platform/Initialization/Initializer.cmake | 24 + .../LoadArduinoPlatformSettings.cmake | 134 + .../RegisterHardwarePlatform.cmake | 18 + .../RegisterSpecificHardwarePlatform.cmake | 96 + .../Platform/Initialization/SetDefaults.cmake | 6 + .../Initialization/SetupArduinoSettings.cmake | 9 + .../SetupCompilerSettings.cmake | 96 + .../SetupExampleCategories.cmake | 21 + .../SetupFirmwareSizeScript.cmake | 11 + .../SetupLibraryBlacklist.cmake | 3 + .../Platform/Initialization/TestSetup.cmake | 15 + firmware/common/toolchain/README.rst | 1346 ++++++++++ 51 files changed, 3988 insertions(+), 2263 deletions(-) create mode 100644 firmware/common/toolchain/Platform/Core/BoardFlags/CompilerFlagsSetter.cmake create mode 100644 firmware/common/toolchain/Platform/Core/BoardFlags/FlagsSetter.cmake create mode 100644 firmware/common/toolchain/Platform/Core/BoardFlags/LinkerFlagsSetter.cmake create mode 100644 firmware/common/toolchain/Platform/Core/BoardPropertiesReader.cmake create mode 100644 firmware/common/toolchain/Platform/Core/Examples/ArduinoExampleFactory.cmake create mode 100644 firmware/common/toolchain/Platform/Core/Examples/ArduinoLibraryExampleFactory.cmake create mode 100644 firmware/common/toolchain/Platform/Core/Libraries/ArduinoLibraryFactory.cmake create mode 100644 firmware/common/toolchain/Platform/Core/Libraries/BlacklistedLibrariesRemover.cmake create mode 100644 firmware/common/toolchain/Platform/Core/Libraries/CoreLibraryFactory.cmake create mode 100644 firmware/common/toolchain/Platform/Core/LibraryFinder.cmake create mode 100644 firmware/common/toolchain/Platform/Core/Sketch/ArduinoSketchFactory.cmake create mode 100644 firmware/common/toolchain/Platform/Core/Sketch/ArduinoSketchToCppConverter.cmake create mode 100644 firmware/common/toolchain/Platform/Core/SourceFinder.cmake create mode 100644 firmware/common/toolchain/Platform/Core/Targets/ArduinoBootloaderArgumentsBuilder.cmake create mode 100644 firmware/common/toolchain/Platform/Core/Targets/ArduinoBootloaderBurnTargetCreator.cmake create mode 100644 firmware/common/toolchain/Platform/Core/Targets/ArduinoBootloaderUploadTargetCreator.cmake create mode 100644 firmware/common/toolchain/Platform/Core/Targets/ArduinoFirmwareTargetCreator.cmake create mode 100644 firmware/common/toolchain/Platform/Core/Targets/ArduinoProgrammerArgumentsBuilder.cmake create mode 100644 firmware/common/toolchain/Platform/Core/Targets/ArduinoProgrammerBurnTargetCreator.cmake create mode 100644 firmware/common/toolchain/Platform/Core/Targets/ArduinoSerialTargetCreator.cmake create mode 100644 firmware/common/toolchain/Platform/Core/Targets/ArduinoUploadTargetCreator.cmake create mode 100644 firmware/common/toolchain/Platform/Core/VariableValidator.cmake create mode 100644 firmware/common/toolchain/Platform/Extras/CalculateFirmwareSize.cmake create mode 100644 firmware/common/toolchain/Platform/Extras/DebugOptions.cmake create mode 100644 firmware/common/toolchain/Platform/Extras/GeneratorSettingsLoader.cmake create mode 100644 firmware/common/toolchain/Platform/Extras/Macros.cmake create mode 100644 firmware/common/toolchain/Platform/Extras/Printer.cmake create mode 100644 firmware/common/toolchain/Platform/Generation/ArduinoExampleGenerator.cmake create mode 100644 firmware/common/toolchain/Platform/Generation/ArduinoFirmwareGenerator.cmake create mode 100644 firmware/common/toolchain/Platform/Generation/ArduinoLibraryExampleGenerator.cmake create mode 100644 firmware/common/toolchain/Platform/Generation/ArduinoLibraryGenerator.cmake create mode 100644 firmware/common/toolchain/Platform/Generation/AvrFirmwareGenerator.cmake create mode 100644 firmware/common/toolchain/Platform/Generation/AvrLibraryGenerator.cmake create mode 100644 firmware/common/toolchain/Platform/Initialization/DefineAdvancedVariables.cmake create mode 100644 firmware/common/toolchain/Platform/Initialization/DetectVersion.cmake create mode 100644 firmware/common/toolchain/Platform/Initialization/FindPrograms.cmake create mode 100644 firmware/common/toolchain/Platform/Initialization/Initializer.cmake create mode 100644 firmware/common/toolchain/Platform/Initialization/LoadArduinoPlatformSettings.cmake create mode 100644 firmware/common/toolchain/Platform/Initialization/RegisterHardwarePlatform.cmake create mode 100644 firmware/common/toolchain/Platform/Initialization/RegisterSpecificHardwarePlatform.cmake create mode 100644 firmware/common/toolchain/Platform/Initialization/SetDefaults.cmake create mode 100644 firmware/common/toolchain/Platform/Initialization/SetupArduinoSettings.cmake create mode 100644 firmware/common/toolchain/Platform/Initialization/SetupCompilerSettings.cmake create mode 100644 firmware/common/toolchain/Platform/Initialization/SetupExampleCategories.cmake create mode 100644 firmware/common/toolchain/Platform/Initialization/SetupFirmwareSizeScript.cmake create mode 100644 firmware/common/toolchain/Platform/Initialization/SetupLibraryBlacklist.cmake create mode 100644 firmware/common/toolchain/Platform/Initialization/TestSetup.cmake create mode 100644 firmware/common/toolchain/README.rst diff --git a/.gitignore b/.gitignore index ed0013cd..deabfcac 100644 --- a/.gitignore +++ b/.gitignore @@ -7,3 +7,6 @@ **/tests/**/Cargo.lock **/tests/**/common/ **/tests/**/target/ + +#cucumber port +cucumber.wire diff --git a/firmware/common/toolchain/ArduinoToolchain.cmake b/firmware/common/toolchain/ArduinoToolchain.cmake index f320898d..90c1949b 100644 --- a/firmware/common/toolchain/ArduinoToolchain.cmake +++ b/firmware/common/toolchain/ArduinoToolchain.cmake @@ -6,78 +6,89 @@ # License, v. 2.0. If a copy of the MPL was not distributed with this file, # You can obtain one at http://mozilla.org/MPL/2.0/. #=============================================================================# +if (_IS_TOOLCHAIN_PROCESSED) + return() +endif () +set(_IS_TOOLCHAIN_PROCESSED True) + set(CMAKE_SYSTEM_NAME Arduino) -set(CMAKE_C_COMPILER avr-gcc) +set(CMAKE_C_COMPILER avr-gcc) +set(CMAKE_ASM_COMPILER avr-gcc) set(CMAKE_CXX_COMPILER avr-g++) # Add current directory to CMake Module path automatically -if(EXISTS ${CMAKE_CURRENT_LIST_DIR}/Platform/Arduino.cmake) - set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_CURRENT_LIST_DIR}) -endif() +if (EXISTS ${CMAKE_CURRENT_LIST_DIR}/Platform/Arduino.cmake) + set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_CURRENT_LIST_DIR}) +endif () #=============================================================================# # System Paths # #=============================================================================# -if(UNIX) +if (UNIX) include(Platform/UnixPaths) - if(APPLE) + if (APPLE) list(APPEND CMAKE_SYSTEM_PREFIX_PATH ~/Applications - /Applications - /Developer/Applications - /sw # Fink - /opt/local) # MacPorts - endif() -elseif(WIN32) + /Applications + /Developer/Applications + /sw # Fink + /opt/local) # MacPorts + endif () +elseif (WIN32) include(Platform/WindowsPaths) -endif() - +endif () #=============================================================================# # Detect Arduino SDK # #=============================================================================# -if(NOT ARDUINO_SDK_PATH) +if ((NOT ARDUINO_SDK_PATH) AND (NOT DEFINED ENV{_ARDUINO_CMAKE_WORKAROUND_ARDUINO_SDK_PATH})) set(ARDUINO_PATHS) - foreach(DETECT_VERSION_MAJOR 1) - foreach(DETECT_VERSION_MINOR RANGE 5 0) + foreach (DETECT_VERSION_MAJOR 1) + foreach (DETECT_VERSION_MINOR RANGE 5 0) list(APPEND ARDUINO_PATHS arduino-${DETECT_VERSION_MAJOR}.${DETECT_VERSION_MINOR}) - foreach(DETECT_VERSION_PATCH RANGE 3 0) + foreach (DETECT_VERSION_PATCH RANGE 3 0) list(APPEND ARDUINO_PATHS arduino-${DETECT_VERSION_MAJOR}.${DETECT_VERSION_MINOR}.${DETECT_VERSION_PATCH}) - endforeach() - endforeach() - endforeach() + endforeach () + endforeach () + endforeach () - foreach(VERSION RANGE 23 19) + foreach (VERSION RANGE 23 19) list(APPEND ARDUINO_PATHS arduino-00${VERSION}) - endforeach() + endforeach () - if(UNIX) - file(GLOB SDK_PATH_HINTS /usr/share/arduino* - /opt/local/arduino* - /opt/arduino* - /usr/local/share/arduino*) - elseif(WIN32) - set(SDK_PATH_HINTS "C:\\Program Files\\Arduino" - "C:\\Program Files (x86)\\Arduino" - ) - endif() + if (UNIX) + file(GLOB SDK_PATH_HINTS + /usr/share/arduino* + /opt/local/arduino* + /opt/arduino* + /usr/local/share/arduino*) + elseif (WIN32) + set(SDK_PATH_HINTS + "C:\\Program Files\\Arduino" + "C:\\Program Files (x86)\\Arduino") + endif () list(SORT SDK_PATH_HINTS) list(REVERSE SDK_PATH_HINTS) -endif() -find_path(ARDUINO_SDK_PATH - NAMES lib/version.txt - PATH_SUFFIXES share/arduino - Arduino.app/Contents/Resources/Java/ - ${ARDUINO_PATHS} - HINTS ${SDK_PATH_HINTS} - DOC "Arduino SDK path.") + if (DEFINED ENV{ARDUINO_SDK_PATH}) + list(APPEND SDK_PATH_HINTS $ENV{ARDUINO_SDK_PATH}) + endif () + + find_path(ARDUINO_SDK_PATH + NAMES lib/version.txt + PATH_SUFFIXES share/arduino Arduino.app/Contents/Resources/Java/ Arduino.app/Contents/Java/ ${ARDUINO_PATHS} + HINTS ${SDK_PATH_HINTS} + DOC "Arduino SDK base directory") +elseif ((NOT ARDUINO_SDK_PATH) AND (DEFINED ENV{_ARDUINO_CMAKE_WORKAROUND_ARDUINO_SDK_PATH})) + set(ARDUINO_SDK_PATH "$ENV{_ARDUINO_CMAKE_WORKAROUND_ARDUINO_SDK_PATH}") +endif () + +if (ARDUINO_SDK_PATH) + set(ENV{_ARDUINO_CMAKE_WORKAROUND_ARDUINO_SDK_PATH} "${ARDUINO_SDK_PATH}") -if(ARDUINO_SDK_PATH) list(APPEND CMAKE_SYSTEM_PREFIX_PATH ${ARDUINO_SDK_PATH}/hardware/tools/avr) list(APPEND CMAKE_SYSTEM_PREFIX_PATH ${ARDUINO_SDK_PATH}/hardware/tools/avr/utils) -else() +else () message(FATAL_ERROR "Could not find Arduino SDK (set ARDUINO_SDK_PATH)!") -endif() - +endif () diff --git a/firmware/common/toolchain/Platform/Arduino.cmake b/firmware/common/toolchain/Platform/Arduino.cmake index 042a3c1a..5cec4cea 100644 --- a/firmware/common/toolchain/Platform/Arduino.cmake +++ b/firmware/common/toolchain/Platform/Arduino.cmake @@ -1,2232 +1,75 @@ #=============================================================================# -# generate_arduino_firmware(name -# [BOARD board_id] -# [SKETCH sketch_path | -# SRCS src1 src2 ... srcN] -# [HDRS hdr1 hdr2 ... hdrN] -# [LIBS lib1 lib2 ... libN] -# [PORT port] -# [SERIAL serial_cmd] -# [PROGRAMMER programmer_id] -# [AFLAGS flags] -# [NO_AUTOLIBS] -# [MANUAL]) -# -#=============================================================================# -# -# generaters firmware and libraries for Arduino devices -# -# The arguments are as follows: -# -# name # The name of the firmware target [REQUIRED] -# BOARD # Board name (such as uno, mega2560, ...) [REQUIRED] -# SKETCH # Arduino sketch [must have SRCS or SKETCH] -# SRCS # Sources [must have SRCS or SKETCH] -# HDRS # Headers -# LIBS # Libraries to link -# ARDLIBS # Arduino libraries to link (Wire, Servo, SPI, etc) -# PORT # Serial port (enables upload support) -# SERIAL # Serial command for serial target -# PROGRAMMER # Programmer id (enables programmer support) -# AFLAGS # Avrdude flags for target -# NO_AUTOLIBS # Disables Arduino library detection -# MANUAL # (Advanced) Only use AVR Libc/Includes -# -# Here is a short example for a target named test: -# -# generate_arduino_firmware( -# NAME test -# SRCS test.cpp -# test2.cpp -# HDRS test.h test2.h -# BOARD uno) -# -# Alternatively you can specify the option by variables: -# -# set(test_SRCS test.cpp test2.cpp) -# set(test_HDRS test.h test2.h -# set(test_BOARD uno) -# -# generate_arduino_firmware(test) -# -# All variables need to be prefixed with the target name (${TARGET_NAME}_${OPTION}). -# -#=============================================================================# -# generate_avr_firmware(name -# [BOARD board_id] -# SRCS src1 src2 ... srcN] -# [HDRS hdr1 hdr2 ... hdrN] -# [LIBS lib1 lib2 ... libN] -# [PORT port] -# [SERIAL serial_cmd] -# [PROGRAMMER programmer_id] -# [AFLAGS flags]) -#=============================================================================# -# -# generaters firmware and libraries for AVR devices -# it simply calls generate_arduino_firmware() with NO_AUTOLIBS and MANUAL -# -# The arguments are as follows: -# -# name # The name of the firmware target [REQUIRED] -# BOARD # Board name (such as uno, mega2560, ...) [REQUIRED] -# SRCS # Sources [REQUIRED] -# HDRS # Headers -# LIBS # Libraries to link -# PORT # Serial port (enables upload support) -# SERIAL # Serial command for serial target -# PROGRAMMER # Programmer id (enables programmer support) -# AFLAGS # Avrdude flags for target -# -# Here is a short example for a target named test: -# -# generate_avr_firmware( -# NAME test -# SRCS test.cpp -# test2.cpp -# HDRS test.h test2.h -# BOARD uno) -# -# Alternatively you can specify the option by variables: -# -# set(test_SRCS test.cpp test2.cpp) -# set(test_HDRS test.h test2.h -# set(test_BOARD uno) -# -# generate_avr_firmware(test) -# -# All variables need to be prefixed with the target name (${TARGET_NAME}_${OPTION}). -# -#=============================================================================# -# generate_arduino_library(name -# [BOARD board_id] -# [SRCS src1 src2 ... srcN] -# [HDRS hdr1 hdr2 ... hdrN] -# [LIBS lib1 lib2 ... libN] -# [NO_AUTOLIBS] -# [MANUAL]) -#=============================================================================# -# generaters firmware and libraries for Arduino devices -# -# The arguments are as follows: -# -# name # The name of the firmware target [REQUIRED] -# BOARD # Board name (such as uno, mega2560, ...) [REQUIRED] -# SRCS # Sources [REQUIRED] -# HDRS # Headers -# LIBS # Libraries to link -# NO_AUTOLIBS # Disables Arduino library detection -# MANUAL # (Advanced) Only use AVR Libc/Includes -# -# Here is a short example for a target named test: -# -# generate_arduino_library( -# NAME test -# SRCS test.cpp -# test2.cpp -# HDRS test.h test2.h -# BOARD uno) -# -# Alternatively you can specify the option by variables: -# -# set(test_SRCS test.cpp test2.cpp) -# set(test_HDRS test.h test2.h -# set(test_BOARD uno) -# -# generate_arduino_library(test) -# -# All variables need to be prefixed with the target name (${TARGET_NAME}_${OPTION}). -# -#=============================================================================# -# generate_avr_library(name -# [BOARD board_id] -# [SRCS src1 src2 ... srcN] -# [HDRS hdr1 hdr2 ... hdrN] -# [LIBS lib1 lib2 ... libN]) -#=============================================================================# -# generaters firmware and libraries for AVR devices -# it simply calls generate_arduino_library() with NO_AUTOLIBS and MANUAL -# -# The arguments are as follows: -# -# name # The name of the firmware target [REQUIRED] -# BOARD # Board name (such as uno, mega2560, ...) [REQUIRED] -# SRCS # Sources [REQUIRED] -# HDRS # Headers -# LIBS # Libraries to link -# -# Here is a short example for a target named test: -# -# generate_avr_library( -# NAME test -# SRCS test.cpp -# test2.cpp -# HDRS test.h test2.h -# BOARD uno) -# -# Alternatively you can specify the option by variables: -# -# set(test_SRCS test.cpp test2.cpp) -# set(test_HDRS test.h test2.h -# set(test_BOARD uno) -# -# generate_avr_library(test) -# -# All variables need to be prefixed with the target name (${TARGET_NAME}_${OPTION}). -# -#=============================================================================# -# generate_arduino_example(name -# LIBRARY library_name -# EXAMPLE example_name -# [BOARD board_id] -# [PORT port] -# [SERIAL serial command] -# [PORGRAMMER programmer_id] -# [AFLAGS avrdude_flags]) -#=============================================================================# -# -# name - The name of the library example [REQUIRED] -# LIBRARY - Library name [REQUIRED] -# EXAMPLE - Example name [REQUIRED] -# BOARD - Board ID -# PORT - Serial port [optional] -# SERIAL - Serial command [optional] -# PROGRAMMER - Programmer id (enables programmer support) -# AFLAGS - Avrdude flags for target -# -# Creates a example from the specified library. -# -# -#=============================================================================# -# print_board_list() -#=============================================================================# -# -# Print list of detected Arduino Boards. -# -#=============================================================================# -# print_programmer_list() -#=============================================================================# -# -# Print list of detected Programmers. -# -#=============================================================================# -# print_programmer_settings(PROGRAMMER) -#=============================================================================# -# -# PROGRAMMER - programmer id -# -# Print the detected Programmer settings. -# -#=============================================================================# -# print_board_settings(ARDUINO_BOARD) -#=============================================================================# -# -# ARDUINO_BOARD - Board id -# -# Print the detected Arduino board settings. -# -#=============================================================================# -# register_hardware_platform(HARDWARE_PLATFORM_PATH) -#=============================================================================# -# -# HARDWARE_PLATFORM_PATH - Hardware platform path -# -# Registers a Hardware Platform path. -# See: http://code.google.com/p/arduino/wiki/Platforms -# -# This enables you to register new types of hardware platforms such as the -# Sagnuino, without having to copy the files into your Arduion SDK. -# -# A Hardware Platform is a directory containing the following: -# -# HARDWARE_PLATFORM_PATH/ -# |-- bootloaders/ -# |-- cores/ -# |-- variants/ -# |-- boards.txt -# `-- programmers.txt -# -# The board.txt describes the target boards and bootloaders. While -# programmers.txt the programmer defintions. -# -# A good example of a Hardware Platform is in the Arduino SDK: -# -# ${ARDUINO_SDK_PATH}/hardware/arduino/ -# -#=============================================================================# -# Configuration Options -#=============================================================================# -# -# ARDUINO_SDK_PATH - Arduino SDK Path -# ARDUINO_AVRDUDE_PROGRAM - Full path to avrdude programmer -# ARDUINO_AVRDUDE_CONFIG_PATH - Full path to avrdude configuration file -# -# ARDUINO_C_FLAGS - C compiler flags -# ARDUINO_CXX_FLAGS - C++ compiler flags -# ARDUINO_LINKER_FLAGS - Linker flags -# -# ARDUINO_DEFAULT_BOARD - Default Arduino Board ID when not specified. -# ARDUINO_DEFAULT_PORT - Default Arduino port when not specified. -# ARDUINO_DEFAULT_SERIAL - Default Arduino Serial command when not specified. -# ARDUINO_DEFAULT_PROGRAMMER - Default Arduino Programmer ID when not specified. -# -# -# ARDUINO_FOUND - Set to True when the Arduino SDK is detected and configured. -# ARDUINO_SDK_VERSION - Set to the version of the detected Arduino SDK (ex: 1.0) - -#=============================================================================# -# Author: Tomasz Bogdal (QueezyTheGreat) -# Home: https://github.com/queezythegreat/arduino-cmake +# Original Author: Tomasz Bogdal (QueezyTheGreat) +# Current Author: Timor Gruber (MrPointer) +# Original Home: https://github.com/queezythegreat/arduino-cmake +# Current Home: https://github.com/arduino-cmake/arduino-cmake # # This Source Code Form is subject to the terms of the Mozilla Public # License, v. 2.0. If a copy of the MPL was not distributed with this file, # You can obtain one at http://mozilla.org/MPL/2.0/. #=============================================================================# -cmake_minimum_required(VERSION 2.8.5) -include(CMakeParseArguments) - - - - - - -#=============================================================================# -# User Functions -#=============================================================================# - -#=============================================================================# -# [PUBLIC/USER] -# -# print_board_list() -# -# see documentation at top -#=============================================================================# -function(PRINT_BOARD_LIST) - foreach(PLATFORM ${ARDUINO_PLATFORMS}) - if(${PLATFORM}_BOARDS) - message(STATUS "${PLATFORM} Boards:") - print_list(${PLATFORM}_BOARDS) - message(STATUS "") - endif() - endforeach() -endfunction() - -#=============================================================================# -# [PUBLIC/USER] -# -# print_programmer_list() -# -# see documentation at top -#=============================================================================# -function(PRINT_PROGRAMMER_LIST) - foreach(PLATFORM ${ARDUINO_PLATFORMS}) - if(${PLATFORM}_PROGRAMMERS) - message(STATUS "${PLATFORM} Programmers:") - print_list(${PLATFORM}_PROGRAMMERS) - endif() - message(STATUS "") - endforeach() -endfunction() - -#=============================================================================# -# [PUBLIC/USER] -# -# print_programmer_settings(PROGRAMMER) -# -# see documentation at top -#=============================================================================# -function(PRINT_PROGRAMMER_SETTINGS PROGRAMMER) - if(${PROGRAMMER}.SETTINGS) - message(STATUS "Programmer ${PROGRAMMER} Settings:") - print_settings(${PROGRAMMER}) - endif() -endfunction() - -# [PUBLIC/USER] -# -# print_board_settings(ARDUINO_BOARD) -# -# see documentation at top -function(PRINT_BOARD_SETTINGS ARDUINO_BOARD) - if(${ARDUINO_BOARD}.SETTINGS) - message(STATUS "Arduino ${ARDUINO_BOARD} Board:") - print_settings(${ARDUINO_BOARD}) - endif() -endfunction() - -#=============================================================================# -# [PUBLIC/USER] -# see documentation at top -#=============================================================================# -function(GENERATE_ARDUINO_LIBRARY INPUT_NAME) - message(STATUS "Generating ${INPUT_NAME}") - parse_generator_arguments(${INPUT_NAME} INPUT - "NO_AUTOLIBS;MANUAL" # Options - "BOARD" # One Value Keywords - "SRCS;HDRS;LIBS" # Multi Value Keywords - ${ARGN}) - - if(NOT INPUT_BOARD) - set(INPUT_BOARD ${ARDUINO_DEFAULT_BOARD}) - endif() - if(NOT INPUT_MANUAL) - set(INPUT_MANUAL FALSE) - endif() - required_variables(VARS INPUT_SRCS INPUT_BOARD MSG "must define for target ${INPUT_NAME}") - - set(ALL_LIBS) - set(ALL_SRCS ${INPUT_SRCS} ${INPUT_HDRS}) - - if(NOT INPUT_MANUAL) - setup_arduino_core(CORE_LIB ${INPUT_BOARD}) - endif() - - find_arduino_libraries(TARGET_LIBS "${ALL_SRCS}" "") - set(LIB_DEP_INCLUDES) - foreach(LIB_DEP ${TARGET_LIBS}) - set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} -I\"${LIB_DEP}\"") - endforeach() - - if(NOT ${INPUT_NO_AUTOLIBS}) - setup_arduino_libraries(ALL_LIBS ${INPUT_BOARD} "${ALL_SRCS}" "" "${LIB_DEP_INCLUDES}" "") - endif() - - list(APPEND ALL_LIBS ${CORE_LIB} ${INPUT_LIBS}) - - add_library(${INPUT_NAME} ${ALL_SRCS}) - - get_arduino_flags(ARDUINO_COMPILE_FLAGS ARDUINO_LINK_FLAGS ${INPUT_BOARD} ${INPUT_MANUAL}) - - set_target_properties(${INPUT_NAME} PROPERTIES - COMPILE_FLAGS "${ARDUINO_COMPILE_FLAGS} ${COMPILE_FLAGS} ${LIB_DEP_INCLUDES}" - LINK_FLAGS "${ARDUINO_LINK_FLAGS} ${LINK_FLAGS}") - - target_link_libraries(${INPUT_NAME} ${ALL_LIBS} "-lc -lm") -endfunction() - -#=============================================================================# -# [PUBLIC/USER] -# see documentation at top -#=============================================================================# -function(GENERATE_AVR_LIBRARY INPUT_NAME) - message(STATUS "Generating ${INPUT_NAME}") - parse_generator_arguments(${INPUT_NAME} INPUT - "NO_AUTOLIBS;MANUAL" # Options - "BOARD" # One Value Keywords - "SRCS;HDRS;LIBS" # Multi Value Keywords - ${ARGN}) - - if(NOT INPUT_BOARD) - set(INPUT_BOARD ${ARDUINO_DEFAULT_BOARD}) - endif() - - required_variables(VARS INPUT_SRCS INPUT_BOARD MSG "must define for target ${INPUT_NAME}") - - if(INPUT_HDRS) - set( INPUT_HDRS "SRCS ${INPUT_HDRS}" ) - endif() - if(INPUT_LIBS) - set( INPUT_LIBS "LIBS ${INPUT_LIBS}" ) - endif() - if(INPUT_HDRS) - list(INSERT INPUT_HDRS 0 "HDRS") - endif() - if(INPUT_LIBS) - list(INSERT INPUT_LIBS 0 "LIBS") - endif() - - - generate_arduino_library( ${INPUT_NAME} - NO_AUTOLIBS - MANUAL - BOARD ${INPUT_BOARD} - SRCS ${INPUT_SRCS} - ${INPUT_HDRS} - ${INPUT_LIBS} ) - -endfunction() - -#=============================================================================# -# [PUBLIC/USER] -# see documentation at top -#=============================================================================# -function(GENERATE_ARDUINO_FIRMWARE INPUT_NAME) - message(STATUS "Generating ${INPUT_NAME}") - parse_generator_arguments(${INPUT_NAME} INPUT - "NO_AUTOLIBS;MANUAL" # Options - "BOARD;PORT;SKETCH;PROGRAMMER" # One Value Keywords - "SERIAL;SRCS;HDRS;LIBS;ARDLIBS;AFLAGS" # Multi Value Keywords - ${ARGN}) - - if(NOT INPUT_BOARD) - set(INPUT_BOARD ${ARDUINO_DEFAULT_BOARD}) - endif() - if(NOT INPUT_PORT) - set(INPUT_PORT ${ARDUINO_DEFAULT_PORT}) - endif() - if(NOT INPUT_SERIAL) - set(INPUT_SERIAL ${ARDUINO_DEFAULT_SERIAL}) - endif() - if(NOT INPUT_PROGRAMMER) - set(INPUT_PROGRAMMER ${ARDUINO_DEFAULT_PROGRAMMER}) - endif() - if(NOT INPUT_MANUAL) - set(INPUT_MANUAL FALSE) - endif() - required_variables(VARS INPUT_BOARD MSG "must define for target ${INPUT_NAME}") - - set(ALL_LIBS) - set(ALL_SRCS ${INPUT_SRCS} ${INPUT_HDRS}) - set(LIB_DEP_INCLUDES) - - if(NOT INPUT_MANUAL) - setup_arduino_core(CORE_LIB ${INPUT_BOARD}) - endif() - - if(NOT "${INPUT_SKETCH}" STREQUAL "") - get_filename_component(INPUT_SKETCH "${INPUT_SKETCH}" ABSOLUTE) - setup_arduino_sketch(${INPUT_NAME} ${INPUT_SKETCH} ALL_SRCS) - if (IS_DIRECTORY "${INPUT_SKETCH}") - set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} -I\"${INPUT_SKETCH}\"") - else() - get_filename_component(INPUT_SKETCH_PATH "${INPUT_SKETCH}" PATH) - set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} -I\"${INPUT_SKETCH_PATH}\"") - endif() - endif() - - required_variables(VARS ALL_SRCS MSG "must define SRCS or SKETCH for target ${INPUT_NAME}") - - find_arduino_libraries(TARGET_LIBS "${ALL_SRCS}" "${INPUT_ARDLIBS}") - foreach(LIB_DEP ${TARGET_LIBS}) - arduino_debug_msg("Arduino Library: ${LIB_DEP}") - set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} -I\"${LIB_DEP}\"") - endforeach() - - if(NOT INPUT_NO_AUTOLIBS) - setup_arduino_libraries(ALL_LIBS ${INPUT_BOARD} "${ALL_SRCS}" "${INPUT_ARDLIBS}" "${LIB_DEP_INCLUDES}" "") - foreach(LIB_INCLUDES ${ALL_LIBS_INCLUDES}) - arduino_debug_msg("Arduino Library Includes: ${LIB_INCLUDES}") - set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} ${LIB_INCLUDES}") - endforeach() - endif() - - list(APPEND ALL_LIBS ${CORE_LIB} ${INPUT_LIBS}) - - setup_arduino_target(${INPUT_NAME} ${INPUT_BOARD} "${ALL_SRCS}" "${ALL_LIBS}" "${LIB_DEP_INCLUDES}" "" "${INPUT_MANUAL}") - - if(INPUT_PORT) - setup_arduino_upload(${INPUT_BOARD} ${INPUT_NAME} ${INPUT_PORT} "${INPUT_PROGRAMMER}" "${INPUT_AFLAGS}") - endif() - - if(INPUT_SERIAL) - setup_serial_target(${INPUT_NAME} "${INPUT_SERIAL}" "${INPUT_PORT}") - endif() - -endfunction() - -#=============================================================================# -# [PUBLIC/USER] -# see documentation at top -#=============================================================================# -function(GENERATE_AVR_FIRMWARE INPUT_NAME) - # TODO: This is not optimal!!!! - message(STATUS "Generating ${INPUT_NAME}") - parse_generator_arguments(${INPUT_NAME} INPUT - "NO_AUTOLIBS;MANUAL" # Options - "BOARD;PORT;PROGRAMMER" # One Value Keywords - "SERIAL;SRCS;HDRS;LIBS;AFLAGS" # Multi Value Keywords - ${ARGN}) - - if(NOT INPUT_BOARD) - set(INPUT_BOARD ${ARDUINO_DEFAULT_BOARD}) - endif() - if(NOT INPUT_PORT) - set(INPUT_PORT ${ARDUINO_DEFAULT_PORT}) - endif() - if(NOT INPUT_SERIAL) - set(INPUT_SERIAL ${ARDUINO_DEFAULT_SERIAL}) - endif() - if(NOT INPUT_PROGRAMMER) - set(INPUT_PROGRAMMER ${ARDUINO_DEFAULT_PROGRAMMER}) - endif() - - required_variables(VARS INPUT_BOARD INPUT_SRCS MSG "must define for target ${INPUT_NAME}") - - if(INPUT_HDRS) - list(INSERT INPUT_HDRS 0 "HDRS") - endif() - if(INPUT_LIBS) - list(INSERT INPUT_LIBS 0 "LIBS") - endif() - if(INPUT_AFLAGS) - list(INSERT INPUT_AFLAGS 0 "AFLAGS") - endif() - - generate_arduino_firmware( ${INPUT_NAME} - NO_AUTOLIBS - MANUAL - BOARD ${INPUT_BOARD} - PORT ${INPUT_PORT} - PROGRAMMER ${INPUT_PROGRAMMER} - SERIAL ${INPUT_SERIAL} - SRCS ${INPUT_SRCS} - ${INPUT_HDRS} - ${INPUT_LIBS} - ${INPUT_AFLAGS} ) - -endfunction() - -#=============================================================================# -# [PUBLIC/USER] -# see documentation at top -#=============================================================================# -function(GENERATE_ARDUINO_EXAMPLE INPUT_NAME) - parse_generator_arguments(${INPUT_NAME} INPUT - "" # Options - "LIBRARY;EXAMPLE;BOARD;PORT;PROGRAMMER" # One Value Keywords - "SERIAL;AFLAGS" # Multi Value Keywords - ${ARGN}) - - - if(NOT INPUT_BOARD) - set(INPUT_BOARD ${ARDUINO_DEFAULT_BOARD}) - endif() - if(NOT INPUT_PORT) - set(INPUT_PORT ${ARDUINO_DEFAULT_PORT}) - endif() - if(NOT INPUT_SERIAL) - set(INPUT_SERIAL ${ARDUINO_DEFAULT_SERIAL}) - endif() - if(NOT INPUT_PROGRAMMER) - set(INPUT_PROGRAMMER ${ARDUINO_DEFAULT_PROGRAMMER}) - endif() - required_variables(VARS INPUT_LIBRARY INPUT_EXAMPLE INPUT_BOARD - MSG "must define for target ${INPUT_NAME}") - - message(STATUS "Generating ${INPUT_NAME}") - - set(ALL_LIBS) - set(ALL_SRCS) - - setup_arduino_core(CORE_LIB ${INPUT_BOARD}) - - setup_arduino_example("${INPUT_NAME}" "${INPUT_LIBRARY}" "${INPUT_EXAMPLE}" ALL_SRCS) - - if(NOT ALL_SRCS) - message(FATAL_ERROR "Missing sources for example, aborting!") - endif() - - find_arduino_libraries(TARGET_LIBS "${ALL_SRCS}" "") - set(LIB_DEP_INCLUDES) - foreach(LIB_DEP ${TARGET_LIBS}) - set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} -I\"${LIB_DEP}\"") - endforeach() - - setup_arduino_libraries(ALL_LIBS ${INPUT_BOARD} "${ALL_SRCS}" "" "${LIB_DEP_INCLUDES}" "") - - list(APPEND ALL_LIBS ${CORE_LIB} ${INPUT_LIBS}) - - setup_arduino_target(${INPUT_NAME} ${INPUT_BOARD} "${ALL_SRCS}" "${ALL_LIBS}" "${LIB_DEP_INCLUDES}" "" FALSE) - - if(INPUT_PORT) - setup_arduino_upload(${INPUT_BOARD} ${INPUT_NAME} ${INPUT_PORT} "${INPUT_PROGRAMMER}" "${INPUT_AFLAGS}") - endif() - - if(INPUT_SERIAL) - setup_serial_target(${INPUT_NAME} "${INPUT_SERIAL}" "${INPUT_PORT}") - endif() -endfunction() - -#=============================================================================# -# [PUBLIC/USER] -# see documentation at top -#=============================================================================# -function(REGISTER_HARDWARE_PLATFORM PLATFORM_PATH) - string(REGEX REPLACE "/$" "" PLATFORM_PATH ${PLATFORM_PATH}) - GET_FILENAME_COMPONENT(PLATFORM ${PLATFORM_PATH} NAME) - - if(PLATFORM) - string(TOUPPER ${PLATFORM} PLATFORM) - list(FIND ARDUINO_PLATFORMS ${PLATFORM} platform_exists) - - if (platform_exists EQUAL -1) - set(${PLATFORM}_PLATFORM_PATH ${PLATFORM_PATH} CACHE INTERNAL "The path to ${PLATFORM}") - set(ARDUINO_PLATFORMS ${ARDUINO_PLATFORMS} ${PLATFORM} CACHE INTERNAL "A list of registered platforms") - - find_file(${PLATFORM}_CORES_PATH - NAMES cores - PATHS ${PLATFORM_PATH} - DOC "Path to directory containing the Arduino core sources.") - - find_file(${PLATFORM}_VARIANTS_PATH - NAMES variants - PATHS ${PLATFORM_PATH} - DOC "Path to directory containing the Arduino variant sources.") - - find_file(${PLATFORM}_BOOTLOADERS_PATH - NAMES bootloaders - PATHS ${PLATFORM_PATH} - DOC "Path to directory containing the Arduino bootloader images and sources.") - - find_file(${PLATFORM}_PROGRAMMERS_PATH - NAMES programmers.txt - PATHS ${PLATFORM_PATH} - DOC "Path to Arduino programmers definition file.") - - find_file(${PLATFORM}_BOARDS_PATH - NAMES boards.txt - PATHS ${PLATFORM_PATH} - DOC "Path to Arduino boards definition file.") - - if(${PLATFORM}_BOARDS_PATH) - load_arduino_style_settings(${PLATFORM}_BOARDS "${PLATFORM_PATH}/boards.txt") - endif() - - if(${PLATFORM}_PROGRAMMERS_PATH) - load_arduino_style_settings(${PLATFORM}_PROGRAMMERS "${ARDUINO_PROGRAMMERS_PATH}") - endif() - - if(${PLATFORM}_VARIANTS_PATH) - file(GLOB sub-dir ${${PLATFORM}_VARIANTS_PATH}/*) - foreach(dir ${sub-dir}) - if(IS_DIRECTORY ${dir}) - get_filename_component(variant ${dir} NAME) - set(VARIANTS ${VARIANTS} ${variant} CACHE INTERNAL "A list of registered variant boards") - set(${variant}.path ${dir} CACHE INTERNAL "The path to the variant ${variant}") - endif() - endforeach() - endif() - - if(${PLATFORM}_CORES_PATH) - file(GLOB sub-dir ${${PLATFORM}_CORES_PATH}/*) - foreach(dir ${sub-dir}) - if(IS_DIRECTORY ${dir}) - get_filename_component(core ${dir} NAME) - set(CORES ${CORES} ${core} CACHE INTERNAL "A list of registered cores") - set(${core}.path ${dir} CACHE INTERNAL "The path to the core ${core}") - endif() - endforeach() - endif() - endif() - endif() - -endfunction() - -#=============================================================================# -# Internal Functions -#=============================================================================# - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# parse_generator_arguments(TARGET_NAME PREFIX OPTIONS ARGS MULTI_ARGS [ARG1 ARG2 .. ARGN]) -# -# PREFIX - Parsed options prefix -# OPTIONS - List of options -# ARGS - List of one value keyword arguments -# MULTI_ARGS - List of multi value keyword arguments -# [ARG1 ARG2 .. ARGN] - command arguments [optional] -# -# Parses generator options from either variables or command arguments -# -#=============================================================================# -macro(PARSE_GENERATOR_ARGUMENTS TARGET_NAME PREFIX OPTIONS ARGS MULTI_ARGS) - cmake_parse_arguments(${PREFIX} "${OPTIONS}" "${ARGS}" "${MULTI_ARGS}" ${ARGN}) - error_for_unparsed(${PREFIX}) - load_generator_settings(${TARGET_NAME} ${PREFIX} ${OPTIONS} ${ARGS} ${MULTI_ARGS}) -endmacro() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# load_generator_settings(TARGET_NAME PREFIX [SUFFIX_1 SUFFIX_2 .. SUFFIX_N]) -# -# TARGET_NAME - The base name of the user settings -# PREFIX - The prefix name used for generator settings -# SUFFIX_XX - List of suffixes to load -# -# Loads a list of user settings into the generators scope. User settings have -# the following syntax: -# -# ${BASE_NAME}${SUFFIX} -# -# The BASE_NAME is the target name and the suffix is a specific generator settings. -# -# For every user setting found a generator setting is created of the follwoing fromat: -# -# ${PREFIX}${SUFFIX} -# -# The purpose of loading the settings into the generator is to not modify user settings -# and to have a generic naming of the settings within the generator. -# -#=============================================================================# -function(LOAD_GENERATOR_SETTINGS TARGET_NAME PREFIX) - foreach(GEN_SUFFIX ${ARGN}) - if(${TARGET_NAME}_${GEN_SUFFIX} AND NOT ${PREFIX}_${GEN_SUFFIX}) - set(${PREFIX}_${GEN_SUFFIX} ${${TARGET_NAME}_${GEN_SUFFIX}} PARENT_SCOPE) - endif() - endforeach() -endfunction() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# get_arduino_flags(COMPILE_FLAGS LINK_FLAGS BOARD_ID MANUAL) -# -# COMPILE_FLAGS_VAR -Variable holding compiler flags -# LINK_FLAGS_VAR - Variable holding linker flags -# BOARD_ID - The board id name -# MANUAL - (Advanced) Only use AVR Libc/Includes -# -# Configures the the build settings for the specified Arduino Board. -# -#=============================================================================# -function(get_arduino_flags COMPILE_FLAGS_VAR LINK_FLAGS_VAR BOARD_ID MANUAL) - - set(BOARD_CORE ${${BOARD_ID}.build.core}) - if(BOARD_CORE) - if(ARDUINO_SDK_VERSION MATCHES "([0-9]+)[.]([0-9]+)") - string(REPLACE "." "" ARDUINO_VERSION_DEFINE "${ARDUINO_SDK_VERSION}") # Normalize version (remove all periods) - set(ARDUINO_VERSION_DEFINE "") - if(CMAKE_MATCH_1 GREATER 0) - set(ARDUINO_VERSION_DEFINE "${CMAKE_MATCH_1}") - endif() - if(CMAKE_MATCH_2 GREATER 10) - set(ARDUINO_VERSION_DEFINE "${ARDUINO_VERSION_DEFINE}${CMAKE_MATCH_2}") - else() - set(ARDUINO_VERSION_DEFINE "${ARDUINO_VERSION_DEFINE}0${CMAKE_MATCH_2}") - endif() - else() - message("Invalid Arduino SDK Version (${ARDUINO_SDK_VERSION})") - endif() - - # output - set(COMPILE_FLAGS "-DF_CPU=${${BOARD_ID}.build.f_cpu} -DARDUINO=${ARDUINO_VERSION_DEFINE} -mmcu=${${BOARD_ID}.build.mcu}") - if(DEFINED ${BOARD_ID}.build.vid) - set(COMPILE_FLAGS "${COMPILE_FLAGS} -DUSB_VID=${${BOARD_ID}.build.vid}") - endif() - if(DEFINED ${BOARD_ID}.build.pid) - set(COMPILE_FLAGS "${COMPILE_FLAGS} -DUSB_PID=${${BOARD_ID}.build.pid}") - endif() - if(NOT MANUAL) - set(COMPILE_FLAGS "${COMPILE_FLAGS} -I\"${${BOARD_CORE}.path}\" -I\"${ARDUINO_LIBRARIES_PATH}\"") - endif() - set(LINK_FLAGS "-mmcu=${${BOARD_ID}.build.mcu}") - if(ARDUINO_SDK_VERSION VERSION_GREATER 1.0 OR ARDUINO_SDK_VERSION VERSION_EQUAL 1.0) - if(NOT MANUAL) - set(PIN_HEADER ${${${BOARD_ID}.build.variant}.path}) - if(PIN_HEADER) - set(COMPILE_FLAGS "${COMPILE_FLAGS} -I\"${PIN_HEADER}\"") - endif() - endif() - endif() - - # output - set(${COMPILE_FLAGS_VAR} "${COMPILE_FLAGS}" PARENT_SCOPE) - set(${LINK_FLAGS_VAR} "${LINK_FLAGS}" PARENT_SCOPE) - - else() - message(FATAL_ERROR "Invalid Arduino board ID (${BOARD_ID}), aborting.") - endif() -endfunction() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# setup_arduino_core(VAR_NAME BOARD_ID) -# -# VAR_NAME - Variable name that will hold the generated library name -# BOARD_ID - Arduino board id -# -# Creates the Arduino Core library for the specified board, -# each board gets it's own version of the library. -# -#=============================================================================# -function(setup_arduino_core VAR_NAME BOARD_ID) - set(CORE_LIB_NAME ${BOARD_ID}_CORE) - set(BOARD_CORE ${${BOARD_ID}.build.core}) - if(BOARD_CORE) - if(NOT TARGET ${CORE_LIB_NAME}) - set(BOARD_CORE_PATH ${${BOARD_CORE}.path}) - find_sources(CORE_SRCS ${BOARD_CORE_PATH} True) - # Debian/Ubuntu fix - list(REMOVE_ITEM CORE_SRCS "${BOARD_CORE_PATH}/main.cxx") - add_library(${CORE_LIB_NAME} ${CORE_SRCS}) - get_arduino_flags(ARDUINO_COMPILE_FLAGS ARDUINO_LINK_FLAGS ${BOARD_ID} FALSE) - set_target_properties(${CORE_LIB_NAME} PROPERTIES - COMPILE_FLAGS "${ARDUINO_COMPILE_FLAGS}" - LINK_FLAGS "${ARDUINO_LINK_FLAGS}") - endif() - set(${VAR_NAME} ${CORE_LIB_NAME} PARENT_SCOPE) - endif() -endfunction() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# find_arduino_libraries(VAR_NAME SRCS ARDLIBS) -# -# VAR_NAME - Variable name which will hold the results -# SRCS - Sources that will be analized -# ARDLIBS - Arduino libraries identified by name (e.g., Wire, SPI, Servo) -# -# returns a list of paths to libraries found. -# -# Finds all Arduino type libraries included in sources. Available libraries -# are ${ARDUINO_SDK_PATH}/libraries and ${CMAKE_CURRENT_SOURCE_DIR}. -# -# Also adds Arduino libraries specifically names in ALIBS. We add ".h" to the -# names and then process them just like the Arduino libraries found in the sources. -# -# A Arduino library is a folder that has the same name as the include header. -# For example, if we have a include "#include " then the following -# directory structure is considered a Arduino library: -# -# LibraryName/ -# |- LibraryName.h -# `- LibraryName.c -# -# If such a directory is found then all sources within that directory are considred -# to be part of that Arduino library. -# -#=============================================================================# -function(find_arduino_libraries VAR_NAME SRCS ARDLIBS) - set(ARDUINO_LIBS ) - foreach(SRC ${SRCS}) - - # Skipping generated files. They are, probably, not exist yet. - # TODO: Maybe it's possible to skip only really nonexisting files, - # but then it wiil be less deterministic. - get_source_file_property(_srcfile_generated ${SRC} GENERATED) - # Workaround for sketches, which are marked as generated - get_source_file_property(_sketch_generated ${SRC} GENERATED_SKETCH) - - if(NOT ${_srcfile_generated} OR ${_sketch_generated}) - if(NOT (EXISTS ${SRC} OR - EXISTS ${CMAKE_CURRENT_SOURCE_DIR}/${SRC} OR - EXISTS ${CMAKE_CURRENT_BINARY_DIR}/${SRC})) - message(FATAL_ERROR "Invalid source file: ${SRC}") - endif() - file(STRINGS ${SRC} SRC_CONTENTS) - - foreach(LIBNAME ${ARDLIBS}) - list(APPEND SRC_CONTENTS "#include <${LIBNAME}.h>") - endforeach() +cmake_minimum_required(VERSION 2.8.5) - foreach(SRC_LINE ${SRC_CONTENTS}) - if("${SRC_LINE}" MATCHES "^[ \t]*#[ \t]*include[ \t]*[<\"]([^>\"]*)[>\"]") - get_filename_component(INCLUDE_NAME ${CMAKE_MATCH_1} NAME_WE) - get_property(LIBRARY_SEARCH_PATH - DIRECTORY # Property Scope - PROPERTY LINK_DIRECTORIES) - foreach(LIB_SEARCH_PATH ${LIBRARY_SEARCH_PATH} ${ARDUINO_LIBRARIES_PATH} ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/libraries ${ARDUINO_EXTRA_LIBRARIES_PATH}) - if(EXISTS ${LIB_SEARCH_PATH}/${INCLUDE_NAME}/${CMAKE_MATCH_1}) - list(APPEND ARDUINO_LIBS ${LIB_SEARCH_PATH}/${INCLUDE_NAME}) - break() - endif() - if(EXISTS ${LIB_SEARCH_PATH}/${CMAKE_MATCH_1}) - list(APPEND ARDUINO_LIBS ${LIB_SEARCH_PATH}) - break() - endif() - endforeach() - endif() - endforeach() - endif() - endforeach() - if(ARDUINO_LIBS) - list(REMOVE_DUPLICATES ARDUINO_LIBS) - endif() - set(${VAR_NAME} ${ARDUINO_LIBS} PARENT_SCOPE) -endfunction() +set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_CURRENT_LIST_DIR}) +set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_CURRENT_LIST_DIR}/Initialization) +set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_CURRENT_LIST_DIR}/Core) +set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_CURRENT_LIST_DIR}/Core/BoardFlags) +set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_CURRENT_LIST_DIR}/Core/Libraries) +set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_CURRENT_LIST_DIR}/Core/Targets) +set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_CURRENT_LIST_DIR}/Core/Sketch) +set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_CURRENT_LIST_DIR}/Core/Examples) +set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_CURRENT_LIST_DIR}/Extras) +set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_CURRENT_LIST_DIR}/Generation) -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# setup_arduino_library(VAR_NAME BOARD_ID LIB_PATH COMPILE_FLAGS LINK_FLAGS) -# -# VAR_NAME - Vairable wich will hold the generated library names -# BOARD_ID - Board ID -# LIB_PATH - Path of the library -# COMPILE_FLAGS - Compile flags -# LINK_FLAGS - Link flags -# -# Creates an Arduino library, with all it's library dependencies. -# -# ${LIB_NAME}_RECURSE controls if the library will recurse -# when looking for source files. -# -#=============================================================================# +include(CMakeParseArguments) -# For known libraries can list recurse here +include(VariableValidator) +include(Initializer) + +include(Macros) +include(BoardPropertiesReader) +include(FlagsSetter) +include(SourceFinder) +include(LibraryFinder) +include(DebugOptions) +include(Printer) +include(GeneratorSettingsLoader) + +include(ArduinoSketchToCppConverter) +include(ArduinoSketchFactory) + +include(CoreLibraryFactory) +include(ArduinoLibraryFactory) +include(BlacklistedLibrariesRemover) + +include(ArduinoExampleFactory) +include(ArduinoLibraryExampleFactory) + +include(ArduinoBootloaderArgumentsBuilder) +include(ArduinoBootloaderBurnTargetCreator) +include(ArduinoBootloaderUploadTargetCreator) +include(ArduinoFirmwareTargetCreator) +include(ArduinoProgrammerArgumentsBuilder) +include(ArduinoProgrammerBurnTargetCreator) +include(ArduinoSerialTargetCreator) +include(ArduinoUploadTargetCreator) + +include(AvrLibraryGenerator) +include(AvrFirmwareGenerator) +include(ArduinoLibraryGenerator) +include(ArduinoFirmwareGenerator) +include(ArduinoExampleGenerator) +include(ArduinoLibraryExampleGenerator) + +if (IS_SCRIPT_PROCESSED) + return() +endif () + +# Define the 'RECURSE' flag for libraries known to depend on it +# on each reload set(Wire_RECURSE True) set(Ethernet_RECURSE True) set(SD_RECURSE True) -function(setup_arduino_library VAR_NAME BOARD_ID LIB_PATH COMPILE_FLAGS LINK_FLAGS) - set(LIB_TARGETS) - set(LIB_INCLUDES) - - get_filename_component(LIB_NAME ${LIB_PATH} NAME) - set(TARGET_LIB_NAME ${BOARD_ID}_${LIB_NAME}) - if(NOT TARGET ${TARGET_LIB_NAME}) - string(REGEX REPLACE ".*/" "" LIB_SHORT_NAME ${LIB_NAME}) - - # Detect if recursion is needed - if (NOT DEFINED ${LIB_SHORT_NAME}_RECURSE) - set(${LIB_SHORT_NAME}_RECURSE False) - endif() - - find_sources(LIB_SRCS ${LIB_PATH} ${${LIB_SHORT_NAME}_RECURSE}) - if(LIB_SRCS) - - arduino_debug_msg("Generating Arduino ${LIB_NAME} library") - add_library(${TARGET_LIB_NAME} STATIC ${LIB_SRCS}) - - get_arduino_flags(ARDUINO_COMPILE_FLAGS ARDUINO_LINK_FLAGS ${BOARD_ID} FALSE) - - find_arduino_libraries(LIB_DEPS "${LIB_SRCS}" "") - - foreach(LIB_DEP ${LIB_DEPS}) - setup_arduino_library(DEP_LIB_SRCS ${BOARD_ID} ${LIB_DEP} "${COMPILE_FLAGS}" "${LINK_FLAGS}") - list(APPEND LIB_TARGETS ${DEP_LIB_SRCS}) - list(APPEND LIB_INCLUDES ${DEP_LIB_SRCS_INCLUDES}) - endforeach() - - if (LIB_INCLUDES) - string(REPLACE ";" " " LIB_INCLUDES "${LIB_INCLUDES}") - endif() - - set_target_properties(${TARGET_LIB_NAME} PROPERTIES - COMPILE_FLAGS "${ARDUINO_COMPILE_FLAGS} ${LIB_INCLUDES} -I\"${LIB_PATH}\" -I\"${LIB_PATH}/utility\" ${COMPILE_FLAGS}" - LINK_FLAGS "${ARDUINO_LINK_FLAGS} ${LINK_FLAGS}") - list(APPEND LIB_INCLUDES "-I\"${LIB_PATH}\" -I\"${LIB_PATH}/utility\"") - - target_link_libraries(${TARGET_LIB_NAME} ${BOARD_ID}_CORE ${LIB_TARGETS}) - list(APPEND LIB_TARGETS ${TARGET_LIB_NAME}) - - endif() - else() - # Target already exists, skiping creating - list(APPEND LIB_TARGETS ${TARGET_LIB_NAME}) - endif() - if(LIB_TARGETS) - list(REMOVE_DUPLICATES LIB_TARGETS) - endif() - set(${VAR_NAME} ${LIB_TARGETS} PARENT_SCOPE) - set(${VAR_NAME}_INCLUDES ${LIB_INCLUDES} PARENT_SCOPE) -endfunction() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# setup_arduino_libraries(VAR_NAME BOARD_ID SRCS COMPILE_FLAGS LINK_FLAGS) -# -# VAR_NAME - Vairable wich will hold the generated library names -# BOARD_ID - Board ID -# SRCS - source files -# COMPILE_FLAGS - Compile flags -# LINK_FLAGS - Linker flags -# -# Finds and creates all dependency libraries based on sources. -# -#=============================================================================# -function(setup_arduino_libraries VAR_NAME BOARD_ID SRCS ARDLIBS COMPILE_FLAGS LINK_FLAGS) - set(LIB_TARGETS) - set(LIB_INCLUDES) - - find_arduino_libraries(TARGET_LIBS "${SRCS}" ARDLIBS) - foreach(TARGET_LIB ${TARGET_LIBS}) - # Create static library instead of returning sources - setup_arduino_library(LIB_DEPS ${BOARD_ID} ${TARGET_LIB} "${COMPILE_FLAGS}" "${LINK_FLAGS}") - list(APPEND LIB_TARGETS ${LIB_DEPS}) - list(APPEND LIB_INCLUDES ${LIB_DEPS_INCLUDES}) - endforeach() - - set(${VAR_NAME} ${LIB_TARGETS} PARENT_SCOPE) - set(${VAR_NAME}_INCLUDES ${LIB_INCLUDES} PARENT_SCOPE) -endfunction() - - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# setup_arduino_target(TARGET_NAME ALL_SRCS ALL_LIBS COMPILE_FLAGS LINK_FLAGS MANUAL) -# -# TARGET_NAME - Target name -# BOARD_ID - Arduino board ID -# ALL_SRCS - All sources -# ALL_LIBS - All libraries -# COMPILE_FLAGS - Compile flags -# LINK_FLAGS - Linker flags -# MANUAL - (Advanced) Only use AVR Libc/Includes -# -# Creates an Arduino firmware target. -# -#=============================================================================# -function(setup_arduino_target TARGET_NAME BOARD_ID ALL_SRCS ALL_LIBS COMPILE_FLAGS LINK_FLAGS MANUAL) - - add_executable(${TARGET_NAME} ${ALL_SRCS}) - set_target_properties(${TARGET_NAME} PROPERTIES SUFFIX ".elf") - - get_arduino_flags(ARDUINO_COMPILE_FLAGS ARDUINO_LINK_FLAGS ${BOARD_ID} ${MANUAL}) - - set_target_properties(${TARGET_NAME} PROPERTIES - COMPILE_FLAGS "${ARDUINO_COMPILE_FLAGS} ${COMPILE_FLAGS}" - LINK_FLAGS "${ARDUINO_LINK_FLAGS} ${LINK_FLAGS}") - target_link_libraries(${TARGET_NAME} ${ALL_LIBS} "-lc -lm") - - if(NOT EXECUTABLE_OUTPUT_PATH) - set(EXECUTABLE_OUTPUT_PATH ${CMAKE_CURRENT_BINARY_DIR}) - endif() - set(TARGET_PATH ${EXECUTABLE_OUTPUT_PATH}/${TARGET_NAME}) - add_custom_command(TARGET ${TARGET_NAME} POST_BUILD - COMMAND ${CMAKE_OBJCOPY} - ARGS ${ARDUINO_OBJCOPY_EEP_FLAGS} - ${TARGET_PATH}.elf - ${TARGET_PATH}.eep - COMMENT "Generating EEP image" - VERBATIM) - - # Convert firmware image to ASCII HEX format - add_custom_command(TARGET ${TARGET_NAME} POST_BUILD - COMMAND ${CMAKE_OBJCOPY} - ARGS ${ARDUINO_OBJCOPY_HEX_FLAGS} - ${TARGET_PATH}.elf - ${TARGET_PATH}.hex - COMMENT "Generating HEX image" - VERBATIM) - - # Display target size - add_custom_command(TARGET ${TARGET_NAME} POST_BUILD - COMMAND ${CMAKE_COMMAND} - ARGS -DFIRMWARE_IMAGE=${TARGET_PATH}.elf - -DMCU=${${BOARD_ID}.build.mcu} - -DEEPROM_IMAGE=${TARGET_PATH}.eep - -P ${ARDUINO_SIZE_SCRIPT} - COMMENT "Calculating image size" - VERBATIM) - - # Create ${TARGET_NAME}-size target - add_custom_target(${TARGET_NAME}-size - COMMAND ${CMAKE_COMMAND} - -DFIRMWARE_IMAGE=${TARGET_PATH}.elf - -DMCU=${${BOARD_ID}.build.mcu} - -DEEPROM_IMAGE=${TARGET_PATH}.eep - -P ${ARDUINO_SIZE_SCRIPT} - DEPENDS ${TARGET_NAME} - COMMENT "Calculating ${TARGET_NAME} image size") - -endfunction() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# setup_arduino_upload(BOARD_ID TARGET_NAME PORT) -# -# BOARD_ID - Arduino board id -# TARGET_NAME - Target name -# PORT - Serial port for upload -# PROGRAMMER_ID - Programmer ID -# AVRDUDE_FLAGS - avrdude flags -# -# Create an upload target (${TARGET_NAME}-upload) for the specified Arduino target. -# -#=============================================================================# -function(setup_arduino_upload BOARD_ID TARGET_NAME PORT PROGRAMMER_ID AVRDUDE_FLAGS) - setup_arduino_bootloader_upload(${TARGET_NAME} ${BOARD_ID} ${PORT} "${AVRDUDE_FLAGS}") - - # Add programmer support if defined - if(PROGRAMMER_ID AND ${PROGRAMMER_ID}.protocol) - setup_arduino_programmer_burn(${TARGET_NAME} ${BOARD_ID} ${PROGRAMMER_ID} ${PORT} "${AVRDUDE_FLAGS}") - setup_arduino_bootloader_burn(${TARGET_NAME} ${BOARD_ID} ${PROGRAMMER_ID} ${PORT} "${AVRDUDE_FLAGS}") - endif() -endfunction() - - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# setup_arduino_bootloader_upload(TARGET_NAME BOARD_ID PORT) -# -# TARGET_NAME - target name -# BOARD_ID - board id -# PORT - serial port -# AVRDUDE_FLAGS - avrdude flags (override) -# -# Set up target for upload firmware via the bootloader. -# -# The target for uploading the firmware is ${TARGET_NAME}-upload . -# -#=============================================================================# -function(setup_arduino_bootloader_upload TARGET_NAME BOARD_ID PORT AVRDUDE_FLAGS) - set(UPLOAD_TARGET ${TARGET_NAME}-upload) - set(AVRDUDE_ARGS) - - setup_arduino_bootloader_args(${BOARD_ID} ${TARGET_NAME} ${PORT} "${AVRDUDE_FLAGS}" AVRDUDE_ARGS) - - if(NOT AVRDUDE_ARGS) - message("Could not generate default avrdude bootloader args, aborting!") - return() - endif() - - if(NOT EXECUTABLE_OUTPUT_PATH) - set(EXECUTABLE_OUTPUT_PATH ${CMAKE_CURRENT_BINARY_DIR}) - endif() - set(TARGET_PATH ${EXECUTABLE_OUTPUT_PATH}/${TARGET_NAME}) - - list(APPEND AVRDUDE_ARGS "-Uflash:w:${TARGET_PATH}.hex") - list(APPEND AVRDUDE_ARGS "-Ueeprom:w:${TARGET_PATH}.eep:i") - add_custom_target(${UPLOAD_TARGET} - ${ARDUINO_AVRDUDE_PROGRAM} - ${AVRDUDE_ARGS} - DEPENDS ${TARGET_NAME}) - - # Global upload target - if(NOT TARGET upload) - add_custom_target(upload) - endif() - - add_dependencies(upload ${UPLOAD_TARGET}) -endfunction() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# setup_arduino_programmer_burn(TARGET_NAME BOARD_ID PROGRAMMER PORT AVRDUDE_FLAGS) -# -# TARGET_NAME - name of target to burn -# BOARD_ID - board id -# PROGRAMMER - programmer id -# PORT - serial port -# AVRDUDE_FLAGS - avrdude flags (override) -# -# Sets up target for burning firmware via a programmer. -# -# The target for burning the firmware is ${TARGET_NAME}-burn . -# -#=============================================================================# -function(setup_arduino_programmer_burn TARGET_NAME BOARD_ID PROGRAMMER PORT AVRDUDE_FLAGS) - set(PROGRAMMER_TARGET ${TARGET_NAME}-burn) - - set(AVRDUDE_ARGS) - - setup_arduino_programmer_args(${BOARD_ID} ${PROGRAMMER} ${TARGET_NAME} ${PORT} "${AVRDUDE_FLAGS}" AVRDUDE_ARGS) - - if(NOT AVRDUDE_ARGS) - message("Could not generate default avrdude programmer args, aborting!") - return() - endif() - - if(NOT EXECUTABLE_OUTPUT_PATH) - set(EXECUTABLE_OUTPUT_PATH ${CMAKE_CURRENT_BINARY_DIR}) - endif() - set(TARGET_PATH ${EXECUTABLE_OUTPUT_PATH}/${TARGET_NAME}) - - list(APPEND AVRDUDE_ARGS "-Uflash:w:${TARGET_PATH}.hex") - - add_custom_target(${PROGRAMMER_TARGET} - ${ARDUINO_AVRDUDE_PROGRAM} - ${AVRDUDE_ARGS} - DEPENDS ${TARGET_NAME}) -endfunction() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# setup_arduino_bootloader_burn(TARGET_NAME BOARD_ID PROGRAMMER PORT AVRDUDE_FLAGS) -# -# TARGET_NAME - name of target to burn -# BOARD_ID - board id -# PROGRAMMER - programmer id -# PORT - serial port -# AVRDUDE_FLAGS - avrdude flags (override) -# -# Create a target for burning a bootloader via a programmer. -# -# The target for burning the bootloader is ${TARGET_NAME}-burn-bootloader -# -#=============================================================================# -function(setup_arduino_bootloader_burn TARGET_NAME BOARD_ID PROGRAMMER PORT AVRDUDE_FLAGS) - set(BOOTLOADER_TARGET ${TARGET_NAME}-burn-bootloader) - - set(AVRDUDE_ARGS) - - setup_arduino_programmer_args(${BOARD_ID} ${PROGRAMMER} ${TARGET_NAME} ${PORT} "${AVRDUDE_FLAGS}" AVRDUDE_ARGS) - - if(NOT AVRDUDE_ARGS) - message("Could not generate default avrdude programmer args, aborting!") - return() - endif() - - foreach( ITEM unlock_bits high_fuses low_fuses path file) - if(NOT ${BOARD_ID}.bootloader.${ITEM}) - message("Missing ${BOARD_ID}.bootloader.${ITEM}, not creating bootloader burn target ${BOOTLOADER_TARGET}.") - return() - endif() - endforeach() - - if(NOT EXISTS "${ARDUINO_BOOTLOADERS_PATH}/${${BOARD_ID}.bootloader.path}/${${BOARD_ID}.bootloader.file}") - message("${ARDUINO_BOOTLOADERS_PATH}/${${BOARD_ID}.bootloader.path}/${${BOARD_ID}.bootloader.file}") - message("Missing bootloader image, not creating bootloader burn target ${BOOTLOADER_TARGET}.") - return() - endif() - - # Erase the chip - list(APPEND AVRDUDE_ARGS "-e") - - # Set unlock bits and fuses (because chip is going to be erased) - list(APPEND AVRDUDE_ARGS "-Ulock:w:${${BOARD_ID}.bootloader.unlock_bits}:m") - if(${BOARD_ID}.bootloader.extended_fuses) - list(APPEND AVRDUDE_ARGS "-Uefuse:w:${${BOARD_ID}.bootloader.extended_fuses}:m") - endif() - list(APPEND AVRDUDE_ARGS - "-Uhfuse:w:${${BOARD_ID}.bootloader.high_fuses}:m" - "-Ulfuse:w:${${BOARD_ID}.bootloader.low_fuses}:m") - - # Set bootloader image - list(APPEND AVRDUDE_ARGS "-Uflash:w:${${BOARD_ID}.bootloader.file}:i") - - # Set lockbits - list(APPEND AVRDUDE_ARGS "-Ulock:w:${${BOARD_ID}.bootloader.lock_bits}:m") - - # Create burn bootloader target - add_custom_target(${BOOTLOADER_TARGET} - ${ARDUINO_AVRDUDE_PROGRAM} - ${AVRDUDE_ARGS} - WORKING_DIRECTORY ${ARDUINO_BOOTLOADERS_PATH}/${${BOARD_ID}.bootloader.path} - DEPENDS ${TARGET_NAME}) -endfunction() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# setup_arduino_programmer_args(BOARD_ID PROGRAMMER TARGET_NAME PORT AVRDUDE_FLAGS OUTPUT_VAR) -# -# BOARD_ID - board id -# PROGRAMMER - programmer id -# TARGET_NAME - target name -# PORT - serial port -# AVRDUDE_FLAGS - avrdude flags (override) -# OUTPUT_VAR - name of output variable for result -# -# Sets up default avrdude settings for burning firmware via a programmer. -#=============================================================================# -function(setup_arduino_programmer_args BOARD_ID PROGRAMMER TARGET_NAME PORT AVRDUDE_FLAGS OUTPUT_VAR) - set(AVRDUDE_ARGS ${${OUTPUT_VAR}}) - - if(NOT AVRDUDE_FLAGS) - set(AVRDUDE_FLAGS ${ARDUINO_AVRDUDE_FLAGS}) - endif() - - list(APPEND AVRDUDE_ARGS "-C${ARDUINO_AVRDUDE_CONFIG_PATH}") - - #TODO: Check mandatory settings before continuing - if(NOT ${PROGRAMMER}.protocol) - message(FATAL_ERROR "Missing ${PROGRAMMER}.protocol, aborting!") - endif() - - list(APPEND AVRDUDE_ARGS "-c${${PROGRAMMER}.protocol}") # Set programmer - - if(${PROGRAMMER}.communication STREQUAL "usb") - list(APPEND AVRDUDE_ARGS "-Pusb") # Set USB as port - elseif(${PROGRAMMER}.communication STREQUAL "serial") - list(APPEND AVRDUDE_ARGS "-P${PORT}") # Set port - if(${PROGRAMMER}.speed) - list(APPEND AVRDUDE_ARGS "-b${${PROGRAMMER}.speed}") # Set baud rate - endif() - endif() - - if(${PROGRAMMER}.force) - list(APPEND AVRDUDE_ARGS "-F") # Set force - endif() - - if(${PROGRAMMER}.delay) - list(APPEND AVRDUDE_ARGS "-i${${PROGRAMMER}.delay}") # Set delay - endif() - - list(APPEND AVRDUDE_ARGS "-p${${BOARD_ID}.build.mcu}") # MCU Type - - list(APPEND AVRDUDE_ARGS ${AVRDUDE_FLAGS}) - - set(${OUTPUT_VAR} ${AVRDUDE_ARGS} PARENT_SCOPE) -endfunction() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# setup_arduino_bootloader_args(BOARD_ID TARGET_NAME PORT AVRDUDE_FLAGS OUTPUT_VAR) -# -# BOARD_ID - board id -# TARGET_NAME - target name -# PORT - serial port -# AVRDUDE_FLAGS - avrdude flags (override) -# OUTPUT_VAR - name of output variable for result -# -# Sets up default avrdude settings for uploading firmware via the bootloader. -#=============================================================================# -function(setup_arduino_bootloader_args BOARD_ID TARGET_NAME PORT AVRDUDE_FLAGS OUTPUT_VAR) - set(AVRDUDE_ARGS ${${OUTPUT_VAR}}) - - if(NOT AVRDUDE_FLAGS) - set(AVRDUDE_FLAGS ${ARDUINO_AVRDUDE_FLAGS}) - endif() - - list(APPEND AVRDUDE_ARGS - "-C${ARDUINO_AVRDUDE_CONFIG_PATH}" # avrdude config - "-p${${BOARD_ID}.build.mcu}" # MCU Type - ) - - # Programmer - if(NOT ${BOARD_ID}.upload.protocol OR ${BOARD_ID}.upload.protocol STREQUAL "stk500") - list(APPEND AVRDUDE_ARGS "-cstk500v1") - else() - list(APPEND AVRDUDE_ARGS "-c${${BOARD_ID}.upload.protocol}") - endif() - - set(UPLOAD_SPEED "19200") - if(${BOARD_ID}.upload.speed) - set(UPLOAD_SPEED ${${BOARD_ID}.upload.speed}) - endif() - - list(APPEND AVRDUDE_ARGS - "-b${UPLOAD_SPEED}" # Baud rate - "-P${PORT}" # Serial port - "-D" # Dont erase - ) - - list(APPEND AVRDUDE_ARGS ${AVRDUDE_FLAGS}) - - set(${OUTPUT_VAR} ${AVRDUDE_ARGS} PARENT_SCOPE) -endfunction() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# find_sources(VAR_NAME LIB_PATH RECURSE) -# -# VAR_NAME - Variable name that will hold the detected sources -# LIB_PATH - The base path -# RECURSE - Whether or not to recurse -# -# Finds all C/C++ sources located at the specified path. -# -#=============================================================================# -function(find_sources VAR_NAME LIB_PATH RECURSE) - set(FILE_SEARCH_LIST - ${LIB_PATH}/*.cpp - ${LIB_PATH}/*.c - ${LIB_PATH}/*.cc - ${LIB_PATH}/*.cxx - ${LIB_PATH}/*.h - ${LIB_PATH}/*.hh - ${LIB_PATH}/*.hxx) - - if(RECURSE) - file(GLOB_RECURSE LIB_FILES ${FILE_SEARCH_LIST}) - else() - file(GLOB LIB_FILES ${FILE_SEARCH_LIST}) - endif() - - if(LIB_FILES) - set(${VAR_NAME} ${LIB_FILES} PARENT_SCOPE) - endif() -endfunction() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# setup_serial_target(TARGET_NAME CMD) -# -# TARGET_NAME - Target name -# CMD - Serial terminal command -# -# Creates a target (${TARGET_NAME}-serial) for launching the serial termnial. -# -#=============================================================================# -function(setup_serial_target TARGET_NAME CMD SERIAL_PORT) - string(CONFIGURE "${CMD}" FULL_CMD @ONLY) - add_custom_target(${TARGET_NAME}-serial - COMMAND ${FULL_CMD}) -endfunction() - - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# detect_arduino_version(VAR_NAME) -# -# VAR_NAME - Variable name where the detected version will be saved -# -# Detects the Arduino SDK Version based on the revisions.txt file. The -# following variables will be generated: -# -# ${VAR_NAME} -> the full version (major.minor.patch) -# ${VAR_NAME}_MAJOR -> the major version -# ${VAR_NAME}_MINOR -> the minor version -# ${VAR_NAME}_PATCH -> the patch version -# -#=============================================================================# -function(detect_arduino_version VAR_NAME) - if(ARDUINO_VERSION_PATH) - file(READ ${ARDUINO_VERSION_PATH} RAW_VERSION) - if("${RAW_VERSION}" MATCHES " *[0]+([0-9]+)") - set(PARSED_VERSION 0.${CMAKE_MATCH_1}.0) - elseif("${RAW_VERSION}" MATCHES "[ ]*([0-9]+[.][0-9]+[.][0-9]+)") - set(PARSED_VERSION ${CMAKE_MATCH_1}) - elseif("${RAW_VERSION}" MATCHES "[ ]*([0-9]+[.][0-9]+)") - set(PARSED_VERSION ${CMAKE_MATCH_1}.0) - endif() - - if(NOT PARSED_VERSION STREQUAL "") - string(REPLACE "." ";" SPLIT_VERSION ${PARSED_VERSION}) - list(GET SPLIT_VERSION 0 SPLIT_VERSION_MAJOR) - list(GET SPLIT_VERSION 1 SPLIT_VERSION_MINOR) - list(GET SPLIT_VERSION 2 SPLIT_VERSION_PATCH) - - set(${VAR_NAME} "${PARSED_VERSION}" PARENT_SCOPE) - set(${VAR_NAME}_MAJOR "${SPLIT_VERSION_MAJOR}" PARENT_SCOPE) - set(${VAR_NAME}_MINOR "${SPLIT_VERSION_MINOR}" PARENT_SCOPE) - set(${VAR_NAME}_PATCH "${SPLIT_VERSION_PATCH}" PARENT_SCOPE) - endif() - endif() -endfunction() - - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# load_arduino_style_settings(SETTINGS_LIST SETTINGS_PATH) -# -# SETTINGS_LIST - Variable name of settings list -# SETTINGS_PATH - File path of settings file to load. -# -# Load a Arduino style settings file into the cache. -# -# Examples of this type of settings file is the boards.txt and -# programmers.txt files located in ${ARDUINO_SDK}/hardware/arduino. -# -# Settings have to following format: -# -# entry.setting[.subsetting] = value -# -# where [.subsetting] is optional -# -# For example, the following settings: -# -# uno.name=Arduino Uno -# uno.upload.protocol=stk500 -# uno.upload.maximum_size=32256 -# uno.build.mcu=atmega328p -# uno.build.core=arduino -# -# will generate the follwoing equivalent CMake variables: -# -# set(uno.name "Arduino Uno") -# set(uno.upload.protocol "stk500") -# set(uno.upload.maximum_size "32256") -# set(uno.build.mcu "atmega328p") -# set(uno.build.core "arduino") -# -# set(uno.SETTINGS name upload build) # List of settings for uno -# set(uno.upload.SUBSETTINGS protocol maximum_size) # List of sub-settings for uno.upload -# set(uno.build.SUBSETTINGS mcu core) # List of sub-settings for uno.build -# -# The ${ENTRY_NAME}.SETTINGS variable lists all settings for the entry, while -# ${ENTRY_NAME}.SUBSETTINGS variables lists all settings for a sub-setting of -# a entry setting pair. -# -# These variables are generated in order to be able to programatically traverse -# all settings (for a example see print_board_settings() function). -# -#=============================================================================# -function(LOAD_ARDUINO_STYLE_SETTINGS SETTINGS_LIST SETTINGS_PATH) - - if(NOT ${SETTINGS_LIST} AND EXISTS ${SETTINGS_PATH}) - file(STRINGS ${SETTINGS_PATH} FILE_ENTRIES) # Settings file split into lines - - foreach(FILE_ENTRY ${FILE_ENTRIES}) - if("${FILE_ENTRY}" MATCHES "^[^#]+=.*") - string(REGEX MATCH "^[^=]+" SETTING_NAME ${FILE_ENTRY}) - string(REGEX MATCH "[^=]+$" SETTING_VALUE ${FILE_ENTRY}) - string(REPLACE "." ";" ENTRY_NAME_TOKENS ${SETTING_NAME}) - string(STRIP "${SETTING_VALUE}" SETTING_VALUE) - - list(LENGTH ENTRY_NAME_TOKENS ENTRY_NAME_TOKENS_LEN) - - # Add entry to settings list if it does not exist - list(GET ENTRY_NAME_TOKENS 0 ENTRY_NAME) - list(FIND ${SETTINGS_LIST} ${ENTRY_NAME} ENTRY_NAME_INDEX) - if(ENTRY_NAME_INDEX LESS 0) - # Add entry to main list - list(APPEND ${SETTINGS_LIST} ${ENTRY_NAME}) - endif() - - # Add entry setting to entry settings list if it does not exist - set(ENTRY_SETTING_LIST ${ENTRY_NAME}.SETTINGS) - list(GET ENTRY_NAME_TOKENS 1 ENTRY_SETTING) - list(FIND ${ENTRY_SETTING_LIST} ${ENTRY_SETTING} ENTRY_SETTING_INDEX) - if(ENTRY_SETTING_INDEX LESS 0) - # Add setting to entry - list(APPEND ${ENTRY_SETTING_LIST} ${ENTRY_SETTING}) - set(${ENTRY_SETTING_LIST} ${${ENTRY_SETTING_LIST}} - CACHE INTERNAL "Arduino ${ENTRY_NAME} Board settings list") - endif() - - set(FULL_SETTING_NAME ${ENTRY_NAME}.${ENTRY_SETTING}) - - # Add entry sub-setting to entry sub-settings list if it does not exists - if(ENTRY_NAME_TOKENS_LEN GREATER 2) - set(ENTRY_SUBSETTING_LIST ${ENTRY_NAME}.${ENTRY_SETTING}.SUBSETTINGS) - list(GET ENTRY_NAME_TOKENS 2 ENTRY_SUBSETTING) - list(FIND ${ENTRY_SUBSETTING_LIST} ${ENTRY_SUBSETTING} ENTRY_SUBSETTING_INDEX) - if(ENTRY_SUBSETTING_INDEX LESS 0) - list(APPEND ${ENTRY_SUBSETTING_LIST} ${ENTRY_SUBSETTING}) - set(${ENTRY_SUBSETTING_LIST} ${${ENTRY_SUBSETTING_LIST}} - CACHE INTERNAL "Arduino ${ENTRY_NAME} Board sub-settings list") - endif() - set(FULL_SETTING_NAME ${FULL_SETTING_NAME}.${ENTRY_SUBSETTING}) - endif() - - # Save setting value - set(${FULL_SETTING_NAME} ${SETTING_VALUE} - CACHE INTERNAL "Arduino ${ENTRY_NAME} Board setting") - - - endif() - endforeach() - set(${SETTINGS_LIST} ${${SETTINGS_LIST}} - CACHE STRING "List of detected Arduino Board configurations") - mark_as_advanced(${SETTINGS_LIST}) - endif() -endfunction() - -#=============================================================================# -# print_settings(ENTRY_NAME) -# -# ENTRY_NAME - name of entry -# -# Print the entry settings (see load_arduino_syle_settings()). -# -#=============================================================================# -function(PRINT_SETTINGS ENTRY_NAME) - if(${ENTRY_NAME}.SETTINGS) - - foreach(ENTRY_SETTING ${${ENTRY_NAME}.SETTINGS}) - if(${ENTRY_NAME}.${ENTRY_SETTING}) - message(STATUS " ${ENTRY_NAME}.${ENTRY_SETTING}=${${ENTRY_NAME}.${ENTRY_SETTING}}") - endif() - if(${ENTRY_NAME}.${ENTRY_SETTING}.SUBSETTINGS) - foreach(ENTRY_SUBSETTING ${${ENTRY_NAME}.${ENTRY_SETTING}.SUBSETTINGS}) - if(${ENTRY_NAME}.${ENTRY_SETTING}.${ENTRY_SUBSETTING}) - message(STATUS " ${ENTRY_NAME}.${ENTRY_SETTING}.${ENTRY_SUBSETTING}=${${ENTRY_NAME}.${ENTRY_SETTING}.${ENTRY_SUBSETTING}}") - endif() - endforeach() - endif() - message(STATUS "") - endforeach() - endif() -endfunction() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# print_list(SETTINGS_LIST) -# -# SETTINGS_LIST - Variables name of settings list -# -# Print list settings and names (see load_arduino_syle_settings()). -#=============================================================================# -function(PRINT_LIST SETTINGS_LIST) - if(${SETTINGS_LIST}) - set(MAX_LENGTH 0) - foreach(ENTRY_NAME ${${SETTINGS_LIST}}) - string(LENGTH "${ENTRY_NAME}" CURRENT_LENGTH) - if(CURRENT_LENGTH GREATER MAX_LENGTH) - set(MAX_LENGTH ${CURRENT_LENGTH}) - endif() - endforeach() - foreach(ENTRY_NAME ${${SETTINGS_LIST}}) - string(LENGTH "${ENTRY_NAME}" CURRENT_LENGTH) - math(EXPR PADDING_LENGTH "${MAX_LENGTH}-${CURRENT_LENGTH}") - set(PADDING "") - foreach(X RANGE ${PADDING_LENGTH}) - set(PADDING "${PADDING} ") - endforeach() - message(STATUS " ${PADDING}${ENTRY_NAME}: ${${ENTRY_NAME}.name}") - endforeach() - endif() -endfunction() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# setup_arduino_example(TARGET_NAME LIBRARY_NAME EXAMPLE_NAME OUTPUT_VAR) -# -# TARGET_NAME - Target name -# LIBRARY_NAME - Library name -# EXAMPLE_NAME - Example name -# OUTPUT_VAR - Variable name to save sketch path. -# -# Creates a Arduino example from a the specified library. -#=============================================================================# -function(SETUP_ARDUINO_EXAMPLE TARGET_NAME LIBRARY_NAME EXAMPLE_NAME OUTPUT_VAR) - set(EXAMPLE_SKETCH_PATH ) - - get_property(LIBRARY_SEARCH_PATH - DIRECTORY # Property Scope - PROPERTY LINK_DIRECTORIES) - foreach(LIB_SEARCH_PATH ${LIBRARY_SEARCH_PATH} ${ARDUINO_LIBRARIES_PATH} ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/libraries) - if(EXISTS "${LIB_SEARCH_PATH}/${LIBRARY_NAME}/examples/${EXAMPLE_NAME}") - set(EXAMPLE_SKETCH_PATH "${LIB_SEARCH_PATH}/${LIBRARY_NAME}/examples/${EXAMPLE_NAME}") - break() - endif() - endforeach() - - if(EXAMPLE_SKETCH_PATH) - setup_arduino_sketch(${TARGET_NAME} ${EXAMPLE_SKETCH_PATH} SKETCH_CPP) - set("${OUTPUT_VAR}" ${${OUTPUT_VAR}} ${SKETCH_CPP} PARENT_SCOPE) - else() - message(FATAL_ERROR "Could not find example ${EXAMPLE_NAME} from library ${LIBRARY_NAME}") - endif() -endfunction() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# setup_arduino_sketch(TARGET_NAME SKETCH_PATH OUTPUT_VAR) -# -# TARGET_NAME - Target name -# SKETCH_PATH - Path to sketch directory -# OUTPUT_VAR - Variable name where to save generated sketch source -# -# Generates C++ sources from Arduino Sketch. -#=============================================================================# -function(SETUP_ARDUINO_SKETCH TARGET_NAME SKETCH_PATH OUTPUT_VAR) - get_filename_component(SKETCH_NAME "${SKETCH_PATH}" NAME) - get_filename_component(SKETCH_PATH "${SKETCH_PATH}" ABSOLUTE) - - if(EXISTS "${SKETCH_PATH}") - set(SKETCH_CPP ${CMAKE_CURRENT_BINARY_DIR}/${TARGET_NAME}_${SKETCH_NAME}.cpp) - - if (IS_DIRECTORY "${SKETCH_PATH}") - # Sketch directory specified, try to find main sketch... - set(MAIN_SKETCH ${SKETCH_PATH}/${SKETCH_NAME}) - - if(EXISTS "${MAIN_SKETCH}.pde") - set(MAIN_SKETCH "${MAIN_SKETCH}.pde") - elseif(EXISTS "${MAIN_SKETCH}.ino") - set(MAIN_SKETCH "${MAIN_SKETCH}.ino") - else() - message(FATAL_ERROR "Could not find main sketch (${SKETCH_NAME}.pde or ${SKETCH_NAME}.ino) at ${SKETCH_PATH}! Please specify the main sketch file path instead of directory.") - endif() - else() - # Sektch file specified, assuming parent directory as sketch directory - set(MAIN_SKETCH ${SKETCH_PATH}) - get_filename_component(SKETCH_PATH "${SKETCH_PATH}" PATH) - endif() - arduino_debug_msg("sketch: ${MAIN_SKETCH}") - - # Find all sketch files - file(GLOB SKETCH_SOURCES ${SKETCH_PATH}/*.pde ${SKETCH_PATH}/*.ino) - list(REMOVE_ITEM SKETCH_SOURCES ${MAIN_SKETCH}) - list(SORT SKETCH_SOURCES) - - generate_cpp_from_sketch("${MAIN_SKETCH}" "${SKETCH_SOURCES}" "${SKETCH_CPP}") - - # Regenerate build system if sketch changes - add_custom_command(OUTPUT ${SKETCH_CPP} - COMMAND ${CMAKE_COMMAND} ${CMAKE_SOURCE_DIR} - WORKING_DIRECTORY ${CMAKE_BINARY_DIR} - DEPENDS ${MAIN_SKETCH} ${SKETCH_SOURCES} - COMMENT "Regnerating ${SKETCH_NAME} Sketch") - set_source_files_properties(${SKETCH_CPP} PROPERTIES GENERATED TRUE) - # Mark file that it exists for find_file - set_source_files_properties(${SKETCH_CPP} PROPERTIES GENERATED_SKETCH TRUE) - - set("${OUTPUT_VAR}" ${${OUTPUT_VAR}} ${SKETCH_CPP} PARENT_SCOPE) - else() - message(FATAL_ERROR "Sketch does not exist: ${SKETCH_PATH}") - endif() -endfunction() - - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# generate_cpp_from_sketch(MAIN_SKETCH_PATH SKETCH_SOURCES SKETCH_CPP) -# -# MAIN_SKETCH_PATH - Main sketch file path -# SKETCH_SOURCES - Setch source paths -# SKETCH_CPP - Name of file to generate -# -# Generate C++ source file from Arduino sketch files. -#=============================================================================# -function(GENERATE_CPP_FROM_SKETCH MAIN_SKETCH_PATH SKETCH_SOURCES SKETCH_CPP) - file(WRITE ${SKETCH_CPP} "// automatically generated by arduino-cmake\n") - file(READ ${MAIN_SKETCH_PATH} MAIN_SKETCH) - - # remove comments - remove_comments(MAIN_SKETCH MAIN_SKETCH_NO_COMMENTS) - - # find first statement - string(REGEX MATCH "[\n][_a-zA-Z0-9]+[^\n]*" FIRST_STATEMENT "${MAIN_SKETCH_NO_COMMENTS}") - string(FIND "${MAIN_SKETCH}" "${FIRST_STATEMENT}" HEAD_LENGTH) - if ("${HEAD_LENGTH}" STREQUAL "-1") - set(HEAD_LENGTH 0) - endif() - #message(STATUS "FIRST STATEMENT: ${FIRST_STATEMENT}") - #message(STATUS "FIRST STATEMENT POSITION: ${HEAD_LENGTH}") - string(LENGTH "${MAIN_SKETCH}" MAIN_SKETCH_LENGTH) - - string(SUBSTRING "${MAIN_SKETCH}" 0 ${HEAD_LENGTH} SKETCH_HEAD) - #arduino_debug_msg("SKETCH_HEAD:\n${SKETCH_HEAD}") - - # find the body of the main pde - math(EXPR BODY_LENGTH "${MAIN_SKETCH_LENGTH}-${HEAD_LENGTH}") - string(SUBSTRING "${MAIN_SKETCH}" "${HEAD_LENGTH}+1" "${BODY_LENGTH}-1" SKETCH_BODY) - #arduino_debug_msg("BODY:\n${SKETCH_BODY}") - - # write the file head - file(APPEND ${SKETCH_CPP} "#line 1 \"${MAIN_SKETCH_PATH}\"\n${SKETCH_HEAD}") - - # Count head line offset (for GCC error reporting) - file(STRINGS ${SKETCH_CPP} SKETCH_HEAD_LINES) - list(LENGTH SKETCH_HEAD_LINES SKETCH_HEAD_LINES_COUNT) - math(EXPR SKETCH_HEAD_OFFSET "${SKETCH_HEAD_LINES_COUNT}+2") - - # add arduino include header - #file(APPEND ${SKETCH_CPP} "\n#line 1 \"autogenerated\"\n") - file(APPEND ${SKETCH_CPP} "\n#line ${SKETCH_HEAD_OFFSET} \"${SKETCH_CPP}\"\n") - if(ARDUINO_SDK_VERSION VERSION_LESS 1.0) - file(APPEND ${SKETCH_CPP} "#include \"WProgram.h\"\n") - else() - file(APPEND ${SKETCH_CPP} "#include \"Arduino.h\"\n") - endif() - - # add function prototypes - foreach(SKETCH_SOURCE_PATH ${SKETCH_SOURCES} ${MAIN_SKETCH_PATH}) - arduino_debug_msg("Sketch: ${SKETCH_SOURCE_PATH}") - file(READ ${SKETCH_SOURCE_PATH} SKETCH_SOURCE) - remove_comments(SKETCH_SOURCE SKETCH_SOURCE) - - set(ALPHA "a-zA-Z") - set(NUM "0-9") - set(ALPHANUM "${ALPHA}${NUM}") - set(WORD "_${ALPHANUM}") - set(LINE_START "(^|[\n])") - set(QUALIFIERS "[ \t]*([${ALPHA}]+[ ])*") - set(TYPE "[${WORD}]+([ ]*[\n][\t]*|[ ])+") - set(FNAME "[${WORD}]+[ ]?[\n]?[\t]*[ ]*") - set(FARGS "[(]([\t]*[ ]*[*&]?[ ]?[${WORD}](\\[([${NUM}]+)?\\])*[,]?[ ]*[\n]?)*([,]?[ ]*[\n]?)?[)]") - set(BODY_START "([ ]*[\n][\t]*|[ ]|[\n])*{") - set(PROTOTYPE_PATTERN "${LINE_START}${QUALIFIERS}${TYPE}${FNAME}${FARGS}${BODY_START}") - - string(REGEX MATCHALL "${PROTOTYPE_PATTERN}" SKETCH_PROTOTYPES "${SKETCH_SOURCE}") - - # Write function prototypes - file(APPEND ${SKETCH_CPP} "\n//=== START Forward: ${SKETCH_SOURCE_PATH}\n") - foreach(SKETCH_PROTOTYPE ${SKETCH_PROTOTYPES}) - string(REPLACE "\n" " " SKETCH_PROTOTYPE "${SKETCH_PROTOTYPE}") - string(REPLACE "{" "" SKETCH_PROTOTYPE "${SKETCH_PROTOTYPE}") - arduino_debug_msg("\tprototype: ${SKETCH_PROTOTYPE};") - # " else if(var == other) {" shoudn't be listed as prototype - if(NOT SKETCH_PROTOTYPE MATCHES "(if[ ]?[\n]?[\t]*[ ]*[)])") - file(APPEND ${SKETCH_CPP} "${SKETCH_PROTOTYPE};\n") - else() - arduino_debug_msg("\trejected prototype: ${SKETCH_PROTOTYPE};") - endif() - file(APPEND ${SKETCH_CPP} "${SKETCH_PROTOTYPE};\n") - endforeach() - file(APPEND ${SKETCH_CPP} "//=== END Forward: ${SKETCH_SOURCE_PATH}\n") - endforeach() - - # Write Sketch CPP source - get_num_lines("${SKETCH_HEAD}" HEAD_NUM_LINES) - file(APPEND ${SKETCH_CPP} "#line ${HEAD_NUM_LINES} \"${MAIN_SKETCH_PATH}\"\n") - file(APPEND ${SKETCH_CPP} "\n${SKETCH_BODY}") - foreach (SKETCH_SOURCE_PATH ${SKETCH_SOURCES}) - file(READ ${SKETCH_SOURCE_PATH} SKETCH_SOURCE) - file(APPEND ${SKETCH_CPP} "\n//=== START : ${SKETCH_SOURCE_PATH}\n") - file(APPEND ${SKETCH_CPP} "#line 1 \"${SKETCH_SOURCE_PATH}\"\n") - file(APPEND ${SKETCH_CPP} "${SKETCH_SOURCE}") - file(APPEND ${SKETCH_CPP} "\n//=== END : ${SKETCH_SOURCE_PATH}\n") - endforeach() -endfunction() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# setup_arduino_size_script(OUTPUT_VAR) -# -# OUTPUT_VAR - Output variable that will contain the script path -# -# Generates script used to display the firmware size. -#=============================================================================# -function(SETUP_ARDUINO_SIZE_SCRIPT OUTPUT_VAR) - set(ARDUINO_SIZE_SCRIPT_PATH ${CMAKE_BINARY_DIR}/CMakeFiles/FirmwareSize.cmake) - - file(WRITE ${ARDUINO_SIZE_SCRIPT_PATH} " - set(AVRSIZE_PROGRAM ${AVRSIZE_PROGRAM}) - set(AVRSIZE_FLAGS -C --mcu=\${MCU}) - - execute_process(COMMAND \${AVRSIZE_PROGRAM} \${AVRSIZE_FLAGS} \${FIRMWARE_IMAGE} \${EEPROM_IMAGE} - OUTPUT_VARIABLE SIZE_OUTPUT) - - - string(STRIP \"\${SIZE_OUTPUT}\" RAW_SIZE_OUTPUT) - - # Convert lines into a list - string(REPLACE \"\\n\" \";\" SIZE_OUTPUT_LIST \"\${SIZE_OUTPUT}\") - - set(SIZE_OUTPUT_LINES) - foreach(LINE \${SIZE_OUTPUT_LIST}) - if(NOT \"\${LINE}\" STREQUAL \"\") - list(APPEND SIZE_OUTPUT_LINES \"\${LINE}\") - endif() - endforeach() - - function(EXTRACT LIST_NAME INDEX VARIABLE) - list(GET \"\${LIST_NAME}\" \${INDEX} RAW_VALUE) - string(STRIP \"\${RAW_VALUE}\" VALUE) - - set(\${VARIABLE} \"\${VALUE}\" PARENT_SCOPE) - endfunction() - function(PARSE INPUT VARIABLE_PREFIX) - if(\${INPUT} MATCHES \"([^:]+):[ \\t]*([0-9]+)[ \\t]*([^ \\t]+)[ \\t]*[(]([0-9.]+)%.*\") - set(ENTRY_NAME \${CMAKE_MATCH_1}) - set(ENTRY_SIZE \${CMAKE_MATCH_2}) - set(ENTRY_SIZE_TYPE \${CMAKE_MATCH_3}) - set(ENTRY_PERCENT \${CMAKE_MATCH_4}) - endif() - - set(\${VARIABLE_PREFIX}_NAME \${ENTRY_NAME} PARENT_SCOPE) - set(\${VARIABLE_PREFIX}_SIZE \${ENTRY_SIZE} PARENT_SCOPE) - set(\${VARIABLE_PREFIX}_SIZE_TYPE \${ENTRY_SIZE_TYPE} PARENT_SCOPE) - set(\${VARIABLE_PREFIX}_PERCENT \${ENTRY_PERCENT} PARENT_SCOPE) - endfunction() - - list(LENGTH SIZE_OUTPUT_LINES SIZE_OUTPUT_LENGTH) - #message(\"\${SIZE_OUTPUT_LINES}\") - #message(\"\${SIZE_OUTPUT_LENGTH}\") - if (\${SIZE_OUTPUT_LENGTH} STREQUAL 14) - EXTRACT(SIZE_OUTPUT_LINES 3 FIRMWARE_PROGRAM_SIZE_ROW) - EXTRACT(SIZE_OUTPUT_LINES 5 FIRMWARE_DATA_SIZE_ROW) - PARSE(FIRMWARE_PROGRAM_SIZE_ROW FIRMWARE_PROGRAM) - PARSE(FIRMWARE_DATA_SIZE_ROW FIRMWARE_DATA) - - set(FIRMWARE_STATUS \"Firmware Size: \") - set(FIRMWARE_STATUS \"\${FIRMWARE_STATUS} [\${FIRMWARE_PROGRAM_NAME}: \${FIRMWARE_PROGRAM_SIZE} \${FIRMWARE_PROGRAM_SIZE_TYPE} (\${FIRMWARE_PROGRAM_PERCENT}%)] \") - set(FIRMWARE_STATUS \"\${FIRMWARE_STATUS} [\${FIRMWARE_DATA_NAME}: \${FIRMWARE_DATA_SIZE} \${FIRMWARE_DATA_SIZE_TYPE} (\${FIRMWARE_DATA_PERCENT}%)]\") - set(FIRMWARE_STATUS \"\${FIRMWARE_STATUS} on \${MCU}\") - - EXTRACT(SIZE_OUTPUT_LINES 10 EEPROM_PROGRAM_SIZE_ROW) - EXTRACT(SIZE_OUTPUT_LINES 12 EEPROM_DATA_SIZE_ROW) - PARSE(EEPROM_PROGRAM_SIZE_ROW EEPROM_PROGRAM) - PARSE(EEPROM_DATA_SIZE_ROW EEPROM_DATA) - - set(EEPROM_STATUS \"EEPROM Size: \") - set(EEPROM_STATUS \"\${EEPROM_STATUS} [\${EEPROM_PROGRAM_NAME}: \${EEPROM_PROGRAM_SIZE} \${EEPROM_PROGRAM_SIZE_TYPE} (\${EEPROM_PROGRAM_PERCENT}%)] \") - set(EEPROM_STATUS \"\${EEPROM_STATUS} [\${EEPROM_DATA_NAME}: \${EEPROM_DATA_SIZE} \${EEPROM_DATA_SIZE_TYPE} (\${EEPROM_DATA_PERCENT}%)]\") - set(EEPROM_STATUS \"\${EEPROM_STATUS} on \${MCU}\") - - message(\"\${FIRMWARE_STATUS}\") - message(\"\${EEPROM_STATUS}\\n\") - - if(\$ENV{VERBOSE}) - message(\"\${RAW_SIZE_OUTPUT}\\n\") - elseif(\$ENV{VERBOSE_SIZE}) - message(\"\${RAW_SIZE_OUTPUT}\\n\") - endif() - else() - message(\"\${RAW_SIZE_OUTPUT}\") - endif() - ") - - set(${OUTPUT_VAR} ${ARDUINO_SIZE_SCRIPT_PATH} PARENT_SCOPE) -endfunction() - - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# arduino_debug_on() -# -# Enables Arduino module debugging. -#=============================================================================# -function(ARDUINO_DEBUG_ON) - set(ARDUINO_DEBUG True PARENT_SCOPE) -endfunction() - - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# arduino_debug_off() -# -# Disables Arduino module debugging. -#=============================================================================# -function(ARDUINO_DEBUG_OFF) - set(ARDUINO_DEBUG False PARENT_SCOPE) -endfunction() - - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# arduino_debug_msg(MSG) -# -# MSG - Message to print -# -# Print Arduino debugging information. In order to enable printing -# use arduino_debug_on() and to disable use arduino_debug_off(). -#=============================================================================# -function(ARDUINO_DEBUG_MSG MSG) - if(ARDUINO_DEBUG) - message("## ${MSG}") - endif() -endfunction() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# remove_comments(SRC_VAR OUT_VAR) -# -# SRC_VAR - variable holding sources -# OUT_VAR - variable holding sources with no comments -# -# Removes all comments from the source code. -#=============================================================================# -function(REMOVE_COMMENTS SRC_VAR OUT_VAR) - string(REGEX REPLACE "[\\./\\\\]" "_" FILE "${NAME}") - - set(SRC ${${SRC_VAR}}) - - #message(STATUS "removing comments from: ${FILE}") - #file(WRITE "${CMAKE_BINARY_DIR}/${FILE}_pre_remove_comments.txt" ${SRC}) - #message(STATUS "\n${SRC}") - - # remove all comments - string(REGEX REPLACE "([/][/][^\n]*)|([/][\\*]([^\\*]|([\\*]+[^/\\*]))*[\\*]+[/])" "" OUT "${SRC}") - - #file(WRITE "${CMAKE_BINARY_DIR}/${FILE}_post_remove_comments.txt" ${SRC}) - #message(STATUS "\n${SRC}") - - set(${OUT_VAR} ${OUT} PARENT_SCOPE) - -endfunction() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# get_num_lines(DOCUMENT OUTPUT_VAR) -# -# DOCUMENT - Document contents -# OUTPUT_VAR - Variable which will hold the line number count -# -# Counts the line number of the document. -#=============================================================================# -function(GET_NUM_LINES DOCUMENT OUTPUT_VAR) - string(REGEX MATCHALL "[\n]" MATCH_LIST "${DOCUMENT}") - list(LENGTH MATCH_LIST NUM) - set(${OUTPUT_VAR} ${NUM} PARENT_SCOPE) -endfunction() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# required_variables(MSG msg VARS var1 var2 .. varN) -# -# MSG - Message to be displayed in case of error -# VARS - List of variables names to check -# -# Ensure the specified variables are not empty, otherwise a fatal error is emmited. -#=============================================================================# -function(REQUIRED_VARIABLES) - cmake_parse_arguments(INPUT "" "MSG" "VARS" ${ARGN}) - error_for_unparsed(INPUT) - foreach(VAR ${INPUT_VARS}) - if ("${${VAR}}" STREQUAL "") - message(FATAL_ERROR "${VAR} not set: ${INPUT_MSG}") - endif() - endforeach() -endfunction() - -#=============================================================================# -# [PRIVATE/INTERNAL] -# -# error_for_unparsed(PREFIX) -# -# PREFIX - Prefix name -# -# Emit fatal error if there are unparsed argument from cmake_parse_arguments(). -#=============================================================================# -function(ERROR_FOR_UNPARSED PREFIX) - set(ARGS "${${PREFIX}_UNPARSED_ARGUMENTS}") - if (NOT ( "${ARGS}" STREQUAL "") ) - message(FATAL_ERROR "unparsed argument: ${ARGS}") - endif() -endfunction() - - - - - - -#=============================================================================# -# C Flags -#=============================================================================# -if (NOT DEFINED ARDUINO_C_FLAGS) - set(ARDUINO_C_FLAGS "-mcall-prologues -ffunction-sections -fdata-sections") -endif (NOT DEFINED ARDUINO_C_FLAGS) -set(CMAKE_C_FLAGS "-g -Os ${ARDUINO_C_FLAGS}" CACHE STRING "") -set(CMAKE_C_FLAGS_DEBUG "-g ${ARDUINO_C_FLAGS}" CACHE STRING "") -set(CMAKE_C_FLAGS_MINSIZEREL "-Os -DNDEBUG ${ARDUINO_C_FLAGS}" CACHE STRING "") -set(CMAKE_C_FLAGS_RELEASE "-Os -DNDEBUG -w ${ARDUINO_C_FLAGS}" CACHE STRING "") -set(CMAKE_C_FLAGS_RELWITHDEBINFO "-Os -g -w ${ARDUINO_C_FLAGS}" CACHE STRING "") - -#=============================================================================# -# C++ Flags -#=============================================================================# -if (NOT DEFINED ARDUINO_CXX_FLAGS) - set(ARDUINO_CXX_FLAGS "${ARDUINO_C_FLAGS} -fno-exceptions") -endif (NOT DEFINED ARDUINO_CXX_FLAGS) -set(CMAKE_CXX_FLAGS "-g -Os ${ARDUINO_CXX_FLAGS}" CACHE STRING "") -set(CMAKE_CXX_FLAGS_DEBUG "-g ${ARDUINO_CXX_FLAGS}" CACHE STRING "") -set(CMAKE_CXX_FLAGS_MINSIZEREL "-Os -DNDEBUG ${ARDUINO_CXX_FLAGS}" CACHE STRING "") -set(CMAKE_CXX_FLAGS_RELEASE "-Os -DNDEBUG ${ARDUINO_CXX_FLAGS}" CACHE STRING "") -set(CMAKE_CXX_FLAGS_RELWITHDEBINFO "-Os -g ${ARDUINO_CXX_FLAGS}" CACHE STRING "") - -#=============================================================================# -# Executable Linker Flags # -#=============================================================================# -set(ARDUINO_LINKER_FLAGS "-Wl,--gc-sections -lm") -set(CMAKE_EXE_LINKER_FLAGS "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_EXE_LINKER_FLAGS_DEBUG "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_EXE_LINKER_FLAGS_MINSIZEREL "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_EXE_LINKER_FLAGS_RELEASE "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") - -#=============================================================================# -#=============================================================================# -# Shared Lbrary Linker Flags # -#=============================================================================# -set(CMAKE_SHARED_LINKER_FLAGS "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_SHARED_LINKER_FLAGS_DEBUG "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_SHARED_LINKER_FLAGS_RELEASE "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") - -set(CMAKE_MODULE_LINKER_FLAGS "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_MODULE_LINKER_FLAGS_DEBUG "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_MODULE_LINKER_FLAGS_RELEASE "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") -set(CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") - - -#=============================================================================# -# Arduino Settings -#=============================================================================# -set(ARDUINO_OBJCOPY_EEP_FLAGS -O ihex -j .eeprom --set-section-flags=.eeprom=alloc,load - --no-change-warnings --change-section-lma .eeprom=0 CACHE STRING "") -set(ARDUINO_OBJCOPY_HEX_FLAGS -O ihex -R .eeprom CACHE STRING "") -set(ARDUINO_AVRDUDE_FLAGS -V CACHE STRING "") - -#=============================================================================# -# Initialization -#=============================================================================# -if(NOT ARDUINO_FOUND AND ARDUINO_SDK_PATH) - register_hardware_platform(${ARDUINO_SDK_PATH}/hardware/arduino/) - - find_file(ARDUINO_LIBRARIES_PATH - NAMES libraries - PATHS ${ARDUINO_SDK_PATH} - DOC "Path to directory containing the Arduino libraries.") - - find_file(ARDUINO_VERSION_PATH - NAMES lib/version.txt - PATHS ${ARDUINO_SDK_PATH} - DOC "Path to Arduino version file.") - - find_program(ARDUINO_AVRDUDE_PROGRAM - NAMES avrdude - PATHS ${ARDUINO_SDK_PATH} - PATH_SUFFIXES hardware/tools hardware/tools/avr/bin - NO_DEFAULT_PATH) - - find_program(ARDUINO_AVRDUDE_PROGRAM - NAMES avrdude - DOC "Path to avrdude programmer binary.") - - find_program(AVRSIZE_PROGRAM - NAMES avr-size) - - find_file(ARDUINO_AVRDUDE_CONFIG_PATH - NAMES avrdude.conf - PATHS ${ARDUINO_SDK_PATH} /etc/avrdude /etc - PATH_SUFFIXES hardware/tools - hardware/tools/avr/etc - DOC "Path to avrdude programmer configuration file.") - - if(NOT CMAKE_OBJCOPY) - find_program(AVROBJCOPY_PROGRAM - avr-objcopy) - set(ADDITIONAL_REQUIRED_VARS AVROBJCOPY_PROGRAM) - set(CMAKE_OBJCOPY ${AVROBJCOPY_PROGRAM}) - endif(NOT CMAKE_OBJCOPY) - - set(ARDUINO_DEFAULT_BOARD uno CACHE STRING "Default Arduino Board ID when not specified.") - set(ARDUINO_DEFAULT_PORT CACHE STRING "Default Arduino port when not specified.") - set(ARDUINO_DEFAULT_SERIAL CACHE STRING "Default Arduino Serial command when not specified.") - set(ARDUINO_DEFAULT_PROGRAMMER CACHE STRING "Default Arduino Programmer ID when not specified.") - - # Ensure that all required paths are found - required_variables(VARS - ARDUINO_PLATFORMS - ARDUINO_CORES_PATH - ARDUINO_BOOTLOADERS_PATH - ARDUINO_LIBRARIES_PATH - ARDUINO_BOARDS_PATH - ARDUINO_PROGRAMMERS_PATH - ARDUINO_VERSION_PATH - ARDUINO_AVRDUDE_FLAGS - ARDUINO_AVRDUDE_PROGRAM - ARDUINO_AVRDUDE_CONFIG_PATH - AVRSIZE_PROGRAM - ${ADDITIONAL_REQUIRED_VARS} - MSG "Invalid Arduino SDK path (${ARDUINO_SDK_PATH}).\n") - - detect_arduino_version(ARDUINO_SDK_VERSION) - set(ARDUINO_SDK_VERSION ${ARDUINO_SDK_VERSION} CACHE STRING "Arduino SDK Version") - set(ARDUINO_SDK_VERSION_MAJOR ${ARDUINO_SDK_VERSION_MAJOR} CACHE STRING "Arduino SDK Major Version") - set(ARDUINO_SDK_VERSION_MINOR ${ARDUINO_SDK_VERSION_MINOR} CACHE STRING "Arduino SDK Minor Version") - set(ARDUINO_SDK_VERSION_PATCH ${ARDUINO_SDK_VERSION_PATCH} CACHE STRING "Arduino SDK Patch Version") - - if(ARDUINO_SDK_VERSION VERSION_LESS 0.19) - message(FATAL_ERROR "Unsupported Arduino SDK (require verion 0.19 or higher)") - endif() - - message(STATUS "Arduino SDK version ${ARDUINO_SDK_VERSION}: ${ARDUINO_SDK_PATH}") - - setup_arduino_size_script(ARDUINO_SIZE_SCRIPT) - set(ARDUINO_SIZE_SCRIPT ${ARDUINO_SIZE_SCRIPT} CACHE INTERNAL "Arduino Size Script") - - #print_board_list() - #print_programmer_list() - - set(ARDUINO_FOUND True CACHE INTERNAL "Arduino Found") - mark_as_advanced( - ARDUINO_CORES_PATH - ARDUINO_VARIANTS_PATH - ARDUINO_BOOTLOADERS_PATH - ARDUINO_LIBRARIES_PATH - ARDUINO_BOARDS_PATH - ARDUINO_PROGRAMMERS_PATH - ARDUINO_VERSION_PATH - ARDUINO_AVRDUDE_FLAGS - ARDUINO_AVRDUDE_PROGRAM - ARDUINO_AVRDUDE_CONFIG_PATH - ARDUINO_OBJCOPY_EEP_FLAGS - ARDUINO_OBJCOPY_HEX_FLAGS - AVRSIZE_PROGRAM) -endif() +set(IS_SCRIPT_PROCESSED True) diff --git a/firmware/common/toolchain/Platform/Core/BoardFlags/CompilerFlagsSetter.cmake b/firmware/common/toolchain/Platform/Core/BoardFlags/CompilerFlagsSetter.cmake new file mode 100644 index 00000000..fd7c58a6 --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/BoardFlags/CompilerFlagsSetter.cmake @@ -0,0 +1,36 @@ +# ToDo: Comment +function(set_board_compiler_flags COMPILER_FLAGS NORMALIZED_SDK_VERSION BOARD_ID IS_MANUAL) + + _get_board_property(${BOARD_ID} build.f_cpu FCPU) + _get_board_property(${BOARD_ID} build.mcu MCU) + set(COMPILE_FLAGS "-DF_CPU=${FCPU} -DARDUINO=${NORMALIZED_SDK_VERSION} -mmcu=${MCU}") + + _try_get_board_property(${BOARD_ID} build.vid VID) + _try_get_board_property(${BOARD_ID} build.pid PID) + if (VID) + set(COMPILE_FLAGS "${COMPILE_FLAGS} -DUSB_VID=${VID}") + endif () + if (PID) + set(COMPILE_FLAGS "${COMPILE_FLAGS} -DUSB_PID=${PID}") + endif () + + if (NOT IS_MANUAL) + _get_board_property(${BOARD_ID} build.core BOARD_CORE) + set(COMPILE_FLAGS "${COMPILE_FLAGS} -I\"${${BOARD_CORE}.path}\" -I\"${ARDUINO_LIBRARIES_PATH}\"") + if (${ARDUINO_PLATFORM_LIBRARIES_PATH}) + set(COMPILE_FLAGS "${COMPILE_FLAGS} -I\"${ARDUINO_PLATFORM_LIBRARIES_PATH}\"") + endif () + endif () + if (ARDUINO_SDK_VERSION VERSION_GREATER 1.0 OR ARDUINO_SDK_VERSION VERSION_EQUAL 1.0) + if (NOT IS_MANUAL) + _get_board_property(${BOARD_ID} build.variant VARIANT) + set(PIN_HEADER ${${VARIANT}.path}) + if (PIN_HEADER) + set(COMPILE_FLAGS "${COMPILE_FLAGS} -I\"${PIN_HEADER}\"") + endif () + endif () + endif () + + set(${COMPILER_FLAGS} "${COMPILE_FLAGS}" PARENT_SCOPE) + +endfunction() diff --git a/firmware/common/toolchain/Platform/Core/BoardFlags/FlagsSetter.cmake b/firmware/common/toolchain/Platform/Core/BoardFlags/FlagsSetter.cmake new file mode 100644 index 00000000..de0f97a9 --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/BoardFlags/FlagsSetter.cmake @@ -0,0 +1,103 @@ +include(CompilerFlagsSetter) +include(LinkerFlagsSetter) + +#=============================================================================# +# set_board_flags +# [PRIVATE/INTERNAL] +# +# set_board_flags(COMPILER_FLAGS LINKER_FLAGS BOARD_ID IS_MANUAL) +# +# COMPILER_FLAGS - Variable holding compiler flags +# LINKER_FLAGS - Variable holding linker flags +# BOARD_ID - The board id name +# IS_MANUAL - (Advanced) Only use AVR Libc/Includes +# +# Configures the build settings for the specified Arduino Board. +# +#=============================================================================# +function(set_board_flags COMPILER_FLAGS LINKER_FLAGS BOARD_ID IS_MANUAL) + + _get_board_property(${BOARD_ID} build.core BOARD_CORE) + if (BOARD_CORE) + _get_normalized_sdk_version(NORMALIZED_SDK_VERSION) + + set_board_compiler_flags(COMPILE_FLAGS ${NORMALIZED_SDK_VERSION} ${BOARD_ID} ${IS_MANUAL}) + set_board_linker_flags(LINK_FLAGS ${BOARD_ID} ${IS_MANUAL}) + + # output + set(${COMPILER_FLAGS} "${COMPILE_FLAGS}" PARENT_SCOPE) + set(${LINKER_FLAGS} "${LINK_FLAGS}" PARENT_SCOPE) + + else () + message(FATAL_ERROR "Invalid Arduino board ID (${BOARD_ID}), aborting.") + endif () + +endfunction() + +#=============================================================================# +# _get_normalized_sdk_version +# [PRIVATE/INTERNAL] +# +# _get_normalized_sdk_version(OUTPUT_VAR) +# +# OUTPUT_VAR - Returned variable storing the normalized version +# +# Normalizes SDK's version for a proper use of the '-DARDUINO' compile flag. +# Note that there are differences between normalized versions in specific SDK versions: +# SDK Version 1.5.8 and above - Appends zeros to version parts. +# e.g Version 1.6.5 will be normalized as 10605 +# SDK Versions between 1.0.0 and 1.5.8 - Joins all version parts together. +# e.g Version 1.5.3 will be normalized as 153 +# SDK Version 1.0.0 and below - Uses only the 'Minor' version part. +# e.g Version 0.20.0 will be normalized as 20 +# +#=============================================================================# +function(_get_normalized_sdk_version OUTPUT_VAR) + + if (${ARDUINO_SDK_VERSION} VERSION_GREATER 1.5.8) + # -DARDUINO format has changed since 1.6.0 by appending zeros when required, + # e.g for 1.6.5 version -DARDUINO=10605 + _append_suffix_zero_to_version_if_required(${ARDUINO_SDK_VERSION_MAJOR} 10 MAJOR_VERSION) + _append_suffix_zero_to_version_if_required(${ARDUINO_SDK_VERSION_MINOR} 10 MINOR_VERSION) + set(NORMALIZED_VERSION + "${MAJOR_VERSION}${MINOR_VERSION}${ARDUINO_SDK_VERSION_PATCH}") + else () + # -DARDUINO format before 1.0.0 uses only minor version, + # e.g. for 0020 version -DARDUINO=20 + if (${ARDUINO_SDK_VERSION} VERSION_LESS 1.0.0) + set(NORMALIZED_VERSION "${ARDUINO_SDK_VERSION_MINOR}") + else () + # -DARDUINO format after 1.0.0 combines all 3 version parts together, + # e.g. for 1.5.3 version -DARDUINO=153 + set(NORMALIZED_VERSION + "${ARDUINO_SDK_VERSION_MAJOR}${ARDUINO_SDK_VERSION_MINOR}${ARDUINO_SDK_VERSION_PATCH}") + endif () + endif () + + set(${OUTPUT_VAR} ${NORMALIZED_VERSION} PARENT_SCOPE) + +endfunction() + +#=============================================================================# +# _append_suffix_zero_to_version_if_required +# [PRIVATE/INTERNAL] +# +# _append_suffix_zero_to_version_if_required(VERSION_PART VERSION_LIMIT OUTPUT_VAR) +# +# VERSION_PART - Version to check and possibly append to. +# Must be a version part - Major, Minor or Patch. +# VERSION_LIMIT - Append limit. For a version greater than this number +# a zero will NOT be appended. +# OUTPUT_VAR - Returned variable storing the normalized version. +# +# Appends a suffic zero to the given version part if it's below than the given limit. +# Otherwise, the version part is returned as it is. +# +#=============================================================================# +macro(_append_suffix_zero_to_version_if_required VERSION_PART VERSION_LIMIT OUTPUT_VAR) + if (${VERSION_PART} LESS ${VERSION_LIMIT}) + set(${OUTPUT_VAR} "${VERSION_PART}0") + else () + set(${OUTPUT_VAR} "${VERSION_PART}") + endif () +endmacro() diff --git a/firmware/common/toolchain/Platform/Core/BoardFlags/LinkerFlagsSetter.cmake b/firmware/common/toolchain/Platform/Core/BoardFlags/LinkerFlagsSetter.cmake new file mode 100644 index 00000000..6b416cd0 --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/BoardFlags/LinkerFlagsSetter.cmake @@ -0,0 +1,8 @@ +# ToDo: Comment +function(set_board_linker_flags LINKER_FLAGS BOARD_ID IS_MANUAL) + + _get_board_property(${BOARD_ID} build.mcu MCU) + set(LINK_FLAGS "-mmcu=${MCU}") + set(${LINKER_FLAGS} "${LINK_FLAGS}" PARENT_SCOPE) + +endfunction() diff --git a/firmware/common/toolchain/Platform/Core/BoardPropertiesReader.cmake b/firmware/common/toolchain/Platform/Core/BoardPropertiesReader.cmake new file mode 100644 index 00000000..76f752f5 --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/BoardPropertiesReader.cmake @@ -0,0 +1,89 @@ +#=============================================================================# +# _get_board_id +# [PRIVATE/INTERNAL] +# +# _get_board_id(BOARD_NAME BOARD_CPU TARGET_NAME OUTPUT_VAR) +# +# BOARD_NAME - name of the board, eg.: nano, uno, etc... +# BOARD_CPU - come boards has multiple versions with different cpus, eg.: nano has atmega168 and atmega328 +# TARGET_NAME - name of the build target, used to show clearer error message +# OUT_VAR - BOARD_ID constructed from BOARD_NAME and BOARD_CPU +# +# returns BOARD_ID constructing from BOARD_NAME and BOARD_CPU, if board doesn't has multiple cpus then BOARD_ID = BOARD_NAME +# if board has multiple CPUS, and BOARD_CPU is not defined or incorrect, fatal error will be invoked. +#=============================================================================# +function(_GET_BOARD_ID BOARD_NAME BOARD_CPU TARGET_NAME OUTPUT_VAR) + if (${BOARD_NAME}.menu.CPUS) + if (BOARD_CPU) + LIST(FIND ${BOARD_NAME}.menu.CPUS ${BOARD_CPU} CPU_INDEX) + if (CPU_INDEX EQUAL -1) + message(FATAL_ERROR "Invalid BOARD_CPU (valid cpus: ${${BOARD_NAME}.menu.CPUS}).") + endif() + else() + message(FATAL_ERROR "Board has multiple CPU versions (${${BOARD_NAME}.menu.CPUS}). BOARD_CPU must be defined for target ${TARGET_NAME}.") + endif() + set(${OUTPUT_VAR} ${BOARD_NAME}.${BOARD_CPU} PARENT_SCOPE) + else() + set(${OUTPUT_VAR} ${BOARD_NAME} PARENT_SCOPE) + endif() +endfunction() + +#=============================================================================# +# _get_board_property +# [PRIVATE/INTERNAL] +# +# _get_board_property(BOARD_ID PROPERTY_NAME OUTPUT_VAR) +# +# BOARD_ID - return value from function "_get_board_id (BOARD_NAME, BOARD_CPU)". It contains BOARD_NAME and BOARD_CPU +# PROPERTY_NAME - property name for the board, eg.: bootloader.high_fuses +# OUT_VAR - variable holding value for the property +# +# Gets board property. +# Reconstructs BOARD_NAME and BOARD_CPU from BOARD_ID and tries to find value at ${BOARD_NAME}.${PROPERTY_NAME}, +# if not found than try to find value at ${BOARD_NAME}.menu.cpu.${BOARD_CPU}.${PROPERTY_NAME} +# if not found that show fatal error +#=============================================================================# +function(_GET_BOARD_PROPERTY BOARD_ID PROPERTY_NAME OUTPUT_VAR) + string(REPLACE "." ";" BOARD_INFO ${BOARD_ID}) + list(GET BOARD_INFO 0 BOARD_NAME) + set(VALUE ${${BOARD_NAME}.${PROPERTY_NAME}}) + if(NOT VALUE) + list(LENGTH BOARD_INFO INFO_PARAMS_COUNT) + if (${INFO_PARAMS_COUNT} EQUAL 2) + list(GET BOARD_INFO 1 BOARD_CPU) + VALIDATE_VARIABLES_NOT_EMPTY(VARS BOARD_CPU MSG "cannot find CPU info, must define BOARD_CPU.") + set(VALUE ${${BOARD_NAME}.menu.cpu.${BOARD_CPU}.${PROPERTY_NAME}}) + endif() + endif() + if (NOT VALUE) + message(FATAL_ERROR "Board info not found: BoardName='${BOARD_NAME}' BoardCPU='${BOARD_CPU}' PropertyName='${PROPERTY_NAME}'") + endif() + set(${OUTPUT_VAR} ${VALUE} PARENT_SCOPE) +endfunction() + +#=============================================================================# +# _get_board_property_if_exists +# [PRIVATE/INTERNAL] +# +# _get_board_property_if_exists(BOARD_ID PROPERTY_NAME OUTPUT_VAR) +# +# BOARD_ID - return value from function "_get_board_id (BOARD_NAME, BOARD_CPU)". It contains BOARD_NAME and BOARD_CPU +# PROPERTY_NAME - property name for the board, eg.: bootloader.high_fuses +# OUT_VAR - variable holding value for the property +# +# Similar to _get_board_property, except it returns empty value if value was not found. +#=============================================================================# +function(_try_get_board_property BOARD_ID PROPERTY_NAME OUTPUT_VAR) + string(REPLACE "." ";" BOARD_INFO ${BOARD_ID}) + list(GET BOARD_INFO 0 BOARD_NAME) + set(VALUE ${${BOARD_NAME}.${PROPERTY_NAME}}) + if(NOT VALUE) + list(LENGTH BOARD_INFO INFO_PARAMS_COUNT) + if (${INFO_PARAMS_COUNT} EQUAL 2) + list(GET BOARD_INFO 1 BOARD_CPU) + VALIDATE_VARIABLES_NOT_EMPTY(VARS BOARD_CPU MSG "cannot find CPU info, must define BOARD_CPU.") + set(VALUE ${${BOARD_NAME}.menu.cpu.${BOARD_CPU}.${PROPERTY_NAME}}) + endif() + endif() + set(${OUTPUT_VAR} ${VALUE} PARENT_SCOPE) +endfunction() diff --git a/firmware/common/toolchain/Platform/Core/Examples/ArduinoExampleFactory.cmake b/firmware/common/toolchain/Platform/Core/Examples/ArduinoExampleFactory.cmake new file mode 100644 index 00000000..0991cd77 --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/Examples/ArduinoExampleFactory.cmake @@ -0,0 +1,70 @@ +#=============================================================================# +# make_arduino_example +# [PRIVATE/INTERNAL] +# +# make_arduino_example(TARGET_NAME EXAMPLE_NAME OUTPUT_VAR [CATEGORY_NAME]) +# +# TARGET_NAME - Target name +# EXAMPLE_NAME - Example name +# OUTPUT_VAR - Variable name to save sketch path. +# [CATEGORY_NAME] - Optional name of the example's parent category, such as 'Basics' is for 'Blink'. +# +# Creates an Arduino example from the built-in categories. +#=============================================================================# +function(make_arduino_example TARGET_NAME EXAMPLE_NAME OUTPUT_VAR) + + set(OPTIONAL_ARGUMENTS ${ARGN}) + list(LENGTH OPTIONAL_ARGUMENTS ARGC) + if (${ARGC} GREATER 0) + list(GET OPTIONAL_ARGUMENTS 0 CATEGORY_NAME) + endif () + + # Case-insensitive support + string(TOLOWER ${EXAMPLE_NAME} EXAMPLE_NAME) + + if (CATEGORY_NAME) + string(TOLOWER ${CATEGORY_NAME} LOWER_CATEGORY_NAME) + list(FIND ARDUINO_EXAMPLE_CATEGORIES ${LOWER_CATEGORY_NAME} CATEGORY_INDEX) + if (${CATEGORY_INDEX} LESS 0) + message(SEND_ERROR "${CATEGORY_NAME} example category doesn't exist, please check your spelling") + return() + endif () + INCREMENT_EXAMPLE_CATEGORY_INDEX(CATEGORY_INDEX) + set(CATEGORY_NAME ${CATEGORY_INDEX}.${CATEGORY_NAME}) + file(GLOB EXAMPLES RELATIVE ${ARDUINO_EXAMPLES_PATH}/${CATEGORY_NAME} + ${ARDUINO_EXAMPLES_PATH}/${CATEGORY_NAME}/*) + foreach (EXAMPLE_PATH ${EXAMPLES}) + string(TOLOWER ${EXAMPLE_PATH} LOWER_EXAMPLE_PATH) + if (${LOWER_EXAMPLE_PATH} STREQUAL ${EXAMPLE_NAME}) + set(EXAMPLE_SKETCH_PATH + "${ARDUINO_EXAMPLES_PATH}/${CATEGORY_NAME}/${EXAMPLE_PATH}") + break() + endif () + endforeach () + + else () + + file(GLOB CATEGORIES RELATIVE ${ARDUINO_EXAMPLES_PATH} ${ARDUINO_EXAMPLES_PATH}/*) + foreach (CATEGORY_PATH ${CATEGORIES}) + file(GLOB EXAMPLES RELATIVE ${ARDUINO_EXAMPLES_PATH}/${CATEGORY_PATH} + ${ARDUINO_EXAMPLES_PATH}/${CATEGORY_PATH}/*) + foreach (EXAMPLE_PATH ${EXAMPLES}) + string(TOLOWER ${EXAMPLE_PATH} LOWER_EXAMPLE_PATH) + if (${LOWER_EXAMPLE_PATH} STREQUAL ${EXAMPLE_NAME}) + set(EXAMPLE_SKETCH_PATH + "${ARDUINO_EXAMPLES_PATH}/${CATEGORY_PATH}/${EXAMPLE_PATH}") + break() + endif () + endforeach () + endforeach () + + endif () + + if (EXAMPLE_SKETCH_PATH) + make_arduino_sketch(${TARGET_NAME} ${EXAMPLE_SKETCH_PATH} SKETCH_CPP) + set("${OUTPUT_VAR}" ${${OUTPUT_VAR}} ${SKETCH_CPP} PARENT_SCOPE) + else () + message(FATAL_ERROR "Could not find example ${EXAMPLE_NAME}") + endif () + +endfunction() diff --git a/firmware/common/toolchain/Platform/Core/Examples/ArduinoLibraryExampleFactory.cmake b/firmware/common/toolchain/Platform/Core/Examples/ArduinoLibraryExampleFactory.cmake new file mode 100644 index 00000000..0df094fa --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/Examples/ArduinoLibraryExampleFactory.cmake @@ -0,0 +1,35 @@ +#=============================================================================# +# make_arduino_library_example +# [PRIVATE/INTERNAL] +# +# make_arduino_library_example(TARGET_NAME LIBRARY_NAME EXAMPLE_NAME OUTPUT_VAR) +# +# TARGET_NAME - Target name +# LIBRARY_NAME - Library name +# EXAMPLE_NAME - Example name +# OUTPUT_VAR - Variable name to save sketch path. +# +# Creates a Arduino example from the specified library. +#=============================================================================# +function(make_arduino_library_example TARGET_NAME LIBRARY_NAME EXAMPLE_NAME OUTPUT_VAR) + set(EXAMPLE_SKETCH_PATH) + + get_property(LIBRARY_SEARCH_PATH + DIRECTORY # Property Scope + PROPERTY LINK_DIRECTORIES) + foreach (LIB_SEARCH_PATH ${LIBRARY_SEARCH_PATH} ${ARDUINO_LIBRARIES_PATH} + ${ARDUINO_PLATFORM_LIBRARIES_PATH} ${CMAKE_CURRENT_SOURCE_DIR} + ${CMAKE_CURRENT_SOURCE_DIR}/libraries) + if (EXISTS "${LIB_SEARCH_PATH}/${LIBRARY_NAME}/examples/${EXAMPLE_NAME}") + set(EXAMPLE_SKETCH_PATH "${LIB_SEARCH_PATH}/${LIBRARY_NAME}/examples/${EXAMPLE_NAME}") + break() + endif () + endforeach () + + if (EXAMPLE_SKETCH_PATH) + make_arduino_sketch(${TARGET_NAME} ${EXAMPLE_SKETCH_PATH} SKETCH_CPP) + set("${OUTPUT_VAR}" ${${OUTPUT_VAR}} ${SKETCH_CPP} PARENT_SCOPE) + else () + message(FATAL_ERROR "Could not find example ${EXAMPLE_NAME} from library ${LIBRARY_NAME}") + endif () +endfunction() diff --git a/firmware/common/toolchain/Platform/Core/Libraries/ArduinoLibraryFactory.cmake b/firmware/common/toolchain/Platform/Core/Libraries/ArduinoLibraryFactory.cmake new file mode 100644 index 00000000..2dd392f3 --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/Libraries/ArduinoLibraryFactory.cmake @@ -0,0 +1,112 @@ +#=============================================================================# +# make_arduino_library +# [PRIVATE/INTERNAL] +# +# make_arduino_library(VAR_NAME BOARD_ID LIB_PATH COMPILE_FLAGS LINK_FLAGS) +# +# VAR_NAME - Vairable wich will hold the generated library names +# BOARD_ID - Board ID +# LIB_PATH - Path of the library +# COMPILE_FLAGS - Compile flags +# LINK_FLAGS - Link flags +# +# Creates an Arduino library, with all it's library dependencies. +# +# ${LIB_NAME}_RECURSE controls if the library will recurse +# when looking for source files. +# +#=============================================================================# +function(make_arduino_library VAR_NAME BOARD_ID LIB_PATH COMPILE_FLAGS LINK_FLAGS) + + string(REGEX REPLACE "/src/?$" "" LIB_PATH_STRIPPED ${LIB_PATH}) + get_filename_component(LIB_NAME ${LIB_PATH_STRIPPED} NAME) + set(TARGET_LIB_NAME ${BOARD_ID}_${LIB_NAME}) + + if (NOT TARGET ${TARGET_LIB_NAME}) + string(REGEX REPLACE ".*/" "" LIB_SHORT_NAME ${LIB_NAME}) + + # Detect if recursion is needed + if (NOT DEFINED ${LIB_SHORT_NAME}_RECURSE) + set(${LIB_SHORT_NAME}_RECURSE ${ARDUINO_CMAKE_RECURSION_DEFAULT}) + endif () + + find_sources(LIB_SRCS ${LIB_PATH} ${${LIB_SHORT_NAME}_RECURSE}) + if (LIB_SRCS) + + arduino_debug_msg("Generating Arduino ${LIB_NAME} library") + add_library(${TARGET_LIB_NAME} STATIC ${LIB_SRCS}) + + set_board_flags(ARDUINO_COMPILE_FLAGS ARDUINO_LINK_FLAGS ${BOARD_ID} FALSE) + + find_arduino_libraries(LIB_DEPS "${LIB_SRCS}" "") + + foreach (LIB_DEP ${LIB_DEPS}) + make_arduino_library(DEP_LIB_SRCS ${BOARD_ID} ${LIB_DEP} + "${COMPILE_FLAGS}" "${LINK_FLAGS}") + list(APPEND LIB_TARGETS ${DEP_LIB_SRCS}) + list(APPEND LIB_INCLUDES ${DEP_LIB_SRCS_INCLUDES}) + endforeach () + + if (LIB_INCLUDES) + string(REPLACE ";" " " LIB_INCLUDES_SPACE_SEPARATED "${LIB_INCLUDES}") + endif () + + set_target_properties(${TARGET_LIB_NAME} PROPERTIES + COMPILE_FLAGS "${ARDUINO_COMPILE_FLAGS} ${LIB_INCLUDES_SPACE_SEPARATED} -I\"${LIB_PATH}\" -I\"${LIB_PATH}/utility\" ${COMPILE_FLAGS}" + LINK_FLAGS "${ARDUINO_LINK_FLAGS} ${LINK_FLAGS}") + list(APPEND LIB_INCLUDES "-I\"${LIB_PATH}\";-I\"${LIB_PATH}/utility\"") + + if (LIB_TARGETS) + list(REMOVE_ITEM LIB_TARGETS ${TARGET_LIB_NAME}) + endif () + + target_link_libraries(${TARGET_LIB_NAME} ${BOARD_ID}_CORE ${LIB_TARGETS}) + list(APPEND LIB_TARGETS ${TARGET_LIB_NAME}) + + endif () + + else () + # Target already exists, skiping creating + list(APPEND LIB_TARGETS ${TARGET_LIB_NAME}) + list(APPEND LIB_INCLUDES "-I\"${LIB_PATH}\"") + endif () + + if (LIB_TARGETS) + list(REMOVE_DUPLICATES LIB_TARGETS) + endif () + if (LIB_INCLUDES) + list(REMOVE_DUPLICATES LIB_INCLUDES) + endif () + + set(${VAR_NAME} ${LIB_TARGETS} PARENT_SCOPE) + set(${VAR_NAME}_INCLUDES ${LIB_INCLUDES} PARENT_SCOPE) + +endfunction() + +#=============================================================================# +# make_arduino_libraries +# [PRIVATE/INTERNAL] +# +# make_arduino_libraries(VAR_NAME BOARD_ID SRCS COMPILE_FLAGS LINK_FLAGS) +# +# VAR_NAME - Vairable wich will hold the generated library names +# BOARD_ID - Board ID +# SRCS - source files +# COMPILE_FLAGS - Compile flags +# LINK_FLAGS - Linker flags +# +# Finds and creates all dependency libraries based on sources. +# +#=============================================================================# +function(make_arduino_libraries VAR_NAME BOARD_ID SRCS ARDLIBS COMPILE_FLAGS LINK_FLAGS) + foreach (TARGET_LIB ${ARDLIBS}) + # Create static library instead of returning sources + make_arduino_library(LIB_DEPS ${BOARD_ID} ${TARGET_LIB} + "${COMPILE_FLAGS}" "${LINK_FLAGS}") + list(APPEND LIB_TARGETS ${LIB_DEPS}) + list(APPEND LIB_INCLUDES ${LIB_DEPS_INCLUDES}) + endforeach () + + set(${VAR_NAME} ${LIB_TARGETS} PARENT_SCOPE) + set(${VAR_NAME}_INCLUDES ${LIB_INCLUDES} PARENT_SCOPE) +endfunction() diff --git a/firmware/common/toolchain/Platform/Core/Libraries/BlacklistedLibrariesRemover.cmake b/firmware/common/toolchain/Platform/Core/Libraries/BlacklistedLibrariesRemover.cmake new file mode 100644 index 00000000..6bf27eb8 --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/Libraries/BlacklistedLibrariesRemover.cmake @@ -0,0 +1,34 @@ +#=============================================================================# +# _REMOVE_BLACKLISTED_LIBRARIES +# [PRIVATE/INTERNAL] +# +# _REMOVE_BLACKLISTED_LIBRARIES(LIBRARY_LIST OUTPUT_VAR) +# +# LIBRARY_LIST - List of libraries to remove blacklisted libraries from +# OUTPUT_VAR - Original list of libraries without blacklisted libraries. +# +# Returns a list of libraries without blacklisted libraries. +# +# Arduino-CMake looks for Arduino libraries whose names match those of include files encountered. +# Under certain circumstances this leads to undesired behavior. +# An example is an include file 'Keyboard.h' in a project that has no relation to +# Arduino's standard Keyboard library. +# To prevent the standard library from being falsely added to the list of libraries to build, +# this function removes all blacklisted libraries from the source list, which contains +# all the included libraries found in the search process. +# In the example above the blacklisted and remove library would be +# ${ARDUINO_SDK_PATH}/libraries/Keyboard/src). +# +function(_REMOVE_BLACKLISTED_LIBRARIES LIBRARY_LIST OUTPUT_VAR) + set(NEW_LIBS) + foreach (LIB ${LIBRARY_LIST}) + list(FIND ARDUINO_LIBRARY_BLACKLIST "${LIB}" BLACKLISTED_LIB_INDEX) + if (NOT ${BLACKLISTED_LIB_INDEX} GREATER -1) + list(APPEND NEW_LIBS "${LIB}") + else () + ARDUINO_DEBUG_MSG("Suppressing blacklisted library ${LIB}") + endif () + endforeach () + + set("${OUTPUT_VAR}" "${NEW_LIBS}" PARENT_SCOPE) +endfunction() \ No newline at end of file diff --git a/firmware/common/toolchain/Platform/Core/Libraries/CoreLibraryFactory.cmake b/firmware/common/toolchain/Platform/Core/Libraries/CoreLibraryFactory.cmake new file mode 100644 index 00000000..f580997b --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/Libraries/CoreLibraryFactory.cmake @@ -0,0 +1,31 @@ +#=============================================================================# +# make_core_library +# [PRIVATE/INTERNAL] +# +# make_core_library(OUTPUT_VAR BOARD_ID) +# +# OUTPUT_VAR - Variable name that will hold the generated library name +# BOARD_ID - Arduino board id +# +# Creates the Arduino Core library for the specified board, +# each board gets it's own version of the library. +# +#=============================================================================# +function(make_core_library OUTPUT_VAR BOARD_ID) + set(CORE_LIB_NAME ${BOARD_ID}_CORE) + _get_board_property(${BOARD_ID} build.core BOARD_CORE) + if (BOARD_CORE) + if (NOT TARGET ${CORE_LIB_NAME}) + set(BOARD_CORE_PATH ${${BOARD_CORE}.path}) + find_sources(CORE_SRCS ${BOARD_CORE_PATH} True) + # Debian/Ubuntu fix + list(REMOVE_ITEM CORE_SRCS "${BOARD_CORE_PATH}/main.cxx") + add_library(${CORE_LIB_NAME} ${CORE_SRCS}) + set_board_flags(ARDUINO_COMPILE_FLAGS ARDUINO_LINK_FLAGS ${BOARD_ID} FALSE) + set_target_properties(${CORE_LIB_NAME} PROPERTIES + COMPILE_FLAGS "${ARDUINO_COMPILE_FLAGS}" + LINK_FLAGS "${ARDUINO_LINK_FLAGS}") + endif () + set(${OUTPUT_VAR} ${CORE_LIB_NAME} PARENT_SCOPE) + endif () +endfunction() diff --git a/firmware/common/toolchain/Platform/Core/LibraryFinder.cmake b/firmware/common/toolchain/Platform/Core/LibraryFinder.cmake new file mode 100644 index 00000000..62fca6ee --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/LibraryFinder.cmake @@ -0,0 +1,128 @@ +#=============================================================================# +# find_arduino_libraries +# [PRIVATE/INTERNAL] +# +# find_arduino_libraries(VAR_NAME SRCS ARDLIBS) +# +# VAR_NAME - Variable name which will hold the results +# SRCS - Sources that will be analized +# ARDLIBS - Arduino libraries identified by name (e.g., Wire, SPI, Servo) +# +# returns a list of paths to libraries found. +# +# Finds all Arduino type libraries included in sources. Available libraries +# are ${ARDUINO_SDK_PATH}/libraries and ${CMAKE_CURRENT_SOURCE_DIR}. +# +# Also adds Arduino libraries specifically names in ALIBS. We add ".h" to the +# names and then process them just like the Arduino libraries found in the sources. +# +# A Arduino library is a folder that has the same name as the include header. +# For example, if we have a include "#include " then the following +# directory structure is considered a Arduino library: +# +# LibraryName/ +# |- LibraryName.h +# `- LibraryName.c +# +# If such a directory is found then all sources within that directory are considred +# to be part of that Arduino library. +# +#=============================================================================# +function(find_arduino_libraries VAR_NAME SRCS ARDLIBS) + set(ARDUINO_LIBS) + + if (ARDLIBS) # Libraries are known in advance, just find their absoltue paths + + foreach (LIB ${ARDLIBS}) + get_property(LIBRARY_SEARCH_PATH + DIRECTORY # Property Scope + PROPERTY LINK_DIRECTORIES) + + foreach (LIB_SEARCH_PATH ${LIBRARY_SEARCH_PATH} + ${ARDUINO_LIBRARIES_PATH} + ${ARDUINO_PLATFORM_LIBRARIES_PATH} ${CMAKE_CURRENT_SOURCE_DIR} + ${CMAKE_CURRENT_SOURCE_DIR}/libraries) + + if (EXISTS ${LIB_SEARCH_PATH}/${LIB}/${LIB}.h) + list(APPEND ARDUINO_LIBS ${LIB_SEARCH_PATH}/${LIB}) + break() + endif () + if (EXISTS ${LIB_SEARCH_PATH}/${LIB}.h) + list(APPEND ARDUINO_LIBS ${LIB_SEARCH_PATH}) + break() + endif () + + # Some libraries like Wire and SPI require building from source + if (EXISTS ${LIB_SEARCH_PATH}/${LIB}/src/${LIB}.h) + message(STATUS "avr library found: ${LIB}") + list(APPEND ARDUINO_LIBS ${LIB_SEARCH_PATH}/${LIB}/src) + break() + endif () + if (EXISTS ${LIB_SEARCH_PATH}/src/${LIB}.h) + list(APPEND ARDUINO_LIBS ${LIB_SEARCH_PATH}/src) + break() + endif () + + endforeach () + endforeach () + + else () + + foreach (SRC ${SRCS}) + + # Skipping generated files. They are, probably, not exist yet. + # TODO: Maybe it's possible to skip only really nonexisting files, + # but then it wiil be less deterministic. + get_source_file_property(_srcfile_generated ${SRC} GENERATED) + # Workaround for sketches, which are marked as generated + get_source_file_property(_sketch_generated ${SRC} GENERATED_SKETCH) + + if (NOT ${_srcfile_generated} OR ${_sketch_generated}) + if (NOT (EXISTS ${SRC} OR + EXISTS ${CMAKE_CURRENT_SOURCE_DIR}/${SRC} OR + EXISTS ${CMAKE_CURRENT_BINARY_DIR}/${SRC})) + message(FATAL_ERROR "Invalid source file: ${SRC}") + endif () + file(STRINGS ${SRC} SRC_CONTENTS) + + foreach (LIBNAME ${ARDLIBS}) + list(APPEND SRC_CONTENTS "#include <${LIBNAME}.h>") + endforeach () + + foreach (SRC_LINE ${SRC_CONTENTS}) + if ("${SRC_LINE}" MATCHES + "^[ \t]*#[ \t]*include[ \t]*[<\"]([^>\"]*)[>\"]") + + get_filename_component(INCLUDE_NAME ${CMAKE_MATCH_1} NAME_WE) + get_property(LIBRARY_SEARCH_PATH + DIRECTORY # Property Scope + PROPERTY LINK_DIRECTORIES) + foreach (LIB_SEARCH_PATH ${LIBRARY_SEARCH_PATH} ${ARDUINO_LIBRARIES_PATH} ${ARDUINO_PLATFORM_LIBRARIES_PATH} ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/libraries ${ARDUINO_EXTRA_LIBRARIES_PATH}) + if (EXISTS ${LIB_SEARCH_PATH}/${INCLUDE_NAME}/${CMAKE_MATCH_1}) + list(APPEND ARDUINO_LIBS ${LIB_SEARCH_PATH}/${INCLUDE_NAME}) + break() + endif () + + # Some libraries like Wire and SPI require building from source + if (EXISTS ${LIB_SEARCH_PATH}/${INCLUDE_NAME}/src/${CMAKE_MATCH_1}) + list(APPEND ARDUINO_LIBS ${LIB_SEARCH_PATH}/${INCLUDE_NAME}/src) + break() + endif () + endforeach () + + endif () + endforeach () + + endif () + endforeach () + + endif () + + if (ARDUINO_LIBS) + list(REMOVE_DUPLICATES ARDUINO_LIBS) + endif () + + _REMOVE_BLACKLISTED_LIBRARIES("${ARDUINO_LIBS}" FILTERED_LIBRARIES) + set(${VAR_NAME} ${FILTERED_LIBRARIES} PARENT_SCOPE) + +endfunction() diff --git a/firmware/common/toolchain/Platform/Core/Sketch/ArduinoSketchFactory.cmake b/firmware/common/toolchain/Platform/Core/Sketch/ArduinoSketchFactory.cmake new file mode 100644 index 00000000..59496597 --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/Sketch/ArduinoSketchFactory.cmake @@ -0,0 +1,50 @@ +#=============================================================================# +# make_arduino_sketch +# [PRIVATE/INTERNAL] +# +# make_arduino_sketch(TARGET_NAME SKETCH_PATH OUTPUT_VAR) +# +# TARGET_NAME - Target name +# SKETCH_PATH - Path to sketch directory +# OUTPUT_VAR - Variable name where to save generated sketch source +# +# Generates C++ sources from Arduino Sketch. +#=============================================================================# +function(make_arduino_sketch TARGET_NAME SKETCH_PATH OUTPUT_VAR) + get_filename_component(SKETCH_NAME "${SKETCH_PATH}" NAME) + get_filename_component(SKETCH_PATH "${SKETCH_PATH}" ABSOLUTE) + + if (EXISTS "${SKETCH_PATH}") + set(SKETCH_CPP ${CMAKE_CURRENT_BINARY_DIR}/${TARGET_NAME}_${SKETCH_NAME}.cpp) + + # Always set sketch path to the parent directory - + # Sketch files will be found later + string(REGEX REPLACE "[^\\/]+(.\\.((pde)|(ino)))" "" + SKETCH_PATH ${SKETCH_PATH}) + + # Find all sketch files + file(GLOB SKETCH_SOURCES ${SKETCH_PATH}/*.pde ${SKETCH_PATH}/*.ino) + list(LENGTH SKETCH_SOURCES NUMBER_OF_SOURCES) + if (NUMBER_OF_SOURCES LESS 0) # Sketch sources not found + message(FATAL_ERROR "Could not find sketch + (${SKETCH_NAME}.pde or ${SKETCH_NAME}.ino) at ${SKETCH_PATH}!") + endif () + list(SORT SKETCH_SOURCES) + + convert_sketch_to_cpp(${SKETCH_SOURCES} ${SKETCH_CPP}) + + # Regenerate build system if sketch changes + add_custom_command(OUTPUT ${SKETCH_CPP} + COMMAND ${CMAKE_COMMAND} ${CMAKE_SOURCE_DIR} + WORKING_DIRECTORY ${CMAKE_BINARY_DIR} + DEPENDS ${MAIN_SKETCH} ${SKETCH_SOURCES} + COMMENT "Regnerating ${SKETCH_NAME} Sketch") + set_source_files_properties(${SKETCH_CPP} PROPERTIES GENERATED TRUE) + # Mark file that it exists for find_file + set_source_files_properties(${SKETCH_CPP} PROPERTIES GENERATED_SKETCH TRUE) + + set(${OUTPUT_VAR} ${${OUTPUT_VAR}} ${SKETCH_CPP} PARENT_SCOPE) + else () + message(FATAL_ERROR "Sketch does not exist: ${SKETCH_PATH}") + endif () +endfunction() diff --git a/firmware/common/toolchain/Platform/Core/Sketch/ArduinoSketchToCppConverter.cmake b/firmware/common/toolchain/Platform/Core/Sketch/ArduinoSketchToCppConverter.cmake new file mode 100644 index 00000000..54129f78 --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/Sketch/ArduinoSketchToCppConverter.cmake @@ -0,0 +1,109 @@ +#=============================================================================# +# convert_sketch_to_cpp +# [PRIVATE/INTERNAL] +# +# convert_sketch_to_cpp(MAIN_SKETCH_PATH SKETCH_SOURCES SKETCH_CPP) +# +# SKETCH_SOURCES - Setch source paths +# SKETCH_CPP - Name of file to generate +# +# Generate C++ source file from Arduino sketch files. +#=============================================================================# +function(convert_sketch_to_cpp SKETCH_SOURCES SKETCH_CPP) + file(WRITE ${SKETCH_CPP} "// automatically generated by arduino-cmake\n") + list(GET SKETCH_SOURCES 0 MAIN_SKETCH) + file(READ ${MAIN_SKETCH} MAIN_SKETCH_CONTENT) + + # remove comments + remove_comments(MAIN_SKETCH_CONTENT MAIN_SKETCH_NO_COMMENTS) + + # find first statement + string(REGEX MATCH "[\n][_a-zA-Z0-9]+[^\n]*" FIRST_STATEMENT "${MAIN_SKETCH_NO_COMMENTS}") + string(FIND "${MAIN_SKETCH_CONTENT}" "${FIRST_STATEMENT}" HEAD_LENGTH) + if ("${HEAD_LENGTH}" STREQUAL "-1") + set(HEAD_LENGTH 0) + endif () + string(LENGTH "${MAIN_SKETCH_CONTENT}" MAIN_SKETCH_LENGTH) + + string(SUBSTRING "${MAIN_SKETCH_CONTENT}" 0 ${HEAD_LENGTH} SKETCH_HEAD) + + # find the body of the main pde + math(EXPR BODY_LENGTH "${MAIN_SKETCH_LENGTH}-${HEAD_LENGTH}") + string(SUBSTRING "${MAIN_SKETCH_CONTENT}" "${HEAD_LENGTH}+1" "${BODY_LENGTH}-1" SKETCH_BODY) + + # write the file head + file(APPEND ${SKETCH_CPP} "#line 1 \"${MAIN_SKETCH_PATH}\"\n${SKETCH_HEAD}") + + # Count head line offset (for GCC error reporting) + file(STRINGS ${SKETCH_CPP} SKETCH_HEAD_LINES) + list(LENGTH SKETCH_HEAD_LINES SKETCH_HEAD_LINES_COUNT) + math(EXPR SKETCH_HEAD_OFFSET "${SKETCH_HEAD_LINES_COUNT}+2") + + # add arduino include header + file(APPEND ${SKETCH_CPP} "\n#line ${SKETCH_HEAD_OFFSET} \"${SKETCH_CPP}\"\n") + if (ARDUINO_SDK_VERSION VERSION_LESS 1.0) + file(APPEND ${SKETCH_CPP} "#include \"WProgram.h\"\n") + else () + file(APPEND ${SKETCH_CPP} "#include \"Arduino.h\"\n") + endif () + + get_number_of_lines_in_document("${SKETCH_HEAD}" HEAD_NUM_LINES) + file(APPEND ${SKETCH_CPP} "#line ${HEAD_NUM_LINES} \"${MAIN_SKETCH_PATH}\"\n") + file(APPEND ${SKETCH_CPP} "\n${SKETCH_BODY}") + list(REMOVE_ITEM SKETCH_SOURCES ${MAIN_SKETCH}) + foreach (SKETCH_SOURCE_PATH ${SKETCH_SOURCES}) + file(READ ${SKETCH_SOURCE_PATH} SKETCH_SOURCE) + file(APPEND ${SKETCH_CPP} "\n//=== START : ${SKETCH_SOURCE_PATH}\n") + file(APPEND ${SKETCH_CPP} "#line 1 \"${SKETCH_SOURCE_PATH}\"\n") + file(APPEND ${SKETCH_CPP} "${SKETCH_SOURCE}") + file(APPEND ${SKETCH_CPP} "\n//=== END : ${SKETCH_SOURCE_PATH}\n") + endforeach () +endfunction() + +#=============================================================================# +# remove_comments +# [PRIVATE/INTERNAL] +# +# remove_comments(SRC_VAR OUT_VAR) +# +# SRC_VAR - variable holding sources +# OUT_VAR - variable holding sources with no comments +# +# Removes all comments from the source code. +#=============================================================================# +function(remove_comments SRC_VAR OUT_VAR) + string(REGEX REPLACE "[\\./\\\\]" "_" FILE "${NAME}") + + set(SRC ${${SRC_VAR}}) + + #message(STATUS "removing comments from: ${FILE}") + #file(WRITE "${CMAKE_BINARY_DIR}/${FILE}_pre_remove_comments.txt" ${SRC}) + #message(STATUS "\n${SRC}") + + # remove all comments + string(REGEX REPLACE "([/][/][^\n]*)|([/][\\*]([^\\*]|([\\*]+[^/\\*]))*[\\*]+[/])" + "" OUT "${SRC}") + + #file(WRITE "${CMAKE_BINARY_DIR}/${FILE}_post_remove_comments.txt" ${SRC}) + #message(STATUS "\n${SRC}") + + set(${OUT_VAR} ${OUT} PARENT_SCOPE) + +endfunction() + +#=============================================================================# +# get_number_of_lines_in_document +# [PRIVATE/INTERNAL] +# +# get_number_of_lines_in_document(DOCUMENT OUTPUT_VAR) +# +# DOCUMENT - Document's content +# OUTPUT_VAR - Variable which will hold the line number count +# +# Counts the line number of the document. +#=============================================================================# +function(get_number_of_lines_in_document DOCUMENT OUTPUT_VAR) + string(REGEX MATCHALL "[\n]" MATCH_LIST "${DOCUMENT}") + list(LENGTH MATCH_LIST NUM) + set(${OUTPUT_VAR} ${NUM} PARENT_SCOPE) +endfunction() diff --git a/firmware/common/toolchain/Platform/Core/SourceFinder.cmake b/firmware/common/toolchain/Platform/Core/SourceFinder.cmake new file mode 100644 index 00000000..cb89aabc --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/SourceFinder.cmake @@ -0,0 +1,36 @@ +#=============================================================================# +# find_sources +# [PRIVATE/INTERNAL] +# +# find_sources(VAR_NAME LIB_PATH RECURSE) +# +# VAR_NAME - Variable name that will hold the detected sources +# LIB_PATH - The base path +# RECURSE - Whether or not to recurse +# +# Finds all C/C++ sources located at the specified path. +# +#=============================================================================# +function(find_sources VAR_NAME LIB_PATH RECURSE) + set(FILE_SEARCH_LIST + ${LIB_PATH}/*.cpp + ${LIB_PATH}/*.c + ${LIB_PATH}/*.cc + ${LIB_PATH}/*.cxx + ${LIB_PATH}/*.h + ${LIB_PATH}/*.hh + ${LIB_PATH}/*.hxx + ${LIB_PATH}/*.[sS] + ) + + if (RECURSE) + file(GLOB_RECURSE SOURCE_FILES ${FILE_SEARCH_LIST}) + else () + file(GLOB SOURCE_FILES ${FILE_SEARCH_LIST}) + endif () + + if (SOURCE_FILES) + set(${VAR_NAME} ${SOURCE_FILES} PARENT_SCOPE) + endif () +endfunction() + diff --git a/firmware/common/toolchain/Platform/Core/Targets/ArduinoBootloaderArgumentsBuilder.cmake b/firmware/common/toolchain/Platform/Core/Targets/ArduinoBootloaderArgumentsBuilder.cmake new file mode 100644 index 00000000..e1ea560b --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/Targets/ArduinoBootloaderArgumentsBuilder.cmake @@ -0,0 +1,47 @@ +#=============================================================================# +# build_arduino_bootloader_arguments +# [PRIVATE/INTERNAL] +# +# build_arduino_bootloader_arguments(BOARD_ID TARGET_NAME PORT AVRDUDE_FLAGS OUTPUT_VAR) +# +# BOARD_ID - board id +# TARGET_NAME - target name +# PORT - serial port +# AVRDUDE_FLAGS - avrdude flags (override) +# OUTPUT_VAR - name of output variable for result +# +# Sets up default avrdude settings for uploading firmware via the bootloader. +#=============================================================================# +function(build_arduino_bootloader_arguments BOARD_ID TARGET_NAME PORT AVRDUDE_FLAGS OUTPUT_VAR) + set(AVRDUDE_ARGS ${${OUTPUT_VAR}}) + + if (NOT AVRDUDE_FLAGS) + set(AVRDUDE_FLAGS ${ARDUINO_AVRDUDE_FLAGS}) + endif () + _get_board_property(${BOARD_ID} build.mcu MCU) + list(APPEND AVRDUDE_ARGS + "-C${ARDUINO_AVRDUDE_CONFIG_PATH}" # avrdude config + "-p${MCU}" # MCU Type + ) + + # Programmer + _get_board_property(${BOARD_ID} upload.protocol UPLOAD_PROTOCOL) + if (${UPLOAD_PROTOCOL} STREQUAL "stk500") + list(APPEND AVRDUDE_ARGS "-cstk500v1") + else () + list(APPEND AVRDUDE_ARGS "-c${UPLOAD_PROTOCOL}") + endif () + + + _get_board_property(${BOARD_ID} upload.speed UPLOAD_SPEED) + list(APPEND AVRDUDE_ARGS + "-b${UPLOAD_SPEED}" # Baud rate + "-P${PORT}" # Serial port + "-D" # Dont erase + ) + + list(APPEND AVRDUDE_ARGS ${AVRDUDE_FLAGS}) + + set(${OUTPUT_VAR} ${AVRDUDE_ARGS} PARENT_SCOPE) + +endfunction() diff --git a/firmware/common/toolchain/Platform/Core/Targets/ArduinoBootloaderBurnTargetCreator.cmake b/firmware/common/toolchain/Platform/Core/Targets/ArduinoBootloaderBurnTargetCreator.cmake new file mode 100644 index 00000000..a28a2ef0 --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/Targets/ArduinoBootloaderBurnTargetCreator.cmake @@ -0,0 +1,82 @@ +#=============================================================================# +# create_arduino_bootloader_burn_target +# [PRIVATE/INTERNAL] +# +# create_arduino_bootloader_burn_target(TARGET_NAME BOARD_ID PROGRAMMER PORT AVRDUDE_FLAGS) +# +# TARGET_NAME - name of target to burn +# BOARD_ID - board id +# PROGRAMMER - programmer id +# PORT - serial port +# AVRDUDE_FLAGS - avrdude flags (override) +# +# Create a target for burning a bootloader via a programmer. +# +# The target for burning the bootloader is ${TARGET_NAME}-burn-bootloader +# +#=============================================================================# +function(create_arduino_bootloader_burn_target TARGET_NAME BOARD_ID PROGRAMMER PORT AVRDUDE_FLAGS) + set(BOOTLOADER_TARGET ${TARGET_NAME}-burn-bootloader) + + set(AVRDUDE_ARGS) + + build_arduino_programmer_arguments(${BOARD_ID} ${PROGRAMMER} ${TARGET_NAME} ${PORT} "${AVRDUDE_FLAGS}" AVRDUDE_ARGS) + + if (NOT AVRDUDE_ARGS) + message("Could not generate default avrdude programmer args, aborting!") + return() + endif () + + # look at bootloader.file + _try_get_board_property(${BOARD_ID} bootloader.file BOOTLOADER_FILE) + if (NOT BOOTLOADER_FILE) + message("Missing bootloader.file, not creating bootloader burn target ${BOOTLOADER_TARGET}.") + return() + endif() + + # build bootloader.path from bootloader.file... + string(REGEX MATCH "(.+/)*" BOOTLOADER_PATH ${BOOTLOADER_FILE}) + string(REGEX REPLACE "/" "" BOOTLOADER_PATH ${BOOTLOADER_PATH}) + # and fix bootloader.file + string(REGEX MATCH "/.(.+)$" BOOTLOADER_FILE_NAME ${BOOTLOADER_FILE}) + string(REGEX REPLACE "/" "" BOOTLOADER_FILE_NAME ${BOOTLOADER_FILE_NAME}) + + if (NOT EXISTS "${ARDUINO_BOOTLOADERS_PATH}/${BOOTLOADER_PATH}/${BOOTLOADER_FILE_NAME}") + message("Missing bootloader image '${ARDUINO_BOOTLOADERS_PATH}/${BOOTLOADER_PATH}/${BOOTLOADER_FILE_NAME}', not creating bootloader burn target ${BOOTLOADER_TARGET}.") + return() + endif () + + #check for required bootloader parameters + foreach (ITEM lock_bits unlock_bits high_fuses low_fuses) + #do not make fatal error if field doesn't exists, just don't create bootloader burn target + _try_get_board_property(${BOARD_ID} bootloader.${ITEM} BOOTLOADER_${ITEM}) + if (NOT BOOTLOADER_${ITEM}) + message("Missing bootloader.${ITEM}, not creating bootloader burn target ${BOOTLOADER_TARGET}.") + return() + endif () + endforeach () + + # Erase the chip + list(APPEND AVRDUDE_ARGS "-e") + + # Set unlock bits and fuses (because chip is going to be erased) + list(APPEND AVRDUDE_ARGS "-Ulock:w:${BOOTLOADER_unlock_bits}:m") + # extended fuses is optional + _try_get_board_property(${BOARD_ID} bootloader.extended_fuses BOOTLOADER_extended_fuses) + if (BOOTLOADER_extended_fuses) + list(APPEND AVRDUDE_ARGS "-Uefuse:w:${BOOTLOADER_extended_fuses}:m") + endif() + + list(APPEND AVRDUDE_ARGS + "-Uhfuse:w:${BOOTLOADER_high_fuses}:m" + "-Ulfuse:w:${BOOTLOADER_low_fuses}:m" + "-Uflash:w:${BOOTLOADER_FILE_NAME}:i" + "-Ulock:w:${BOOTLOADER_lock_bits}:m") + + # Create burn bootloader target + add_custom_target(${BOOTLOADER_TARGET} + ${ARDUINO_AVRDUDE_PROGRAM} + ${AVRDUDE_ARGS} + WORKING_DIRECTORY ${ARDUINO_BOOTLOADERS_PATH}/${BOOTLOADER_PATH} + DEPENDS ${TARGET_NAME}) +endfunction() diff --git a/firmware/common/toolchain/Platform/Core/Targets/ArduinoBootloaderUploadTargetCreator.cmake b/firmware/common/toolchain/Platform/Core/Targets/ArduinoBootloaderUploadTargetCreator.cmake new file mode 100644 index 00000000..99bf4e05 --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/Targets/ArduinoBootloaderUploadTargetCreator.cmake @@ -0,0 +1,48 @@ + + +#=============================================================================# +# setup_arduino_bootloader_upload +# [PRIVATE/INTERNAL] +# +# setup_arduino_bootloader_upload(TARGET_NAME BOARD_ID PORT) +# +# TARGET_NAME - target name +# BOARD_ID - board id +# PORT - serial port +# AVRDUDE_FLAGS - avrdude flags (override) +# +# Set up target for upload firmware via the bootloader. +# +# The target for uploading the firmware is ${TARGET_NAME}-upload . +# +#=============================================================================# +function(create_arduino_bootloader_upload_target TARGET_NAME BOARD_ID PORT AVRDUDE_FLAGS) + set(UPLOAD_TARGET ${TARGET_NAME}-upload) + set(AVRDUDE_ARGS) + + build_arduino_bootloader_arguments(${BOARD_ID} ${TARGET_NAME} ${PORT} "${AVRDUDE_FLAGS}" AVRDUDE_ARGS) + + if (NOT AVRDUDE_ARGS) + message("Could not generate default avrdude bootloader args, aborting!") + return() + endif () + + if (NOT EXECUTABLE_OUTPUT_PATH) + set(EXECUTABLE_OUTPUT_PATH ${CMAKE_CURRENT_BINARY_DIR}) + endif () + set(TARGET_PATH ${EXECUTABLE_OUTPUT_PATH}/${TARGET_NAME}) + + list(APPEND AVRDUDE_ARGS "-Uflash:w:\"${TARGET_PATH}.hex\":i") + list(APPEND AVRDUDE_ARGS "-Ueeprom:w:\"${TARGET_PATH}.eep\":i") + add_custom_target(${UPLOAD_TARGET} + ${ARDUINO_AVRDUDE_PROGRAM} + ${AVRDUDE_ARGS} + DEPENDS ${TARGET_NAME}) + + # Global upload target + if (NOT TARGET upload) + add_custom_target(upload) + endif () + + add_dependencies(upload ${UPLOAD_TARGET}) +endfunction() diff --git a/firmware/common/toolchain/Platform/Core/Targets/ArduinoFirmwareTargetCreator.cmake b/firmware/common/toolchain/Platform/Core/Targets/ArduinoFirmwareTargetCreator.cmake new file mode 100644 index 00000000..866742c4 --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/Targets/ArduinoFirmwareTargetCreator.cmake @@ -0,0 +1,73 @@ +#=============================================================================# +# create_arduino_target +# [PRIVATE/INTERNAL] +# +# create_arduino_target(TARGET_NAME ALL_SRCS ALL_LIBS COMPILE_FLAGS LINK_FLAGS MANUAL) +# +# TARGET_NAME - Target name +# BOARD_ID - Arduino board ID +# ALL_SRCS - All sources +# ALL_LIBS - All libraries +# COMPILE_FLAGS - Compile flags +# LINK_FLAGS - Linker flags +# MANUAL - (Advanced) Only use AVR Libc/Includes +# +# Creates an Arduino firmware target. +# +#=============================================================================# +function(create_arduino_firmware_target TARGET_NAME BOARD_ID ALL_SRCS ALL_LIBS + COMPILE_FLAGS LINK_FLAGS MANUAL) + + string(STRIP "${ALL_SRCS}" ALL_SRCS) + add_executable(${TARGET_NAME} "${ALL_SRCS}") + set_target_properties(${TARGET_NAME} PROPERTIES SUFFIX ".elf") + + set_board_flags(ARDUINO_COMPILE_FLAGS ARDUINO_LINK_FLAGS ${BOARD_ID} ${MANUAL}) + + set_target_properties(${TARGET_NAME} PROPERTIES + COMPILE_FLAGS "${ARDUINO_COMPILE_FLAGS} ${COMPILE_FLAGS}" + LINK_FLAGS "${ARDUINO_LINK_FLAGS} ${LINK_FLAGS}") + target_link_libraries(${TARGET_NAME} ${ALL_LIBS} "-lc -lm") + + if (NOT EXECUTABLE_OUTPUT_PATH) + set(EXECUTABLE_OUTPUT_PATH ${CMAKE_CURRENT_BINARY_DIR}) + endif () + set(TARGET_PATH ${EXECUTABLE_OUTPUT_PATH}/${TARGET_NAME}) + add_custom_command(TARGET ${TARGET_NAME} POST_BUILD + COMMAND ${CMAKE_OBJCOPY} + ARGS ${ARDUINO_OBJCOPY_EEP_FLAGS} + ${TARGET_PATH}.elf + ${TARGET_PATH}.eep + COMMENT "Generating EEP image" + VERBATIM) + + # Convert firmware image to ASCII HEX format + add_custom_command(TARGET ${TARGET_NAME} POST_BUILD + COMMAND ${CMAKE_OBJCOPY} + ARGS ${ARDUINO_OBJCOPY_HEX_FLAGS} + ${TARGET_PATH}.elf + ${TARGET_PATH}.hex + COMMENT "Generating HEX image" + VERBATIM) + _get_board_property(${BOARD_ID} build.mcu MCU) + # Display target size + add_custom_command(TARGET ${TARGET_NAME} POST_BUILD + COMMAND ${CMAKE_COMMAND} + ARGS -DFIRMWARE_IMAGE=${TARGET_PATH}.elf + -DMCU=${MCU} + -DEEPROM_IMAGE=${TARGET_PATH}.eep + -P ${ARDUINO_SIZE_SCRIPT} + COMMENT "Calculating image size" + VERBATIM) + + # Create ${TARGET_NAME}-size target + add_custom_target(${TARGET_NAME}-size + COMMAND ${CMAKE_COMMAND} + -DFIRMWARE_IMAGE=${TARGET_PATH}.elf + -DMCU=${MCU} + -DEEPROM_IMAGE=${TARGET_PATH}.eep + -P ${ARDUINO_SIZE_SCRIPT} + DEPENDS ${TARGET_NAME} + COMMENT "Calculating ${TARGET_NAME} image size") + +endfunction() diff --git a/firmware/common/toolchain/Platform/Core/Targets/ArduinoProgrammerArgumentsBuilder.cmake b/firmware/common/toolchain/Platform/Core/Targets/ArduinoProgrammerArgumentsBuilder.cmake new file mode 100644 index 00000000..1ff6ed4d --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/Targets/ArduinoProgrammerArgumentsBuilder.cmake @@ -0,0 +1,55 @@ +#=============================================================================# +# build_arduino_programmer_arguments +# [PRIVATE/INTERNAL] +# +# build_arduino_programmer_arguments(BOARD_ID PROGRAMMER TARGET_NAME PORT AVRDUDE_FLAGS OUTPUT_VAR) +# +# BOARD_ID - board id +# PROGRAMMER - programmer id +# TARGET_NAME - target name +# PORT - serial port +# AVRDUDE_FLAGS - avrdude flags (override) +# OUTPUT_VAR - name of output variable for result +# +# Sets up default avrdude settings for burning firmware via a programmer. +#=============================================================================# +function(build_arduino_programmer_arguments BOARD_ID PROGRAMMER TARGET_NAME PORT AVRDUDE_FLAGS OUTPUT_VAR) + set(AVRDUDE_ARGS ${${OUTPUT_VAR}}) + + if (NOT AVRDUDE_FLAGS) + set(AVRDUDE_FLAGS ${ARDUINO_AVRDUDE_FLAGS}) + endif () + + list(APPEND AVRDUDE_ARGS "-C${ARDUINO_AVRDUDE_CONFIG_PATH}") + + #TODO: Check mandatory settings before continuing + if (NOT ${PROGRAMMER}.protocol) + message(FATAL_ERROR "Missing ${PROGRAMMER}.protocol, aborting!") + endif () + + list(APPEND AVRDUDE_ARGS "-c${${PROGRAMMER}.protocol}") # Set programmer + + if (${PROGRAMMER}.communication STREQUAL "usb") + list(APPEND AVRDUDE_ARGS "-Pusb") # Set USB as port + elseif (${PROGRAMMER}.communication STREQUAL "serial") + list(APPEND AVRDUDE_ARGS "-P${PORT}") # Set port + if (${PROGRAMMER}.speed) + list(APPEND AVRDUDE_ARGS "-b${${PROGRAMMER}.speed}") # Set baud rate + endif () + endif () + + if (${PROGRAMMER}.force) + list(APPEND AVRDUDE_ARGS "-F") # Set force + endif () + + if (${PROGRAMMER}.delay) + list(APPEND AVRDUDE_ARGS "-i${${PROGRAMMER}.delay}") # Set delay + endif () + + _get_board_property(${BOARD_ID} build.mcu MCU) + list(APPEND AVRDUDE_ARGS "-p${MCU}") # MCU Type + + list(APPEND AVRDUDE_ARGS ${AVRDUDE_FLAGS}) + + set(${OUTPUT_VAR} ${AVRDUDE_ARGS} PARENT_SCOPE) +endfunction() diff --git a/firmware/common/toolchain/Platform/Core/Targets/ArduinoProgrammerBurnTargetCreator.cmake b/firmware/common/toolchain/Platform/Core/Targets/ArduinoProgrammerBurnTargetCreator.cmake new file mode 100644 index 00000000..78594d2f --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/Targets/ArduinoProgrammerBurnTargetCreator.cmake @@ -0,0 +1,41 @@ +#=============================================================================# +# create_arduino_programmer_burn_target +# [PRIVATE/INTERNAL] +# +# create_arduino_programmer_burn_target(TARGET_NAME BOARD_ID PROGRAMMER PORT AVRDUDE_FLAGS) +# +# TARGET_NAME - name of target to burn +# BOARD_ID - board id +# PROGRAMMER - programmer id +# PORT - serial port +# AVRDUDE_FLAGS - avrdude flags (override) +# +# Sets up target for burning firmware via a programmer. +# +# The target for burning the firmware is ${TARGET_NAME}-burn . +# +#=============================================================================# +function(create_arduino_programmer_burn_target TARGET_NAME BOARD_ID PROGRAMMER PORT AVRDUDE_FLAGS) + set(PROGRAMMER_TARGET ${TARGET_NAME}-burn) + + set(AVRDUDE_ARGS) + + build_arduino_programmer_arguments(${BOARD_ID} ${PROGRAMMER} ${TARGET_NAME} ${PORT} "${AVRDUDE_FLAGS}" AVRDUDE_ARGS) + + if (NOT AVRDUDE_ARGS) + message("Could not generate default avrdude programmer args, aborting!") + return() + endif () + + if (NOT EXECUTABLE_OUTPUT_PATH) + set(EXECUTABLE_OUTPUT_PATH ${CMAKE_CURRENT_BINARY_DIR}) + endif () + set(TARGET_PATH ${EXECUTABLE_OUTPUT_PATH}/${TARGET_NAME}) + + list(APPEND AVRDUDE_ARGS "-Uflash:w:\"${TARGET_PATH}.hex\":i") + + add_custom_target(${PROGRAMMER_TARGET} + ${ARDUINO_AVRDUDE_PROGRAM} + ${AVRDUDE_ARGS} + DEPENDS ${TARGET_NAME}) +endfunction() diff --git a/firmware/common/toolchain/Platform/Core/Targets/ArduinoSerialTargetCreator.cmake b/firmware/common/toolchain/Platform/Core/Targets/ArduinoSerialTargetCreator.cmake new file mode 100644 index 00000000..a82a5279 --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/Targets/ArduinoSerialTargetCreator.cmake @@ -0,0 +1,17 @@ +#=============================================================================# +# create_serial_target +# [PRIVATE/INTERNAL] +# +# create_serial_target(TARGET_NAME CMD) +# +# TARGET_NAME - Target name +# CMD - Serial terminal command +# +# Creates a target (${TARGET_NAME}-serial) for launching the serial termnial. +# +#=============================================================================# +function(create_serial_target TARGET_NAME CMD SERIAL_PORT) + string(CONFIGURE "${CMD}" FULL_CMD @ONLY) + add_custom_target(${TARGET_NAME}-serial + COMMAND ${FULL_CMD}) +endfunction() diff --git a/firmware/common/toolchain/Platform/Core/Targets/ArduinoUploadTargetCreator.cmake b/firmware/common/toolchain/Platform/Core/Targets/ArduinoUploadTargetCreator.cmake new file mode 100644 index 00000000..b67ad851 --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/Targets/ArduinoUploadTargetCreator.cmake @@ -0,0 +1,26 @@ +include(ArduinoBootloaderUploadTargetCreator) + +#=============================================================================# +# create_arduino_upload_target +# [PRIVATE/INTERNAL] +# +# create_arduino_upload_target(BOARD_ID TARGET_NAME PORT) +# +# BOARD_ID - Arduino board id +# TARGET_NAME - Target name +# PORT - Serial port for upload +# PROGRAMMER_ID - Programmer ID +# AVRDUDE_FLAGS - avrdude flags +# +# Create an upload target (${TARGET_NAME}-upload) for the specified Arduino target. +# +#=============================================================================# +function(create_arduino_upload_target BOARD_ID TARGET_NAME PORT PROGRAMMER_ID AVRDUDE_FLAGS) + create_arduino_bootloader_upload_target(${TARGET_NAME} ${BOARD_ID} ${PORT} "${AVRDUDE_FLAGS}") + + # Add programmer support if defined + if (PROGRAMMER_ID AND ${PROGRAMMER_ID}.protocol) + create_arduino_programmer_burn_target(${TARGET_NAME} ${BOARD_ID} ${PROGRAMMER_ID} ${PORT} "${AVRDUDE_FLAGS}") + create_arduino_bootloader_burn_target(${TARGET_NAME} ${BOARD_ID} ${PROGRAMMER_ID} ${PORT} "${AVRDUDE_FLAGS}") + endif () +endfunction() diff --git a/firmware/common/toolchain/Platform/Core/VariableValidator.cmake b/firmware/common/toolchain/Platform/Core/VariableValidator.cmake new file mode 100644 index 00000000..50af23cb --- /dev/null +++ b/firmware/common/toolchain/Platform/Core/VariableValidator.cmake @@ -0,0 +1,37 @@ +#=============================================================================# +# VALIDATE_VARIABLES_NOT_EMPTY +# [PRIVATE/INTERNAL] +# +# VALIDATE_VARIABLES_NOT_EMPTY(MSG msg VARS var1 var2 .. varN) +# +# MSG - Message to display in case of error +# VARS - List of variables names to check +# +# Ensure the specified variables are not empty, otherwise a fatal error is emmited. +#=============================================================================# +function(VALIDATE_VARIABLES_NOT_EMPTY) + cmake_parse_arguments(INPUT "" "MSG" "VARS" ${ARGN}) + error_for_unparsed(INPUT) + foreach (VAR ${INPUT_VARS}) + if ("${${VAR}}" STREQUAL "") + message(FATAL_ERROR "${VAR} not set: ${INPUT_MSG}") + endif () + endforeach () +endfunction() + +#=============================================================================# +# error_for_unparsed +# [PRIVATE/INTERNAL] +# +# error_for_unparsed(PREFIX) +# +# PREFIX - Prefix name +# +# Emit fatal error if there are unparsed argument from cmake_parse_arguments(). +#=============================================================================# +function(ERROR_FOR_UNPARSED PREFIX) + set(ARGS "${${PREFIX}_UNPARSED_ARGUMENTS}") + if (NOT ("${ARGS}" STREQUAL "")) + message(FATAL_ERROR "unparsed argument: ${ARGS}") + endif () +endfunction() diff --git a/firmware/common/toolchain/Platform/Extras/CalculateFirmwareSize.cmake b/firmware/common/toolchain/Platform/Extras/CalculateFirmwareSize.cmake new file mode 100644 index 00000000..c2d1c850 --- /dev/null +++ b/firmware/common/toolchain/Platform/Extras/CalculateFirmwareSize.cmake @@ -0,0 +1,71 @@ +set(AVRSIZE_PROGRAM "PLACEHOLDER_1") +set(AVRSIZE_FLAGS -C --mcu=${MCU}) +execute_process(COMMAND ${AVRSIZE_PROGRAM} ${AVRSIZE_FLAGS} ${FIRMWARE_IMAGE} ${EEPROM_IMAGE} + OUTPUT_VARIABLE SIZE_OUTPUT) + +string(STRIP "${SIZE_OUTPUT}" RAW_SIZE_OUTPUT) + +# Convert lines into a list +string(REPLACE "\n" ";" SIZE_OUTPUT_LIST "${SIZE_OUTPUT}") + +set(SIZE_OUTPUT_LINES) +foreach (LINE ${SIZE_OUTPUT_LIST}) + if (NOT "${LINE}" STREQUAL "") + list(APPEND SIZE_OUTPUT_LINES "${LINE}") + endif () +endforeach () + +function(EXTRACT LIST_NAME INDEX VARIABLE) + list(GET "${LIST_NAME}" ${INDEX} RAW_VALUE) + string(STRIP "${RAW_VALUE}" VALUE) + set(${VARIABLE} "${VALUE}" PARENT_SCOPE) +endfunction() + +function(PARSE INPUT VARIABLE_PREFIX) + if (${INPUT} MATCHES "([^:]+):[ \t]*([0-9]+)[ \t]*([^ \t]+)[ \t]*[(]([0-9.]+)%.*") + set(ENTRY_NAME ${CMAKE_MATCH_1}) + set(ENTRY_SIZE ${CMAKE_MATCH_2}) + set(ENTRY_SIZE_TYPE ${CMAKE_MATCH_3}) + set(ENTRY_PERCENT ${CMAKE_MATCH_4}) + endif () + + set(${VARIABLE_PREFIX}_NAME ${ENTRY_NAME} PARENT_SCOPE) + set(${VARIABLE_PREFIX}_SIZE ${ENTRY_SIZE} PARENT_SCOPE) + set(${VARIABLE_PREFIX}_SIZE_TYPE ${ENTRY_SIZE_TYPE} PARENT_SCOPE) + set(${VARIABLE_PREFIX}_PERCENT ${ENTRY_PERCENT} PARENT_SCOPE) +endfunction() + +list(LENGTH SIZE_OUTPUT_LINES SIZE_OUTPUT_LENGTH) + +if (${SIZE_OUTPUT_LENGTH} STREQUAL 14) + EXTRACT(SIZE_OUTPUT_LINES 3 FIRMWARE_PROGRAM_SIZE_ROW) + EXTRACT(SIZE_OUTPUT_LINES 5 FIRMWARE_DATA_SIZE_ROW) + PARSE(FIRMWARE_PROGRAM_SIZE_ROW FIRMWARE_PROGRAM) + PARSE(FIRMWARE_DATA_SIZE_ROW FIRMWARE_DATA) + + set(FIRMWARE_STATUS "Firmware Size: ") + set(FIRMWARE_STATUS "${FIRMWARE_STATUS} [${FIRMWARE_PROGRAM_NAME}: ${FIRMWARE_PROGRAM_SIZE} ${FIRMWARE_PROGRAM_SIZE_TYPE} (${FIRMWARE_PROGRAM_PERCENT}%) ] ") + set(FIRMWARE_STATUS "${FIRMWARE_STATUS} [${FIRMWARE_DATA_NAME}: ${FIRMWARE_DATA_SIZE} ${FIRMWARE_DATA_SIZE_TYPE} (${FIRMWARE_DATA_PERCENT}%) ]") + set(FIRMWARE_STATUS "${FIRMWARE_STATUS} on ${MCU}") + + EXTRACT(SIZE_OUTPUT_LINES 10 EEPROM_PROGRAM_SIZE_ROW) + EXTRACT(SIZE_OUTPUT_LINES 12 EEPROM_DATA_SIZE_ROW) + PARSE(EEPROM_PROGRAM_SIZE_ROW EEPROM_PROGRAM) + PARSE(EEPROM_DATA_SIZE_ROW EEPROM_DATA) + + set(EEPROM_STATUS "EEPROM Size: ") + set(EEPROM_STATUS "${EEPROM_STATUS} [${EEPROM_PROGRAM_NAME}: ${EEPROM_PROGRAM_SIZE} ${EEPROM_PROGRAM_SIZE_TYPE} (${EEPROM_PROGRAM_PERCENT}%) ] ") + set(EEPROM_STATUS "${EEPROM_STATUS} [${EEPROM_DATA_NAME}: ${EEPROM_DATA_SIZE} ${EEPROM_DATA_SIZE_TYPE} (${EEPROM_DATA_PERCENT}%) ]") + set(EEPROM_STATUS "${EEPROM_STATUS} on ${MCU}") + + message("${FIRMWARE_STATUS}") + message("${EEPROM_STATUS}\n") + + if ($ENV{VERBOSE}) + message("${RAW_SIZE_OUTPUT}\n") + elseif (\$ENV{VERBOSE_SIZE}) + message("${RAW_SIZE_OUTPUT}\n") + endif () +else () + message("${RAW_SIZE_OUTPUT}") +endif () diff --git a/firmware/common/toolchain/Platform/Extras/DebugOptions.cmake b/firmware/common/toolchain/Platform/Extras/DebugOptions.cmake new file mode 100644 index 00000000..5a709849 --- /dev/null +++ b/firmware/common/toolchain/Platform/Extras/DebugOptions.cmake @@ -0,0 +1,40 @@ +#=============================================================================# +# arduino_debug_on() +# [PRIVATE/INTERNAL] +# +# arduino_debug_on() +# +# Enables Arduino module debugging. +#=============================================================================# +function(ARDUINO_DEBUG_ON) + set(ARDUINO_DEBUG True PARENT_SCOPE) +endfunction() + +#=============================================================================# +# arduino_debug_on() +# [PRIVATE/INTERNAL] +# +# arduino_debug_off() +# +# Disables Arduino module debugging. +#=============================================================================# +function(ARDUINO_DEBUG_OFF) + set(ARDUINO_DEBUG False PARENT_SCOPE) +endfunction() + +#=============================================================================# +# arduino_debug_msg +# [PRIVATE/INTERNAL] +# +# arduino_debug_msg(MSG) +# +# MSG - Message to print +# +# Print Arduino debugging information. In order to enable printing +# use arduino_debug_on() and to disable use arduino_debug_off(). +#=============================================================================# +function(ARDUINO_DEBUG_MSG MSG) + if (ARDUINO_DEBUG) + message("## ${MSG}") + endif () +endfunction() diff --git a/firmware/common/toolchain/Platform/Extras/GeneratorSettingsLoader.cmake b/firmware/common/toolchain/Platform/Extras/GeneratorSettingsLoader.cmake new file mode 100644 index 00000000..e2eb63d1 --- /dev/null +++ b/firmware/common/toolchain/Platform/Extras/GeneratorSettingsLoader.cmake @@ -0,0 +1,32 @@ +#=============================================================================# +# load_generator_settings +# [PRIVATE/INTERNAL] +# +# load_generator_settings(TARGET_NAME PREFIX [SUFFIX_1 SUFFIX_2 .. SUFFIX_N]) +# +# TARGET_NAME - The base name of the user settings +# PREFIX - The prefix name used for generator settings +# SUFFIX_XX - List of suffixes to load +# +# Loads a list of user settings into the generators scope. User settings have +# the following syntax: +# +# ${BASE_NAME}${SUFFIX} +# +# The BASE_NAME is the target name and the suffix is a specific generator settings. +# +# For every user setting found a generator setting is created of the follwoing fromat: +# +# ${PREFIX}${SUFFIX} +# +# The purpose of loading the settings into the generator is to not modify user settings +# and to have a generic naming of the settings within the generator. +# +#=============================================================================# +function(LOAD_GENERATOR_SETTINGS TARGET_NAME PREFIX) + foreach (GEN_SUFFIX ${ARGN}) + if (${TARGET_NAME}_${GEN_SUFFIX} AND NOT ${PREFIX}_${GEN_SUFFIX}) + set(${PREFIX}_${GEN_SUFFIX} ${${TARGET_NAME}_${GEN_SUFFIX}} PARENT_SCOPE) + endif () + endforeach () +endfunction() diff --git a/firmware/common/toolchain/Platform/Extras/Macros.cmake b/firmware/common/toolchain/Platform/Extras/Macros.cmake new file mode 100644 index 00000000..06c7dc74 --- /dev/null +++ b/firmware/common/toolchain/Platform/Extras/Macros.cmake @@ -0,0 +1,58 @@ +#=============================================================================# +# parse_generator_arguments +# [PRIVATE/INTERNAL] +# +# parse_generator_arguments(TARGET_NAME PREFIX OPTIONS ARGS MULTI_ARGS [ARG1 ARG2 .. ARGN]) +# +# PREFIX - Parsed options prefix +# OPTIONS - List of options +# ARGS - List of one value keyword arguments +# MULTI_ARGS - List of multi value keyword arguments +# [ARG1 ARG2 .. ARGN] - command arguments [optional] +# +# Parses generator options from either variables or command arguments +# +#=============================================================================# +macro(PARSE_GENERATOR_ARGUMENTS TARGET_NAME PREFIX OPTIONS ARGS MULTI_ARGS) + cmake_parse_arguments(${PREFIX} "${OPTIONS}" "${ARGS}" "${MULTI_ARGS}" ${ARGN}) + error_for_unparsed(${PREFIX}) + load_generator_settings(${TARGET_NAME} ${PREFIX} ${OPTIONS} ${ARGS} ${MULTI_ARGS}) +endmacro() + +#=============================================================================# +# get_mcu +# [PRIVATE/INTERNAL] +# +# get_mcu(FULL_MCU_NAME, OUTPUT_VAR) +# +# FULL_MCU_NAME - Board's full mcu name, including a trailing 'p' if present +# OUTPUT_VAR - String value in which a regex match will be stored +# +# Matches the board's mcu without leading or trailing characters that would rather mess +# further processing that requires the board's mcu. +# +#=============================================================================# +macro(GET_MCU FULL_MCU_NAME OUTPUT_VAR) + string(REGEX MATCH "^.+[^p]" ${OUTPUT_VAR} "FULL_MCU_NAME" PARENT_SCOPE) +endmacro() + +#=============================================================================# +# increment_example_category_index +# [PRIVATE/INTERNAL] +# +# increment_example_category_index(OUTPUT_VAR) +# +# OUTPUT_VAR - A number representing an example's category prefix +# +# Increments the given number by one, taking into consideration the number notation +# which is defined (Some SDK's or OSs use a leading '0' in single-digit numbers. +# +#=============================================================================# +macro(INCREMENT_EXAMPLE_CATEGORY_INDEX OUTPUT_VAR) + math(EXPR INC_INDEX "${${OUTPUT_VAR}}+1") + if (EXAMPLE_CATEGORY_INDEX_LENGTH GREATER 1 AND INC_INDEX LESS 10) + set(${OUTPUT_VAR} "0${INC_INDEX}") + else () + set(${OUTPUT_VAR} ${INC_INDEX}) + endif () +endmacro() diff --git a/firmware/common/toolchain/Platform/Extras/Printer.cmake b/firmware/common/toolchain/Platform/Extras/Printer.cmake new file mode 100644 index 00000000..d554e2c9 --- /dev/null +++ b/firmware/common/toolchain/Platform/Extras/Printer.cmake @@ -0,0 +1,125 @@ +#=============================================================================# +# print_board_list +# [PUBLIC/USER] +# +# print_board_list() +# +# see documentation at top +#=============================================================================# +function(PRINT_BOARD_LIST) + foreach (PLATFORM ${ARDUINO_PLATFORMS}) + if (${PLATFORM}_BOARDS) + message(STATUS "${PLATFORM} Boards:") + print_list(${PLATFORM}_BOARDS) + message(STATUS "") + endif () + endforeach () +endfunction() + +#=============================================================================# +# print_programmer_list +# [PUBLIC/USER] +# +# print_programmer_list() +# +# see documentation at top +#=============================================================================# +function(PRINT_PROGRAMMER_LIST) + foreach (PLATFORM ${ARDUINO_PLATFORMS}) + if (${PLATFORM}_PROGRAMMERS) + message(STATUS "${PLATFORM} Programmers:") + print_list(${PLATFORM}_PROGRAMMERS) + endif () + message(STATUS "") + endforeach () +endfunction() + +#=============================================================================# +# print_programmer_settings +# [PUBLIC/USER] +# +# print_programmer_settings(PROGRAMMER) +# +# see documentation at top +#=============================================================================# +function(PRINT_PROGRAMMER_SETTINGS PROGRAMMER) + if (${PROGRAMMER}.SETTINGS) + message(STATUS "Programmer ${PROGRAMMER} Settings:") + print_settings(${PROGRAMMER}) + endif () +endfunction() + +#=============================================================================# +# print_board_settings +# [PUBLIC/USER] +# +# print_board_settings(ARDUINO_BOARD) +# +# see documentation at top +function(PRINT_BOARD_SETTINGS ARDUINO_BOARD) + if (${ARDUINO_BOARD}.SETTINGS) + message(STATUS "Arduino ${ARDUINO_BOARD} Board:") + print_settings(${ARDUINO_BOARD}) + endif () +endfunction() + +#=============================================================================# +# print_settings +# [PRIVATE/INTERNAL] +# +# print_settings(ENTRY_NAME) +# +# ENTRY_NAME - name of entry +# +# Print the entry settings (see load_arduino_syle_settings()). +# +#=============================================================================# +function(PRINT_SETTINGS ENTRY_NAME) + if (${ENTRY_NAME}.SETTINGS) + + foreach (ENTRY_SETTING ${${ENTRY_NAME}.SETTINGS}) + if (${ENTRY_NAME}.${ENTRY_SETTING}) + message(STATUS " ${ENTRY_NAME}.${ENTRY_SETTING}=${${ENTRY_NAME}.${ENTRY_SETTING}}") + endif () + if (${ENTRY_NAME}.${ENTRY_SETTING}.SUBSETTINGS) + foreach (ENTRY_SUBSETTING ${${ENTRY_NAME}.${ENTRY_SETTING}.SUBSETTINGS}) + if (${ENTRY_NAME}.${ENTRY_SETTING}.${ENTRY_SUBSETTING}) + message(STATUS " ${ENTRY_NAME}.${ENTRY_SETTING}.${ENTRY_SUBSETTING}=${${ENTRY_NAME}.${ENTRY_SETTING}.${ENTRY_SUBSETTING}}") + endif () + endforeach () + endif () + message(STATUS "") + endforeach () + endif () +endfunction() + +#=============================================================================# +# print_list +# [PRIVATE/INTERNAL] +# +# print_list(SETTINGS_LIST) +# +# SETTINGS_LIST - Variables name of settings list +# +# Print list settings and names (see load_arduino_syle_settings()). +#=============================================================================# +function(PRINT_LIST SETTINGS_LIST) + if (${SETTINGS_LIST}) + set(MAX_LENGTH 0) + foreach (ENTRY_NAME ${${SETTINGS_LIST}}) + string(LENGTH "${ENTRY_NAME}" CURRENT_LENGTH) + if (CURRENT_LENGTH GREATER MAX_LENGTH) + set(MAX_LENGTH ${CURRENT_LENGTH}) + endif () + endforeach () + foreach (ENTRY_NAME ${${SETTINGS_LIST}}) + string(LENGTH "${ENTRY_NAME}" CURRENT_LENGTH) + math(EXPR PADDING_LENGTH "${MAX_LENGTH}-${CURRENT_LENGTH}") + set(PADDING "") + foreach (X RANGE ${PADDING_LENGTH}) + set(PADDING "${PADDING} ") + endforeach () + message(STATUS " ${PADDING}${ENTRY_NAME}: ${${ENTRY_NAME}.name}") + endforeach () + endif () +endfunction() diff --git a/firmware/common/toolchain/Platform/Generation/ArduinoExampleGenerator.cmake b/firmware/common/toolchain/Platform/Generation/ArduinoExampleGenerator.cmake new file mode 100644 index 00000000..24c4ac41 --- /dev/null +++ b/firmware/common/toolchain/Platform/Generation/ArduinoExampleGenerator.cmake @@ -0,0 +1,63 @@ +#=============================================================================# +# GENERATE_ARDUINO_EXAMPLE +# [PUBLIC/USER] +# see documentation at README +#=============================================================================# +function(GENERATE_ARDUINO_EXAMPLE INPUT_NAME) + parse_generator_arguments(${INPUT_NAME} INPUT + "" # Options + "CATEGORY;EXAMPLE;BOARD;BOARD_CPU;PORT;PROGRAMMER" # One Value Keywords + "SERIAL;AFLAGS" # Multi Value Keywords + ${ARGN}) + + + if (NOT INPUT_BOARD) + set(INPUT_BOARD ${ARDUINO_DEFAULT_BOARD}) + endif () + if (NOT INPUT_PORT) + set(INPUT_PORT ${ARDUINO_DEFAULT_PORT}) + endif () + if (NOT INPUT_SERIAL) + set(INPUT_SERIAL ${ARDUINO_DEFAULT_SERIAL}) + endif () + if (NOT INPUT_PROGRAMMER) + set(INPUT_PROGRAMMER ${ARDUINO_DEFAULT_PROGRAMMER}) + endif () + VALIDATE_VARIABLES_NOT_EMPTY(VARS INPUT_EXAMPLE INPUT_BOARD + MSG "must define for target ${INPUT_NAME}") + + _get_board_id(${INPUT_BOARD} "${INPUT_BOARD_CPU}" ${INPUT_NAME} BOARD_ID) + + message(STATUS "Generating ${INPUT_NAME}") + + set(ALL_LIBS) + set(ALL_SRCS) + + make_core_library(CORE_LIB ${BOARD_ID}) + + make_arduino_example("${INPUT_NAME}" "${INPUT_EXAMPLE}" ALL_SRCS "${INPUT_CATEGORY}") + + if (NOT ALL_SRCS) + message(FATAL_ERROR "Missing sources for example, aborting!") + endif () + + find_arduino_libraries(TARGET_LIBS "${ALL_SRCS}" "") + set(LIB_DEP_INCLUDES) + foreach (LIB_DEP ${TARGET_LIBS}) + set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} -I\"${LIB_DEP}\"") + endforeach () + + make_arduino_libraries(ALL_LIBS ${BOARD_ID} "${ALL_SRCS}" "" "${LIB_DEP_INCLUDES}" "") + + list(APPEND ALL_LIBS ${CORE_LIB} ${INPUT_LIBS}) + + create_arduino_firmware_target(${INPUT_NAME} ${BOARD_ID} "${ALL_SRCS}" "${ALL_LIBS}" "${LIB_DEP_INCLUDES}" "" FALSE) + + if (INPUT_PORT) + create_arduino_upload_target(${BOARD_ID} ${INPUT_NAME} ${INPUT_PORT} "${INPUT_PROGRAMMER}" "${INPUT_AFLAGS}") + endif () + + if (INPUT_SERIAL) + create_serial_target(${INPUT_NAME} "${INPUT_SERIAL}" "${INPUT_PORT}") + endif () +endfunction() diff --git a/firmware/common/toolchain/Platform/Generation/ArduinoFirmwareGenerator.cmake b/firmware/common/toolchain/Platform/Generation/ArduinoFirmwareGenerator.cmake new file mode 100644 index 00000000..dc4a4090 --- /dev/null +++ b/firmware/common/toolchain/Platform/Generation/ArduinoFirmwareGenerator.cmake @@ -0,0 +1,80 @@ +#=============================================================================# +# GENERATE_ARDUINO_FIRMWARE +# [PUBLIC/USER] +# see documentation at README +#=============================================================================# +function(GENERATE_ARDUINO_FIRMWARE INPUT_NAME) + message(STATUS "Generating ${INPUT_NAME}") + parse_generator_arguments(${INPUT_NAME} INPUT + "NO_AUTOLIBS;MANUAL" # Options + "BOARD;BOARD_CPU;PORT;SKETCH;PROGRAMMER" # One Value Keywords + "SERIAL;SRCS;HDRS;LIBS;ARDLIBS;AFLAGS" # Multi Value Keywords + ${ARGN}) + + if (NOT INPUT_BOARD) + set(INPUT_BOARD ${ARDUINO_DEFAULT_BOARD}) + endif () + if (NOT INPUT_PORT) + set(INPUT_PORT ${ARDUINO_DEFAULT_PORT}) + endif () + if (NOT INPUT_SERIAL) + set(INPUT_SERIAL ${ARDUINO_DEFAULT_SERIAL}) + endif () + if (NOT INPUT_PROGRAMMER) + set(INPUT_PROGRAMMER ${ARDUINO_DEFAULT_PROGRAMMER}) + endif () + if (NOT INPUT_MANUAL) + set(INPUT_MANUAL FALSE) + endif () + VALIDATE_VARIABLES_NOT_EMPTY(VARS INPUT_BOARD MSG "must define for target ${INPUT_NAME}") + + _get_board_id(${INPUT_BOARD} "${INPUT_BOARD_CPU}" ${INPUT_NAME} BOARD_ID) + + set(ALL_LIBS) + set(ALL_SRCS ${INPUT_SRCS} ${INPUT_HDRS}) + set(LIB_DEP_INCLUDES) + + if (NOT INPUT_MANUAL) + make_core_library(CORE_LIB ${BOARD_ID}) + endif () + + if (NOT "${INPUT_SKETCH}" STREQUAL "") + get_filename_component(INPUT_SKETCH "${INPUT_SKETCH}" ABSOLUTE) + make_arduino_sketch(${INPUT_NAME} ${INPUT_SKETCH} ALL_SRCS) + if (IS_DIRECTORY "${INPUT_SKETCH}") + set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} -I\"${INPUT_SKETCH}\"") + else () + get_filename_component(INPUT_SKETCH_PATH "${INPUT_SKETCH}" PATH) + set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} -I\"${INPUT_SKETCH_PATH}\"") + endif () + endif () + + VALIDATE_VARIABLES_NOT_EMPTY(VARS ALL_SRCS MSG "must define SRCS or SKETCH for target ${INPUT_NAME}") + + find_arduino_libraries(TARGET_LIBS "${ALL_SRCS}" "${INPUT_ARDLIBS}") + foreach (LIB_DEP ${TARGET_LIBS}) + arduino_debug_msg("Arduino Library: ${LIB_DEP}") + set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} -I\"${LIB_DEP}\"") + endforeach () + + if (NOT INPUT_NO_AUTOLIBS) + make_arduino_libraries(ALL_LIBS ${BOARD_ID} "${ALL_SRCS}" "${TARGET_LIBS}" "${LIB_DEP_INCLUDES}" "") + foreach (LIB_INCLUDES ${ALL_LIBS_INCLUDES}) + arduino_debug_msg("Arduino Library Includes: ${LIB_INCLUDES}") + set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} ${LIB_INCLUDES}") + endforeach () + endif () + + list(APPEND ALL_LIBS ${CORE_LIB} ${INPUT_LIBS}) + + create_arduino_firmware_target(${INPUT_NAME} ${BOARD_ID} "${ALL_SRCS}" "${ALL_LIBS}" "${LIB_DEP_INCLUDES}" "" "${INPUT_MANUAL}") + + if (INPUT_PORT) + create_arduino_upload_target(${BOARD_ID} ${INPUT_NAME} ${INPUT_PORT} "${INPUT_PROGRAMMER}" "${INPUT_AFLAGS}") + endif () + + if (INPUT_SERIAL) + create_serial_target(${INPUT_NAME} "${INPUT_SERIAL}" "${INPUT_PORT}") + endif () + +endfunction() \ No newline at end of file diff --git a/firmware/common/toolchain/Platform/Generation/ArduinoLibraryExampleGenerator.cmake b/firmware/common/toolchain/Platform/Generation/ArduinoLibraryExampleGenerator.cmake new file mode 100644 index 00000000..8eddf9a4 --- /dev/null +++ b/firmware/common/toolchain/Platform/Generation/ArduinoLibraryExampleGenerator.cmake @@ -0,0 +1,65 @@ +#=============================================================================# +# GENERATE_ARDUINO_LIBRARY_EXAMPLE +# [PUBLIC/USER] +# see documentation at README +#=============================================================================# +function(GENERATE_ARDUINO_LIBRARY_EXAMPLE INPUT_NAME) + parse_generator_arguments(${INPUT_NAME} INPUT + "" # Options + "LIBRARY;EXAMPLE;BOARD;BOARD_CPU;PORT;PROGRAMMER" # One Value Keywords + "SERIAL;AFLAGS" # Multi Value Keywords + ${ARGN}) + + if (NOT INPUT_BOARD) + set(INPUT_BOARD ${ARDUINO_DEFAULT_BOARD}) + endif () + if (NOT INPUT_PORT) + set(INPUT_PORT ${ARDUINO_DEFAULT_PORT}) + endif () + if (NOT INPUT_SERIAL) + set(INPUT_SERIAL ${ARDUINO_DEFAULT_SERIAL}) + endif () + if (NOT INPUT_PROGRAMMER) + set(INPUT_PROGRAMMER ${ARDUINO_DEFAULT_PROGRAMMER}) + endif () + VALIDATE_VARIABLES_NOT_EMPTY(VARS INPUT_LIBRARY INPUT_EXAMPLE INPUT_BOARD + MSG "must define for target ${INPUT_NAME}") + _get_board_id(${INPUT_BOARD} "${INPUT_BOARD_CPU}" ${INPUT_NAME} BOARD_ID) + + message(STATUS "Generating ${INPUT_NAME}") + + set(ALL_LIBS) + set(ALL_SRCS) + + make_core_library(CORE_LIB ${BOARD_ID}) + + find_arduino_libraries(TARGET_LIBS "" "${INPUT_LIBRARY}") + set(LIB_DEP_INCLUDES) + foreach (LIB_DEP ${TARGET_LIBS}) + set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} -I\"${LIB_DEP}\"") + endforeach () + + make_arduino_library_example("${INPUT_NAME}" "${INPUT_LIBRARY}" + "${INPUT_EXAMPLE}" ALL_SRCS) + + if (NOT ALL_SRCS) + message(FATAL_ERROR "Missing sources for example, aborting!") + endif () + + make_arduino_libraries(ALL_LIBS ${BOARD_ID} "${ALL_SRCS}" "${TARGET_LIBS}" + "${LIB_DEP_INCLUDES}" "") + + list(APPEND ALL_LIBS ${CORE_LIB} ${INPUT_LIBS}) + + create_arduino_firmware_target(${INPUT_NAME} ${BOARD_ID} "${ALL_SRCS}" "${ALL_LIBS}" + "${LIB_DEP_INCLUDES}" "" FALSE) + + if (INPUT_PORT) + create_arduino_upload_target(${BOARD_ID} ${INPUT_NAME} ${INPUT_PORT} + "${INPUT_PROGRAMMER}" "${INPUT_AFLAGS}") + endif () + + if (INPUT_SERIAL) + create_serial_target(${INPUT_NAME} "${INPUT_SERIAL}" "${INPUT_PORT}") + endif () +endfunction() \ No newline at end of file diff --git a/firmware/common/toolchain/Platform/Generation/ArduinoLibraryGenerator.cmake b/firmware/common/toolchain/Platform/Generation/ArduinoLibraryGenerator.cmake new file mode 100644 index 00000000..d50e5c48 --- /dev/null +++ b/firmware/common/toolchain/Platform/Generation/ArduinoLibraryGenerator.cmake @@ -0,0 +1,52 @@ +#=============================================================================# +# GENERATE_ARDUINO_LIBRARY +# [PUBLIC/USER] +# see documentation at README +#=============================================================================# +function(GENERATE_ARDUINO_LIBRARY INPUT_NAME) + message(STATUS "Generating ${INPUT_NAME}") + parse_generator_arguments(${INPUT_NAME} INPUT + "NO_AUTOLIBS;MANUAL" # Options + "BOARD;BOARD_CPU" # One Value Keywords + "SRCS;HDRS;LIBS" # Multi Value Keywords + ${ARGN}) + + if (NOT INPUT_BOARD) + set(INPUT_BOARD ${ARDUINO_DEFAULT_BOARD}) + endif () + if (NOT INPUT_MANUAL) + set(INPUT_MANUAL FALSE) + endif () + VALIDATE_VARIABLES_NOT_EMPTY(VARS INPUT_SRCS INPUT_BOARD MSG "must define for target ${INPUT_NAME}") + + _get_board_id(${INPUT_BOARD} "${INPUT_BOARD_CPU}" ${INPUT_NAME} BOARD_ID) + + set(ALL_LIBS) + set(ALL_SRCS ${INPUT_SRCS} ${INPUT_HDRS}) + + if (NOT INPUT_MANUAL) + make_core_library(CORE_LIB ${BOARD_ID}) + endif () + + find_arduino_libraries(TARGET_LIBS "${ALL_SRCS}" "") + set(LIB_DEP_INCLUDES) + foreach (LIB_DEP ${TARGET_LIBS}) + set(LIB_DEP_INCLUDES "${LIB_DEP_INCLUDES} -I\"${LIB_DEP}\"") + endforeach () + + if (NOT ${INPUT_NO_AUTOLIBS}) + make_arduino_libraries(ALL_LIBS ${BOARD_ID} "${ALL_SRCS}" "" "${LIB_DEP_INCLUDES}" "") + endif () + + list(APPEND ALL_LIBS ${CORE_LIB} ${INPUT_LIBS}) + + add_library(${INPUT_NAME} ${ALL_SRCS}) + + set_board_flags(ARDUINO_COMPILE_FLAGS ARDUINO_LINK_FLAGS ${BOARD_ID} ${INPUT_MANUAL}) + + set_target_properties(${INPUT_NAME} PROPERTIES + COMPILE_FLAGS "${ARDUINO_COMPILE_FLAGS} ${COMPILE_FLAGS} ${LIB_DEP_INCLUDES}" + LINK_FLAGS "${ARDUINO_LINK_FLAGS} ${LINK_FLAGS}") + + target_link_libraries(${INPUT_NAME} ${ALL_LIBS} "-lc -lm") +endfunction() diff --git a/firmware/common/toolchain/Platform/Generation/AvrFirmwareGenerator.cmake b/firmware/common/toolchain/Platform/Generation/AvrFirmwareGenerator.cmake new file mode 100644 index 00000000..3a9667e2 --- /dev/null +++ b/firmware/common/toolchain/Platform/Generation/AvrFirmwareGenerator.cmake @@ -0,0 +1,53 @@ +#=============================================================================# +# GENERATE_AVR_FIRMWARE +# [PUBLIC/USER] +# see documentation at README +#=============================================================================# +function(GENERATE_AVR_FIRMWARE INPUT_NAME) + # TODO: This is not optimal!!!! + message(STATUS "Generating ${INPUT_NAME}") + parse_generator_arguments(${INPUT_NAME} INPUT + "NO_AUTOLIBS;MANUAL" # Options + "BOARD;BOARD_CPU;PORT;PROGRAMMER" # One Value Keywords + "SERIAL;SRCS;HDRS;LIBS;AFLAGS" # Multi Value Keywords + ${ARGN}) + + if (NOT INPUT_BOARD) + set(INPUT_BOARD ${ARDUINO_DEFAULT_BOARD}) + endif () + if (NOT INPUT_PORT) + set(INPUT_PORT ${ARDUINO_DEFAULT_PORT}) + endif () + if (NOT INPUT_SERIAL) + set(INPUT_SERIAL ${ARDUINO_DEFAULT_SERIAL}) + endif () + if (NOT INPUT_PROGRAMMER) + set(INPUT_PROGRAMMER ${ARDUINO_DEFAULT_PROGRAMMER}) + endif () + + VALIDATE_VARIABLES_NOT_EMPTY(VARS INPUT_BOARD INPUT_SRCS MSG "must define for target ${INPUT_NAME}") + + if (INPUT_HDRS) + list(INSERT INPUT_HDRS 0 "HDRS") + endif () + if (INPUT_LIBS) + list(INSERT INPUT_LIBS 0 "LIBS") + endif () + if (INPUT_AFLAGS) + list(INSERT INPUT_AFLAGS 0 "AFLAGS") + endif () + + generate_arduino_firmware(${INPUT_NAME} + NO_AUTOLIBS + MANUAL + BOARD ${INPUT_BOARD} + BOARD_CPU ${INPUT_BOARD_CPU} + PORT ${INPUT_PORT} + PROGRAMMER ${INPUT_PROGRAMMER} + SERIAL ${INPUT_SERIAL} + SRCS ${INPUT_SRCS} + ${INPUT_HDRS} + ${INPUT_LIBS} + ${INPUT_AFLAGS}) + +endfunction() diff --git a/firmware/common/toolchain/Platform/Generation/AvrLibraryGenerator.cmake b/firmware/common/toolchain/Platform/Generation/AvrLibraryGenerator.cmake new file mode 100644 index 00000000..9d827de4 --- /dev/null +++ b/firmware/common/toolchain/Platform/Generation/AvrLibraryGenerator.cmake @@ -0,0 +1,44 @@ +#=============================================================================# +# GENERATE_AVR_LIBRARY +# [PUBLIC/USER] +# see documentation at README +#=============================================================================# +function(GENERATE_AVR_LIBRARY INPUT_NAME) + message(STATUS "Generating ${INPUT_NAME}") + parse_generator_arguments(${INPUT_NAME} INPUT + "NO_AUTOLIBS;MANUAL" # Options + "BOARD;BOARD_CPU" # One Value Keywords + "SRCS;HDRS;LIBS" # Multi Value Keywords + ${ARGN}) + + if (NOT INPUT_BOARD) + set(INPUT_BOARD ${ARDUINO_DEFAULT_BOARD}) + endif () + + VALIDATE_VARIABLES_NOT_EMPTY(VARS INPUT_SRCS INPUT_BOARD MSG "must define for target ${INPUT_NAME}") + + if (INPUT_HDRS) + set(INPUT_HDRS "SRCS ${INPUT_HDRS}") + endif () + if (INPUT_LIBS) + set(INPUT_LIBS "LIBS ${INPUT_LIBS}") + endif () + + if (INPUT_HDRS) + list(INSERT INPUT_HDRS 0 "HDRS") + endif () + if (INPUT_LIBS) + list(INSERT INPUT_LIBS 0 "LIBS") + endif () + + + generate_arduino_library(${INPUT_NAME} + NO_AUTOLIBS + MANUAL + BOARD ${INPUT_BOARD} + BOARD_CPU ${INPUT_BOARD_CPU} + SRCS ${INPUT_SRCS} + ${INPUT_HDRS} + ${INPUT_LIBS}) + +endfunction() diff --git a/firmware/common/toolchain/Platform/Initialization/DefineAdvancedVariables.cmake b/firmware/common/toolchain/Platform/Initialization/DefineAdvancedVariables.cmake new file mode 100644 index 00000000..f02c7c8c --- /dev/null +++ b/firmware/common/toolchain/Platform/Initialization/DefineAdvancedVariables.cmake @@ -0,0 +1,14 @@ +mark_as_advanced( + ARDUINO_CORES_PATH + ARDUINO_VARIANTS_PATH + ARDUINO_BOOTLOADERS_PATH + ARDUINO_LIBRARIES_PATH + ARDUINO_BOARDS_PATH + ARDUINO_PROGRAMMERS_PATH + ARDUINO_VERSION_PATH + ARDUINO_AVRDUDE_FLAGS + ARDUINO_AVRDUDE_PROGRAM + ARDUINO_AVRDUDE_CONFIG_PATH + ARDUINO_OBJCOPY_EEP_FLAGS + ARDUINO_OBJCOPY_HEX_FLAGS + AVRSIZE_PROGRAM) diff --git a/firmware/common/toolchain/Platform/Initialization/DetectVersion.cmake b/firmware/common/toolchain/Platform/Initialization/DetectVersion.cmake new file mode 100644 index 00000000..d7d1115c --- /dev/null +++ b/firmware/common/toolchain/Platform/Initialization/DetectVersion.cmake @@ -0,0 +1,67 @@ +#=============================================================================# +# Detects the Arduino SDK Version based on the revisions.txt file. +# The following variables will be generated: +# +# ${OUTPUT_VAR_NAME} -> the full version (major.minor.patch) +# ${OUTPUT_VAR_NAME}_MAJOR -> the major version +# ${OUTPUT_VAR_NAME}_MINOR -> the minor version +# ${OUTPUT_VAR_NAME}_PATCH -> the patch version +# +#=============================================================================# +find_file(ARDUINO_VERSION_PATH + NAMES lib/version.txt + PATHS ${ARDUINO_SDK_PATH} + DOC "Path to Arduino version file.") + +find_file(ARDUINO_REVISION_PATH + NAMES revisions.txt + PATHS ${ARDUINO_SDK_PATH} + DOC "Path to Arduino's revision-tracking file.") + +if (NOT ARDUINO_VERSION_PATH) + message(FATAL_ERROR "Couldn't find SDK's version file, aborting.") +endif () + +file(READ ${ARDUINO_VERSION_PATH} RAW_VERSION) +if ("${RAW_VERSION}" MATCHES " *[0]+([0-9]+)") + set(PARSED_VERSION 0.${CMAKE_MATCH_1}.0) +elseif ("${RAW_VERSION}" MATCHES "[ ]*([0-9]+[.][0-9]+[.][0-9]+)") + set(PARSED_VERSION ${CMAKE_MATCH_1}) +elseif ("${RAW_VERSION}" MATCHES "[ ]*([0-9]+[.][0-9]+)") + set(PARSED_VERSION ${CMAKE_MATCH_1}.0) +endif () + +if (NOT ARDUINO_REVISION_PATH) + message(WARNING "Couldn't find SDK's revisions file, defaulting to 0.") +else () + file(READ ${ARDUINO_REVISION_PATH} RAW_REVISION 0 30) + if ("${RAW_REVISION}" MATCHES ".*${PARSED_VERSION}.*[-].*") + string(REGEX MATCH "[-][ ]?([0-9]+[.][0-9]+[.][0-9]+)" + TMP_REV ${RAW_REVISION}) + set(PARSED_REVISION ${CMAKE_MATCH_1}) + else () + set(PARSED_REVISION 0) + endif () +endif () + +if (NOT PARSED_VERSION STREQUAL "") + string(REPLACE "." ";" SPLIT_VERSION ${PARSED_VERSION}) + list(GET SPLIT_VERSION 0 SPLIT_VERSION_MAJOR) + list(GET SPLIT_VERSION 1 SPLIT_VERSION_MINOR) + list(GET SPLIT_VERSION 2 SPLIT_VERSION_PATCH) + + string(CONCAT FULL_SDK_VERSION "${PARSED_VERSION}" "-" "${PARSED_REVISION}") + + set(ARDUINO_SDK_VERSION "${PARSED_VERSION}" CACHE STRING "Arduino SDK Version") + set(ARUDINO_SDK_FULL_VERSION "${FULL_SDK_VERSION}" CACHE STRING "Full Arduino SDK version") + set(ARDUINO_SDK_VERSION_MAJOR ${SPLIT_VERSION_MAJOR} CACHE STRING "Arduino SDK Major Version") + set(ARDUINO_SDK_VERSION_MINOR ${SPLIT_VERSION_MINOR} CACHE STRING "Arduino SDK Minor Version") + set(ARDUINO_SDK_VERSION_PATCH ${SPLIT_VERSION_PATCH} CACHE STRING "Arduino SDK Patch Version") + set(ARDUINO_SDK_VERSION_REVISION ${PARSED_REVISION} CACHE STRING "Arduino SDK Revision") +endif () + +if (ARDUINO_SDK_VERSION VERSION_LESS 0.19) + message(FATAL_ERROR "Unsupported Arduino SDK (requires version 0.19 or higher)") +endif () + +message(STATUS "Arduino SDK version ${ARUDINO_SDK_FULL_VERSION}: ${ARDUINO_SDK_PATH}") diff --git a/firmware/common/toolchain/Platform/Initialization/FindPrograms.cmake b/firmware/common/toolchain/Platform/Initialization/FindPrograms.cmake new file mode 100644 index 00000000..8bbe5b2d --- /dev/null +++ b/firmware/common/toolchain/Platform/Initialization/FindPrograms.cmake @@ -0,0 +1,58 @@ +find_file(ARDUINO_EXAMPLES_PATH + NAMES examples + PATHS ${ARDUINO_SDK_PATH} + DOC "Path to directory containg the Arduino built-in examples." + NO_DEFAULT_PATH) + +find_file(ARDUINO_LIBRARIES_PATH + NAMES libraries + PATHS ${ARDUINO_SDK_PATH} + DOC "Path to directory containing the Arduino libraries." + NO_DEFAULT_PATH) + +find_program(ARDUINO_AVRDUDE_PROGRAM + NAMES avrdude + PATHS ${ARDUINO_SDK_PATH} + PATH_SUFFIXES hardware/tools hardware/tools/avr/bin + NO_DEFAULT_PATH) + +find_program(ARDUINO_AVRDUDE_PROGRAM + NAMES avrdude + DOC "Path to avrdude programmer binary.") + +find_program(AVRSIZE_PROGRAM + NAMES avr-size) + +find_file(ARDUINO_AVRDUDE_CONFIG_PATH + NAMES avrdude.conf + PATHS ${ARDUINO_SDK_PATH} /etc/avrdude /etc + PATH_SUFFIXES hardware/tools + hardware/tools/avr/etc + DOC "Path to avrdude programmer configuration file.") + +if (ARDUINO_SDK_VERSION VERSION_LESS 1.0.0) + find_file(ARDUINO_PLATFORM_HEADER_FILE_PATH + NAMES WProgram.h + PATHS ${ARDUINO_SDK_PATH} + PATH_SUFFIXES hardware/arduino/avr/cores/arduino + DOC "Path to Arduino platform's main header file" + NO_DEFAULT_PATH) +else () + find_file(ARDUINO_PLATFORM_HEADER_FILE_PATH + NAMES Arduino.h + PATHS ${ARDUINO_SDK_PATH} + PATH_SUFFIXES hardware/arduino/avr/cores/arduino + DOC "Path to Arduino platform's main header file" + NO_DEFAULT_PATH) +endif () + +if (NOT CMAKE_OBJCOPY) + find_program(AVROBJCOPY_PROGRAM + avr-objcopy) + set(ADDITIONAL_REQUIRED_VARS AVROBJCOPY_PROGRAM) + set(CMAKE_OBJCOPY ${AVROBJCOPY_PROGRAM}) +endif (NOT CMAKE_OBJCOPY) + +if (EXISTS "${ARDUINO_EXAMPLES_PATH}") + include(SetupExampleCategories) +endif () diff --git a/firmware/common/toolchain/Platform/Initialization/Initializer.cmake b/firmware/common/toolchain/Platform/Initialization/Initializer.cmake new file mode 100644 index 00000000..80e63bec --- /dev/null +++ b/firmware/common/toolchain/Platform/Initialization/Initializer.cmake @@ -0,0 +1,24 @@ +#=============================================================================# +# Initialization +#=============================================================================# + +if (NOT ARDUINO_FOUND AND ARDUINO_SDK_PATH) + + include(SetupCompilerSettings) + include(SetupArduinoSettings) + + # get version first (some stuff depends on versions) + include(DetectVersion) + + include(RegisterHardwarePlatform) + include(FindPrograms) + include(SetDefaults) + include(SetupFirmwareSizeScript) + include(SetupLibraryBlacklist) + + include(TestSetup) + include(DefineAdvancedVariables) + + set(ARDUINO_FOUND True CACHE INTERNAL "Arduino Found") + +endif () diff --git a/firmware/common/toolchain/Platform/Initialization/LoadArduinoPlatformSettings.cmake b/firmware/common/toolchain/Platform/Initialization/LoadArduinoPlatformSettings.cmake new file mode 100644 index 00000000..843fdb6a --- /dev/null +++ b/firmware/common/toolchain/Platform/Initialization/LoadArduinoPlatformSettings.cmake @@ -0,0 +1,134 @@ +# SETTINGS_LIST - Variable name of settings list +# SETTINGS_PATH - File path of settings file to load. +# +# Loads an Arduino settings file into the cache. +# +# Examples of this type of settings file is the boards.txt and +# programmers.txt files located in ${ARDUINO_SDK}/hardware/arduino. +# +# Settings have to following format: +# +# entry.setting[.subsetting] = value +# +# where [.subsetting] is optional +# +# For example, the following settings: +# +# uno.name=Arduino Uno +# uno.upload.protocol=stk500 +# uno.upload.maximum_size=32256 +# uno.build.mcu=atmega328p +# uno.build.core=arduino +# +# will generate the follwoing equivalent CMake variables: +# +# set(uno.name "Arduino Uno") +# set(uno.upload.protocol "stk500") +# set(uno.upload.maximum_size "32256") +# set(uno.build.mcu "atmega328p") +# set(uno.build.core "arduino") +# +# set(uno.SETTINGS name upload build) # List of settings for uno +# set(uno.upload.SUBSETTINGS protocol maximum_size) # List of sub-settings for uno.upload +# set(uno.build.SUBSETTINGS mcu core) # List of sub-settings for uno.build +# +# Note that Arduino 1.6 SDK or greater treats most of the settings differently for some boards, +# by grouping them into menus which differentiate on their cpu architecture. +# +# For example, the settings declared earlier for "regular" SDKs +# would be declared as such in 1.6: +# +# mega.name=Arduino Uno +# mega.menu.cpu.atmega2560.upload.protocol=wiring +# mega.menu.cpu.atmega2560.upload.maximum_size=253952 +# mega.menu.cpu.atmega2560.build.mcu=atmega2560 +# mega.build.core=arduino +# +# The ${ENTRY_NAME}.SETTINGS variable lists all settings for the entry, while +# ${ENTRY_NAME}.SUBSETTINGS variables lists all settings for a sub-setting of +# a entry setting pair. +# +# These variables are generated in order to be able to programatically traverse +# all settings (for a example see print_board_settings() function). +# +#=============================================================================# +if (NOT ${SETTINGS_LIST} AND EXISTS ${SETTINGS_PATH}) + file(STRINGS ${SETTINGS_PATH} FILE_ENTRIES) # Settings file split into lines + + foreach (FILE_ENTRY ${FILE_ENTRIES}) + if ("${FILE_ENTRY}" MATCHES "^[^#]+=.*") + string(REGEX MATCH "^[^=]+" SETTING_NAME ${FILE_ENTRY}) + string(REGEX MATCH "[^=]+$" SETTING_VALUE ${FILE_ENTRY}) + string(REPLACE "." ";" ENTRY_NAME_TOKENS ${SETTING_NAME}) + string(STRIP "${SETTING_VALUE}" SETTING_VALUE) + + list(LENGTH ENTRY_NAME_TOKENS ENTRY_NAME_TOKENS_LEN) + + # Add entry to settings list if it does not exist + list(GET ENTRY_NAME_TOKENS 0 ENTRY_NAME) + list(FIND ${SETTINGS_LIST} ${ENTRY_NAME} ENTRY_NAME_INDEX) + if (ENTRY_NAME_INDEX LESS 0) + # Add entry to main list + list(APPEND ${SETTINGS_LIST} ${ENTRY_NAME}) + endif () + + # Add entry setting to entry settings list if it does not exist + set(ENTRY_SETTING_LIST ${ENTRY_NAME}.SETTINGS) + + # menu.cpu.architecture settings + if (ENTRY_NAME_TOKENS_LEN GREATER 5) + list(GET ENTRY_NAME_TOKENS 3 CPU_ARCH) + list(GET ENTRY_NAME_TOKENS 4 ENTRY_SETTING) + set(ENTRY_SETTING menu.cpu.${CPU_ARCH}.${ENTRY_SETTING}) + else () + list(GET ENTRY_NAME_TOKENS 1 ENTRY_SETTING) + endif () + + list(FIND ${ENTRY_SETTING_LIST} ${ENTRY_SETTING} ENTRY_SETTING_INDEX) + if (ENTRY_SETTING_INDEX LESS 0) + # Add setting to entry + list(APPEND ${ENTRY_SETTING_LIST} ${ENTRY_SETTING}) + set(${ENTRY_SETTING_LIST} ${${ENTRY_SETTING_LIST}} + CACHE INTERNAL "Arduino ${ENTRY_NAME} Board settings list") + endif () + + set(FULL_SETTING_NAME ${ENTRY_NAME}.${ENTRY_SETTING}) + + # Add entry sub-setting to entry sub-settings list if it does not exists + if (ENTRY_NAME_TOKENS_LEN GREATER 2) + + set(ENTRY_SUBSETTING_LIST ${ENTRY_NAME}.${ENTRY_SETTING}.SUBSETTINGS) + if (ENTRY_NAME_TOKENS_LEN GREATER 5) + list(GET ENTRY_NAME_TOKENS 5 ENTRY_SUBSETTING) + elseif (ENTRY_NAME_TOKENS_LEN GREATER 3) + # Search for special cpu sub-settings + list(GET ENTRY_NAME_TOKENS 2 ENTRY_SUBSETTING) + string(TOLOWER ${ENTRY_SUBSETTING} ENTRY_SUBSETTING) + if ("${ENTRY_SUBSETTING}" STREQUAL "cpu") + # cpu setting found, determine architecture + list(GET ENTRY_NAME_TOKENS 3 ENTRY_SUBSETTING) + set(ENTRY_SUBSETTING_LIST ${ENTRY_NAME}.${ENTRY_SETTING}.CPUS) + endif () + else () + list(GET ENTRY_NAME_TOKENS 2 ENTRY_SUBSETTING) + endif () + list(FIND ${ENTRY_SUBSETTING_LIST} ${ENTRY_SUBSETTING} ENTRY_SUBSETTING_INDEX) + if (ENTRY_SUBSETTING_INDEX LESS 0) + list(APPEND ${ENTRY_SUBSETTING_LIST} ${ENTRY_SUBSETTING}) + set(${ENTRY_SUBSETTING_LIST} ${${ENTRY_SUBSETTING_LIST}} + CACHE INTERNAL "Arduino ${ENTRY_NAME} Board sub-settings list") + endif () + set(FULL_SETTING_NAME ${FULL_SETTING_NAME}.${ENTRY_SUBSETTING}) + + endif () + + # Save setting value + set(${FULL_SETTING_NAME} ${SETTING_VALUE} + CACHE INTERNAL "Arduino ${ENTRY_NAME} Board setting") + + endif () + endforeach () + set(${SETTINGS_LIST} ${${SETTINGS_LIST}} + CACHE STRING "List of detected Arduino Board configurations") + mark_as_advanced(${SETTINGS_LIST}) +endif () diff --git a/firmware/common/toolchain/Platform/Initialization/RegisterHardwarePlatform.cmake b/firmware/common/toolchain/Platform/Initialization/RegisterHardwarePlatform.cmake new file mode 100644 index 00000000..a8902667 --- /dev/null +++ b/firmware/common/toolchain/Platform/Initialization/RegisterHardwarePlatform.cmake @@ -0,0 +1,18 @@ +if (NOT PLATFORM_PATH) + # Arduino is assumed as the default platform + set(PLATFORM_PATH ${ARDUINO_SDK_PATH}/hardware/arduino/) +endif () +string(REGEX REPLACE "/$" "" PLATFORM_PATH ${PLATFORM_PATH}) +GET_FILENAME_COMPONENT(VENDOR_ID ${PLATFORM_PATH} NAME) +GET_FILENAME_COMPONENT(BASE_PATH ${PLATFORM_PATH} PATH) + +if (NOT PLATFORM_ARCHITECTURE) + # avr is the default architecture + set(PLATFORM_ARCHITECTURE "avr") +endif () + +if (CUSTOM_PLATFORM_REGISTRATION_SCRIPT) + include("${CUSTOM_PLATFORM_REGISTRATION_SCRIPT}") +else () + include(RegisterSpecificHardwarePlatform) +endif () diff --git a/firmware/common/toolchain/Platform/Initialization/RegisterSpecificHardwarePlatform.cmake b/firmware/common/toolchain/Platform/Initialization/RegisterSpecificHardwarePlatform.cmake new file mode 100644 index 00000000..434384f7 --- /dev/null +++ b/firmware/common/toolchain/Platform/Initialization/RegisterSpecificHardwarePlatform.cmake @@ -0,0 +1,96 @@ +#=============================================================================# +# ToDo: Document +#=============================================================================# + +set(PLATFORM_PATH "${BASE_PATH}/${VENDOR_ID}/${PLATFORM_ARCHITECTURE}") +set(PLATFORM "${VENDOR_ID}") +set(ARCHITECTURE_ID ${PLATFORM_ARCHITECTURE}) + +# Avoid defining a platform multiple times if it has already been defined before +string(TOUPPER ${PLATFORM} PLATFORM) +list(FIND ARDUINO_PLATFORMS ${PLATFORM} PLATFORM_EXISTS) + +if (PLATFORM_EXISTS GREATER -1) + return() +endif () + +set(${PLATFORM}_PLATFORM_PATH ${PLATFORM_PATH} CACHE INTERNAL "The path to ${PLATFORM}") +set(ARDUINO_PLATFORMS ${ARDUINO_PLATFORMS} ${PLATFORM} CACHE INTERNAL "A list of registered platforms") + +find_file(${PLATFORM}_CORES_PATH + NAMES cores + PATHS ${PLATFORM_PATH} + DOC "Path to directory containing the Arduino core sources.") + +find_file(${PLATFORM}_VARIANTS_PATH + NAMES variants + PATHS ${PLATFORM_PATH} + DOC "Path to directory containing the Arduino variant sources.") + +find_file(${PLATFORM}_BOOTLOADERS_PATH + NAMES bootloaders + PATHS ${PLATFORM_PATH} + DOC "Path to directory containing the Arduino bootloader images and sources.") + +find_file(${PLATFORM}_PROGRAMMERS_PATH + NAMES programmers.txt + PATHS ${PLATFORM_PATH} + DOC "Path to Arduino programmers definition file.") + +find_file(${PLATFORM}_BOARDS_PATH + NAMES boards.txt + PATHS ${PLATFORM_PATH} + DOC "Path to Arduino boards definition file.") + +# some libraries are in platform path in versions 1.5 and greater +if (ARDUINO_SDK_VERSION VERSION_GREATER 1.0.5) + find_file(${PLATFORM}_PLATFORM_LIBRARIES_PATH + NAMES libraries + PATHS ${PLATFORM_PATH} + DOC "Path to platform directory containing the Arduino libraries.") + set(ARDUINO_PLATFORM_LIBRARIES_PATH "${${PLATFORM}_PLATFORM_LIBRARIES_PATH}") +else () + set(ARDUINO_PLATFORM_LIBRARIES_PATH "") +endif () + +if (${PLATFORM}_BOARDS_PATH) + set(SETTINGS_LIST ${PLATFORM}_BOARDS) + set(SETTINGS_PATH "${${PLATFORM}_BOARDS_PATH}") + include(LoadArduinoPlatformSettings) +endif () + +if (${PLATFORM}_PROGRAMMERS_PATH) + set(SETTINGS_LIST ${PLATFORM}_PROGRAMMERS) + set(SETTINGS_PATH "${${PLATFORM}_PROGRAMMERS_PATH}") + include(LoadArduinoPlatformSettings) +endif () + +if (${PLATFORM}_VARIANTS_PATH) + file(GLOB sub-dir ${${PLATFORM}_VARIANTS_PATH}/*) + foreach (dir ${sub-dir}) + if (IS_DIRECTORY ${dir}) + get_filename_component(variant ${dir} NAME) + set(VARIANTS ${VARIANTS} ${variant} CACHE INTERNAL "A list of registered variant boards") + set(${variant}.path ${dir} CACHE INTERNAL "The path to the variant ${variant}") + endif () + endforeach () +endif () + +if (${PLATFORM}_CORES_PATH) + file(GLOB sub-dir ${${PLATFORM}_CORES_PATH}/*) + foreach (dir ${sub-dir}) + if (IS_DIRECTORY ${dir}) + get_filename_component(core ${dir} NAME) + set(CORES ${CORES} ${core} CACHE INTERNAL "A list of registered cores") + set(${core}.path ${dir} CACHE INTERNAL "The path to the core ${core}") + + # See https://github.com/arduino/Arduino/wiki/Arduino-IDE-1.5-3rd-party-Hardware-specification#referencing-another-core-variant-or-tool + # for an explanation why cores must also be available as : + # and :: + set(CORES ${CORES} "${VENDOR_ID}:${core}" CACHE INTERNAL "A list of registered cores") + set(${VENDOR_ID}:${core}.path ${dir} CACHE INTERNAL "The path to the core ${core}") + set(CORES ${CORES} "${VENDOR_ID}:${ARCHITECTURE_ID}:${core}" CACHE INTERNAL "A list of registered cores") + + endif () + endforeach () +endif () diff --git a/firmware/common/toolchain/Platform/Initialization/SetDefaults.cmake b/firmware/common/toolchain/Platform/Initialization/SetDefaults.cmake new file mode 100644 index 00000000..945a9d04 --- /dev/null +++ b/firmware/common/toolchain/Platform/Initialization/SetDefaults.cmake @@ -0,0 +1,6 @@ +set(ARDUINO_DEFAULT_BOARD uno CACHE STRING "Default Arduino Board ID when not specified.") +set(ARDUINO_DEFAULT_PORT CACHE STRING "Default Arduino port when not specified.") +set(ARDUINO_DEFAULT_SERIAL CACHE STRING "Default Arduino Serial command when not specified.") +set(ARDUINO_DEFAULT_PROGRAMMER CACHE STRING "Default Arduino Programmer ID when not specified.") +set(ARDUINO_CMAKE_RECURSION_DEFAULT FALSE CACHE BOOL + "The default recursion behavior during library setup") diff --git a/firmware/common/toolchain/Platform/Initialization/SetupArduinoSettings.cmake b/firmware/common/toolchain/Platform/Initialization/SetupArduinoSettings.cmake new file mode 100644 index 00000000..4c48cdd2 --- /dev/null +++ b/firmware/common/toolchain/Platform/Initialization/SetupArduinoSettings.cmake @@ -0,0 +1,9 @@ +#=============================================================================# +# Arduino Settings +#=============================================================================# +# Setups some basic flags for the arduino upload tools. +#=============================================================================# +set(ARDUINO_OBJCOPY_EEP_FLAGS -O ihex -j .eeprom --set-section-flags=.eeprom=alloc,load + --no-change-warnings --change-section-lma .eeprom=0 CACHE STRING "") +set(ARDUINO_OBJCOPY_HEX_FLAGS -O ihex -R .eeprom CACHE STRING "") +set(ARDUINO_AVRDUDE_FLAGS -V CACHE STRING "") diff --git a/firmware/common/toolchain/Platform/Initialization/SetupCompilerSettings.cmake b/firmware/common/toolchain/Platform/Initialization/SetupCompilerSettings.cmake new file mode 100644 index 00000000..5e98ae0a --- /dev/null +++ b/firmware/common/toolchain/Platform/Initialization/SetupCompilerSettings.cmake @@ -0,0 +1,96 @@ +#=============================================================================# +# C Flags +#=============================================================================# +#=============================================================================# +# setup_c_flags +# [PRIVATE/INTERNAL] +# +# setup_c_flags() +# +# Setups some basic flags for the gcc compiler to use later. +#=============================================================================# +function(setup_c_flags) + if (NOT DEFINED ARDUINO_C_FLAGS) + set(ARDUINO_C_FLAGS "-mcall-prologues -ffunction-sections -fdata-sections") + endif (NOT DEFINED ARDUINO_C_FLAGS) + set(CMAKE_C_FLAGS "-g -Os ${ARDUINO_C_FLAGS}" CACHE STRING "") + set(CMAKE_C_FLAGS_DEBUG "-g ${ARDUINO_C_FLAGS}" CACHE STRING "") + set(CMAKE_C_FLAGS_MINSIZEREL "-Os -DNDEBUG ${ARDUINO_C_FLAGS}" CACHE STRING "") + set(CMAKE_C_FLAGS_RELEASE "-Os -DNDEBUG -w ${ARDUINO_C_FLAGS}" CACHE STRING "") + set(CMAKE_C_FLAGS_RELWITHDEBINFO "-Os -g -w ${ARDUINO_C_FLAGS}" CACHE STRING "") +endfunction() + +#=============================================================================# +# C++ Flags +#=============================================================================# +#=============================================================================# +# setup_c_flags +# [PRIVATE/INTERNAL] +# +# setup_cxx_flags() +# +# Setups some basic flags for the g++ compiler to use later. +#=============================================================================# +function(setup_cxx_flags) + if (NOT DEFINED ARDUINO_CXX_FLAGS) + set(ARDUINO_CXX_FLAGS "${ARDUINO_C_FLAGS} -fno-exceptions") + endif (NOT DEFINED ARDUINO_CXX_FLAGS) + set(CMAKE_CXX_FLAGS "-g -Os ${ARDUINO_CXX_FLAGS}" CACHE STRING "") + set(CMAKE_CXX_FLAGS_DEBUG "-g ${ARDUINO_CXX_FLAGS}" CACHE STRING "") + set(CMAKE_CXX_FLAGS_MINSIZEREL "-Os -DNDEBUG ${ARDUINO_CXX_FLAGS}" CACHE STRING "") + set(CMAKE_CXX_FLAGS_RELEASE "-Os -DNDEBUG ${ARDUINO_CXX_FLAGS}" CACHE STRING "") + set(CMAKE_CXX_FLAGS_RELWITHDEBINFO "-Os -g ${ARDUINO_CXX_FLAGS}" CACHE STRING "") +endfunction() + +#=============================================================================# +# Executable Linker Flags # +#=============================================================================# +#=============================================================================# +# setup_exe_linker_flags +# [PRIVATE/INTERNAL] +# +# setup_exe_linker_flags() +# +# Setups some basic flags for the gcc linker to use when linking executables. +#=============================================================================# +function(setup_exe_linker_flags) + set(ARDUINO_LINKER_FLAGS "-Wl,--gc-sections -lm") + set(CMAKE_EXE_LINKER_FLAGS "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") + set(CMAKE_EXE_LINKER_FLAGS_DEBUG "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") + set(CMAKE_EXE_LINKER_FLAGS_MINSIZEREL "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") + set(CMAKE_EXE_LINKER_FLAGS_RELEASE "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") + set(CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +endfunction() + +#=============================================================================# +# Shared Library Linker Flags # +#=============================================================================# +#=============================================================================# +# setup_shared_lib_flags +# [PRIVATE/INTERNAL] +# +# setup_shared_lib_flags() +# +# Setups some basic flags for the gcc linker to use when linking shared libraries. +#=============================================================================# +function(setup_shared_lib_flags) + set(CMAKE_SHARED_LINKER_FLAGS "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") + set(CMAKE_SHARED_LINKER_FLAGS_DEBUG "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") + set(CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") + set(CMAKE_SHARED_LINKER_FLAGS_RELEASE "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") + set(CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") + + set(CMAKE_MODULE_LINKER_FLAGS "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") + set(CMAKE_MODULE_LINKER_FLAGS_DEBUG "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") + set(CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") + set(CMAKE_MODULE_LINKER_FLAGS_RELEASE "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") + set(CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO "${ARDUINO_LINKER_FLAGS}" CACHE STRING "") +endfunction() + +#=============================================================================# +# Setups some basic flags for the gcc/g++ compiler and linker. +#=============================================================================# +setup_c_flags() +setup_cxx_flags() +setup_exe_linker_flags() +setup_shared_lib_flags() diff --git a/firmware/common/toolchain/Platform/Initialization/SetupExampleCategories.cmake b/firmware/common/toolchain/Platform/Initialization/SetupExampleCategories.cmake new file mode 100644 index 00000000..1cefedd3 --- /dev/null +++ b/firmware/common/toolchain/Platform/Initialization/SetupExampleCategories.cmake @@ -0,0 +1,21 @@ +# Setups all of Arduino's built-in examples categories, listing it by their names +# without the index prefix ('01.Basics' becomes 'Basics'). +# This list is saved in a cached variable named 'ARDUINO_EXAMPLE_CATEGORIES'. + +file(GLOB EXAMPLE_CATEGORIES RELATIVE ${ARDUINO_EXAMPLES_PATH} ${ARDUINO_EXAMPLES_PATH}/*) +list(SORT EXAMPLE_CATEGORIES) + +foreach (CATEGORY ${EXAMPLE_CATEGORIES}) + if (NOT EXAMPLE_CATEGORY_INDEX_LENGTH) + string(REGEX MATCH "^[0-9]+" CATEGORY_INDEX ${CATEGORY}) + string(LENGTH ${CATEGORY_INDEX} INDEX_LENGTH) + set(EXAMPLE_CATEGORY_INDEX_LENGTH ${INDEX_LENGTH} CACHE INTERNAL + "Number of digits preceeding an example's category path") + endif () + string(REGEX MATCH "[^0-9.]+$" PARSED_CATEGORY ${CATEGORY}) + string(TOLOWER ${PARSED_CATEGORY} PARSED_CATEGORY) + list(APPEND CATEGORIES "${PARSED_CATEGORY}") +endforeach () + +set(ARDUINO_EXAMPLE_CATEGORIES ${CATEGORIES} CACHE INTERNAL + "List of categories containing the built-in Arduino examples") diff --git a/firmware/common/toolchain/Platform/Initialization/SetupFirmwareSizeScript.cmake b/firmware/common/toolchain/Platform/Initialization/SetupFirmwareSizeScript.cmake new file mode 100644 index 00000000..e3254d01 --- /dev/null +++ b/firmware/common/toolchain/Platform/Initialization/SetupFirmwareSizeScript.cmake @@ -0,0 +1,11 @@ +set(FIRMWARE_SIZE_SCRIPT_PATH "${CMAKE_CURRENT_LIST_DIR}/../Extras/CalculateFirmwareSize.cmake") +file(READ ${FIRMWARE_SIZE_SCRIPT_PATH} FIRMWARE_SIZE_SCRIPT) + +# Replace placeholders with matching arguments +string(REGEX REPLACE "PLACEHOLDER_1" "${AVRSIZE_PROGRAM}" FIRMWARE_SIZE_SCRIPT "${FIRMWARE_SIZE_SCRIPT}") + +# Create the replaced file in the build's cache directory +set(CACHED_FIRMWARE_SCRIPT_PATH ${CMAKE_BINARY_DIR}/CMakeFiles/FirmwareSize.cmake) +file(WRITE ${CACHED_FIRMWARE_SCRIPT_PATH} "${FIRMWARE_SIZE_SCRIPT}") + +set(ARDUINO_SIZE_SCRIPT ${CACHED_FIRMWARE_SCRIPT_PATH} CACHE INTERNAL "Arduino Size Script") diff --git a/firmware/common/toolchain/Platform/Initialization/SetupLibraryBlacklist.cmake b/firmware/common/toolchain/Platform/Initialization/SetupLibraryBlacklist.cmake new file mode 100644 index 00000000..94253c2b --- /dev/null +++ b/firmware/common/toolchain/Platform/Initialization/SetupLibraryBlacklist.cmake @@ -0,0 +1,3 @@ +set(ARDUINO_LIBRARY_BLACKLIST "" CACHE STRING + "A list of absolute paths to Arduino libraries that are meant to be ignored \ +during library search") \ No newline at end of file diff --git a/firmware/common/toolchain/Platform/Initialization/TestSetup.cmake b/firmware/common/toolchain/Platform/Initialization/TestSetup.cmake new file mode 100644 index 00000000..91c7aa7b --- /dev/null +++ b/firmware/common/toolchain/Platform/Initialization/TestSetup.cmake @@ -0,0 +1,15 @@ +# Ensure that all required paths are found +VALIDATE_VARIABLES_NOT_EMPTY(VARS + ARDUINO_PLATFORMS + ARDUINO_CORES_PATH + ARDUINO_BOOTLOADERS_PATH + ARDUINO_LIBRARIES_PATH + ARDUINO_BOARDS_PATH + ARDUINO_PROGRAMMERS_PATH + ARDUINO_VERSION_PATH + ARDUINO_AVRDUDE_FLAGS + ARDUINO_AVRDUDE_PROGRAM + ARDUINO_AVRDUDE_CONFIG_PATH + AVRSIZE_PROGRAM + ${ADDITIONAL_REQUIRED_VARS} + MSG "Invalid Arduino SDK path (${ARDUINO_SDK_PATH}).\n") diff --git a/firmware/common/toolchain/README.rst b/firmware/common/toolchain/README.rst new file mode 100644 index 00000000..1ce72385 --- /dev/null +++ b/firmware/common/toolchain/README.rst @@ -0,0 +1,1346 @@ +============= +Arduino CMake +============= +.. image:: https://travis-ci.org/arduino-cmake/arduino-cmake.svg?branch=master + :target: https://travis-ci.org/arduino-cmake/arduino-cmake + +Arduino is a great development platform, which is easy to use. It has everything a beginner should need. The *Arduino IDE* simplifies a lot of things for the standard user, but if you are a professional programmer the IDE can feel simplistic and restrictive. + +One major drawback of the *Arduino IDE* is that you cannot do anything without it, which for me is a **complete buzz kill**. Thats why queezythegreat created an alternative build system for the Arduino using CMake. With the original repository not being updated since 2014 and lacking some important features like support for the latest Arduino SDKs, we decided to fix things up for 1.6; now that some people have started using this as their preferred fork, we decided to accept our fate of being the current maintainers. + +CMake is great cross-platform build system that works on practically any operating system. With it you are not constrained to a single build system. CMake lets you generate the build system that fits your needs, using the tools you like. It can generate any type of build system, from simple Makefiles, to complete projects for Eclipse, Visual Studio, XCode, etc. + +The **Arduino CMake** build system integrates tightly with the *Arduino SDK*. + +*Arduino SDK* version **0.19** or higher is required. + +So if you like to do things from the command line (using make), or to build your firmware where you're in control, or if you would like to use an IDE such as Eclipse, KDevelop, XCode, CodeBlocks or something similar, then **Arduino CMake** is the system for you. + +Features +-------- + +* Integrates with *Arduino SDK* +* Supports all Arduino boards. +* Supports Arduino type libraries. +* Automatic detection of Arduino libraries. +* Generates firmware images. +* Generates built-in examples. +* Generates libraries. +* Sketch support. +* Upload support. +* Hardware Platform support. +* Programmer support (with bootloader upload). +* Supports multiple build system types (Makefiles, Eclipse, KDevelop, CodeBlocks, XCode, etc). +* Cross-platform: Windows, Linux, Mac. +* Extensible build system, thanks to CMake. + + +Feedback +-------- + +**Arduino CMake** is hosted on GitHub and is available on multiple forks (At the time of writing up to **161(!)**), +with one the more advanced and maintainable being the following: + +https://github.com/arduino-cmake/arduino-cmake/ + +However, none of this would have been possible with the generous bunch of work the original author queezythegreat invested into this project, who definately earns most of the credit for getting things running: + +https://github.com/queezythegreat/arduino-cmake + +We want to stress again that he did all the initial work to even make CMake spit out Arduino firmwares. Without the effort queezythegreat put into this, we would not have been able to even think about getting an Arduino 1.6 project running. This is by no means a hostile fork and we would give him ownership of the organization as well at any time, should he wish so. + +Did you find a bug or would like a specific feature, please report it at: + +https://github.com/arduino-cmake/arduino-cmake/issues + +If you would like to hack on this project, don't hesitate to fork it on GitHub. +We will be glad to integrate your changes if you send me a ``Pull Request``. + + +Requirements +------------ + +* Base requirements: + + - ``CMake`` - http://www.cmake.org/cmake/resources/software.html + - ``Arduino SDK`` - http://www.arduino.cc/en/Main/Software + +* Linux requirements: + + - ``gcc-avr`` - AVR GNU GCC compiler + - ``binutils-avr`` - AVR binary tools + - ``avr-libc`` - AVR C library + - ``avrdude`` - Firmware uploader + + +Contributors +------------ + +I would like to thank the following people for contributing to **Arduino CMake**: + +* Juan José Herrero Barbosa (`Souler`_) +* Bei Chen Liu (`Baycken`_) +* MrPointer (`MrPointer`_) +* Marc Plano-Lesay (`Kernald`_) +* James Goppert (`jgoppert`_) +* Matt Tyler (`matt-tyler`_) +* Andrew Stromme (`astromme`_) +* `johnyb`_ +* `arunh`_ +* Sebastian Herp (`sebastianherp`_) +* Michael Daffin (`james147`_) +* Pavel Ilin (`PIlin`_) +* Igor Mikolic-Torreira (`igormiktor`_) +* Claudio Henrique Fortes Felix (`chffelix`_) +* Alexandre Tuleu (`atuleu`_) +* `getSurreal`_ +* Sebastian Zaffarano (`szaffarano`_) +* `cheshirekow`_ +* Logan Engstrom (`meadowstream`_) +* Francisco Ramírez (`franramirez688`_) +* Brendan Shillingford (`bshillingford`_) +* Mike Purvis (`mikepurvis`_) +* Steffen Hanikel (`hanikesn`_) +* Tomasz Bogdal (`queezythegreat`_) (original author of arduino-cmake) +* Jonas (`JonasProgrammer`_) + +.. _Souler: https://github.com/Souler +.. _Baycken: https://github.com/Baycken +.. _MrPointer: https://github.com/MrPointer +.. _Kernald: https://github.com/Kernald +.. _jgoppert: https://github.com/jgoppert +.. _matt-tyler: https://github.com/matt-tyler +.. _astromme: https://github.com/astromme +.. _johnyb: https://github.com/johnyb +.. _arunh: https://github.com/arunh +.. _sebastianherp: https://github.com/sebastianherp +.. _james147: https://github.com/james147 +.. _PIlin: https://github.com/PIlin +.. _igormiktor: https://github.com/igormiktor +.. _chffelix: https://github.com/chffelix +.. _atuleu: https://github.com/atuleu +.. _getSurreal: https://github.com/getSurreal +.. _szaffarano: https://github.com/szaffarano +.. _cheshirekow: https://github.com/cheshirekow +.. _meadowstream: https://github.com/meadowstream +.. _franramirez688: https://github.com/franramirez688 +.. _bshillingford: https://github.com/bshillingford +.. _mikepurvis: https://github.com/mikepurvis +.. _hanikesn: https://github.com/hanikesn +.. _queezythegreat: https://github.com/queezythegreat +.. _JonasProgrammer: https://github.com/JonasProgrammer + +License +------- +This Source Code Form is subject to the terms of the Mozilla Public +License, v. 2.0. If a copy of the MPL was not distributed with this file, +You can obtain one at http://mozilla.org/MPL/2.0/. + +TODO +---- + +* Test more complex configurations and error handling + +Contents +-------- + +1. `Getting Started`_ +2. `Using Arduino CMake`_ + + 1. `Creating Firmware Images`_ + 2. `Creating Libraries`_ + 3. `Arduino Sketches`_ + 4. `Arduino Built-in Examples`_ + 5. `Arduino Libraries`_ + 6. `Arduino Library Examples`_ + 7. `Compiler and Linker Flags`_ + 8. `Programmers`_ + 9. `Pure AVR Development`_ + 10. `Advanced Options`_ + 11. `Miscellaneous Functions`_ + 12. `Bundling Arduino CMake`_ + +3. `Linux Environment`_ + + 1. `Linux Serial Naming`_ + 2. `Linux Serial Terminals`_ + +4. `Mac OS X Environment`_ + + 1. `Mac Serial Naming`_ + 2. `Mac Serial Terminals`_ + +5. `Windows Environment`_ + + 1. `CMake Generators`_ + 2. `Windows Serial Naming`_ + 3. `Windows Serial Terminals`_ + +6. `Eclipse Environment`_ +7. `Troubleshooting`_ + + 1. `undefined reference to `__cxa_pure_virtual'`_ + 2. `Arduino Mega 2560 image does not work`_ + 3. `Library not detected automatically`_ + 4. `error: attempt to use poisoned "SIG_USART0_RECV"`_ + +8. `Resources`_ + + + + + + +Getting Started +--------------- + + +The following instructions are for **\*nix** type systems, specifically this is a Linux example. + +In short you can get up and running using the following commands:: + + mkdir build + cd build + cmake .. + make + make upload # to upload all firmware images [optional] + make blink-serial # to get a serial terminal to wire_serial [optional] + +For a more detailed explanation, please read on... + +1. Toolchain file + + In order to build firmware for the Arduino you have to specify a toolchain file to enable cross-compilation. There are two ways of specifying the file, either at the command line or from within the *CMakeLists.txt* configuration files. The bundled example uses the second approach like so:: + + set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/ArduinoToolchain.cmake) + + Please note that this must be before the ``project(...)`` command. + + If you would like to specify it from the command line, heres how:: + + cmake -DCMAKE_TOOLCHAIN_FILE=../path/to/toolchain/file.cmake PATH_TO_SOURCE_DIR + +2. Creating a build directory + + The second order of business is creating a build directory. CMake has a great feature called out-of-source builds, what this means is the building is done in a completely separate directory from where the sources are. The benefit of this is you don't have any clutter in you source directory and you won't accidentally commit something that is auto-generated. + + So let's create that build directory:: + + mkdir build + cd build + +3. Creating the build system + + Now let's create the build system that will create our firmware:: + + cmake .. + + To specify the build system type, use the ``-G`` option, for example:: + + cmake -G"Eclipse CDT4 - Unix Makefiles" .. + + If you rather use a GUI, use:: + + cmake-gui .. + +4. Building + + Next we will build everything:: + + make + +5. Uploading + + Once everything built correctly we can upload. Depending on your Arduino you will have to update the serial port used for uploading the firmware. To change the port please edit the following variable in *CMakeLists.txt*:: + + set(${FIRMWARE_NAME}_PORT /path/to/device) + + Ok lets do a upload of all firmware images:: + + make upload + + If you have an upload sync error then try resetting/ power cycling the board before starting the upload process. + +6. Serial output + + If you have some serial output, you can launch a serial terminal from the build system. The command used for executing the serial terminal is user configurable by the following setting:: + + set(${FIRMWARE_NAME}_SERIAL serial command goes here) + + In order to get access to the serial port use the following in your command:: + + @SERIAL_PORT@ + + That constant will get replaced with the actual serial port used (see uploading). In the case of our example configuration we can get the serial terminal by executing the following:: + + make blink-serial + + + + + + + + + + +Using Arduino CMake +------------------- + +In order to use **Arduino CMake** just include the toolchain file, everything will get set up for building. You can set the toolchain +in `CMakeList.txt` like so:: + + set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/ArduinoToolchain.cmake) + +Please note that this must be before the ``project(...)`` command. + +You can also specify it at build configuration time:: + + cmake -DCMAKE_TOOLCHAIN_FILE=../path/to/toolchain/file.cmake PATH_TO_SOURCE_DIR + + +Creating Firmware Images +~~~~~~~~~~~~~~~~~~~~~~~~ + +Once you have the **Arduino CMake** loaded you can start defining firmware images. + +To create Arduino firmware in CMake you use the ``generate_arduino_firmware`` command. The full syntax of the command is:: + + generate_arduino_firmware(target_name + [BOARD board_name] + [BOARD_CPU board_cpu] + [SKETCH sketch_path | SRCS src1 src2 ... srcN] + [HDRS hdr1 hdr2 ... hdrN] + [LIBS lib1 lib2 ... libN] + [PORT port] + [SERIAL serial_cmd] + [PROGRAMMER programmer_id] + [AFLAGS flags] + [NO_AUTOLIBS]) + + +The options are: + ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **Name** | **Description** | **REQUIRED** | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **BOARD** | Board name *(such as uno, mega2560, ...)* | **REQUIRED** | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **BOARD_CPU** | Board CPU *(such as atmega328, atmega168, ...)* | **REQUIRED** if board cpu is ambiguous | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **SKETCH** | Sketch path (see `Arduino Sketches`_) | **SKETCH or SRCS are REQUIRED** | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **SRCS** | Source files | **SKETCH or SRCS are REQUIRED** | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **HDRS** | Headers files *(for project based build systems)* | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **LIBS** | Libraries to link (see `Creating libraries`_) | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **PORT** | Serial port, for upload and serial targets (see `Upload Firmware`_) | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **SERIAL** | Serial command for serial target (see `Serial Terminal`_) | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **PROGRAMMER** | Programmer ID, enables programmer burning (see `Programmers`_). | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **ARDLIBS** | Manual list of Arduino type libraries, common use case is when the | | +| | library header name does not match the librarie's directory name. | | +| | **ADVANCED OPTION!** Can be used in conjuction with **NO_AUTOLIBS**. | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **AFLAGS** | avrdude flags for target | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **NO_AUTOLIBS** | Disable Arduino library detection *(default On)* | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **MANUAL** | Disable Arduino Core (enables pure AVR development) | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ + +You can specify the options in two ways, either as the command arguments or as variables. When specifying the options as variables they must be named:: + + ${TARGET_NAME}_${OPTION_NAME} + +Where **${TARGET_NAME}** is the name of you target and **${OPTION_NAME}** is the name of the option. + +So to create a target (firmware image) called ``blink``, composed of ``blink.h`` and ``blink.cpp`` source files for the *Arduino Uno*, you write the following:: + + set(blink_SRCS blink.cpp) + set(blink_HDRS blink.h) + set(blink_BOARD uno) + + generate_arduino_firmware(blink) + +The previous example can be rewritten as:: + + generate_arduino_firmware(blink + SRCS blink.cpp + HDRS blink.h + BOARD uno) + +Upload Firmware +_______________ + +To enable firmware upload functionality, you need to add the ``PORT`` option:: + + set(blink_SRCS blink.cpp) + set(blink_HDRS blink.h) + set(blink_PORT /dev/ttyUSB0) + set(blink_BOARD nano) + set(blink_BOARD_CPU atmega328) # required because nano has atmega328 and atmega168 models + + generate_arduino_firmware(blink) + +Or:: + + generate_arduino_firmware(blink + SRCS blink.cpp + HDRS blink.h + PORT /dev/ttyUSB0 + BOARD_CPU atmega328 + BOARD nano) + +Once defined there will be two targets available for uploading, ``${TARGET_NAME}-upload`` and a global ``upload`` target (which will depend on all other upload targets defined in the build): + +* ``blink-upload`` - will upload just the ``blink`` firmware +* ``upload`` - upload all firmware images registered for uploading + +Serial Terminal +_______________ +To enable serial terminal, use the ``SERIAL`` option (``@SERIAL_PORT@`` will be replaced with the ``PORT`` option):: + + set(blink_SRCS blink.cpp) + set(blink_HDRS blink.h) + set(blink_PORT /dev/ttyUSB0) + set(blink_SERIAL picocom @SERIAL_PORT@ -b 9600 -l) + set(blink_BOARD uno) + + generate_arduino_firmware(blink) + +Alternatively:: + + generate_arduino_firmware(blink + SRCS blink.cpp + HDRS blink.h + PORT /dev/ttyUSB0 + SERIAL picocom @SERIAL_PORT@ -b 9600 -l + BOARD uno) + +This will create a target named ``${TARGET_NAME}-serial`` (in this example: blink-serial). + + + + +Creating Libraries +~~~~~~~~~~~~~~~~~~ + +Creating libraries is very similar to defining a firmware image, except we use the ``generate_arduino_library`` command. This command creates static libraries, and are not to be confused with `Arduino Libraries`_. The full command syntax:: + + generate_arduino_library(name + [BOARD board_name] + [BOARD_CPU board_cpu] + [SRCS src1 src2 ... srcN] + [HDRS hdr1 hdr2 ... hdrN] + [LIBS lib1 lib2 ... libN] + [NO_AUTOLIBS]) + +The options are: + ++--------------------+------------------------------------------------------+----------------------------------------+ +| **Name** | **Description** | **REQUIRED** | ++--------------------+------------------------------------------------------+----------------------------------------+ +| **BOARD** | Board name *(such as uno, mega2560, ...)* | **REQUIRED** | ++--------------------+------------------------------------------------------+----------------------------------------+ +| **BOARD_CPU** | Board CPU *(such as atmega328, atmega168, ...)* | **REQUIRED** if board cpu is ambiguous | ++--------------------+------------------------------------------------------+----------------------------------------+ +| **SRCS** | Source files | **REQUIRED** | ++--------------------+------------------------------------------------------+----------------------------------------+ +| **HDRS** | Headers files *(for project based build systems)* | | ++--------------------+------------------------------------------------------+----------------------------------------+ +| **LIBS** | Libraries to link *(sets up dependency tracking)* | | ++--------------------+------------------------------------------------------+----------------------------------------+ +| **NO_AUTOLIBS** | Disable Arduino library detection *(default On)* | | ++--------------------+------------------------------------------------------+----------------------------------------+ +| **MANUAL** | Disable Arduino Core (enables pure AVR development) | | ++--------------------+------------------------------------------------------+----------------------------------------+ + +You can specify the options in two ways, either as the command arguments or as variables. When specifying the options as variables they must be named:: + + ${TARGET_NAME}_${OPTION_NAME} + +Where **${TARGET_NAME}** is the name of you target and **${OPTION_NAME}** is the name of the option. + +Let's define a simple library called ``blink_lib`` with two sources files for the *Arduino Uno*:: + + set(blink_lib_SRCS blink_lib.cpp) + set(blink_lib_HDRS blink_lib.h) + set(blink_lib_BOARD uno) + + generate_arduino_library(blink_lib) + +The other way of defining the same thing is:: + + generate_arduino_library(blink_lib + SRCS blink_lib.cpp + HDRS blink_lib.h + BOARD uno) + +Once that library is defined we can use it in our other firmware images... Let's add ``blink_lib`` to the ``blink`` firmware:: + + set(blink_SRCS blink.cpp) + set(blink_HDRS blink.h) + set(blink_LIBS blink_lib) + set(blink_BOARD uno) + + generate_arduino_firmware(blink) + +CMake has automatic dependency tracking, so when you build the ``blink`` target, ``blink_lib`` will automatically get built, in the right order. + + +Arduino Sketches +~~~~~~~~~~~~~~~~ + +To build a Arduino sketch use the **SKETCH** option (see `Creating firmware images`_). For example:: + + set(blink_SKETCH ${ARDUINO_SDK_PATH}/examples/1.Basics/Blink) # Path to sketch directory + set(blink_BOARD uno) + + generate_arduino_firmware(blink) + +This will build the **blink** example from the **Arduino SDK**. + +Note: When specifying the sketch directory path, arduino-cmake is expecting to find a sketch file named after the directory (with a extension of .pde or .ino). + +You can also specify the path to the main sketch file, then the parent directory of that sketch will be search for additional sketch files. + +Arduino Built-in Examples +~~~~~~~~~~~~~~~~~~~~~~~~~ + +The Arduino SDK comes with a handful of code examples, providing an easy setup for simple operations. +Since there are many examples, they were categorized, making each example be under a certain category. +Each example consists of at least one source file, named after the example and has the *.ino* or *.pde* extension, and sits under a directory which is also named after the example. +Each category is a directory named after it, having all its examples as sub-directories, named after them. +One such example is ``Blink``, probrably the most popular one as well. It's located under the ``Basics`` category and has a source file named ``Blink.ino``. + +**Arduino CMake** has the abillity to automatically generate these examples, simply by passing their name and optionally their category, as some sort of an optimization. **It supports case-insensitive names** +If you would like to generate and upload some of those examples you can use the `generate_arduino_example` command. The syntax of the command is:: + + generate_arduino_example(target_name + [EXAMPLE example_name] + [BOARD board_name] + [BOARD_CPU board_cpu] + [CATEGORY category_name] + [PORT port] + [SERIAL serial command] + [PORGRAMMER programmer_id] + [AFLAGS avrdude_flags]) + +The options are: + ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **Name** | **Description** | **REQUIRED** | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **EXAMPLE** | Example name. | **REQUIRED** | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **BOARD** | Board name *(such as uno, mega2560, ...)* | **REQUIRED** | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **BOARD_CPU** | Board CPU *(such as atmega328, atmega168, ...)* | **REQUIRED** if board cpu is ambiguous | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **CATEGORY** | Category name. | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **PORT** | Serial port, for upload and serial targets (see `Upload Firmware`_) | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **SERIAL** | Serial command for serial target (see `Serial Terminal`_) | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **PROGRAMMER** | Programmer ID, enables programmer burning (see `Programmers`_). | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **AFLAGS** | avrdude flags for target | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ + +To generate a target for the **blink** example from the **Basics** category for the **Uno** board:: + + generate_arduino_example(blink_example + CATEGORY Basics + EXAMPLE Blink + BOARD uno + PORT /dev/ttyUSB0) + +You can also rewrite the previous like so:: + + set(blink_example_CATEGORY Basics) + set(blink_example_EXAMPLE Blink) + set(blink_example_BOARD uno) + set(blink_example_PORT /dev/ttyUSB0) + + generate_arduino_example(blink_example) + +The previous example will generate the following two target:: + + blink_example + blink_example-upload + +**Note:** The above example will work perfectly fine even if the ``Basics`` category hadn't been passed. + +Arduino Libraries +~~~~~~~~~~~~~~~~~ + +Libraries are one of the more powerful features which the Arduino offers to users. Instead of rewriting code, people bundle their code in libraries and share them with others. +The structure of these libraries is very simple, which makes them easy to create. + +An Arduino library is **any directory which contains a header named after the directory**, simple. +Any source files contained within that directory are part of the library. Here is a example of library a called ExampleLib:: + + ExampleLib/ + |-- ExampleLib.h + |-- ExampleLib.cpp + `-- OtherLibSource.cpp + +Now because the power of Arduino lies within those user-created libraries, support for them is built right into **Arduino CMake**. The **Arduino SDK** comes with a large number of default libraries and adding new libraries is simple. + +To incorporate a library into your firmware, you can do one of three things: + +1. Place the library next to the default Arduino libraries (located at **${ARDUINO_SDK}/libraries**) +2. Place the library next to the firmware configuration file (same directory as the **CMakeLists.txt**) +3. Place the library in a separate folder and tell **Arduino CMake** the path to that directory. + + To tell CMake where to search for libraries use the `link_directories` command. The command has to be used before defining any firmware or libraries requiring those libraries. + + For example:: + + link_directories(${CMAKE_CURRENT_SOURCE_DIR}/libraries) + link_directories(/home/username/arduino_libraries) + + +If a library contains nested sources, a special option must be defined to enable recursion. For example to enable recursion for the Arduino Wire library use:: + + set(Wire_RECURSE True) + +The option name should be **${LIBRARY_NAME}_RECURSE**, where in this case **LIBRARY_NAME** is equal to *Wire*. + + +Arduino Libraries are not to be confused with normal static libraries (for exmaple *system libraries* or libraries created using generate_arduino_library). The **LIBS** option only accepts static libraries, so do not list the Arduino Libraries in that option (as you will get an error). + + +Arduino Library Examples +~~~~~~~~~~~~~~~~~~~~~~~~ + +Most Arduino libraries have examples bundled with them. If you would like to generate and upload some of those examples you can use the `generate_arduino_library_example` command. The syntax of the command is:: + + generate_arduino_library_example(target_name + [LIBRARY library_name] + [EXAMPLE example_name] + [BOARD board_name] + [BOARD_CPU board_cpu] + [PORT port] + [SERIAL serial command] + [PORGRAMMER programmer_id] + [AFLAGS avrdude_flags]) + +The options are: + ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **Name** | **Description** | **REQUIRED** | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **LIBRARY** | Library name. | **REQUIRED** | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **EXAMPLE** | Example name. | **REQUIRED** | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **BOARD** | Board name *(such as uno, mega2560, ...)* | **REQUIRED** | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **BOARD_CPU** | Board CPU *(such as atmega328, atmega168, ...)* | **REQUIRED** if board cpu is ambiguous | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **PORT** | Serial port, for upload and serial targets (see `Upload Firmware`_) | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **SERIAL** | Serial command for serial target (see `Serial Terminal`_) | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **PROGRAMMER** | Programmer ID, enables programmer burning (see `Programmers`_). | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **AFLAGS** | avrdude flags for target | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ + +To generate a target for the **master_writer** example from the **Wire** library for the **Uno**:: + + generate_arduino_library_example(wire_example + LIBRARY Wire + EXAMPLE master_writer + BOARD uno + PORT /dev/ttyUSB0) + +You can also rewrite the previous like so:: + + set(wire_example_LIBRARY Wire) + set(wire_example_EXAMPLE master_writer) + set(wire_example_BOARD uno) + set(wire_example_PORT /dev/ttyUSB0) + + generate_arduino_library_example(wire_example) + +The previous example will generate the following two target:: + + wire_example + wire_example-upload + +Compiler and Linker Flags +~~~~~~~~~~~~~~~~~~~~~~~~~ + +The default compiler and linker flags should be fine for most projects. If you required specific compiler/linker flags, use the following options to change them: + ++--------------------------+----------------------+ +| **Name** | **Description** | ++--------------------------+----------------------+ +| **ARDUINO_C_FLAGS** | C compiler flags | ++--------------------------+----------------------+ +| **ARDUINO_CXX_FLAGS** | C++ compiler flags | ++--------------------------+----------------------+ +| **ARDUINO_LINKER_FLAGS** | Linker flags | ++--------------------------+----------------------+ + + +Set these option either before the `project()` like so:: + + set(ARDUINO_C_FLAGS "-ffunction-sections -fdata-sections") + set(ARDUINO_CXX_FLAGS "${ARDUINO_C_FLAGS} -fno-exceptions") + set(ARDUINO_LINKER_FLAGS "-Wl,--gc-sections") + + project(ArduinoExample C CXX) + +or when configuring the project:: + + cmake -D"ARDUINO_C_FLAGS=-ffunction-sections -fdata-sections" ../path/to/sources/ + + +Programmers +~~~~~~~~~~~ + +**Arduino CMake** fully supports programmers for burning firmware and bootloader images directly onto the Arduino. +If you have a programmer that is supported by the *Arduino SDK*, everything should work out of the box. +As of version 1.0 of the *Arduino SDK*, the following programmers are supported: + ++--------------------+---------------------+ +| **Programmer ID** | **Description** | ++--------------------+---------------------+ +| **avrisp** | AVR ISP | ++--------------------+---------------------+ +| **avrispmkii** | AVRISP mkII | ++--------------------+---------------------+ +| **usbtinyisp** | USBtinyISP | ++--------------------+---------------------+ +| **parallel** | Parallel Programmer | ++--------------------+---------------------+ +| **arduinoisp** | Arduino as ISP | ++--------------------+---------------------+ + +The programmers.txt file located in `${ARDUINO_SDK_PATH}/hardware/arduino/` lists all supported programmers by the *Arduino SDK*. + +In order to enable programmer support, you have to use the **PROGRAMMER** option (see `Creating firmware images`_):: + + set(${TARGET_NAME}_PROGRAMMER programmer_id) + +where `programmer_id` is the name of the programmer supported by the *Arduino SDK*. + +Once you have enabled programmer support, two new targets are available in the build system: + +* **${TARGET_NAME}-burn** - burns the firmware image via the programmer +* **${TARGET_NAME}-burn-bootloader** - burns the original **Arduino bootloader** image via the programmer + +If you need to restore the original **Arduino bootloader** onto your Arduino, so that you can use the traditional way of uploading firmware images via the bootloader, use **${TARGET_NAME}-burn-bootloader** to restore it. + + +Pure AVR Development +~~~~~~~~~~~~~~~~~~~~ + +For those developers who don't want any Arduino magic, but still want to utilize the hardware platform you are in luck. This section will outline the `generate_avr_firmware()` and `generate_avr_library()` commands, which enables +you to compile sources for the given Arduino board. + +No Arduino Core or Arduino libraries will get generated, this is for manual compilation of sources. These commands are for people that know what they are doing, or have done pure AVR development. +People starting out, or just familiar with Arduino should not use these commands. + +The `generate_avr_firmware()` command:: + + generate_avr_firmware(name + [BOARD board_name] + [BOARD_CPU board_cpu] + [SRCS src1 src2 ... srcN] + [HDRS hdr1 hdr2 ... hdrN] + [LIBS lib1 lib2 ... libN] + [PORT port] + [SERIAL serial_cmd] + [PROGRAMMER programmer_id] + [AFLAGS flags]) + +This will compile the sources for the specified Arduino board type. + +The options: + ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **Name** | **Description** | **REQUIRED** | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **BOARD** | Board name *(such as uno, mega2560, ...)* | **REQUIRED** | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **BOARD_CPU** | Board CPU *(such as atmega328, atmega168, ...)* | **REQUIRED** if board cpu is ambiguous | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **SRCS** | Source files | **REQUIRED** | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **HDRS** | Headers files *(for project based build systems)* | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **LIBS** | Libraries to link *(sets up dependency tracking)* | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **PORT** | Serial port, for upload and serial targets (see `Upload Firmware`_) | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **SERIAL** | Serial command for serial target (see `Serial Terminal`_) | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **PROGRAMMER** | Programmer ID, enables programmer burning (see `Programmers`_). | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ +| **AFLAGS** | avrdude flags for target | | ++--------------------+----------------------------------------------------------------------+----------------------------------------+ + +You can specify the options in two ways, either as the command arguments or as variables. When specifying the options as variables they must be named:: + + ${TARGET_NAME}_${OPTION_NAME} + +Where **${TARGET_NAME}** is the name of you target and **${OPTION_NAME}** is the name of the option. + + +The `generate_avr_library()` command:: + + generate_avr_library(name + [BOARD board_name] + [BOARD_CPU board_cpu] + [SRCS src1 src2 ... srcN] + [HDRS hdr1 hdr2 ... hdrN] + [LIBS lib1 lib2 ... libN]) + +This will compile a static library for the specified Arduino board type. + +The options: + ++--------------------+---------------------------------------------------+----------------------------------------+ +| **Name** | **Description** | **REQUIRED** | ++--------------------+---------------------------------------------------+----------------------------------------+ +| **BOARD** | Board name *(such as uno, mega2560, ...)* | **REQUIRED** | ++--------------------+---------------------------------------------------+----------------------------------------+ +| **BOARD_CPU** | Board CPU *(such as atmega328, atmega168, ...)* | **REQUIRED** if board cpu is ambiguous | ++--------------------+---------------------------------------------------+----------------------------------------+ +| **SRCS** | Source files | **REQUIRED** | ++--------------------+---------------------------------------------------+----------------------------------------+ +| **HDRS** | Headers files *(for project based build systems)* | | ++--------------------+---------------------------------------------------+----------------------------------------+ +| **LIBS** | Libraries to link *(sets up dependency tracking)* | | ++--------------------+---------------------------------------------------+----------------------------------------+ + +You can specify the options in two ways, either as the command arguments or as variables. When specifying the options as variables they must be named:: + + ${TARGET_NAME}_${OPTION_NAME} + +Where **${TARGET_NAME}** is the name of you target and **${OPTION_NAME}** is the name of the option. + +Register Custom Hardware Platforms +~~~~~~~~~~~~~~~~ +Arduino development may involve the use of additional hardware platforms that behave differently, +such as the Sagnuino e.g. +Arduino CMake allows you to register those platforms without the need to copy their files locally, +exactly as you would register the default Arduino platform. In fact, this is what happens behind the scenes: + +1. Platform's path is determined. By default it's Arduino's path. + See: `Arduino Platforms PRE 1.5`_ and `Arduino Platforms 1.5`_. + +2. Platform's architecture is determined. By default it's avr. + +If one would like to specify a custom platform and/or architecuture, it should set the following variables: + ++--------------------------------+---------------------------------------------------+ +| **Name** | **Description** | ++--------------------------------+---------------------------------------------------+ +| **PLATFORM_PATH** | Platform's path on the local file system.* | ++--------------------------------+---------------------------------------------------+ +| **PLATFORM_ARCHITECTURE** | Platform's architecture* | ++--------------------------------+---------------------------------------------------+ + +**Note:** If variables are to be used, they MUST be set before including the Toolchain file. + +A valid Hardware Platform is a directory containing the following:: + + HARDWARE_PLATFORM_PATH/ + |-- bootloaders/ + |-- cores/ + |-- variants/ + |-- boards.txt + `-- programmers.txt + +The ``board.txt`` describes the target boards and bootloaders, While ``programmers.txt`` the programmer defintions. + +A good example of a *Hardware Platform* is in the Arduino SDK: ``${ARDUINO_SDK_PATH}/hardware/arduino/`` +.. _Arduino Platforms PRE 1.5: http://code.google.com/p/arduino/wiki/Platforms +.. _Arduino Platforms 1.5: http://code.google.com/p/arduino/wiki/Platforms1 + +Advanced Options +~~~~~~~~~~~~~~~~ + +The following options control how **Arduino CMake** is configured: + ++---------------------------------+-----------------------------------------------------+ +| **Name** | **Description** | ++---------------------------------+-----------------------------------------------------+ +| **ARDUINO_SDK_PATH** | Full path to the **Arduino SDK** | ++---------------------------------+-----------------------------------------------------+ +| **ARDUINO_AVRDUDE_PROGRAM** | Full path to `avrdude` programmer | ++---------------------------------+-----------------------------------------------------+ +| **ARDUINO_AVRDUDE_CONFIG_PATH** | Full path to `avrdude` configuration file | ++---------------------------------+-----------------------------------------------------+ +| **ARDUINO_DEFAULT_BOARD** | Default Arduino Board ID, when not specified. | ++---------------------------------+-----------------------------------------------------+ +| **ARDUINO_DEFAULT_PORT** | Default Arduino port, when not specified. | ++---------------------------------+-----------------------------------------------------+ +| **ARDUINO_DEFAULT_SERIAL** | Default Arduino Serial command, when not specified. | ++---------------------------------+-----------------------------------------------------+ +| **ARDUINO_DEFAULT_PROGRAMMER** | Default Arduino Programmer ID, when not specified. | ++---------------------------------+-----------------------------------------------------+ + +To force a specific version of **Arduino SDK**, configure the project like so:: + + cmake -DARDUINO_SDK_PATH=/path/to/arduino_sdk ../path/to/sources + +Note: You must create a new build system if you change **ARDUINO_SDK_PATH**. + + +When **Arduino CMake** is configured properly, these options are defined: + ++---------------------------------+-----------------------------------------------------+ +| **Name** | **Description** | ++---------------------------------+-----------------------------------------------------+ +| **ARDUINO_FOUND** | Set to True when the **Arduino SDK** is detected | +| | and configured. | ++---------------------------------+-----------------------------------------------------+ +| **ARDUINO_SDK_VERSION** | Full version of the **Arduino SDK** (ex: 1.0.0) | ++---------------------------------+-----------------------------------------------------+ +| **ARDUINO_SDK_VERSION_MAJOR** | Major version of the **Arduino SDK** (ex: 1) | ++---------------------------------+-----------------------------------------------------+ +| **ARDUINO_SDK_VERSION_MINOR** | Minor version of the **Arduino SDK** (ex: 0) | ++---------------------------------+-----------------------------------------------------+ +| **ARDUINO_SDK_VERSION_PATCH** | Patch version of the **Arduino SDK** (ex: 0) | ++---------------------------------+-----------------------------------------------------+ + + +During compilation, you can enable the following environment variables. + ++---------------------------------+-----------------------------------------------------+ +| **Name** | **Description** | ++---------------------------------+-----------------------------------------------------+ +| **VERBOSE** | Enables verbose compilation, displays commands | +| | being executed. (Non empty value) | ++---------------------------------+-----------------------------------------------------+ +| **VERBOSE_SIZE** | Enables full/verbose output from avr-size. | +| | (Non empty value) | ++---------------------------------+-----------------------------------------------------+ + +Miscellaneous Functions +~~~~~~~~~~~~~~~~~~~~~~~ + +This section will outlines some of the additional miscellaneous functions available to the user. + +* **print_board_list()**: + + Print list of detected Arduino Boards. +* **print_programmer_list()**: + + Print list of detected Programmers. +* **print_programmer_settings(PROGRAMMER)**: + + *PROGRAMMER* - programmer id + + Print the detected Programmer settings. +* **print_board_settings(BOARD_NAME)**: + + *BOARD_NAME* - Board name (nano, uno, mega...) + + Print the detected Arduino board settings. + +Bundling Arduino CMake +~~~~~~~~~~~~~~~~~~~~~~ + +Using **Arduino CMake** in your own project is simple, you just need a single directory called **cmake**. Just copy that entire directory into you project and you are set. + +Copying the **cmake** directory, although simple is not the best solution. If you are using GIT for source code versioning, the best solution is using a submodule. The submodule gives you the power of updating to the latest version of **Arduino CMake** without any effort. To add a submodule do:: + + git submodule add git://github.com/queezythegreat/arduino-cmake.git arduino-cmake + +Then just set the CMAKE_TOOLCHAIN_FILE variable:: + + set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/arduino-cmake/cmake/ArduinoToolchain.cmake) + +For more information on GIT submodules please read: `GIT Book - Submodules`_ + +.. _GIT Book - Submodules: http://book.git-scm.com/5_submodules.html + +Linux Environment +----------------- + +Running the *Arduino SDK* on Linux is a little bit more involved, because not everything is bundled with the SDK. The AVR GCC toolchain is not distributed alongside the Arduino SDK, so it has to be installed seperately. + +To get **Arduino CMake** up and running follow these steps: + +1. Install the following packages using your package manager: + + * ``gcc-avr`` - AVR GNU GCC compiler + * ``binutils-avr`` - AVR binary tools + * ``avr-libc`` - AVR C library + * ``avrdude`` - Firmware uploader + +2. Install the *Arduino SDK*. + + Depending on your distribution, the *Arduino SDK* may or may not be available. + + If it is available please install it using your packages manager otherwise do: + + 1. Download the `Arduino SDK`_ + 2. Extract it into ``/usr/share`` + + NOTE: Arduino version **0.19** or newer is required! + +3. Install CMake: + + * Using the package manager or + * Using the `CMake installer`_ + + NOTE: CMake version 2.8 or newer is required! + + + +Linux Serial Naming +~~~~~~~~~~~~~~~~~~~ + +On Linux the Arduino serial device is named as follows (where **X** is the device number):: + + /dev/ttyUSBX + /dev/ttyACMX + +Where ``/dev/ttyACMX`` is for the new **Uno** and **Mega** Arduino's, while ``/dev/ttyUSBX`` is for the old ones. + +CMake configuration example:: + + set(${FIRMWARE_NAME}_PORT /dev/ttyUSB0) + + +Linux Serial Terminals +~~~~~~~~~~~~~~~~~~~~~~ + +On Linux a wide range on serial terminal are availabe. Here is a list of a couple: + +* ``minicom`` +* ``picocom`` +* ``gtkterm`` +* ``screen`` + + + + + + + + + + + +Mac OS X Environment +-------------------- + +The *Arduino SDK*, as on Windows, is self contained and has everything needed for building. To get started do the following: + +1. Install the *Arduino SDK* + + 1. Download `Arduino SDK`_ + 2. Copy ``Arduino`` into ``Applications`` + 3. Install ``FTDIUSBSerialDrviver*`` (for FTDI USB Serial) + +2. Install CMake + + 1. Download `CMake`_ + 2. Install ``cmake-*.pkg`` + + NOTE: Make sure to click on **`Install Command Line Links`** + +Mac Serial Naming +~~~~~~~~~~~~~~~~~ + +When specifying the serial port name on Mac OS X, use the following names (where XXX is a unique ID):: + + /dev/tty.usbmodemXXX + /dev/tty.usbserialXXX + +Where ``tty.usbmodemXXX`` is for new **Uno** and **Mega** Arduino's, while ``tty.usbserialXXX`` are the older ones. + +CMake configuration example:: + + set(${FIRMWARE_NAME}_PORT /dev/tty.usbmodem1d11) + +Mac Serial Terminals +~~~~~~~~~~~~~~~~~~~~ + +On Mac the easiest way to get a Serial Terminal is to use the ``screen`` terminal emulator. To start a ``screen`` serial session:: + + screen /dev/tty.usbmodemXXX + +Where ``/dev/tty.usbmodemXXX`` is the terminal device. To exit press ``C-a C-\``. + +CMake configuration example:: + + set(${FIRMWARE_NAME}_SERIAL screen @SERIAL_PORT@) + + + + + + + + + + + +Windows Environment +------------------- + +On Windows the *Arduino SDK* is self contained and has everything needed for building. To setup the environment do the following: + +1. Place the `Arduino SDK`_ either + + * into **Program Files**, or + * onto the **System Path** + + NOTE: Don't change the default *Arduino SDK* directory name, otherwise auto detection will no work properly! + +2. Add to the **System Path**: ``${ARDUINO_SDK_PATH}/hardware/tools/avr/utils/bin`` +3. Install `CMake 2.8`_ + + NOTE: Make sure you check the option to add CMake to the **System Path**. + + +CMake Generators +~~~~~~~~~~~~~~~~ + +Once installed, you can start using CMake the usual way, just make sure to chose either a **MSYS Makefiles** or **Unix Makefiles** type generator:: + + MSYS Makefiles = Generates MSYS makefiles. + Unix Makefiles = Generates standard UNIX makefiles. + CodeBlocks - Unix Makefiles = Generates CodeBlocks project files. + Eclipse CDT4 - Unix Makefiles + = Generates Eclipse CDT 4.0 project files. + +If you want to use a **MinGW Makefiles** type generator, you must generate the build system the following way: + +1. Remove ``${ARDUINO_SDK_PATH}/hardware/tools/avr/utils/bin`` from the **System Path** +2. Generate the build system using CMake with the following option set (either through the GUI or from the command line):: + + CMAKE_MAKE_PROGRAM=${ARDIUNO_SDK_PATH}/hardware/tools/avr/utils/bin/make.exe + +3. Then build the normal way + +The reason for doing this is the MinGW generator cannot have the ``sh.exe`` binary on the **System Path** during generation, otherwise you get an error. + +Windows Serial Naming +~~~~~~~~~~~~~~~~~~~~~ + +When specifying the serial port name on Windows, use the following names:: + + com1 com2 ... comN + +CMake configuration example:: + + set(${FIRMWARE_NAME}_PORT com3) + +Windows Serial Terminals +~~~~~~~~~~~~~~~~~~~~~~~~ + +Putty is a great multi-protocol terminal, which supports SSH, Telnet, Serial, and many more... The latest development snapshot supports command line options for launching a serial terminal, for example:: + + putty -serial COM3 -sercfg 9600,8,n,1,X + +CMake configuration example (assuming putty is on the **System Path**):: + + set(${FIRMWARE_NAME}_SERIAL putty -serial @SERIAL_PORT@) + +Putty - http://tartarus.org/~simon/putty-snapshots/x86/putty-installer.exe + + + + + + + + + + +Eclipse Environment +------------------- + +Eclipse is a great IDE which has a lot of functionality and is much more powerful than the *Arduino IDE*. In order to use Eclipse you will need the following: + +1. Eclipse +2. Eclipse CDT extension (for C/C++ development) + +On most Linux distribution you can install Eclipse + CDT using your package manager, otherwise you can download the `Eclipse IDE for C/C++ Developers`_ bundle. + +Once you have Eclipse, here is how to generate a project using CMake: + +1. Create a build directory that is next to your source directory, like this:: + + build_directory/ + source_directory/ + +2. Run CMake with the `Eclipse CDT4 - Unix Makefiles` generator, inside the build directory:: + + cd build_directory/ + cmake -G"Eclipse CDT4 - Unix Makefiles" ../source_directory + +3. Open Eclipse and import the project from the build directory. + + 1. **File > Import** + 2. Select `Existing Project into Workspace`, and click **Next** + 3. Select *Browse*, and select the build directoy. + 4. Select the project in the **Projects:** list + 5. Click **Finish** + + + +.. _Eclipse IDE for C/C++ Developers: http://www.eclipse.org/downloads/packages/eclipse-ide-cc-developers/heliossr2 + + + + + + + + + + + +Troubleshooting +--------------- + +The following section will outline some solutions to common problems that you may encounter. + +undefined reference to `__cxa_pure_virtual' +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +When linking you'r firmware image you may encounter this error on some systems. An easy fix is to add the following to your firmware source code:: + + extern "C" void __cxa_pure_virtual(void); + void __cxa_pure_virtual(void) { while(1); } + + +The contents of the ``__cxa_pure_virtual`` function can be any error handling code; this function will be called whenever a pure virtual function is called. + +* `What is the purpose of `cxa_pure_virtual``_ + +.. _What is the purpose of `cxa_pure_virtual`: http://stackoverflow.com/questions/920500/what-is-the-purpose-of-cxa-pure-virtual + +Arduino Mega 2560 image does not work +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +If you are working on Linux, and have ``avr-gcc`` >= 4.5 you might have a unpatched version gcc which has the C++ constructor bug. This bug affects the **Atmega2560** when using classes which causes the Arduino firmware to crash. + +If you encounter this problem either downgrade ``avr-gcc`` to **4.3** or rebuild gcc with the following patch:: + + --- gcc-4.5.1.orig/gcc/config/avr/libgcc.S 2009-05-23 17:16:07 +1000 + +++ gcc-4.5.1/gcc/config/avr/libgcc.S 2010-08-12 09:38:05 +1000 + @@ -802,7 +802,9 @@ + mov_h r31, r29 + mov_l r30, r28 + out __RAMPZ__, r20 + + push r20 + XCALL __tablejump_elpm__ + + pop r20 + .L__do_global_ctors_start: + cpi r28, lo8(__ctors_start) + cpc r29, r17 + @@ -843,7 +845,9 @@ + mov_h r31, r29 + mov_l r30, r28 + out __RAMPZ__, r20 + + push r20 + XCALL __tablejump_elpm__ + + pop r20 + .L__do_global_dtors_start: + cpi r28, lo8(__dtors_end) + cpc r29, r17 + +* `AVR GCC Bug 45263 Report`_ +* `The global constructor bug in avr-gcc`_ + +.. _AVR GCC Bug 45263 Report: http://gcc.gnu.org/bugzilla/show_bug.cgi?id=45263 +.. _The global constructor bug in avr-gcc: http://andybrown.me.uk/ws/2010/10/24/the-major-global-constructor-bug-in-avr-gcc/ + + + +Library not detected automatically +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +When a Arduino library does not get detected automatically, it usually means CMake cannot find it (obvious). + +One common reason why the library is not detected, is because the directory name of the library does not match the header. +If I'm including a library header like so:: + + #include "my_library.h" + +Based on this include, **Arduino CMake** is expecting to find a library that has a directory name **my_libray**. +If the directory name does not match the header, it won't be consider a Arduino Library (see `Arduino Libraries`_). + + +When a library being used is located in a non-standard location (not in the **Arduino SDK** or next to the firmware), then that directory must be registered. +To register a non-standard directory containing Arduino libraries, use the following:: + + link_directories(path_to_directory_containing_libraries) + +Remember to **use this command before defining the firmware**, which requires the library from that directory. + + +error: attempt to use poisoned "SIG_USART0_RECV" +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +If you get the following error:: + + /usr/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:91:41: error: attempt to use poisoned "SIG_USART0_RECV" + /usr/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:101:15: error: attempt to use poisoned "SIG_USART0_RECV" + /usr/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:132:15: error: attempt to use poisoned "SIG_USART1_RECV" + /usr/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:145:15: error: attempt to use poisoned "SIG_USART2_RECV" + /usr/share/arduino/hardware/arduino/cores/arduino/HardwareSerial.cpp:158:15: error: attempt to use poisoned "SIG_USART3_RECV" + +You probably recently upgraded `avr-libc` to the latest version, which has deperecated the use of these symbols. There is a `Arduino Patch`_ which +fixes these error, you can read more about this bug here: `Arduino Bug ISSUE 955`_. + +.. _Arduino Bug ISSUE 955: http://code.google.com/p/arduino/issues/detail?id=955 +.. _Arduino Patch: http://arduino.googlecode.com/issues/attachment?aid=9550004000&name=sig-patch.diff&token=R2RWB0LZXQi8OpPLsyAdnMATDNU%3A1351021269609 + +Resources +--------- + +Here are some resources you might find useful in getting started. + +1. CMake: + + * `Offical CMake Tutorial`_ + * `CMake Tutorial`_ + * `CMake Reference`_ + +.. _Offical CMake Tutorial: http://www.cmake.org/cmake/help/cmake_tutorial.html +.. _CMake Tutorial: http://mathnathan.com/2010/07/11/getting-started-with-cmake/ +.. _CMake Reference: http://www.cmake.org/cmake/help/cmake-2-8-docs.html + +2. Arduino: + + * `Getting Started`_ - Introduction to Arduino + * `Playground`_ - User contributed documentation and help + * `Arduino Forums`_ - Official forums + * `Arduino Reference`_ - Official reference manual + +.. _Getting Started: http://www.arduino.cc/en/Guide/HomePage +.. _Playground: http://www.arduino.cc/playground/ +.. _Arduino Reference: http://www.arduino.cc/en/Reference/HomePage +.. _Arduino Forums: http://www.arduino.cc/forum/ + + + + + + + + +.. _CMake 2.8: http://www.cmake.org/cmake/resources/software.html +.. _CMake: http://www.cmake.org/cmake/resources/software.html +.. _CMake Installer: http://www.cmake.org/cmake/resources/software.html +.. _Arduino SDK: http://www.arduino.cc/en/Main/Software From b69cbffe0b7c81740e5c93f8673bc5de6b48f55e Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Thu, 24 May 2018 10:40:36 -0700 Subject: [PATCH 80/80] Update atmega parameters Prior to this commit the mega2560 failed to build from the arduino update because the mega offers multiple cpus. This commit fixes that by specifying the mega board and the board cpu to atmega2560. --- firmware/brake/kia_soul_petrol/CMakeLists.txt | 5 +++-- .../kia_soul_petrol/utils/release_pressure/CMakeLists.txt | 4 +++- .../kia_soul_petrol/utils/serial_actuator/CMakeLists.txt | 4 +++- 3 files changed, 9 insertions(+), 4 deletions(-) diff --git a/firmware/brake/kia_soul_petrol/CMakeLists.txt b/firmware/brake/kia_soul_petrol/CMakeLists.txt index a5f34426..cbbfe608 100644 --- a/firmware/brake/kia_soul_petrol/CMakeLists.txt +++ b/firmware/brake/kia_soul_petrol/CMakeLists.txt @@ -1,4 +1,3 @@ -set(ARDUINO_DEFAULT_BOARD mega2560) generate_arduino_firmware( brake @@ -18,7 +17,9 @@ generate_arduino_firmware( src/brake_control.cpp src/communications.cpp src/init.cpp - src/timers.cpp) + src/timers.cpp + BOARD_CPU atmega2560 + BOARD mega) target_include_directories( brake diff --git a/firmware/brake/kia_soul_petrol/utils/release_pressure/CMakeLists.txt b/firmware/brake/kia_soul_petrol/utils/release_pressure/CMakeLists.txt index a9fcad81..bf88a021 100644 --- a/firmware/brake/kia_soul_petrol/utils/release_pressure/CMakeLists.txt +++ b/firmware/brake/kia_soul_petrol/utils/release_pressure/CMakeLists.txt @@ -2,7 +2,9 @@ project(brake-utils-release-pressure) generate_arduino_firmware( brake-utils-release-pressure - SKETCH src/release_pressure.ino) + SKETCH src/release_pressure.ino + BOARD_CPU atmega2560 + BOARD mega) target_compile_options( brake-utils-release-pressure diff --git a/firmware/brake/kia_soul_petrol/utils/serial_actuator/CMakeLists.txt b/firmware/brake/kia_soul_petrol/utils/serial_actuator/CMakeLists.txt index b1c8a33f..f0c692e3 100644 --- a/firmware/brake/kia_soul_petrol/utils/serial_actuator/CMakeLists.txt +++ b/firmware/brake/kia_soul_petrol/utils/serial_actuator/CMakeLists.txt @@ -17,7 +17,9 @@ generate_arduino_firmware( ../../src/brake_control.cpp ../../src/communications.cpp ../../src/init.cpp - src/serial_actuator.cpp) + src/serial_actuator.cpp + BOARD_CPU atmega2560 + BOARD mega) target_include_directories( brake-utils-serial-actuator