diff --git a/choreonoid_noetic.patch b/choreonoid_noetic.patch new file mode 100644 index 00000000..b381e508 --- /dev/null +++ b/choreonoid_noetic.patch @@ -0,0 +1,124 @@ +diff --git a/CMakeLists.txt b/CMakeLists.txt +index 504d56c7..8f22b7cc 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt +@@ -1,5 +1,6 @@ + cmake_minimum_required(VERSION 3.1.0) # Qt5 requies this version or later + ++ + cmake_policy(SET CMP0003 NEW) + cmake_policy(SET CMP0057 NEW) + set(CMAKE_ALLOW_LOOSE_LOOP_CONSTRUCTS true) +@@ -648,7 +649,9 @@ if(MSVC) + endif() + + # CORBA, omniORB +-option(ENABLE_CORBA "Enable CORBA related modules / plugins" OFF) ++# option(ENABLE_CORBA "Enable CORBA related modules / plugins" OFF) ++option(ENABLE_CORBA "Enable CORBA related modules / plugins" ON) ++option(BUILD_CORBA_PLUGIN "Build CORBA Plugin" ON) + + if(ENABLE_CORBA) + # The OMNIDYNAMIC_XXX variables are used for storing the omniORB information +@@ -904,6 +907,9 @@ if(ENABLE_CORBA) + endif(ENABLE_CORBA) + + # OpenRTM ++# option(BUILD_OPENRTM_PLUGIN "Building OpenRTMPlugin" OFF) ++option(BUILD_OPENRTM_PLUGIN "Building OpenRTMPlugin" ON) ++ + if(BUILD_OPENRTM_PLUGIN) + find_package(OpenRTM REQUIRED CONFIG) + +@@ -912,7 +918,7 @@ if(BUILD_OPENRTM_PLUGIN) + list(APPEND OPENRTM_DEFINITIONS -DOPENRTM_VERSION12) + list(APPEND OPENRTM_DEFINITIONS -Wno-deprecated) + +- elseif(OPENRTM_VERSION VERSION_EQUAL "1.1.2") ++ elseif(OPENRTM_VERSION VERSION_EQUAL "1.1.2" OR OPENRTM_VERSION STREQUAL "1.1.0") + list(APPEND OPENRTM_DEFINITIONS -DOPENRTM_VERSION11) + # Remove extra "-I" from the elements of OPENRTM_INCLUDE_DIRS + unset(include_dirs) +@@ -935,7 +941,8 @@ if(BUILD_OPENRTM_PLUGIN) + + set(IDL_INCLUDE_DIRS ${IDL_INCLUDE_DIRS} ${OPENRTM_INCLUDE_DIRS}) + +- option(USE_BUILTIN_CAMERA_IMAGE_IDL "Enable this option when you run hrpsys-base on Choreonoid" OFF) ++ # option(USE_BUILTIN_CAMERA_IMAGE_IDL "Enable this option when you run hrpsys-base on Choreonoid" OFF) ++ option(USE_BUILTIN_CAMERA_IMAGE_IDL "Enable this option when you run hrpsys-base on Choreonoid" ON) + if(USE_BUILTIN_CAMERA_IMAGE_IDL) + list(APPEND OPENRTM_DEFINITIONS -DUSE_BUILTIN_CAMERA_IMAGE_IDL) + else() +diff --git a/package.xml b/package.xml +index 5e1e1e32..ca8d0594 100644 +--- a/package.xml ++++ b/package.xml +@@ -1,6 +1,6 @@ + + +- ++ + + choreonoid + 1.7.0 +@@ -23,8 +23,9 @@ + yaml + zlib + libjpeg +- libpng12-dev ++ libpng-dev + assimp-dev ++ openrtm_aist + assimp + + qtbast5-dev +@@ -37,8 +38,10 @@ + libqt5-opengl + opengl + +- python +- python-numpy ++ python ++ python-numpy ++ python3 ++ python3-numpy + + libpulse-dev + libsndfile1-dev +diff --git a/sample/SpringModel/CMakeLists.txt b/sample/SpringModel/CMakeLists.txt +index b855a2e9..37fbd57a 100644 +--- a/sample/SpringModel/CMakeLists.txt ++++ b/sample/SpringModel/CMakeLists.txt +@@ -2,7 +2,8 @@ if(NOT ENABLE_GUI) + return() + endif() + +-option(BUILD_SPRING_MODEL_SAMPLE "Building a spring model sample" OFF) ++# option(BUILD_SPRING_MODEL_SAMPLE "Building a spring model sample" OFF) ++option(BUILD_SPRING_MODEL_SAMPLE "Building a spring model sample" ON) + if(NOT BUILD_SPRING_MODEL_SAMPLE) + return() + endif() +diff --git a/src/CorbaPlugin/CMakeLists.txt b/src/CorbaPlugin/CMakeLists.txt +index 4b39461b..5d42d51d 100644 +--- a/src/CorbaPlugin/CMakeLists.txt ++++ b/src/CorbaPlugin/CMakeLists.txt +@@ -2,7 +2,8 @@ + + #set(CMAKE_BUILD_TYPE Debug) + +-option(BUILD_CORBA_PLUGIN "Build CORBA Plugin" OFF) ++# option(BUILD_CORBA_PLUGIN "Build CORBA Plugin" OFF) ++option(BUILD_CORBA_PLUGIN "Build CORBA Plugin" ON) + + if(NOT BUILD_CORBA_PLUGIN) + return() +diff --git a/src/OpenRTM/CMakeLists.txt b/src/OpenRTM/CMakeLists.txt +index 7771c260..ac5fcdc8 100644 +--- a/src/OpenRTM/CMakeLists.txt ++++ b/src/OpenRTM/CMakeLists.txt +@@ -1,4 +1,3 @@ +-option(BUILD_OPENRTM_PLUGIN "Building OpenRTMPlugin" OFF) + if(NOT BUILD_OPENRTM_PLUGIN) + return() + elseif(NOT (ENABLE_CORBA AND BUILD_CORBA_PLUGIN)) diff --git a/hrpsys_choreonoid/launch/add_objects.py b/hrpsys_choreonoid/launch/add_objects.py index a03bb580..2916adc4 100644 --- a/hrpsys_choreonoid/launch/add_objects.py +++ b/hrpsys_choreonoid/launch/add_objects.py @@ -46,6 +46,8 @@ def parse_filename(filestr): pkgname = ret.group(1) #packagepath = commands.getoutput('rospack find %s'%(pkgname)) packagepath = subprocess.check_output(['rospack', 'find', pkgname]) + if sys.version_info >= (3,): + packagepath = packagepath.decode() packagepath = packagepath.rstrip('\n') filestr = filestr[:ret.start(0)] + packagepath + filestr[ret.end(0):] @@ -53,7 +55,7 @@ def parse_filename(filestr): try: f = open(objs_yaml, 'r') - dict_objs = yaml.load(f) + dict_objs = yaml.load(f, Loader=yaml.SafeLoader) f.close() except: print("can not read %s"%(objs_yaml), file=sys.stderr) diff --git a/hrpsys_choreonoid_tutorials/src/hrpsys_choreonoid_tutorials/choreonoid_hrpsys_config.py b/hrpsys_choreonoid_tutorials/src/hrpsys_choreonoid_tutorials/choreonoid_hrpsys_config.py index b629c26d..1c1990d7 100755 --- a/hrpsys_choreonoid_tutorials/src/hrpsys_choreonoid_tutorials/choreonoid_hrpsys_config.py +++ b/hrpsys_choreonoid_tutorials/src/hrpsys_choreonoid_tutorials/choreonoid_hrpsys_config.py @@ -31,15 +31,15 @@ def setupLogger(self, maxlen=15000): if self.abc: self.connectLoggerPort(self.abc, 'rfsensor') self.connectLoggerPort(self.abc, 'lfsensor') - for pn in filter (lambda x : re.match("Trans_", x), self.rh.ports.keys()): + for pn in [x for x in list(self.rh.ports.keys()) if re.match("Trans_", x)]: self.connectLoggerPort(self.rh, pn) ##self.connectLoggerPort(self.abc, 'rhsensor') ##self.connectLoggerPort(self.abc, 'lhsensor') def connectConstraintForceLoggerPorts(self): - for pn in filter (lambda x : re.match("T_", x), self.rh.ports.keys()): + for pn in [x for x in list(self.rh.ports.keys()) if re.match("T_", x)]: self.connectLoggerPort(self.rh, pn) - for pn in filter (lambda x : re.match("F_", x), self.rh.ports.keys()): + for pn in [x for x in list(self.rh.ports.keys()) if re.match("F_", x)]: self.connectLoggerPort(self.rh, pn) def init (self, robotname="Robot", url="", connect_constraint_force_logger_ports = False): diff --git a/hrpsys_ros_bridge_jvrc/scripts/gait_state_manager_node.py b/hrpsys_ros_bridge_jvrc/scripts/gait_state_manager_node.py index 190fcf86..472d2cc9 100755 --- a/hrpsys_ros_bridge_jvrc/scripts/gait_state_manager_node.py +++ b/hrpsys_ros_bridge_jvrc/scripts/gait_state_manager_node.py @@ -44,7 +44,7 @@ def __callGaitStateEvent(self, req): return hrpsys_ros_bridge_jvrc.srv.StringRequestResponse(result) def __change_state_cb(self, e): - print e + print(e) text = jsk_rviz_plugins.msg.OverlayText() text.text = 'GaitState: ' + e.dst text.top = 10 @@ -80,8 +80,8 @@ def flatten(nested_list): else: flat_list.append(node) return flat_list - tmp = flatten(self._map.values()) - return list(set(flatten([[i.keys() for i in tmp], [i.values() for i in tmp]]))) + tmp = flatten(list(self._map.values())) + return list(set(flatten([[list(i.keys()) for i in tmp], [list(i.values()) for i in tmp]]))) ## add_event def add_event(self, cfg): @@ -89,7 +89,7 @@ def add_event(self, cfg): callbacks = cfg['callbacks'] if 'callbacks' in cfg else {} tmap = self._map def add(e): - src = [e['src']] if isinstance(e['src'], basestring) else e['src'] + src = [e['src']] if (isinstance(e['src'], str) or isinstance(e['src'], unicode)) else e['src'] if e['name'] not in tmap: tmap[e['name']] = {} for s in src: diff --git a/hrpsys_ros_bridge_jvrc/scripts/rotate_range.py b/hrpsys_ros_bridge_jvrc/scripts/rotate_range.py index 3bc30bb8..f5a2c6f6 100755 --- a/hrpsys_ros_bridge_jvrc/scripts/rotate_range.py +++ b/hrpsys_ros_bridge_jvrc/scripts/rotate_range.py @@ -39,8 +39,8 @@ def callback (msg): sprox = rospy.ServiceProxy('/SequencePlayerServiceROSBridge/setInterpolationMode', hrpsys_ros_bridge.srv.OpenHRP_SequencePlayerService_setInterpolationMode) res = sprox(hrpsys_ros_bridge.msg.OpenHRP_SequencePlayerService_interpolationMode.LINEAR) - except rospy.ServiceException, e: - print "Service call failed: %s"%e + except rospy.ServiceException as e: + print("Service call failed: %s"%e) ### action rangeAct = actionlib.SimpleActionClient('/range_controller/follow_joint_trajectory_action', diff --git a/hrpsys_ros_bridge_jvrc/scripts/walking.py b/hrpsys_ros_bridge_jvrc/scripts/walking.py index 7ff96be6..90842777 100755 --- a/hrpsys_ros_bridge_jvrc/scripts/walking.py +++ b/hrpsys_ros_bridge_jvrc/scripts/walking.py @@ -46,10 +46,10 @@ def g(x,y,r): hcf.abc_svc.goPos(x, y, r) hcf.abc_svc.waitFootSteps() def h(): - print "funcs, d()=default_mode, s()=speedup_mode, g(x, y, r)=go_pos" + print("funcs, d()=default_mode, s()=speedup_mode, g(x, y, r)=go_pos") def m(): - print "funcs, d()=default_mode, s()=speedup_mode, g(x, y, r)=go_pos" + print("funcs, d()=default_mode, s()=speedup_mode, g(x, y, r)=go_pos") def dor(): doa() # copy from hrpsys/lib/python2.7/dist-packages/hrpsys_config.py @@ -83,9 +83,9 @@ def dor(): hcf.waitForRTCManagerAndRoboHardware(robotname=sys.argv[1]) sys.argv = [sys.argv[0]] + sys.argv[2:] hcf.findComps() - print >> sys.stderr, "[hrpsys.py] #\n[hrpsys.py] # use `hcf` as robot interface, for example hcf.getJointAngles()\n[hrpsys.py] #" + print("[hrpsys.py] #\n[hrpsys.py] # use `hcf` as robot interface, for example hcf.getJointAngles()\n[hrpsys.py] #", file=sys.stderr) while args.c != None: - print >> sys.stderr, ">>", args.c[0] + print(">>", args.c[0], file=sys.stderr) exec(args.c[0]) args.c.pop(0) hcf.startStabilizer()