From 655c907a0777c4fe62594331a7cc5942ff854b3c Mon Sep 17 00:00:00 2001 From: Boris Bidault Date: Wed, 1 Aug 2018 09:21:25 -0700 Subject: [PATCH 01/11] Use OSCC CAN-ID definitions --- CMakeLists.txt | 1 + example/roscco_apollo.cpp | 12 ++++++------ example/roscco_apollo.h | 7 +++---- 3 files changed, 10 insertions(+), 10 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index db01460..ea1e288 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -202,6 +202,7 @@ add_executable( target_include_directories( ${PROJECT_NAME}_apollo PUBLIC include + oscc/api/include ) add_dependencies( diff --git a/example/roscco_apollo.cpp b/example/roscco_apollo.cpp index 5406008..bfbc76b 100644 --- a/example/roscco_apollo.cpp +++ b/example/roscco_apollo.cpp @@ -54,7 +54,7 @@ void RosccoApollo::EVCanFrameCallback( const roscco::CanFrame& input ) { switch( input.frame.can_id ) { - case 512: + case KIA_SOUL_OBD_THROTTLE_PRESSURE_CAN_ID: { throttle_report = input.frame.data[4]; @@ -62,15 +62,15 @@ void RosccoApollo::EVCanFrameCallback( const roscco::CanFrame& input ) break; } - case 544: + case KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID: { brake_report = input.frame.data[4] + input.frame.data[5] * 256; - brake_report = brake_report * EV_BRAKE_RATIO; + brake_report = brake_report * BRAKE_RATIO; break; } - case 688: + case KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID: { steering_angle_report = input.frame.data[0] + input.frame.data[1] * 256; @@ -83,7 +83,7 @@ void RosccoApollo::EVCanFrameCallback( const roscco::CanFrame& input ) break; } - case 1200: + case KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID: { speed_report = input.frame.data[0] + input.frame.data[2] + input.frame.data[4] + input.frame.data[6]; @@ -93,7 +93,7 @@ void RosccoApollo::EVCanFrameCallback( const roscco::CanFrame& input ) speed_report = speed_report / 4; - speed_report = speed_report * EV_SPEED_RATIO; + speed_report = speed_report * SPEED_RATIO; break; } diff --git a/example/roscco_apollo.h b/example/roscco_apollo.h index 8328d42..d0f3ede 100644 --- a/example/roscco_apollo.h +++ b/example/roscco_apollo.h @@ -9,13 +9,12 @@ #include #include #include +#include #define THROTTLE_RATIO 0.393 -#define EV_BRAKE_RATIO 0.118 -#define PETROL_BRAKE_RATIO 0.056 +#define BRAKE_RATIO 0.115 #define STEERING_RATIO 0.018 -#define EV_SPEED_RATIO 0.003 -#define PETROL_SPEED_RATIO 0.02 +#define SPEED_RATIO 0.003 class RosccoApollo From 051f9d5ca944d3622058bb947626b5abebed0513 Mon Sep 17 00:00:00 2001 From: Boris Bidault Date: Wed, 1 Aug 2018 15:02:11 -0700 Subject: [PATCH 02/11] Correct parameters, refactoring --- CMakeLists.txt | 4 +--- README.md | 2 +- example/roscco_apollo.cpp | 6 +++--- example/roscco_apollo.h | 3 +-- 4 files changed, 6 insertions(+), 9 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index ea1e288..01f07f2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -164,8 +164,7 @@ target_link_libraries( endif() -if(APOLLO) -if(KIA_SOUL_EV) +if(APOLLO AND KIA_SOUL_EV) find_package(catkin REQUIRED COMPONENTS @@ -236,7 +235,6 @@ target_link_libraries( vehicle_state_proto_lib ) -endif() endif() ############# diff --git a/README.md b/README.md index 60c99f2..89adf26 100644 --- a/README.md +++ b/README.md @@ -77,7 +77,7 @@ for roscco_node and the roscco_node sends it's received messages to OSCC API. ROSCCO can serve as a bridge to Baidu's open autonomous driving platform Apollo. This example only support the Kia Soul EV. We are planning on extending support to the Kia Niro. -You will need a double channel Kvaser or two single channel Kvaser, can0 will be drivekit CAN and can1 will be diagnostics CAN. +You will need a double channel Kvaser or two single channel Kvaser, to connect to drivekit CAN and diagnostics CAN. #### Installation and build diff --git a/example/roscco_apollo.cpp b/example/roscco_apollo.cpp index bfbc76b..6b5e121 100644 --- a/example/roscco_apollo.cpp +++ b/example/roscco_apollo.cpp @@ -134,9 +134,9 @@ void closedLoopControl( double setpoint, params.max = 1; params.min = -1; params.p_term = 0.016; - params.i_term = 0.0001; - params.d_term = 0.01; - params.i_max = 5000; + params.i_term = 0.004; + params.d_term = 0.001; + params.i_max = 250; output.steering_torque = pidController( ¶ms, &state, steering_angle_report ); } diff --git a/example/roscco_apollo.h b/example/roscco_apollo.h index d0f3ede..260d61d 100644 --- a/example/roscco_apollo.h +++ b/example/roscco_apollo.h @@ -14,8 +14,7 @@ #define THROTTLE_RATIO 0.393 #define BRAKE_RATIO 0.115 #define STEERING_RATIO 0.018 -#define SPEED_RATIO 0.003 - +#define SPEED_RATIO 0.02 class RosccoApollo { From e67cedcd485d98e7db4ded4b59f7b3bce79c61fe Mon Sep 17 00:00:00 2001 From: Boris Bidault Date: Thu, 2 Aug 2018 12:11:23 -0700 Subject: [PATCH 03/11] Add Niro brake & throttle forwarding --- CMakeLists.txt | 2 +- example/roscco_apollo.cpp | 20 ++++++++++++++------ example/roscco_apollo.h | 9 +++++++-- 3 files changed, 22 insertions(+), 9 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 01f07f2..404753a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -164,7 +164,7 @@ target_link_libraries( endif() -if(APOLLO AND KIA_SOUL_EV) +if(APOLLO AND (KIA_SOUL_EV OR KIA_NIRO)) find_package(catkin REQUIRED COMPONENTS diff --git a/example/roscco_apollo.cpp b/example/roscco_apollo.cpp index 6b5e121..7dd2298 100644 --- a/example/roscco_apollo.cpp +++ b/example/roscco_apollo.cpp @@ -13,7 +13,7 @@ RosccoApollo::RosccoApollo() throttle_sub = nh.subscribe( "/apollo/control", 1, &RosccoApollo::throttleCallback, this ); localization_sub = nh.subscribe( "/apollo/localization/pose", 1, &RosccoApollo::localizationCallback, this ); - can_frame_sub = nh.subscribe( "/can_frame", 1, &RosccoApollo::EVCanFrameCallback, this ); + can_frame_sub = nh.subscribe( "/can_frame", 1, &RosccoApollo::canFrameCallback, this ); } @@ -50,13 +50,17 @@ void RosccoApollo::throttleCallback( const apollo::control::ControlCommand& inpu } -void RosccoApollo::EVCanFrameCallback( const roscco::CanFrame& input ) +void RosccoApollo::canFrameCallback( const roscco::CanFrame& input ) { switch( input.frame.can_id ) { case KIA_SOUL_OBD_THROTTLE_PRESSURE_CAN_ID: { - throttle_report = input.frame.data[4]; + #if defined( KIA_SOUL_EV ) + throttle_report = input.frame.data[4]; + #elif defined( KIA_NIRO ) + throttle_report = input.frame.data[7]; + #endif throttle_report = throttle_report * THROTTLE_RATIO; @@ -64,7 +68,11 @@ void RosccoApollo::EVCanFrameCallback( const roscco::CanFrame& input ) } case KIA_SOUL_OBD_BRAKE_PRESSURE_CAN_ID: { - brake_report = input.frame.data[4] + input.frame.data[5] * 256; + #if defined( KIA_SOUL_EV ) + brake_report = input.frame.data[4] + input.frame.data[5] * 256; + #elif defined( KIA_NIRO ) + brake_report = input.frame.data[3] + input.frame.data[4] * 256; + #endif brake_report = brake_report * BRAKE_RATIO; @@ -88,8 +96,8 @@ void RosccoApollo::EVCanFrameCallback( const roscco::CanFrame& input ) speed_report = input.frame.data[0] + input.frame.data[2] + input.frame.data[4] + input.frame.data[6]; - speed_report += ( input.frame.data[1] + input.frame.data[3] - + input.frame.data[5] + input.frame.data[7] ) * 256; + speed_report += ( input.frame.data[1] + input.frame.data[3] + + input.frame.data[5] + input.frame.data[7] ) * 256; speed_report = speed_report / 4; diff --git a/example/roscco_apollo.h b/example/roscco_apollo.h index 260d61d..630388c 100644 --- a/example/roscco_apollo.h +++ b/example/roscco_apollo.h @@ -12,10 +12,15 @@ #include #define THROTTLE_RATIO 0.393 -#define BRAKE_RATIO 0.115 #define STEERING_RATIO 0.018 #define SPEED_RATIO 0.02 +#if defined( KIA_SOUL_EV ) + #define BRAKE_RATIO 0.115 +#elif defined( KIA_NIRO ) + #define BRAKE_RATIO 0.033 +#endif + class RosccoApollo { public: @@ -55,7 +60,7 @@ class RosccoApollo * * @param roscco can frame message to be consumed */ - void EVCanFrameCallback( const roscco::CanFrame& input ); + void canFrameCallback( const roscco::CanFrame& input ); /** * @brief Callback function to log localization From 3868d03b9ce0295cae9c139a20e0efbd32af5cc7 Mon Sep 17 00:00:00 2001 From: Boris Bidault Date: Wed, 15 Aug 2018 15:00:17 -0700 Subject: [PATCH 04/11] Add Niro speed forwarding --- example/roscco_apollo.cpp | 14 ++++++++++---- example/roscco_apollo.h | 5 +++-- 2 files changed, 13 insertions(+), 6 deletions(-) diff --git a/example/roscco_apollo.cpp b/example/roscco_apollo.cpp index 7dd2298..0e4d77c 100644 --- a/example/roscco_apollo.cpp +++ b/example/roscco_apollo.cpp @@ -60,6 +60,10 @@ void RosccoApollo::canFrameCallback( const roscco::CanFrame& input ) throttle_report = input.frame.data[4]; #elif defined( KIA_NIRO ) throttle_report = input.frame.data[7]; + + speed_report = input.frame.data[4]; + + speed_report = speed_report * SPEED_RATIO; #endif throttle_report = throttle_report * THROTTLE_RATIO; @@ -93,15 +97,17 @@ void RosccoApollo::canFrameCallback( const roscco::CanFrame& input ) } case KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID: { - speed_report = input.frame.data[0] + input.frame.data[2] - + input.frame.data[4] + input.frame.data[6]; + #if defined( KIA_SOUL_EV ) + speed_report = input.frame.data[0] + input.frame.data[2] + + input.frame.data[4] + input.frame.data[6]; speed_report += ( input.frame.data[1] + input.frame.data[3] + input.frame.data[5] + input.frame.data[7] ) * 256; - speed_report = speed_report / 4; + speed_report = speed_report / 4; - speed_report = speed_report * SPEED_RATIO; + speed_report = speed_report * SPEED_RATIO; + #endif break; } diff --git a/example/roscco_apollo.h b/example/roscco_apollo.h index 630388c..d8cfb4d 100644 --- a/example/roscco_apollo.h +++ b/example/roscco_apollo.h @@ -13,12 +13,13 @@ #define THROTTLE_RATIO 0.393 #define STEERING_RATIO 0.018 -#define SPEED_RATIO 0.02 #if defined( KIA_SOUL_EV ) - #define BRAKE_RATIO 0.115 + #define BRAKE_RATIO 0.12 + #define SPEED_RATIO 0.02 #elif defined( KIA_NIRO ) #define BRAKE_RATIO 0.033 + #define SPEED_RATIO 0.66 #endif class RosccoApollo From 7b9816960a786f5af01e01b80eb3af3394951167 Mon Sep 17 00:00:00 2001 From: Boris Bidault Date: Mon, 20 Aug 2018 12:07:18 -0700 Subject: [PATCH 05/11] Add Niro & EV vehicle speed support --- example/roscco_apollo.cpp | 17 +++++++---------- example/roscco_apollo.h | 4 ++-- 2 files changed, 9 insertions(+), 12 deletions(-) diff --git a/example/roscco_apollo.cpp b/example/roscco_apollo.cpp index 0e4d77c..060807c 100644 --- a/example/roscco_apollo.cpp +++ b/example/roscco_apollo.cpp @@ -60,10 +60,6 @@ void RosccoApollo::canFrameCallback( const roscco::CanFrame& input ) throttle_report = input.frame.data[4]; #elif defined( KIA_NIRO ) throttle_report = input.frame.data[7]; - - speed_report = input.frame.data[4]; - - speed_report = speed_report * SPEED_RATIO; #endif throttle_report = throttle_report * THROTTLE_RATIO; @@ -95,18 +91,19 @@ void RosccoApollo::canFrameCallback( const roscco::CanFrame& input ) break; } - case KIA_SOUL_OBD_WHEEL_SPEED_CAN_ID: + case KIA_SOUL_OBD_SPEED_CAN_ID: { #if defined( KIA_SOUL_EV ) - speed_report = input.frame.data[0] + input.frame.data[2] - + input.frame.data[4] + input.frame.data[6]; + speed_report = input.frame.data[3] + + input.frame.data[2] * 128; - speed_report += ( input.frame.data[1] + input.frame.data[3] - + input.frame.data[5] + input.frame.data[7] ) * 256; + speed_report = speed_report * SPEED_RATIO; - speed_report = speed_report / 4; + #elif defined( KIA_NIRO ) + speed_report = input.frame.data[0]; speed_report = speed_report * SPEED_RATIO; + #endif break; diff --git a/example/roscco_apollo.h b/example/roscco_apollo.h index d8cfb4d..def3045 100644 --- a/example/roscco_apollo.h +++ b/example/roscco_apollo.h @@ -16,10 +16,10 @@ #if defined( KIA_SOUL_EV ) #define BRAKE_RATIO 0.12 - #define SPEED_RATIO 0.02 + #define SPEED_RATIO 0.002 #elif defined( KIA_NIRO ) #define BRAKE_RATIO 0.033 - #define SPEED_RATIO 0.66 + #define SPEED_RATIO 0.3 #endif class RosccoApollo From f09d4060f52cadf40a6f9fb7a34fca2fbaeb79fc Mon Sep 17 00:00:00 2001 From: Boris Bidault Date: Mon, 20 Aug 2018 14:20:50 -0700 Subject: [PATCH 06/11] Switch oscc to v1.2.3 --- oscc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/oscc b/oscc index 2a2f112..60ac713 160000 --- a/oscc +++ b/oscc @@ -1 +1 @@ -Subproject commit 2a2f1122e620dfe0767206a2ea81ea8a7ca42552 +Subproject commit 60ac71346e671fdf4fba9c979ad3d372809ef5c7 From 5010e6507c7b3f014a77bfeba7a2cb6c072d7ec8 Mon Sep 17 00:00:00 2001 From: Boris Bidault Date: Wed, 22 Aug 2018 14:03:00 -0700 Subject: [PATCH 07/11] refactoring --- CMakeLists.txt | 4 ---- example/roscco_apollo.cpp | 11 +---------- example/roscco_apollo.h | 8 -------- 3 files changed, 1 insertion(+), 22 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 404753a..570b796 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -187,7 +187,6 @@ add_library( link_directories( /apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/canbus/ /apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/control/ - /apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/localization/ /apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/common/proto /apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/drivers/canbus/common/ /apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/drivers/canbus/proto/ @@ -217,13 +216,10 @@ target_link_libraries( ${PROJECT_NAME}_pid_control /apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/canbus/proto/libcanbus_proto_lib.a /apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/control/proto/libcontrol_proto_lib.a - /apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/localization/proto/liblocalization_proto_lib.a - /apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/localization/proto/libpose_proto_lib.a canbus_proto_lib protobuf canbus_lib control_lib - localization_lib canbus_common vehicle_signal_proto_lib pnc_point_proto_lib diff --git a/example/roscco_apollo.cpp b/example/roscco_apollo.cpp index 060807c..edc6e6f 100644 --- a/example/roscco_apollo.cpp +++ b/example/roscco_apollo.cpp @@ -11,7 +11,6 @@ RosccoApollo::RosccoApollo() steering_sub = nh.subscribe( "/apollo/control", 1, &RosccoApollo::steeringCallback, this ); brake_sub = nh.subscribe( "/apollo/control", 1, &RosccoApollo::brakeCallback, this ); throttle_sub = nh.subscribe( "/apollo/control", 1, &RosccoApollo::throttleCallback, this ); - localization_sub = nh.subscribe( "/apollo/localization/pose", 1, &RosccoApollo::localizationCallback, this ); can_frame_sub = nh.subscribe( "/can_frame", 1, &RosccoApollo::canFrameCallback, this ); } @@ -94,8 +93,7 @@ void RosccoApollo::canFrameCallback( const roscco::CanFrame& input ) case KIA_SOUL_OBD_SPEED_CAN_ID: { #if defined( KIA_SOUL_EV ) - speed_report = input.frame.data[3] - + input.frame.data[2] * 128; + speed_report = input.frame.data[3] + input.frame.data[2] * 128; speed_report = speed_report * SPEED_RATIO; @@ -126,13 +124,6 @@ void RosccoApollo::canFrameCallback( const roscco::CanFrame& input ) } -void RosccoApollo::localizationCallback( const apollo::localization::LocalizationEstimate& input ) -{ - std::cout << std::to_string( input.pose().position().x() ) << ", " - << std::to_string( input.pose().position().y() ) << "\n"; -} - - void closedLoopControl( double setpoint, roscco::SteeringCommand& output, double steering_angle_report ) diff --git a/example/roscco_apollo.h b/example/roscco_apollo.h index def3045..d17402f 100644 --- a/example/roscco_apollo.h +++ b/example/roscco_apollo.h @@ -5,7 +5,6 @@ #include #include #include -#include #include #include #include @@ -62,13 +61,6 @@ class RosccoApollo * @param roscco can frame message to be consumed */ void canFrameCallback( const roscco::CanFrame& input ); - - /** - * @brief Callback function to log localization - * - * @param apollo localization message to be consumed - */ - void localizationCallback( const apollo::localization::LocalizationEstimate& input ); ros::NodeHandle nh; From 670b246cd50308af98202f7539735bf0f467ee03 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Thu, 23 Aug 2018 12:06:32 -0700 Subject: [PATCH 08/11] Update to new Jenkins build process Prior to this commit the build process was failing because it had a Jenkinsfile that did not follow the new build format. This commit fixes that by adding a Dockerfile and updating the Jenkinsfile to use a docker image with the required dependencies. --- Dockerfile | 26 ++++++++++++++ Jenkinsfile | 98 +++++++++++++++++++++++++++++++++-------------------- 2 files changed, 87 insertions(+), 37 deletions(-) create mode 100644 Dockerfile diff --git a/Dockerfile b/Dockerfile new file mode 100644 index 0000000..8083ff4 --- /dev/null +++ b/Dockerfile @@ -0,0 +1,26 @@ +FROM ubuntu:16.04 + +WORKDIR /app + +# common packages +RUN apt-get update && \ + apt-get install -y \ + build-essential cmake git wget && \ + rm -rf /var/lib/apt/lists/* + +# add ROS packages to apt package manager +RUN sh -c 'echo "deb http://packages.ros.org/ros/ubuntu xenial main" > /etc/apt/sources.list.d/ros-latest.list' + +RUN apt-key adv --keyserver keyserver.ubuntu.com --recv-key 421C365BD9FF1F717815A3895523BAEEB01FA116 + +# install ros +RUN apt-get update && \ + apt-get install -y ros-kinetic-ros-base + +# install arduino toolchain +RUN wget -nv http://arduino.cc/download.php?f=/arduino-1.8.5-linux64.tar.xz -O arduino-1.8.5.tar.xz + +RUN tar -xf arduino-1.8.5.tar.xz && \ + cd arduino-1.8.5 && \ + mkdir -p /usr/share/arduino && \ + cp -R * /usr/share/arduino diff --git a/Jenkinsfile b/Jenkinsfile index b3322bf..5009117 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -1,43 +1,67 @@ #!groovy -node('xenial') { - try { - stage('Checkout') { - sh 'mkdir -p catkin_ws/src/roscco' - dir('catkin_ws/src/roscco') - { - checkout([ - $class: 'GitSCM', - branches: scm.branches, - doGenerateSubmoduleConfigurations: false, - extensions: scm.extensions + [[$class: 'CleanBeforeCheckout'], - [$class: 'SubmoduleOption', - disableSubmodules: false, - parentCredentials: true, - recursiveSubmodules: true, - reference: '', - trackingSubmodules: false]], - submoduleCfg: [], - userRemoteConfigs: scm.userRemoteConfigs - ]) - } + +node() { + def builds = [:] + def platforms = [:] + + sh 'mkdir -p catkin_ws/src/roscco' + dir('catkin_ws/src/roscco') { + checkout scm + sh "git submodule update --init --recursive" + + def image = docker.build("catkin_make-build:${env.BUILD_ID}") + + + def output = image.inside { + sh returnStdout: true, script: "cmake -LA ./oscc/firmware | grep 'VEHICLE_VALUES' | cut -d'=' -f 2" + } + + platforms = output.trim().tokenize(';')\ } - stage('Build') { - parallel 'kia soul firmware': { - sh '. /opt/ros/kinetic/setup.sh && cd catkin_ws && catkin_make -DKIA_SOUL=ON' - } - echo 'Build Complete!' + + for(int j=0; j Date: Thu, 23 Aug 2018 14:16:33 -0700 Subject: [PATCH 09/11] Add verbosity to test results Prior to this commit the ROS test results call only listed basic information about how many tests passed and failed. This commit fixes that by adding verbose to the results call so that more information is displayed in the jenkins console. --- Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index 5009117..cacb580 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -50,7 +50,7 @@ node() { cd catkin_ws && \ catkin_make -DVEHICLE=${platform} && \ ROS_HOME=${workspace} ROS_LOG_DIR=${workspace} catkin_make run_tests -DVEHICLE=${platform} && \ - catkin_test_results" + catkin_test_results --verbose" } } } From eed90d6da909573313d5a89ec78f0ea708aaecf0 Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Thu, 23 Aug 2018 14:33:46 -0700 Subject: [PATCH 10/11] Remove extra build step Prior to this commit there was an extra build in the test stage. This commit fixes that by removing the extra step. --- Jenkinsfile | 1 - 1 file changed, 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index cacb580..b5d2c3b 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -48,7 +48,6 @@ node() { image.inside{ sh ". /opt/ros/kinetic/setup.sh && \ cd catkin_ws && \ - catkin_make -DVEHICLE=${platform} && \ ROS_HOME=${workspace} ROS_LOG_DIR=${workspace} catkin_make run_tests -DVEHICLE=${platform} && \ catkin_test_results --verbose" } From 6a1b62dac480bbba98b47e10defea2dda0bd218e Mon Sep 17 00:00:00 2001 From: Robert Brown Date: Fri, 24 Aug 2018 09:52:33 -0700 Subject: [PATCH 11/11] Increase sleep time for build delay Prior to this commit tests were intermittently failing due to a backlog in the message passing on slower build machines inside docker containers. This commit fixes that by increasing the sleep time by 2ms so that the test has enough wait time for messages to be passed across the ROS bus in the slower environment. --- test/test_oscc_to_ros.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test/test_oscc_to_ros.cpp b/test/test_oscc_to_ros.cpp index aaa7b74..9b04316 100644 --- a/test/test_oscc_to_ros.cpp +++ b/test/test_oscc_to_ros.cpp @@ -7,7 +7,7 @@ #include // Time to allow ROS to process callbacks and publish a message -const double SLEEP_TIME = 0.02; +const double SLEEP_TIME = 0.05; template class MessageHelper