Skip to content

Commit 2a2f112

Browse files
committed
Merge remote-tracking branch 'origin/devel'
2 parents 99f02fb + f350fd1 commit 2a2f112

125 files changed

Lines changed: 6326 additions & 3434 deletions

File tree

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

.gitignore

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -7,3 +7,6 @@
77
**/tests/**/Cargo.lock
88
**/tests/**/common/
99
**/tests/**/target/
10+
11+
#cucumber port
12+
cucumber.wire

Jenkinsfile

Lines changed: 50 additions & 41 deletions
Original file line numberDiff line numberDiff line change
@@ -1,51 +1,60 @@
11
#!groovy
2-
node('arduino') {
3-
try {
4-
stage('Checkout') {
5-
checkout([
6-
$class: 'GitSCM',
7-
branches: scm.branches,
8-
extensions: scm.extensions + [[$class: 'CleanBeforeCheckout']],
9-
userRemoteConfigs: scm.userRemoteConfigs
10-
])
11-
}
12-
stage('Build') {
13-
parallel 'kia soul petrol firmware': {
14-
sh 'cd firmware && mkdir build_kia_soul_petrol && cd build_kia_soul_petrol && cmake .. -DKIA_SOUL=ON -DCMAKE_BUILD_TYPE=Release && make'
15-
}, 'kia soul EV firmware': {
16-
sh 'cd firmware && mkdir build_kia_soul_ev && cd build_kia_soul_ev && cmake .. -DKIA_SOUL_EV=ON -DCMAKE_BUILD_TYPE=Release && make'
17-
}
18-
echo 'Build Complete!'
19-
}
20-
stage('Kia Soul Petrol Tests') {
21-
parallel 'kia soul petrol unit tests': {
22-
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'
23-
echo 'Kia Soul Petrol Unit Tests Complete!'
24-
}, 'kia soul petrol property-based tests': {
25-
withEnv(["PATH+CARGO=$HOME/.cargo/bin"]) {
26-
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'
27-
echo 'Kia Soul Petrol Property-Based Tests Complete!'
2+
3+
def cleanCheckout() {
4+
checkout([
5+
$class: 'GitSCM',
6+
branches: scm.branches,
7+
extensions: scm.extensions + [[$class: 'CleanBeforeCheckout']],
8+
userRemoteConfigs: scm.userRemoteConfigs
9+
])
10+
}
11+
12+
node('worker'){
13+
def builds = [:]
14+
cleanCheckout()
15+
def output = sh returnStdout: true, script: "cmake -LA ./firmware | grep 'VEHICLE_VALUES' | cut -d'=' -f 2"
16+
def platforms = output.trim().tokenize(';')
17+
18+
for(int j=0; j<platforms.size(); j++) {
19+
def platform_idx = j
20+
def platform = platforms[platform_idx]
21+
builds[platform] = {
22+
node('arduino') {
23+
try {
24+
stage("Checkout") {
25+
cleanCheckout()
26+
}
27+
stage("Build ${platform}") {
28+
sh "cd firmware && mkdir build_${platform} && cd build_${platform} \
29+
&& cmake -DVEHICLE=${platform} -DCMAKE_BUILD_TYPE=Release .. && make"
30+
echo "${platform}: Build Complete!"
31+
}
32+
stage("Test ${platform} unit tests") {
33+
sh "cd firmware && mkdir build_${platform}_tests && \
34+
cd build_${platform}_tests && cmake -DVEHICLE=${platform} \
35+
-DTESTS=ON -DPORT_SUFFIX=${EXECUTOR_NUMBER}${platform_idx} \
36+
-DCMAKE_BUILD_TYPE=Release .. && make run-unit-tests"
37+
echo "${platform}: Unit Tests Complete!"
38+
}
39+
stage("Test ${platform} property-based tests") {
40+
withEnv(["PATH+CARGO=$HOME/.cargo/bin"]) {
41+
sh "cd firmware/build_${platform}_tests && make run-property-tests"
42+
echo "${platform}: Property-Based Tests Complete!"
43+
}
44+
}
2845
}
29-
}
30-
echo 'Kia Soul Petrol Tests Complete!'
31-
}
32-
stage('Kia Soul EV Tests') {
33-
parallel 'kia soul ev unit tests': {
34-
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'
35-
echo 'Kia Soul EV Unit Tests Complete!'
36-
}, 'kia soul ev property-based tests': {
37-
withEnv(["PATH+CARGO=$HOME/.cargo/bin"]) {
38-
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'
39-
echo 'Kia Soul EV Property-Based Tests Complete!'
46+
finally {
47+
deleteDir()
4048
}
4149
}
42-
echo 'Kia Soul EV Tests Complete!'
4350
}
4451
}
45-
catch(Exception e) {
46-
throw e;
52+
53+
try {
54+
parallel builds
4755
}
4856
finally {
4957
deleteDir()
5058
}
51-
}
59+
60+
}

api/OsccConfig.cmake

Lines changed: 1 addition & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1 @@
1-
if(KIA_SOUL)
2-
add_definitions(-DKIA_SOUL)
3-
elseif(KIA_SOUL_EV)
4-
add_definitions(-DKIA_SOUL_EV)
5-
elseif(KIA_NIRO)
6-
add_definitions(-DKIA_NIRO)
7-
else()
8-
message(FATAL_ERROR "No platform selected")
9-
endif()
1+
include(${CMAKE_CURRENT_LIST_DIR}/../firmware/cmake/OsccConfig.cmake)

api/include/can_protocols/oscc.dbc

Lines changed: 109 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,109 @@
1+
VERSION ""
2+
3+
NS_ :
4+
BA_
5+
BA_DEF_
6+
BA_DEF_DEF_
7+
BA_DEF_DEF_REL_
8+
BA_DEF_REL_
9+
BA_DEF_SGTYPE_
10+
BA_REL_
11+
BA_SGTYPE_
12+
BO_TX_BU_
13+
BU_BO_REL_
14+
BU_EV_REL_
15+
BU_SG_REL_
16+
CAT_
17+
CAT_DEF_
18+
CM_
19+
ENVVAR_DATA_
20+
EV_DATA_
21+
FILTER
22+
NS_DESC_
23+
SGTYPE_
24+
SGTYPE_VAL_
25+
SG_MUL_VAL_
26+
SIGTYPE_VALTYPE_
27+
SIG_GROUP_
28+
SIG_TYPE_REF_
29+
SIG_VALTYPE_
30+
VAL_
31+
VAL_TABLE_
32+
33+
BS_:
34+
35+
BU_: BRAKE STEERING THROTTLE FAULT
36+
37+
BO_ 112 BRAKE_ENABLE: 8 BRAKE
38+
SG_ brake_enable_magic : 0|16@1+ (1,0) [0|0] "" BRAKE
39+
SG_ brake_enable_reserved : 16|48@1+ (1,0) [0|0] "" BRAKE
40+
41+
BO_ 113 BRAKE_DISABLE: 8 BRAKE
42+
SG_ brake_disable_magic : 0|16@1+ (1,0) [0|0] "" BRAKE
43+
SG_ brake_disable_reserved : 16|48@1+ (1,0) [0|0] "" BRAKE
44+
45+
BO_ 114 BRAKE_COMMAND: 8 BRAKE
46+
SG_ brake_command_magic : 0|16@1+ (1,0) [0|0] "" BRAKE
47+
SG_ brake_command_pedal_request : 16|32@1+ (1,0) [0|1] "" BRAKE
48+
SG_ brake_command_reserved : 48|16@1+ (1,0) [0|0] "" BRAKE
49+
50+
BO_ 115 BRAKE_REPORT: 8 BRAKE
51+
SG_ brake_report_magic : 0|16@1+ (1,0) [0|0] "" BRAKE
52+
SG_ brake_report_enabled : 16|8@1+ (1,0) [0|0] "" BRAKE
53+
SG_ brake_report_operator_override : 24|8@1+ (1,0) [0|0] "" BRAKE
54+
SG_ brake_report_dtcs : 32|8@1+ (1,0) [0|0] "" BRAKE
55+
SG_ brake_report_reserved : 40|24@1+ (1,0) [0|0] "" BRAKE
56+
57+
BO_ 128 STEERING_ENABLE: 8 STEERING
58+
SG_ steering_enable_magic : 0|16@1+ (1,0) [0|0] "" STEERING
59+
SG_ steering_enable_reserved : 16|48@1+ (1,0) [0|0] "" STEERING
60+
61+
BO_ 129 STEERING_DISABLE: 8 STEERING
62+
SG_ steering_disable_magic : 0|16@1+ (1,0) [0|0] "" STEERING
63+
SG_ steering_disable_reserved : 16|48@1+ (1,0) [0|0] "" STEERING
64+
65+
BO_ 130 STEERING_COMMAND: 8 STEERING
66+
SG_ steering_command_magic : 0|16@1+ (1,0) [0|0] "" STEERING
67+
SG_ steering_command_torque_request : 16|32@1- (1,0) [-1|1] "" STEERING
68+
SG_ steering_command_reserved : 48|16@1+ (1,0) [0|0] "" STEERING
69+
70+
BO_ 131 STEERING_REPORT: 8 STEERING
71+
SG_ steering_report_magic : 0|16@1+ (1,0) [0|0] "" STEERING
72+
SG_ steering_report_enabled : 16|8@1+ (1,0) [0|0] "" STEERING
73+
SG_ steering_report_operator_override : 24|8@1+ (1,0) [0|0] "" STEERING
74+
SG_ steering_report_dtcs : 32|8@1+ (1,0) [0|0] "" STEERING
75+
SG_ steering_report_reserved : 40|24@1+ (1,0) [0|0] "" STEERING
76+
77+
BO_ 144 THROTTLE_ENABLE: 8 THROTTLE
78+
SG_ throttle_enable_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE
79+
SG_ throttle_enable_reserved : 16|48@1+ (1,0) [0|0] "" THROTTLE
80+
81+
BO_ 145 THROTTLE_DISABLE: 8 THROTTLE
82+
SG_ throttle_disable_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE
83+
SG_ throttle_disable_reserved : 16|48@1+ (1,0) [0|0] "" THROTTLE
84+
85+
BO_ 146 THROTTLE_COMMAND: 8 THROTTLE
86+
SG_ throttle_command_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE
87+
SG_ throttle_command_pedal_request : 16|32@1- (1,0) [0|1] "" THROTTLE
88+
SG_ throttle_command_reserved : 48|16@1+ (1,0) [0|0] "" THROTTLE
89+
90+
BO_ 147 THROTTLE_REPORT: 8 THROTTLE
91+
SG_ throttle_report_magic : 0|16@1+ (1,0) [0|0] "" THROTTLE
92+
SG_ throttle_report_enabled : 16|8@1+ (1,0) [0|0] "" THROTTLE
93+
SG_ throttle_report_operator_override : 24|8@1+ (1,0) [0|0] "" THROTTLE
94+
SG_ throttle_report_dtcs : 32|8@1+ (1,0) [0|0] "" THROTTLE
95+
SG_ throttle_report_reserved : 40|24@1+ (1,0) [0|0] "" THROTTLE
96+
97+
BO_ 175 FAULT_REPORT: 8 FAULT
98+
SG_ fault_report_magic : 0|16@1+ (1,0) [0|0] "" FAULT
99+
SG_ fault_report_fault_origin_id : 16|32@1+ (1,0) [0|0] "" FAULT
100+
SG_ fault_report_dtcs : 48|8@1+ (1,0) [0|0] "" FAULT
101+
SG_ fault_report_reserved : 56|8@1+ (1,0) [0|0] "" FAULT
102+
103+
CM_ BU_ BRAKE "The OSCC brake module";
104+
CM_ BU_ STEERING "The OSCC steering module";
105+
CM_ BU_ THROTTLE "The OSCC throttle module";
106+
CM_ BU_ FAULT "The OSCC fault report";
107+
SIG_VALTYPE_ 114 brake_command_pedal_request : 1;
108+
SIG_VALTYPE_ 130 steering_command_torque_request : 1;
109+
SIG_VALTYPE_ 146 throttle_command_pedal_request : 1;

api/include/oscc.h

Lines changed: 143 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -18,17 +18,45 @@
1818
#include "vehicles.h"
1919

2020

21+
/*
22+
* @brief MAX_CAN_IDS is the maximum number unique CAN IDs on the CAN bus used
23+
* for auto detection of CAN channels. Increasing this number increases the wait
24+
* time for checking if a channel contains expected CAN IDs, reducing this
25+
* number below number of CAN IDs broadcast could yield a false negative in auto
26+
* detection.
27+
*
28+
*/
29+
#define MAX_CAN_IDS ( 70 )
30+
31+
32+
/*
33+
* @brief CAN_MESSAGE_TIMEOUT is the time to wait for a CAN message in
34+
* milliseconds used for auto detection of can channels.
35+
*
36+
*/
37+
#define CAN_MESSAGE_TIMEOUT ( 100 )
38+
39+
2140
typedef enum
2241
{
2342
OSCC_OK,
2443
OSCC_ERROR,
2544
OSCC_WARNING
2645
} oscc_result_t;
2746

47+
/**
48+
* @brief Looks for available CAN channels and automatically detects which
49+
* channel is OSCC control and which channel is vehicle CAN for feedback.
50+
*
51+
* @return OSCC_ERROR or OSCC_OK
52+
*
53+
*/
54+
oscc_result_t oscc_init();
2855

2956
/**
30-
* @brief Use provided CAN channel to open communications
31-
* to CAN bus connected to the OSCC modules.
57+
* @brief Use provided CAN channel to open communications to CAN bus connected
58+
* to the OSCC modules. If CAN gateway does not forward Vehicle CAN
59+
* automatically detect if a CAN channel has Vehicle CAN available.
3260
*
3361
* @param [in] channel - CAN channel connected to OSCC modules.
3462
*
@@ -176,4 +204,117 @@ oscc_result_t oscc_subscribe_to_fault_reports( void( *callback )( oscc_fault_rep
176204
oscc_result_t oscc_subscribe_to_obd_messages( void( *callback )( struct can_frame *frame ) );
177205

178206

207+
/**
208+
* @brief Set vehicle right rear wheel speed in kph from CAN frame. (kph)
209+
*
210+
* @param [in] frame - A pointer to \ref struct can_frame that contains the raw CAN data associated
211+
* with wheel speed (CAN ID: \ref KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID)
212+
*
213+
* @param [out] wheel_speed_right_rear - A pointer to double. Set to the unpacked and scaled rear
214+
* right wheel speed reported by the vehicle (kph).
215+
*
216+
* @return:
217+
* \li \ref OSCC_OK on successful unpacking.
218+
* \li \ref OSCC_ERROR if a parameter is NULL or the CAN frame ID is not
219+
* \ref KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID
220+
*/
221+
oscc_result_t get_wheel_speed_right_rear(
222+
struct can_frame const * const frame,
223+
double * wheel_speed_right_rear);
224+
225+
/**
226+
* @brief Get vehicle left rear wheel speed in kph from CAN frame. (kph)
227+
*
228+
* @param [in] frame - A pointer to \ref struct can_frame that contains the raw CAN data associated
229+
* with wheel speed (CAN ID: \ref KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID)
230+
*
231+
* @param [out] wheel_speed_left_rear - A pointer to double. Set to the unpacked and scaled front
232+
* left wheel speed reported by the vehicle (kph).
233+
*
234+
* @return:
235+
* \li \ref OSCC_OK on successful unpacking.
236+
* \li \ref OSCC_ERROR if a parameter is NULL or the CAN frame ID is not
237+
* \ref KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID
238+
*/
239+
oscc_result_t get_wheel_speed_left_rear(
240+
struct can_frame const * const frame,
241+
double * wheel_speed_left_rear);
242+
243+
244+
/**
245+
* @brief Get vehicle right front wheel speed in kph from CAN frame. (kph)
246+
*
247+
* @param [in] frame - A pointer to \ref struct can_frame that contains the raw CAN data associated
248+
* with wheel speed (CAN ID: \ref KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID)
249+
*
250+
* @param [out] wheel_speed_right_front - A pointer to double. Set to the unpacked and scaled front
251+
* right wheel speed reported by the vehicle (kph).
252+
*
253+
* @return:
254+
* \li \ref OSCC_OK on successful unpacking.
255+
* \li \ref OSCC_ERROR if a parameter is NULL or the CAN frame ID is not
256+
* \ref KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID
257+
*/
258+
oscc_result_t get_wheel_speed_right_front(
259+
struct can_frame const * const frame,
260+
double * wheel_speed_right_front);
261+
262+
263+
/**
264+
* @brief Get vehicle left front wheel speed in kph from CAN frame. (kph)
265+
*
266+
* @param [in] frame - A pointer to \ref struct can_frame that contains the raw CAN data associated
267+
* with wheel speed (CAN ID: \ref KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID)
268+
*
269+
* @param [out] wheel_speed_left_front - A pointer to double. Set to the unpacked and scaled rear
270+
* left wheel speed reported by the vehicle (kph).
271+
*
272+
* @return:
273+
* \li \ref OSCC_OK on successful unpacking.
274+
* \li \ref OSCC_ERROR if a parameter is NULL or the CAN frame ID is not
275+
* \ref KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID
276+
*/
277+
oscc_result_t get_wheel_speed_left_front(
278+
struct can_frame const * const frame,
279+
double * wheel_speed_left_front);
280+
281+
282+
/**
283+
* @brief Get vehicle steering wheel angle from CAN frame. (degrees)
284+
*
285+
* @param [in] frame - A pointer to \ref struct can_frame that contains the raw CAN data associated
286+
* with steering wheel angle (CAN ID: \ref KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID)
287+
*
288+
* @param [out] steering_wheel_angle - A pointer to double. Value is set to the unpacked and scaled
289+
* steering wheel angle reported by the vehicle (degrees).
290+
*
291+
* @return:
292+
* \li \ref OSCC_OK on successful unpacking.
293+
* \li \ref OSCC_ERROR if a parameter is NULL or the CAN frame ID is not
294+
* \ref KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID
295+
*/
296+
oscc_result_t get_steering_wheel_angle(
297+
struct can_frame const * const frame,
298+
double * steering_wheel_angle);
299+
300+
301+
/**
302+
* @brief Get vehicle brake pressure from CAN frame. (bar)
303+
*
304+
* @param [in] frame - A pointer to \ref struct can_frame that contains the raw CAN data associated
305+
* with brake pressure (CAN ID: \ref KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID)
306+
*
307+
* @param [out] brake_pressure - A pointer to double. Set to the unpacked and scaled brake pressure
308+
* reported by the vehicle (bar).
309+
*
310+
* @return:
311+
* \li \ref OSCC_OK on successful unpacking.
312+
* \li \ref OSCC_ERROR if a parameter is NULL or the CAN frame ID is not
313+
* \ref KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID
314+
*/
315+
oscc_result_t get_brake_pressure(
316+
struct can_frame const * const frame,
317+
double * brake_pressure);
318+
319+
179320
#endif /* _OSCC_H */

0 commit comments

Comments
 (0)