From 0c1bf094100e604a2fd60118dc1635e498e77547 Mon Sep 17 00:00:00 2001 From: Ed Schmerling Date: Sat, 20 Apr 2019 01:19:16 -0700 Subject: [PATCH 1/2] Changes for PyCall API update getindex -> getproperty; fix #67 --- REQUIRE | 2 +- docs/src/index.md | 4 +-- src/RobotOS.jl | 6 ++--- src/callbacks.jl | 8 +++--- src/gentypes.jl | 58 +++++++++++++++++++++++++----------------- src/pubsub.jl | 8 +++--- src/rospy.jl | 40 ++++++++++++++--------------- src/services.jl | 10 ++++---- src/time.jl | 12 ++++----- test/time.jl | 12 ++++----- test/typegeneration.jl | 14 +++++----- 11 files changed, 92 insertions(+), 82 deletions(-) diff --git a/REQUIRE b/REQUIRE index 42c61d7..6e70cf3 100644 --- a/REQUIRE +++ b/REQUIRE @@ -1,2 +1,2 @@ julia 0.7 -PyCall 1.17.1 +PyCall 1.90.0 diff --git a/docs/src/index.md b/docs/src/index.md index 3ad7959..3aa7b8c 100644 --- a/docs/src/index.md +++ b/docs/src/index.md @@ -175,12 +175,12 @@ if `myproxy` is a `ServiceProxy` object, it can be called with in the `RobotOS` module with the same syntax as in rospy. ### Message Constants -Message constants may be accessed using `getindex` syntax. For example for +Message constants may be accessed using `getproperty` syntax. For example for [visualization_msgs/Marker.msg](http://docs.ros.org/api/visualization_msgs/html/msg/Marker.html) we have: import .visualization_msgs.msg: Marker - Marker[:SPHERE] == getindex(Marker, :SPHERE) == 2 # true + Marker.SPHERE == getproperty(Marker, :SPHERE) == 2 # true ## ROS Integration diff --git a/src/RobotOS.jl b/src/RobotOS.jl index 88f8c11..fc79633 100644 --- a/src/RobotOS.jl +++ b/src/RobotOS.jl @@ -18,11 +18,11 @@ include("callbacks.jl") function __init__() #Put julia's ARGS into python's so remappings will work copy!(_py_sys, pyimport("sys")) - _py_sys["argv"] = ARGS + _py_sys."argv" = ARGS #Fill in empty PyObjects - if ! (dirname(@__FILE__) in _py_sys["path"]) - pushfirst!(_py_sys["path"], dirname(@__FILE__)) + if ! (dirname(@__FILE__) in _py_sys."path") + pushfirst!(_py_sys."path", dirname(@__FILE__)) end copy!(_py_ros_callbacks, pyimport("ros_callbacks")) diff --git a/src/callbacks.jl b/src/callbacks.jl index 3cc5c86..e1871e7 100644 --- a/src/callbacks.jl +++ b/src/callbacks.jl @@ -18,8 +18,8 @@ function _callback_async_loop(rosobj, cond) end function _run_callbacks(sub::Subscriber{M}) where M - while pycall(sub.queue["size"], PyAny) > 0 - msg = pycall(sub.queue["get"], PyObject) + while pycall(sub.queue."size", PyAny) > 0 + msg = pycall(sub.queue."get", PyObject) sub.callback(convert(M, msg), sub.callback_args...) end end @@ -27,9 +27,9 @@ end function _run_callbacks(srv::Service{T}) where T ReqType = _srv_reqtype(T) - req = pycall(srv.cb_interface["get_request"], PyObject) + req = pycall(srv.cb_interface."get_request", PyObject) response = srv.handler(convert(ReqType, req)) #Python callback is blocking until the response is ready - pycall(srv.cb_interface["set_response"], PyAny, convert(PyObject, response)) + pycall(srv.cb_interface."set_response", PyAny, convert(PyObject, response)) end diff --git a/src/gentypes.jl b/src/gentypes.jl index 16d959b..c3b2213 100644 --- a/src/gentypes.jl +++ b/src/gentypes.jl @@ -183,7 +183,7 @@ function addtype!(mod::ROSMsgModule, typ::String) end pymod, pyobj = _pyvars(_fullname(mod), typ) - deptypes = pyobj[:_slot_types] + deptypes = pyobj._slot_types _importdeps!(mod, deptypes) push!(mod.members, typ) @@ -199,15 +199,15 @@ function addtype!(mod::ROSSrvModule, typ::String) @debug("Service type import: ", _fullname(mod), ".", typ) pymod, pyobj = _pyvars(_fullname(mod), typ) - if ! haskey(pyobj, "_request_class") + if ! PyCall.hasproperty(pyobj, "_request_class") error(string("Incorrect service name: ", typ)) end #Immediately import dependencies from the Request/Response classes #Repeats are OK - req_obj = pymod[string(typ,"Request")] - resp_obj = pymod[string(typ,"Response")] - deptypes = [req_obj[:_slot_types]; resp_obj[:_slot_types]] + req_obj = getproperty(pymod, string(typ,"Request")) + resp_obj = getproperty(pymod, string(typ,"Response")) + deptypes = [req_obj._slot_types; resp_obj._slot_types] _importdeps!(mod, deptypes) push!(mod.members, typ) @@ -222,7 +222,7 @@ end function _pyvars(modname::String, typ::String) pymod = _import_rospy_pkg(modname) pyobj = - try pymod[typ] + try getproperty(pymod, typ) catch ex isa(ex, KeyError) || rethrow(ex) error("Message type '$typ' not found in ROS package '$modname', ", @@ -269,7 +269,7 @@ function _import_rospy_pkg(package::String) _rospy_modules[package] = pyimport(package) catch ex show(ex) - error("python import error: $(ex.val[:args][1])") + error("python import error: $(ex.val.args[1])") end end _rospy_modules[package] @@ -324,7 +324,7 @@ function modulecode(mod::ROSModule, rosrootmod::Module) push!(modcode, quote using PyCall - import Base: convert, getindex + import Base: convert, getproperty import RobotOS import RobotOS.Time import RobotOS.Duration @@ -390,8 +390,8 @@ function buildtype(mod::ROSMsgModule, typename::String) global _rospy_objects fulltypestr = _rostypestr(mod, typename) pyobj = _rospy_objects[fulltypestr] - memnames = pyobj[:__slots__] - memtypes = pyobj[:_slot_types] + memnames = pyobj.__slots__ + memtypes = pyobj._slot_types members = collect(zip(memnames, memtypes)) typecode(fulltypestr, :AbstractMsg, members) @@ -404,16 +404,16 @@ function buildtype(mod::ROSSrvModule, typename::String) req_typestr = _rostypestr(mod, string(typename,"Request")) reqobj = _rospy_objects[req_typestr] - memnames = reqobj[:__slots__] - memtypes = reqobj[:_slot_types] + memnames = reqobj.__slots__ + memtypes = reqobj._slot_types reqmems = collect(zip(memnames, memtypes)) pyreq = :(RobotOS._rospy_objects[$req_typestr]) reqexprs = typecode(req_typestr, :AbstractSrv, reqmems) resp_typestr = _rostypestr(mod, string(typename,"Response")) respobj = _rospy_objects[resp_typestr] - memnames = respobj[:__slots__] - memtypes = respobj[:_slot_types] + memnames = respobj.__slots__ + memtypes = respobj._slot_types respmems = collect(zip(memnames, memtypes)) pyresp = :(RobotOS._rospy_objects[$resp_typestr]) respexprs = typecode(resp_typestr, :AbstractSrv, respmems) @@ -436,7 +436,7 @@ end # (2) Default outer constructer with no arguments # (3) convert(PyObject, ...) # (4) convert(..., o::PyObject) -# (5) getindex for accessing member constants +# (5) getproperty for accessing member constants function typecode(rosname::String, super::Symbol, members::Vector) tname = _splittypestr(rosname)[2] @debug("Type: ", tname) @@ -477,7 +477,7 @@ function typecode(rosname::String, super::Symbol, members::Vector) #(4) Convert from PyObject push!(exprs, :( function convert(jlt::Type{$jlsym}, o::PyObject) - if convert(String, o["_type"]) != _typerepr(jlt) + if convert(String, o."_type") != _typerepr(jlt) throw(InexactError(:convert, $jlsym, o)) end jl = $jlsym() @@ -485,9 +485,19 @@ function typecode(rosname::String, super::Symbol, members::Vector) jl end )) - #(5) Accessing member variables through getindex + #(5) Accessing member variables through getproperty push!(exprs, :( - getindex(::Type{$jlsym}, s::Symbol) = RobotOS._rospy_objects[$rosname][s] + function getproperty(::Type{$jlsym}, s::Symbol) + try getproperty(RobotOS._rospy_objects[$rosname], s) + catch ex + isa(ex, KeyError) || rethrow(ex) + try getfield($jlsym, s) + catch ex2 + startswith(ex2.msg, "type DataType has no field") || rethrow(ex2) + error("Message type '" * $("$jlsym") * "' has no property '$s'.") + end + end + end )) #Now add the meat to the empty expressions above @@ -534,25 +544,25 @@ function _addtypemember!(exprs, namestr, typestr) if arraylen >= 0 memexpr = :($namesym::Array{$j_typ,1}) defexpr = :([$j_def for i = 1:$arraylen]) - jlconexpr = :(jl.$namesym = convert(Array{$j_typ,1}, o[$namestr])) + jlconexpr = :(jl.$namesym = convert(Array{$j_typ,1}, o.$namestr)) #uint8[] is string in rospy and PyCall's conversion to bytearray is #rejected by ROS if j_typ == :UInt8 - pyconexpr = :(py[$namestr] = + pyconexpr = :(py.$namestr = pycall(pybuiltin("str"), PyObject, PyObject(o.$namesym)) ) elseif _isrostype(typestr) - pyconexpr = :(py[$namestr] = + pyconexpr = :(py.$namestr = convert(Array{PyObject,1}, o.$namesym)) else - pyconexpr = :(py[$namestr] = o.$namesym) + pyconexpr = :(py.$namestr = o.$namesym) end else memexpr = :($namesym::$j_typ) defexpr = j_def - jlconexpr = :(jl.$namesym = convert($j_typ, o[$namestr])) - pyconexpr = :(py[$namestr] = convert(PyObject, o.$namesym)) + jlconexpr = :(jl.$namesym = convert($j_typ, o.$namestr)) + pyconexpr = :(py.$namestr = convert(PyObject, o.$namesym)) end push!(typeargs, memexpr) insert!(jlconargs, length(jlconargs), jlconexpr) diff --git a/src/pubsub.jl b/src/pubsub.jl index 3e11e07..2237b5c 100644 --- a/src/pubsub.jl +++ b/src/pubsub.jl @@ -14,7 +14,7 @@ struct Publisher{MsgType<:AbstractMsg} function Publisher{MT}(topic::AbstractString; kwargs...) where MT <: AbstractMsg @debug("Creating <$(string(MT))> publisher on topic: '$topic'") rospycls = _get_rospy_class(MT) - return new{MT}(__rospy__[:Publisher](ascii(topic), rospycls; kwargs...)) + return new{MT}(__rospy__.Publisher(ascii(topic), rospycls; kwargs...)) end end @@ -27,7 +27,7 @@ Publisher(topic::AbstractString, ::Type{MT}; kwargs...) where {MT <: AbstractMsg Publish `msg` on `p`, a `Publisher` with matching message type. """ function publish(p::Publisher{MT}, msg::MT) where MT <: AbstractMsg - pycall(p.o["publish"], PyAny, convert(PyObject, msg)) + pycall(p.o."publish", PyAny, convert(PyObject, msg)) end """ @@ -52,8 +52,8 @@ mutable struct Subscriber{MsgType<:AbstractMsg} rospycls = _get_rospy_class(MT) cond = Base.AsyncCondition() - mqueue = _py_ros_callbacks["MessageQueue"](CB_NOTIFY_PTR[], cond.handle) - subobj = __rospy__[:Subscriber](ascii(topic), rospycls, mqueue["storemsg"]; kwargs...) + mqueue = _py_ros_callbacks."MessageQueue"(CB_NOTIFY_PTR[], cond.handle) + subobj = __rospy__.Subscriber(ascii(topic), rospycls, mqueue."storemsg"; kwargs...) rosobj = new{MT}(cb, cb_args, subobj, mqueue) cbloop = Task(() -> _callback_async_loop(rosobj, cond)) diff --git a/src/rospy.jl b/src/rospy.jl index 4154b06..c3dd9c5 100644 --- a/src/rospy.jl +++ b/src/rospy.jl @@ -10,17 +10,17 @@ Initialize this node, registering it with the ROS master. All arguments are pass the rospy init_node function. """ init_node(name::AbstractString; args...) = - __rospy__[:init_node](ascii(name); args...) + __rospy__.init_node(ascii(name); args...) """ is_shutdown() Return the shutdown status of the node. """ -is_shutdown() = __rospy__[:is_shutdown]() +is_shutdown() = __rospy__.is_shutdown() -get_published_topics() = __rospy__[:get_published_topics]() -get_ros_root() = __rospy__[:get_ros_root]() +get_published_topics() = __rospy__.get_published_topics() +get_ros_root() = __rospy__.get_ros_root() """ spin() @@ -45,9 +45,9 @@ default is given, throws a `KeyError` if the parameter cannot be found. function get_param(param_name::AbstractString, def=nothing) try if def == nothing - __rospy__[:get_param](ascii(param_name)) + __rospy__.get_param(ascii(param_name)) else - __rospy__[:get_param](ascii(param_name), def) + __rospy__.get_param(ascii(param_name), def) end catch ex throw(KeyError(pycall(pybuiltin("str"), PyAny, ex.val)[2:end-1])) @@ -60,7 +60,7 @@ end Set the value of a parameter on the parameter server. """ set_param(param_name::AbstractString, val) = - __rospy__[:set_param](ascii(param_name), val) + __rospy__.set_param(ascii(param_name), val) """ has_param(param_name) @@ -68,7 +68,7 @@ set_param(param_name::AbstractString, val) = Return a boolean specifying if a parameter exists on the parameter server. """ has_param(param_name::AbstractString) = - __rospy__[:has_param](ascii(param_name)) + __rospy__.has_param(ascii(param_name)) """ delete_param(param_name) @@ -77,7 +77,7 @@ Delete a parameter from the parameter server. Throws a `KeyError` if no such par """ function delete_param(param_name::AbstractString) try - __rospy__[:delete_param](ascii(param_name)) + __rospy__.delete_param(ascii(param_name)) catch ex throw(KeyError(pycall(pybuiltin("str"), PyAny, ex.val)[2:end-1])) end @@ -85,15 +85,15 @@ end #Doesn't work for some reason #rospy_search_param(param_name::AbstractString) = -# __rospy__[:rospy_search_param](ascii(param_name)) -get_param_names() = __rospy__[:get_param_names]() +# __rospy__.rospy_search_param(ascii(param_name)) +get_param_names() = __rospy__.get_param_names() #Logging API -logdebug(msg, args...) = __rospy__[:logdebug](msg, args...) -loginfo(msg, args...) = __rospy__[:loginfo](msg, args...) -logwarn(msg, args...) = __rospy__[:logwarn](msg, args...) -logerr(msg, args...) = __rospy__[:logerr](msg, args...) -logfatal(msg, args...) = __rospy__[:logfatal](msg, args...) +logdebug(msg, args...) = __rospy__.logdebug(msg, args...) +loginfo(msg, args...) = __rospy__.loginfo(msg, args...) +logwarn(msg, args...) = __rospy__.logwarn(msg, args...) +logerr(msg, args...) = __rospy__.logerr(msg, args...) +logfatal(msg, args...) = __rospy__.logfatal(msg, args...) """ logdebug, loginfo, logwarn, logerr, logfatal @@ -104,7 +104,7 @@ arguments directly. logdebug, loginfo, logwarn, logerr, logfatal #Node information -get_name() = __rospy__[:get_name]() -get_namespace() = __rospy__[:get_namespace]() -get_node_uri() = __rospy__[:get_node_uri]() -get_caller_id() = __rospy__[:get_caller_id]() +get_name() = __rospy__.get_name() +get_namespace() = __rospy__.get_namespace() +get_node_uri() = __rospy__.get_node_uri() +get_caller_id() = __rospy__.get_caller_id() diff --git a/src/services.jl b/src/services.jl index 1aab115..a682bf8 100644 --- a/src/services.jl +++ b/src/services.jl @@ -14,7 +14,7 @@ struct ServiceProxy{SrvType <: AbstractService} function ServiceProxy{ST}(name::AbstractString; kwargs...) where ST <: AbstractService @debug("Creating <$ST> service proxy for '$name'") rospycls = _get_rospy_class(ST) - new{ST}(__rospy__[:ServiceProxy](ascii(name), rospycls; kwargs...)) + new{ST}(__rospy__.ServiceProxy(ascii(name), rospycls; kwargs...)) end end @@ -51,13 +51,13 @@ mutable struct Service{SrvType <: AbstractService} rospycls = _get_rospy_class(ST) cond = Base.AsyncCondition() - pysrv = _py_ros_callbacks["ServiceCallback"](CB_NOTIFY_PTR[], cond.handle) + pysrv = _py_ros_callbacks."ServiceCallback"(CB_NOTIFY_PTR[], cond.handle) srvobj = try - __rospy__[:Service](ascii(name), rospycls, pysrv["srv_cb"]; kwargs...) + __rospy__.Service(ascii(name), rospycls, pysrv."srv_cb"; kwargs...) catch err if isa(err, PyCall.PyError) - error("Problem during service creation: $(err.val[:args][1])") + error("Problem during service creation: $(err.val.args[1])") else rethrow(err) end @@ -85,7 +85,7 @@ Throws an exception if the waiting timeout period is exceeded. """ function wait_for_service(service::AbstractString; kwargs...) try - __rospy__[:wait_for_service](ascii(service); kwargs...) + __rospy__.wait_for_service(ascii(service); kwargs...) catch ex error("Timeout exceeded waiting for service '$service'") end diff --git a/src/time.jl b/src/time.jl index e0df388..7e932b3 100644 --- a/src/time.jl +++ b/src/time.jl @@ -71,10 +71,10 @@ end *(tf::Real, td::Duration) = Duration(tf*td.secs , tf*td.nsecs) #PyObject conversions -convert(::Type{Time}, o::PyObject) = Time( o[:secs],o[:nsecs]) -convert(::Type{Duration}, o::PyObject) = Duration(o[:secs],o[:nsecs]) -convert(::Type{PyObject}, t::Time) = __rospy__[:Time]( t.secs,t.nsecs) -convert(::Type{PyObject}, t::Duration) = __rospy__[:Duration](t.secs,t.nsecs) +convert(::Type{Time}, o::PyObject) = Time( o.secs,o.nsecs) +convert(::Type{Duration}, o::PyObject) = Duration(o.secs,o.nsecs) +convert(::Type{PyObject}, t::Time) = __rospy__.Time( t.secs,t.nsecs) +convert(::Type{PyObject}, t::Duration) = __rospy__.Duration(t.secs,t.nsecs) #Real number conversions """ @@ -117,7 +117,7 @@ Return the current ROS time as a `Time` object. """ function get_rostime() t = try - __rospy__[:get_rostime]() + __rospy__.get_rostime() catch ex error(pycall(pybuiltin("str"), PyAny, ex.val)) end @@ -143,7 +143,7 @@ function rossleep(td::Duration) t0 = time_ns() while time_ns()-t0 < tnsecs yield() #Allow julia callback loops to run - __rospy__[:sleep](0.001) #Allow rospy comm threads to run + __rospy__.sleep(0.001) #Allow rospy comm threads to run end end rossleep(t::Real) = rossleep(Duration(t)) diff --git a/test/time.jl b/test/time.jl index ab42834..6279aa9 100644 --- a/test/time.jl +++ b/test/time.jl @@ -46,16 +46,16 @@ dt = Duration(3,0) #PyObject stuff ptt = convert(PyCall.PyObject, tt) -@test ptt[:secs] == 2 -@test ptt[:nsecs] == 0 -ptt[:nsecs] = 101 +@test ptt.secs == 2 +@test ptt.nsecs == 0 +ptt.nsecs = 101 tt2 = convert(Time, ptt) @test to_nsec(tt2) == 2_000_000_101 pdt = convert(PyCall.PyObject, dt) -@test pdt[:secs] == 3 -@test pdt[:nsecs] == 0 -pdt[:nsecs] = 202 +@test pdt.secs == 3 +@test pdt.nsecs == 0 +pdt.nsecs = 202 dt2 = convert(Duration, pdt) @test to_nsec(dt2) == 3_000_000_202 diff --git a/test/typegeneration.jl b/test/typegeneration.jl index 68d60fa..8c53f91 100644 --- a/test/typegeneration.jl +++ b/test/typegeneration.jl @@ -54,13 +54,13 @@ planresp = nav_msgs.srv.GetPlanResponse() #convert to/from PyObject posestamp.pose.position = geometry_msgs.msg.Point(1,2,3) pypose = convert(PyObject, posestamp) -@test pypose[:pose][:position][:x] == 1. -@test pypose[:pose][:position][:y] == 2. -@test pypose[:pose][:position][:z] == 3. +@test pypose.pose.position.x == 1. +@test pypose.pose.position.y == 2. +@test pypose.pose.position.z == 3. pypose2 = PyObject(posestamp) -@test pypose2[:pose][:position][:x] == 1. -@test pypose2[:pose][:position][:y] == 2. -@test pypose2[:pose][:position][:z] == 3. +@test pypose2.pose.position.x == 1. +@test pypose2.pose.position.y == 2. +@test pypose2.pose.position.z == 3. pose2 = convert(geometry_msgs.msg.PoseStamped, pypose) @test pose2.pose.position.x == 1. @test pose2.pose.position.y == 2. @@ -68,7 +68,7 @@ pose2 = convert(geometry_msgs.msg.PoseStamped, pypose) @test_throws InexactError convert(geometry_msgs.msg.Pose, pypose) #access message enum -@test visualization_msgs.msg.Marker[:CUBE] == 1 +@test visualization_msgs.msg.Marker.CUBE == 1 #Proper array handling path = nav_msgs.msg.Path() From b4ca6046aee0d52fbf79fa95b9c0db018ef47a56 Mon Sep 17 00:00:00 2001 From: Ed Schmerling Date: Sat, 20 Apr 2019 01:42:59 -0700 Subject: [PATCH 2/2] Update Travis CI config to test on Ubuntu Xenial 16.04 --- .travis.yml | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/.travis.yml b/.travis.yml index 9d1f570..d95c1fc 100644 --- a/.travis.yml +++ b/.travis.yml @@ -2,22 +2,26 @@ language: julia julia: - 0.7 - 1.0 + - 1.1 - nightly +matrix: + allow_failures: + - julia: nightly sudo: required -dist: trusty +dist: xenial env: global: - PYTHON=python before_install: - - sudo apt-add-repository -y "deb http://packages.ros.org/ros/ubuntu trusty main" + - sudo apt-add-repository -y "deb http://packages.ros.org/ros/ubuntu xenial main" - wget https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -O - | sudo apt-key add - - sudo apt-get update - - sudo apt-get -y install ros-indigo-ros-base ros-indigo-common-msgs + - sudo apt-get -y install ros-kinetic-ros-base ros-kinetic-common-msgs - sudo rosdep init - rosdep update before_script: - export PATH=/usr/bin:$PATH - - source /opt/ros/indigo/setup.sh + - source /opt/ros/kinetic/setup.sh - roscore & - sleep 5 - python test/echonode.py &