Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add noetic to .travis.yml, remove indigo/lunar #342

Merged
merged 4 commits into from
Aug 14, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 7 additions & 6 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -8,20 +8,21 @@ sudo: true
dist: trusty
language: python
python:
- "3.4"
- "3.6"
env:
global:
- JOB_PATH=/tmp/devel_job
- ABORT_ON_TEST_FAILURE=1
matrix:
- ROS_DISTRO_NAME=indigo OS_NAME=ubuntu OS_CODE_NAME=trusty ARCH=amd64
- CHECK_PYTHON3_COMPILE=true
- 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:
- 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
Expand All @@ -32,15 +33,15 @@ install:
# run devel job for a ROS repository with the same name as this repo
- export REPOSITORY_NAME=`basename $TRAVIS_BUILD_DIR`
# use the code already checked out by Travis
- mkdir -p $JOB_PATH/catkin_workspace/src
- cp -R $TRAVIS_BUILD_DIR $JOB_PATH/catkin_workspace/src/
- mkdir -p $JOB_PATH/ws/src
- cp -R $TRAVIS_BUILD_DIR $JOB_PATH/ws/src/
# generate the script to run a pre-release job for that target and repo
- generate_prerelease_script.py https://raw.githubusercontent.com/ros-infrastructure/ros_buildfarm_config/production/index.yaml $ROS_DISTRO_NAME default $OS_NAME $OS_CODE_NAME $ARCH --output-dir $JOB_PATH
# run the actual job which involves Docker
- cd $JOB_PATH; sh ./prerelease.sh -y
script:
# get summary of test results
- /tmp/catkin/bin/catkin_test_results $JOB_PATH/catkin_workspace/test_results --all
- /tmp/catkin/bin/catkin_test_results $JOB_PATH/ws/test_results --all
notifications:
email: false

18 changes: 9 additions & 9 deletions pr2_controller_manager/scripts/pr2_controller_manager
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ class Tracker:
self.msg = msg

def print_usage(exit_code = 0):
print '''Commands:
print('''Commands:
load <name> - Load the controller named <name>
unload <name> - Unload the controller named <name>
start <name> - Start the controller named <name>
Expand All @@ -28,7 +28,7 @@ def print_usage(exit_code = 0):
list - List active controllers
list-joints - List joints and actuators
list-types - List controller Types
reload-libraries - Reloads all plugin controller libraries'''
reload-libraries - Reloads all plugin controller libraries''')

sys.exit(exit_code)

Expand All @@ -41,9 +41,9 @@ if __name__ == '__main__':
elif args[1] == 'lc' or args[1] == 'list':
pr2_controller_manager_interface.list_controllers()
elif args[1] == 'reload-libraries':
print "ARGS", args, args[2:]
print("ARGS", args, args[2:])
if '--restore' in args[2:]:
print "RE1"
print("RE1")
pr2_controller_manager_interface.reload_libraries(True, restore = True)
else:
pr2_controller_manager_interface.reload_libraries(True)
Expand Down Expand Up @@ -71,18 +71,18 @@ if __name__ == '__main__':
pr2_controller_manager_interface.unload_controller(c)
elif args[1] == 'lj' or args[1] == 'list-joints':
track_mech = Tracker('/mechanism_statistics', MechanismStatistics)
print "Waiting for mechanism statistics message..."
print("Waiting for mechanism statistics message...")
rospy.init_node('mech', anonymous=True)
while not track_mech.msg:
time.sleep(0.01)
if rospy.is_shutdown():
sys.exit(0)
msg = track_mech.msg
print 'Actuators:'
print('Actuators:')
for i in range(len(msg.actuator_statistics)):
print " %3d %s" % (i, msg.actuator_statistics[i].name)
print 'Joints:'
print(" %3d %s" % (i, msg.actuator_statistics[i].name))
print('Joints:')
for i in range(len(msg.joint_statistics)):
print " %3d %s" % (i, msg.joint_statistics[i].name)
print(" %3d %s" % (i, msg.joint_statistics[i].name))
else:
print_usage(1)
6 changes: 3 additions & 3 deletions pr2_controller_manager/scripts/spawner
Original file line number Diff line number Diff line change
Expand Up @@ -44,9 +44,9 @@ from pr2_mechanism_msgs.srv import *
from std_msgs.msg import *

def print_usage(exit_code = 0):
print 'spawner [--stopped] [--wait-for=wait_for_topic] <controller names>'
print " stopped: loads controllers, but doesn't start them"
print " wait-for: doesn't load or start controllers until it hears 'True' on wait_for_topic (Bool)"
print('spawner [--stopped] [--wait-for=wait_for_topic] <controller names>')
print(" stopped: loads controllers, but doesn't start them")
print(" wait-for: doesn't load or start controllers until it hears 'True' on wait_for_topic (Bool)")
sys.exit(exit_code)

load_controller = rospy.ServiceProxy('pr2_controller_manager/load_controller', LoadController)
Expand Down
8 changes: 4 additions & 4 deletions pr2_controller_manager/scripts/unspawner
Original file line number Diff line number Diff line change
Expand Up @@ -77,10 +77,10 @@ def main():


def print_help():
print './unspawner name1 name2 name3'
print ''
print '\tStops a set of controllers until killed.'
print '\tUseful in roslaunch files to temporarily stop controllers'
print('./unspawner name1 name2 name3')
print('')
print('\tStops a set of controllers until killed.')
print('\tUseful in roslaunch files to temporarily stop controllers')

if __name__ == '__main__':
if len(sys.argv) == 1 or sys.argv[1] == '-h' or sys.argv[1] == '--help':
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ def list_controller_types():
s = rospy.ServiceProxy('pr2_controller_manager/list_controller_types', ListControllerTypes)
resp = s.call(ListControllerTypesRequest())
for t in resp.types:
print t
print(t)

def reload_libraries(force_kill, restore = False):
rospy.wait_for_service('pr2_controller_manager/reload_controller_libraries')
Expand All @@ -23,16 +23,16 @@ def reload_libraries(force_kill, restore = False):
load_srv = rospy.ServiceProxy('pr2_controller_manager/load_controller', LoadController)
switch_srv = rospy.ServiceProxy('pr2_controller_manager/switch_controller', SwitchController)

print "Restore:", restore
print("Restore:", restore)
if restore:
originally = list_srv.call(ListControllersRequest())

resp = s.call(ReloadControllerLibrariesRequest(force_kill))
if resp.ok:
print "Successfully reloaded libraries"
print("Successfully reloaded libraries")
result = True
else:
print "Failed to reload libraries. Do you still have controllers loaded?"
print("Failed to reload libraries. Do you still have controllers loaded?")
result = False

if restore:
Expand All @@ -45,7 +45,7 @@ def reload_libraries(force_kill, restore = False):
switch_srv(start_controllers = to_start,
stop_controllers = [],
strictness = SwitchControllerRequest.BEST_EFFORT)
print "Controllers restored to original state"
print("Controllers restored to original state")
return result


Expand All @@ -54,31 +54,31 @@ def list_controllers():
s = rospy.ServiceProxy('pr2_controller_manager/list_controllers', ListControllers)
resp = s.call(ListControllersRequest())
if len(resp.controllers) == 0:
print "No controllers are loaded in mechanism control"
print("No controllers are loaded in mechanism control")
else:
for c, s in zip(resp.controllers, resp.state):
print c, "(",s,")"
print(c, "(",s,")")

def load_controller(name):
rospy.wait_for_service('pr2_controller_manager/load_controller')
s = rospy.ServiceProxy('pr2_controller_manager/load_controller', LoadController)
resp = s.call(LoadControllerRequest(name))
if resp.ok:
print "Loaded", name
print("Loaded", name)
return True
else:
print "Error when loading", name
print("Error when loading", name)
return False

def unload_controller(name):
rospy.wait_for_service('pr2_controller_manager/unload_controller')
s = rospy.ServiceProxy('pr2_controller_manager/unload_controller', UnloadController)
resp = s.call(UnloadControllerRequest(name))
if resp.ok == 1:
print "Unloaded %s successfully" % name
print("Unloaded %s successfully" % name)
return True
else:
print "Error when unloading", name
print("Error when unloading", name)
return False

def start_controller(name):
Expand Down Expand Up @@ -106,13 +106,13 @@ def start_stop_controllers(names, st):
resp = s.call(SwitchControllerRequest(start, stop, strictness))
if resp.ok == 1:
if st:
print "Started %s successfully" % names
print("Started %s successfully" % names)
else:
print "Stopped %s successfully" % names
print("Stopped %s successfully" % names)
return True
else:
if st:
print "Error when starting ", names
print("Error when starting ", names)
else:
print "Error when stopping ", names
print("Error when stopping ", names)
return False
8 changes: 4 additions & 4 deletions pr2_mechanism_diagnostics/test/mech_diag_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -86,20 +86,20 @@ def test_mech_diag(self):
self.assert_(not rospy.is_shutdown(), "Rospy shutdown")

with self._mutex:
if len(self._joints.items()) == 0:
if len(list(self._joints.items())) == 0:
self.assert_(False, "No joint data in diagnostics")
for key, val in self._joints.iteritems():
for key, val in self._joints.items():
if self._nan:
self.assert_(val.level == 2, "Joint %s was not ERROR, but was NaN. Level %d" % (val.name, val.level))
elif self._cal:
self.assert_(val.level == 0, "Joint %s was not OK. Level %d" % (val.name, val.level))
else:
self.assert_(val.level == 1, "Joint %s was not warning, but was uncalibrated. Level %d" % (val.name, val.level))

if len(self._controllers.items()) == 0:
if len(list(self._controllers.items())) == 0:
self.assert_(False, "No controller data in diagnostics")

for key, val in self._controllers.iteritems():
for key, val in self._controllers.items():
if self._overrun:
self.assert_(val.level == 1, "Controller %s was not WARN, but was overrun. Level %d" % (val.name, val.level))
else:
Expand Down