diff --git a/.travis.yml b/.travis.yml index b39f6c0..6e97e2e 100644 --- a/.travis.yml +++ b/.travis.yml @@ -5,23 +5,25 @@ # https://github.com/ros-infrastructure/ros_buildfarm/blob/master/doc/jobs/prerelease_jobs.rst # while this doesn't require sudo we don't want to run within a Docker container sudo: true -dist: trusty +dist: bionic language: python -python: - - "3.4" env: global: - JOB_PATH=/tmp/devel_job - ABORT_ON_TEST_FAILURE=1 + - INDEX_URL=https://raw.githubusercontent.com/ros-infrastructure/ros_buildfarm_config/production/index.yaml matrix: - - ROS_DISTRO_NAME=indigo OS_NAME=ubuntu OS_CODE_NAME=trusty ARCH=amd64 + - CHECK_PYTHON3_COMPILE=true +# - ROS_DISTRO_NAME=indigo OS_NAME=ubuntu OS_CODE_NAME=trusty ARCH=amd64 - ROS_DISTRO_NAME=kinetic OS_NAME=ubuntu OS_CODE_NAME=xenial ARCH=amd64 - - ROS_DISTRO_NAME=lunar OS_NAME=ubuntu OS_CODE_NAME=xenial ARCH=amd64 - ROS_DISTRO_NAME=melodic OS_NAME=ubuntu OS_CODE_NAME=bionic ARCH=amd64 + - ROS_DISTRO_NAME=noetic OS_NAME=ubuntu OS_CODE_NAME=focal ARCH=amd64 # matrix: # allow_failures: # - env: ROS_DISTRO_NAME=kinetic OS_NAME=ubuntu OS_CODE_NAME=xenial ARCH=amd64 install: + # check python3 compatibility + - if [ "${CHECK_PYTHON3_COMPILE}" == "true" ]; then python3 -m compileall .; exit $?; fi # either install the latest released version of ros_buildfarm - pip install ros_buildfarm # or checkout a specific branch diff --git a/package.xml b/package.xml index 684a221..f2d0519 100644 --- a/package.xml +++ b/package.xml @@ -15,7 +15,7 @@ message_generation roscpp - bfl + liborocos-bfl-dev std_msgs geometry_msgs sensor_msgs @@ -25,7 +25,7 @@ message_runtime roscpp - bfl + liborocos-bfl-dev std_msgs geometry_msgs sensor_msgs diff --git a/scripts/wtf.py b/scripts/wtf.py index e99745d..c91d653 100755 --- a/scripts/wtf.py +++ b/scripts/wtf.py @@ -5,9 +5,9 @@ if __name__ == '__main__': rospy.init_node('spawner', anonymous=True) - print 'looking for node robot_pose_ekf...' + print ('looking for node robot_pose_ekf...') rospy.wait_for_service('robot_pose_ekf/get_status') s = rospy.ServiceProxy('robot_pose_ekf/get_status', GetStatus) resp = s.call(GetStatusRequest()) - print resp.status + print (resp.status)