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

fix for ROS noteic #1331

Open
wants to merge 27 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
27 commits
Select commit Hold shift + click to select a range
1c88646
add setup.py, add catkin_package_setup(), use sysconfig.get_config_va…
k-okada Apr 2, 2024
08fe721
mv python -> src/hrpsys for setup.py
k-okada Apr 2, 2024
733433b
CMakeLists.txt: rename add_subdirectory(python) -> add_subdirectory(s…
k-okada Apr 2, 2024
4d88f4e
doc/CMakeLists.txt: avoid target named doc
k-okada Apr 2, 2024
d50a65a
apply 2to3 -w -f print
k-okada Apr 2, 2024
fdec77d
util:simulator/CMakeLists.txt: force link to python38
k-okada Apr 2, 2024
ecfefb9
fix for absolute/relative import for Python3
k-okada Apr 2, 2024
d9ab678
fix for python3 unicode?
k-okada Apr 2, 2024
a7ace0e
hrpsys_config.py: return list, not filter
k-okada Apr 2, 2024
a19fc79
CMakeLists.txt: test subdirectory does not have CMakeLists.txt
k-okada Apr 2, 2024
5f642a1
apply 2to3 -f print in sample, util directory
kirohy Apr 4, 2024
e32eea5
apply 2to3 -f filter in sample directory and hrpsys_config.py
kirohy Apr 4, 2024
6fabc21
apply 2to3 -f map in sample directory, hrpsys_config.py
kirohy Apr 4, 2024
396d634
apply 2to3 -f reduce
kirohy Apr 4, 2024
a8e5417
remove double parentheses in print function
kirohy Apr 4, 2024
601e8f8
apply 2to3 -f execfile
kirohy Apr 4, 2024
eeb22cd
apply 2to3 -f raw_input
kirohy Apr 4, 2024
acca372
apply 2to3 -f raise
kirohy Apr 4, 2024
f1ea180
manually replace filter function, 2to3 could not resolve
kirohy Apr 4, 2024
2e91c25
fix string and byte error
kirohy Apr 4, 2024
50ecb22
fix converting range to list
kirohy Apr 4, 2024
8e9e6c3
use packaging instead of distutils
kirohy Apr 11, 2024
6502712
fix invalid return value in KalmanFilter
kirohy Apr 11, 2024
ae93748
python2 python3 compatible for input() function
kirohy Jun 13, 2024
bca7932
python2 python3 compatible for parsing hrpsys_version
kirohy Jun 14, 2024
67f4fc2
python2 python3 compatible for boost-python
kirohy Jun 14, 2024
ae40b59
Merge pull request #4 from kirohy/fix_20.04
k-okada Jun 26, 2024
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
8 changes: 3 additions & 5 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,7 @@ if(USE_HRPSYSUTIL AND APPLE AND NOT PCL_FOUND)
endif()

execute_process(
COMMAND python -c "from distutils import sysconfig; print sysconfig.get_config_var(\"VERSION\")"
COMMAND python -c "import sys; print(sys.version_info[0])"
OUTPUT_VARIABLE PYTHON_VERSION
RESULT_VARIABLE PYTHON_VERSION_SUCCESS
OUTPUT_STRIP_TRAILING_WHITESPACE)
Expand Down Expand Up @@ -204,7 +204,7 @@ message(STATUS "compile iob with -DROBOT_IOB_VERSION=${ROBOT_IOB_VERSION}")
if(COMPILE_JAVA_STUFF)
add_subdirectory(jython)
endif()
add_subdirectory(python)
add_subdirectory(src/hrpsys) # for doc/html/index.html
add_subdirectory(idl)
add_subdirectory(lib)
add_subdirectory(ec)
Expand All @@ -217,14 +217,12 @@ if (NOT QNXNTO)
add_subdirectory(util)
endif()
add_subdirectory(sample)
if(CATKIN_ENABLE_TESTING)
add_subdirectory(test)
endif()

#if catkin environment
string(REGEX MATCH "catkin" need_catkin "$ENV{_}")
if(need_catkin OR "${CATKIN_BUILD_BINARY_PACKAGE}")
find_package(catkin)
catkin_python_setup()
if(catkin_FOUND)
catkin_package_xml()
if(NOT hrpsys_VERSION VERSION_EQUAL CPACK_PACKAGE_VERSION)
Expand Down
8 changes: 4 additions & 4 deletions doc/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
set(input_files package.h utilities.h
../python/hrpsys_config.py
../python/rtm.py
../src/hrpsys/hrpsys_config.py
../src/hrpsys/rtm.py
../rtc/ApproximateVoxelGridFilter/ApproximateVoxelGridFilter.txt
../rtc/CameraImageViewer/CameraImageViewer.txt
../rtc/CameraImageSaver/CameraImageSaver.txt
Expand Down Expand Up @@ -70,8 +70,8 @@ add_custom_command(
DEPENDS ${CMAKE_CURRENT_BINARY_DIR}/Doxyfile ${input_files}
)

add_custom_target(doc ALL DEPENDS ${output_dir}/index.html)
add_custom_target(doc ALL DEPENDS ${output_dir_xml}/index.xml)
add_custom_target(doc_index_html ALL DEPENDS ${output_dir}/index.html)
add_custom_target(doc_index_xml ALL DEPENDS ${output_dir_xml}/index.xml)

install(DIRECTORY ${output_dir} DESTINATION share/doc/hrpsys/base)
install(DIRECTORY ${output_dir_xml} DESTINATION share/doc/hrpsys/base)
Expand Down
2 changes: 1 addition & 1 deletion jython/poseEditor.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ def __init__(self, url, seq, sh):
for li in self.bodyInfo.links():
if li.jointId >= 0:
self.dof += 1
print "dof=",self.dof
print("dof=",self.dof)
self.setSize(550, 800)
self.seq = seq
self.sh = sh
Expand Down
40 changes: 20 additions & 20 deletions jython/rtm.py
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ def getProperty(self, name):
cfg = self.ref.get_configuration()
cfgsets = cfg.get_configuration_sets()
if len(cfgsets) == 0:
print "configuration set is not found"
print("configuration set is not found")
return None
cfgset = cfgsets[0]
for d in cfgset.configuration_data:
Expand All @@ -108,11 +108,11 @@ def properties(self):
cfg = self.ref.get_configuration()
cfgsets = cfg.get_configuration_sets()
if len(cfgsets) == 0:
print "configuration set is not found"
print("configuration set is not found")
return
cfgset = cfgsets[0]
for d in cfgset.configuration_data:
print d.name,":",d.value.extract_string()
print(d.name,":",d.value.extract_string())


##
Expand Down Expand Up @@ -204,7 +204,7 @@ def load(self, basename):
try:
self.ref.load_module(path, initfunc)
except:
print "failed to load",path
print("failed to load",path)

##
# \brief create an instance of RT component
Expand All @@ -216,7 +216,7 @@ def create(self, module,name=None):
if name != None:
rtc = findRTC(name)
if rtc != None:
print 'RTC named "',name,'" already exists.'
print('RTC named "',name,'" already exists.')
return rtc
args = module
if name != None:
Expand Down Expand Up @@ -277,7 +277,7 @@ def initCORBA():
nshost = System.getProperty("NS_OPT").split(':')[2]
if nshost == "localhost" or nshost == "127.0.0.1":
nshost = socket.gethostname()
print 'nshost =',nshost
print('nshost =',nshost)
orb = ORB.init(args, props)

nameserver = orb.resolve_initial_references("NameService");
Expand Down Expand Up @@ -330,7 +330,7 @@ def findRTCmanager(hostname=None, rnc=None):
obj = findObject("manager","mgr",cxt)
return RTCmanager(ManagerHelper.narrow(obj))
except:
print "exception in findRTCmanager("+hostname+")"
print("exception in findRTCmanager("+hostname+")")

##
# \brief get RT component
Expand Down Expand Up @@ -381,9 +381,9 @@ def serializeComponents(rtcs, stopEC=True):
if ec.add_component(rtc.ref) == ReturnCode_t.RTC_OK:
rtc.ec = ec
else:
print 'error in add_component()'
print('error in add_component()')
else:
print 'already serialized'
print('already serialized')

##
# \brief check two ports are connected or not
Expand Down Expand Up @@ -435,10 +435,10 @@ def connectPorts(outP, inPs, subscription="flush", dataflow="Push", bufferlength
inPs = [inPs]
for inP in inPs:
if isConnected(outP, inP) == True:
print outP.get_port_profile().name,'and',inP.get_port_profile().name,'are already connected'
print(outP.get_port_profile().name,'and',inP.get_port_profile().name,'are already connected')
continue
if dataTypeOfPort(outP) != dataTypeOfPort(inP):
print outP.get_port_profile().name,'and',inP.get_port_profile().name,'have different data types'
print(outP.get_port_profile().name,'and',inP.get_port_profile().name,'have different data types')
continue

con_prof = ConnectorProfile()
Expand Down Expand Up @@ -480,11 +480,11 @@ def connectPorts(outP, inPs, subscription="flush", dataflow="Push", bufferlength
con_prof_holder = ConnectorProfileHolder()
con_prof_holder.value = con_prof
if inP.connect(con_prof_holder) != ReturnCode_t.RTC_OK:
print "failed to connect(",outP.get_port_profile().name,'<->',inP.get_port_profile().name,")"
print("failed to connect(",outP.get_port_profile().name,'<->',inP.get_port_profile().name,")")
continue
# confirm connection
if isConnected(outP, inP) == False:
print "connet() returned RTC_OK, but not connected"
print("connet() returned RTC_OK, but not connected")

##
# \brief convert data into CDR format
Expand Down Expand Up @@ -551,7 +551,7 @@ def writeDataPort(port, data, tm=1.0):
con_prof_holder = ConnectorProfileHolder()
con_prof_holder.value = con_prof
if port.connect(con_prof_holder) != ReturnCode_t.RTC_OK:
print "failed to connect"
print("failed to connect")
return None
for p in con_prof_holder.value.properties:
if p.name == 'dataport.corba_cdr.inport_ior':
Expand All @@ -560,7 +560,7 @@ def writeDataPort(port, data, tm=1.0):
inport = InPortCdrHelper.narrow(obj)
cdr = data2cdr(data)
if inport.put(cdr) != PortStatus.PORT_OK:
print "failed to put"
print("failed to put")
time.sleep(tm)
port.disconnect(con_prof_holder.value.connector_id)
return None
Expand Down Expand Up @@ -604,7 +604,7 @@ def readDataPort(port, timeout = 1.0):
con_prof_holder = ConnectorProfileHolder()
con_prof_holder.value = con_prof
if port.connect(con_prof_holder) != ReturnCode_t.RTC_OK:
print "failed to connect"
print("failed to connect")
return None
for p in con_prof_holder.value.properties:
#print p.name
Expand Down Expand Up @@ -646,7 +646,7 @@ def findService(rtc, port_name, type_name, instance_name):
else:
p = rtc.port(port_name)
if p == None:
print "can't find a port named",port_name
print("can't find a port named",port_name)
return None
else:
port_prof = [p.get_port_profile()]
Expand All @@ -660,7 +660,7 @@ def findService(rtc, port_name, type_name, instance_name):
if aif.instance_name == instance_name and (type_name == "" or aif.type_name == type_name):
port = pp.port_ref
if port == None:
print "can't find a service named",instance_name
print("can't find a service named",instance_name)
return None
#print port
con_prof = ConnectorProfile()
Expand All @@ -684,7 +684,7 @@ def setConfiguration(rtc, nvlist):
cfg = rtc.get_configuration()
cfgsets = cfg.get_configuration_sets()
if len(cfgsets) == 0:
print "configuration set is not found"
print("configuration set is not found")
return
cfgset = cfgsets[0]
for nv in nvlist:
Expand All @@ -698,7 +698,7 @@ def setConfiguration(rtc, nvlist):
found = True
break;
if not found:
print "no such property(",name,")"
print("no such property(",name,")")
cfg.activate_configuration_set('default')

##
Expand Down
4 changes: 2 additions & 2 deletions jython/waitInput.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ def waitInputConfirm(msg):
ret = JOptionPane.showConfirmDialog(f, msg, "waitInputConfirm",
JOptionPane.OK_CANCEL_OPTION)
if ret == 2:
raise StandardError, "script is canceled"
raise Exception("script is canceled")
return True

def waitInputSelect(msg):
Expand All @@ -29,7 +29,7 @@ def waitInputSelect(msg):
elif ret == 1:
return False
elif ret == 2:
raise StandardError, "script is canceled"
raise Exception("script is canceled")

class posFilter(FileFilter):
def accept(self, f):
Expand Down
8 changes: 4 additions & 4 deletions launch/samplerobot-terrain-walk.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,8 @@
samplerobot_terrain_walk.demo()
import sys
if len(sys.argv) != 2:
print "Usage:"
print " ",sys.argv[0]," --StairUp or --StairDown or --SlopeUpDown"
print("Usage:")
print(" ",sys.argv[0]," --StairUp or --StairDown or --SlopeUpDown")
else:
if sys.argv[1] == "--StairUp":
samplerobot_terrain_walk.demoStairUp()
Expand All @@ -38,8 +38,8 @@
elif sys.argv[1] == "--SlopeUpDown":
samplerobot_terrain_walk.demoSlopeUpDown()
else:
print "Usage:"
print " ",sys.argv[0]," --StairUp or --StairDown or --SlopeUpDown"
print("Usage:")
print(" ",sys.argv[0]," --StairUp or --StairDown or --SlopeUpDown")


## IGNORE ME: this code used for rostest
Expand Down
22 changes: 12 additions & 10 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<package>
<package format="3">
<name>hrpsys</name>
<version>315.15.0</version>
<description>
Expand Down Expand Up @@ -42,15 +42,17 @@
<build_depend>python-tk</build_depend>
<build_depend>sdl</build_depend>

<run_depend>cv_bridge</run_depend>
<run_depend>glut</run_depend>
<run_depend>libirrlicht-dev</run_depend>
<run_depend>libqhull</run_depend>
<run_depend>libxml2</run_depend>
<run_depend>libxmu-dev</run_depend>
<run_depend>openhrp3</run_depend>
<run_depend>python-tk</run_depend>
<run_depend>sdl</run_depend>
<exec_depend>cv_bridge</exec_depend>
<exec_depend>glut</exec_depend>
<exec_depend>libirrlicht-dev</exec_depend>
<exec_depend>libqhull</exec_depend>
<exec_depend>libxml2</exec_depend>
<exec_depend>libxmu-dev</exec_depend>
<exec_depend>openhrp3</exec_depend>
<exec_depend>python-tk</exec_depend>
<exec_depend>sdl</exec_depend>
<exec_depend condition="$ROS_PYTHON_VERSION == 2">python-packaging</exec_depend>
<exec_depend condition="$ROS_PYTHON_VERSION == 3">python3-packaging</exec_depend>

<!-- <test_depend>openhrp3</test_depend> -->
<export>
Expand Down
1 change: 1 addition & 0 deletions rtc/KalmanFilter/KalmanFilter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -311,6 +311,7 @@ bool KalmanFilter::resetKalmanFilterState()
{
rpy_kf.resetKalmanFilterState();
ekf_filter.resetKalmanFilterState();
return true;
};

bool KalmanFilter::getKalmanFilterParam(OpenHRP::KalmanFilterService::KalmanFilterParam& i_param)
Expand Down
8 changes: 4 additions & 4 deletions rtc/OccupancyGridMap3D/sample/sample.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,12 +16,12 @@
aabb.size.w = 4.0
aabb.size.h = 0.1
map = ogm_svc.getOGMap3D(aabb)
print "resolution = ",map.resolution
print "number of voxels = ",map.nx,"x",map.ny,"x",map.nz
print("resolution = ",map.resolution)
print("number of voxels = ",map.nx,"x",map.ny,"x",map.nz)
for x in range(map.nx):
for y in range(map.ny):
for z in range(map.nz):
print map.cells[x*map.ny*map.nz+y*map.nz+z],
print
print(map.cells[x*map.ny*map.nz+y*map.nz+z], end=' ')
print()


8 changes: 4 additions & 4 deletions sample/HRP4C/HRP4C.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,15 +29,15 @@ def init():

ms = rtm.findRTCmanager()

print "creating components"
print("creating components")
createComps()

print "connecting components"
print("connecting components")
connectComps()

print "activating components"
print("activating components")
activateComps()
print "initialized successfully"
print("initialized successfully")

def loadPattern(basename, tm=1.0):
seq_svc.loadPattern(basename, tm)
Expand Down
8 changes: 4 additions & 4 deletions sample/PA10/PA10.py
Original file line number Diff line number Diff line change
Expand Up @@ -58,15 +58,15 @@ def init():

ms = rtm.findRTCmanager()

print "creating components"
print("creating components")
createComps()

print "connecting components"
print("connecting components")
connectComps()

print "activating components"
print("activating components")
activateComps()
print "initialized successfully"
print("initialized successfully")

def goInitial(tm=3.0):
seq_svc.setJointAngles([0]*9, tm)
Expand Down
Loading