diff --git a/.travis.yml b/.travis.yml
index 82d845868..e842e487b 100644
--- a/.travis.yml
+++ b/.travis.yml
@@ -26,8 +26,9 @@ env:
- ROS_DISTRO=indigo NOT_TEST_BUILD='true' NOT_TEST_INSTALL='true' POST_PROCESS='I_am_supposed_to_fail'
- ROS_DISTRO=indigo CATKIN_PARALLEL_JOBS='-p1' ROS_PARALLEL_JOBS='-j1' # Intend build on low-power platform
# - env: ROS_DISTRO=indigo PRERELEASE=true ## Comment out because this is meaningless for always failing without prerelease testable contents in industrial_ci.
- - ROS_DISTRO=indigo PRERELEASE=true PRERELEASE_REPONAME=std_msgs PRERELEASE_DOWNSTREAM_DEPTH=0
- - ROS_DISTRO=kinetic PRERELEASE=true PRERELEASE_REPONAME=std_msgs
+ - ROS_DISTRO=indigo PRERELEASE=true PRERELEASE_DOWNSTREAM_DEPTH=1
+ - ROS_DISTRO=indigo PRERELEASE=true USE_MOCKUP='industrial_ci/mockups/failing_test' EXPECT_EXIT_CODE=1
+ - ROS_DISTRO=kinetic PRERELEASE=true PRERELEASE_REPONAME=industrial_ci
- ROS_DISTRO=indigo APTKEY_STORE_SKS=hkp://ha.pool.sks-keyservers.vet # Passing wrong SKS URL as a break test. Should still pass.
- ROS_DISTRO=indigo UPSTREAM_WORKSPACE=debian
- ROS_DISTRO=indigo UPSTREAM_WORKSPACE=file # Using default file name for ROSINSTALL_FILENAME
@@ -40,7 +41,6 @@ env:
- ROS_DISTRO=jade APTKEY_STORE_SKS=hkp://ha.pool.sks-keyservers.vet _DO_NOT_FOLD=true # Passing wrong SKS URL as a break test. Should still pass.
- ROS_DISTRO=jade UPSTREAM_WORKSPACE=file ROSINSTALL_FILENAME=.ci.rosinstall # Testing arbitrary file name without ROS_DISTRO suffix. As of 6/3/2016 this fails due to https://github.com/ros-industrial/industrial_core/pull/144#issuecomment-223186764
- ROS_DISTRO=jade UPSTREAM_WORKSPACE=file ROSINSTALL_FILENAME=.i.do.not.exist EXPECT_EXIT_CODE=1
- - ROS_DISTRO=jade PRERELEASE=true PRERELEASE_REPONAME=i_do_not_exist EXPECT_EXIT_CODE=1 PRERELEASE_DOWNSTREAM_DEPTH=1 # Intended to fail, to test the capability of capturing Prerelease Test failure.
- ROS_DISTRO=kinetic AFTER_SCRIPT='catkin --version'
- ROS_DISTRO=kinetic NOT_TEST_BUILD='true' DEBUG_BASH='true' VERBOSE_OUTPUT='false'
- ROS_DISTRO=lunar ROS_REPO=ros-shadow-fixed
diff --git a/doc/index.rst b/doc/index.rst
index 63e304e81..57d452c74 100644
--- a/doc/index.rst
+++ b/doc/index.rst
@@ -166,9 +166,7 @@ Note that some of these currently tied only to a single option, but we still lea
* `NOT_TEST_INSTALL` (default: not set): If true, tests in `install` space won't be run.
* `PRERELEASE` (default: false): If `true`, run `Prerelease Test on docker that emulates ROS buildfarm `_. The usage of Prerelease Test feature is `explained more in this section `_.
* `PRERELEASE_DOWNSTREAM_DEPTH` (0 to 4, default: 0): Number of the levels of the package dependecies the Prerelease Test targets at. Range of the level is defined by ROS buildfarm (``_). NOTE: a job can run exponentially longer for the values greater than `0` depending on how many packages depend on your package (and remember a job on Travis CI can only run for up to 50 minutes).
-* `PRERELEASE_REPONAME` (default: not set): The target of Prerelease Test (that you select at ``_, ``_ etc.).
- * If not set then it tests the package of the repository's name. You can specify this by your ROS package name format (with underscore e.g. `industrial_core`), not Debian package name format. NOTE that this package name must be listed in the `rosdistro/distribution.yaml` (e.g. [for ROS Indigo](https://github.com/ros/rosdistro/blob/master/indigo/distribution.yaml)) (this requirement comes from ROS buildfarm's Prerelease Test).
- * (As of Dec 2016) when this variable is set, development branch listed in `rosdistro/distribution.yaml` is tested. See [detail](https://github.com/ros-industrial/industrial_ci/pull/85#issue-196409011).
+* `PRERELEASE_REPONAME` (default: TARGET_REPO_NAME): The name of the target of Prerelease Test in rosdistro (that you select at ``_). You can specify this if your repository name differs from the corresponding rosdisto entry. See `here `_ for more usage.
* `PKGS_DOWNSTREAM` (default: explained): Packages in downstream to be tested. By default, `TARGET_PKGS` is used if set, if not then `BUILD_PKGS` is used.
* `ROS_PARALLEL_JOBS` (default: -j8): Maximum number of packages to be built in parallel by the underlining build tool. As of Jan 2016, this is only enabled with `catkin_tools` (with `make` as an underlining builder).
* `ROS_PARALLEL_TEST_JOBS` (default: -j8): Maximum number of packages which could be examined in parallel during the test run by the underlining build tool. If not set it's filled by `ROS_PARALLEL_JOBS`. As of Jan 2016, this is only enabled with `catkin_tools` (with `make` as an underlining builder).
diff --git a/industrial_ci/mockups/failing_test/CMakeLists.txt b/industrial_ci/mockups/failing_test/CMakeLists.txt
new file mode 100644
index 000000000..a347434b9
--- /dev/null
+++ b/industrial_ci/mockups/failing_test/CMakeLists.txt
@@ -0,0 +1,13 @@
+cmake_minimum_required(VERSION 2.8.3)
+project(failing_test)
+
+find_package(catkin REQUIRED)
+
+catkin_package()
+
+if (CATKIN_ENABLE_TESTING)
+ find_package(rostest REQUIRED)
+ add_rostest(test/no_talker.test)
+endif()
+
+install(DIRECTORY test DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
diff --git a/industrial_ci/mockups/failing_test/package.xml b/industrial_ci/mockups/failing_test/package.xml
new file mode 100644
index 000000000..a904e6ddc
--- /dev/null
+++ b/industrial_ci/mockups/failing_test/package.xml
@@ -0,0 +1,13 @@
+
+
+ failing_test
+ 0.3.1
+ packages with a failing test
+
+ Isaac I. Y. Saito
+ Isaac I. Y. Saito
+ Apache License 2.0
+
+ catkin
+ rostest
+
diff --git a/industrial_ci/mockups/failing_test/test/no_talker.test b/industrial_ci/mockups/failing_test/test/no_talker.test
new file mode 100644
index 000000000..9df1eba7d
--- /dev/null
+++ b/industrial_ci/mockups/failing_test/test/no_talker.test
@@ -0,0 +1,11 @@
+
+
+
+
+
+
+
+
+
+
diff --git a/industrial_ci/src/tests/ros_prerelease.sh b/industrial_ci/src/tests/ros_prerelease.sh
index a8f543c01..4aafb9fd7 100644
--- a/industrial_ci/src/tests/ros_prerelease.sh
+++ b/industrial_ci/src/tests/ros_prerelease.sh
@@ -58,6 +58,7 @@ EOF
function run_in_prerelease_docker() {
ici_run_cmd_in_docker $DIND_OPTS \
-v "$WORKSPACE:$WORKSPACE:rw" \
+ -e TRAVIS \
"industrial-ci/prerelease" \
"$@"
@@ -72,41 +73,26 @@ function run_ros_prerelease() {
ici_time_start setup_prerelease_scripts
mkdir -p "$WORKSPACE/catkin_workspace/src/"
- local reponame=$PRERELEASE_REPONAME
- local clone_underlay=true
- if [ -z "$reponame" ]; then
- reponame=$TARGET_REPO_NAME
- mkdir -p catkin_workspace/src
- cp -a "$TARGET_REPO_PATH"/* "$WORKSPACE/catkin_workspace/src/"
- clone_underlay=false
- fi
+ local reponame=${PRERELEASE_REPONAME:-$TARGET_REPO_NAME}
+ cp -a "$TARGET_REPO_PATH" "$WORKSPACE/catkin_workspace/src/$reponame"
# ensure access rights
ici_run_cmd_in_docker $DIND_OPTS -v "$WORKSPACE:$WORKSPACE:rw" --user root "industrial-ci/prerelease" chown -R ci:ci $WORKSPACE
- run_in_prerelease_docker generate_prerelease_script.py https://raw.githubusercontent.com/ros-infrastructure/ros_buildfarm_config/production/index.yaml "$ROS_DISTRO" default ubuntu "$UBUNTU_OS_CODE_NAME" amd64 "${reponame}" --level "$downstream_depth" --output-dir .
- ici_time_end # setup_prerelease_scripts
- if [ "$clone_underlay" = true ]; then
- ici_time_start prerelease_clone_underlay.sh
- run_in_prerelease_docker ./prerelease_clone_underlay.sh
- ici_time_end # prerelease_clone_underlay
+ if [ "${USE_MOCKUP// }" != "" ]; then
+ if [ ! -d "$TARGET_REPO_PATH/$USE_MOCKUP" ]; then
+ error "mockup directory '$USE_MOCKUP' does not exist"
+ fi
+ cp -a "$TARGET_REPO_PATH/$USE_MOCKUP" "$WORKSPACE/catkin_workspace/src"
fi
- ici_time_start prerelease_build_underlay.sh
- run_in_prerelease_docker ./prerelease_build_underlay.sh
- run_in_prerelease_docker catkin_test_results $WORKSPACE/catkin_workspace/test_results
- ici_time_end # prerelease_build_underlay.sh
-
- if [ "$downstream_depth" != "0" ]; then
- ici_time_start run_prerelease_clone_overlay.sh
- run_in_prerelease_docker ./prerelease_clone_overlay.sh
- ici_time_end # run_prerelease_clone_overlay
- ici_time_start prerelease_build_overlay.sh
- run_in_prerelease_docker ./prerelease_build_overlay.sh
- run_in_prerelease_docker catkin_test_results $WORKSPACE/catkin_workspace_overlay/test_results
- ici_time_end # prerelease_build_overlay.sh
- fi
+ run_in_prerelease_docker generate_prerelease_script.py https://raw.githubusercontent.com/ros-infrastructure/ros_buildfarm_config/production/index.yaml "$ROS_DISTRO" default ubuntu "$UBUNTU_OS_CODE_NAME" amd64 --level "$downstream_depth" --output-dir . --custom-repo "$reponame::::"
+ ici_time_end # setup_prerelease_scripts
+
+ ici_time_start prerelease.sh
+ run_in_prerelease_docker env ABORT_ON_TEST_FAILURE=1 ./prerelease.sh -y
+ ici_time_end # prerelease.sh
echo 'ROS Prerelease Test went successful.'
}