Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/devel'
Browse files Browse the repository at this point in the history
  • Loading branch information
rebpdx committed Jun 1, 2018
2 parents 99f02fb + f350fd1 commit 2a2f112
Show file tree
Hide file tree
Showing 125 changed files with 6,326 additions and 3,434 deletions.
3 changes: 3 additions & 0 deletions .gitignore
Expand Up @@ -7,3 +7,6 @@
**/tests/**/Cargo.lock
**/tests/**/common/
**/tests/**/target/

#cucumber port
cucumber.wire
91 changes: 50 additions & 41 deletions Jenkinsfile
@@ -1,51 +1,60 @@
#!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'
}
echo 'Build Complete!'
}
stage('Kia Soul Petrol Tests') {
parallel 'kia soul petrol unit tests': {
sh 'cd firmware && mkdir build_kia_soul_petrol_unit_tests && cd build_kia_soul_petrol_unit_tests && cmake .. -DKIA_SOUL=ON -DTESTS=ON -DCMAKE_BUILD_TYPE=Release && make run-unit-tests'
echo 'Kia Soul Petrol Unit Tests Complete!'
}, 'kia soul petrol property-based tests': {
withEnv(["PATH+CARGO=$HOME/.cargo/bin"]) {
sh 'cd firmware && mkdir build_kia_soul_petrol_property_tests && cd build_kia_soul_petrol_property_tests && cmake .. -DKIA_SOUL=ON -DTESTS=ON -DCMAKE_BUILD_TYPE=Release && make run-property-tests'
echo 'Kia Soul Petrol Property-Based Tests Complete!'

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 ./firmware | grep 'VEHICLE_VALUES' | cut -d'=' -f 2"
def platforms = output.trim().tokenize(';')

for(int j=0; j<platforms.size(); j++) {
def platform_idx = j
def platform = platforms[platform_idx]
builds[platform] = {
node('arduino') {
try {
stage("Checkout") {
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!"
}
stage("Test ${platform} unit tests") {
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 'Kia Soul Petrol Tests Complete!'
}
stage('Kia Soul EV Tests') {
parallel 'kia soul ev unit tests': {
sh 'cd firmware && mkdir build_kia_soul_ev_unit_tests && cd build_kia_soul_ev_unit_tests && cmake .. -DKIA_SOUL_EV=ON -DTESTS=ON -DCMAKE_BUILD_TYPE=Release && make run-unit-tests'
echo 'Kia Soul EV Unit Tests Complete!'
}, 'kia soul ev property-based tests': {
withEnv(["PATH+CARGO=$HOME/.cargo/bin"]) {
sh 'cd firmware && mkdir build_kia_soul_ev_property_tests && cd build_kia_soul_ev_property_tests && cmake .. -DKIA_SOUL_EV=ON -DTESTS=ON -DCMAKE_BUILD_TYPE=Release && make run-property-tests'
echo 'Kia Soul EV Property-Based Tests Complete!'
finally {
deleteDir()
}
}
echo 'Kia Soul EV Tests Complete!'
}
}
catch(Exception e) {
throw e;

try {
parallel builds
}
finally {
deleteDir()
}
}

}
10 changes: 1 addition & 9 deletions 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_CURRENT_LIST_DIR}/../firmware/cmake/OsccConfig.cmake)
109 changes: 109 additions & 0 deletions 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;
145 changes: 143 additions & 2 deletions api/include/oscc.h
Expand Up @@ -18,17 +18,45 @@
#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 ( 70 )


/*
* @brief CAN_MESSAGE_TIMEOUT is the time to wait for a CAN message in
* milliseconds used for auto detection of can channels.
*
*/
#define CAN_MESSAGE_TIMEOUT ( 100 )


typedef enum
{
OSCC_OK,
OSCC_ERROR,
OSCC_WARNING
} oscc_result_t;

/**
* @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
*
*/
oscc_result_t oscc_init();

/**
* @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.
*
Expand Down Expand Up @@ -176,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 */

0 comments on commit 2a2f112

Please sign in to comment.