Skip to content

Commit 6b3a9f0

Browse files
committed
Switch internal rospy module to PyObject
1 parent 582c94e commit 6b3a9f0

File tree

6 files changed

+34
-33
lines changed

6 files changed

+34
-33
lines changed

src/RobotOS.jl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@ module RobotOS
22

33
using PyCall
44
const __rospy__ = try
5-
pywrap(pyimport("rospy"))
5+
pyimport("rospy")
66
catch ex
77
if ex.val[:args][1] == "No module named rospy"
88
error("rospy not found!\nHas an environment setup script been run?")

src/gentypes.jl

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@ using Compat
33

44
export @rosimport, rostypegen, rostypereset, gentypes, cleartypes
55

6+
#Type definitions
67
#Composite types for internal use. Keeps track of the imported types and helps
78
#keep code generation orderly.
89
abstract ROSModule

src/pubsub.jl

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ type Publisher{MsgType<:MsgT}
77
function Publisher(topic::String; kwargs...)
88
@debug("Creating <$(string(MsgType))> publisher on topic: '$topic'")
99
rospycls = _get_rospy_class(MsgType)
10-
return new(__rospy__.Publisher(topic, rospycls; kwargs...))
10+
return new(__rospy__[:Publisher](topic, rospycls; kwargs...))
1111
end
1212
end
1313
Publisher{MsgType<:MsgT}(topic::String, ::Type{MsgType}; kwargs...) =
@@ -28,7 +28,7 @@ type Subscriber{MsgType<:MsgT}
2828
rospycls = _get_rospy_class(MsgType)
2929
jl_callback(msg::PyObject) = cb(convert(MsgType, msg), cb_args...)
3030
return new(
31-
__rospy__.Subscriber(topic, rospycls, jl_callback; kwargs...),
31+
__rospy__[:Subscriber](topic, rospycls, jl_callback; kwargs...),
3232
jl_callback
3333
)
3434
end

src/rospy.jl

Lines changed: 21 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -4,46 +4,46 @@ export init_node, is_shutdown, spin,
44
logdebug, loginfo, logwarn, logerr, logfatal
55

66
#General rospy functions
7-
init_node(name::String; args...) = __rospy__.init_node(name; args...)
8-
spin() = __rospy__.spin()
9-
is_shutdown() = __rospy__.is_shutdown()
10-
get_published_topics() = __rospy__.get_published_topics()
11-
get_ros_root() = __rospy__.get_ros_root()
7+
init_node(name::String; args...) = __rospy__[:init_node](name; args...)
8+
spin() = __rospy__[:spin]()
9+
is_shutdown() = __rospy__[:is_shutdown]()
10+
get_published_topics() = __rospy__[:get_published_topics]()
11+
get_ros_root() = __rospy__[:get_ros_root]()
1212

1313
#Parameter server API
1414
get_param(param_name::String, def=nothing) = begin
1515
try
1616
if def == nothing
17-
__rospy__.get_param(param_name)
17+
__rospy__[:get_param](param_name)
1818
else
19-
__rospy__.get_param(param_name, def)
19+
__rospy__[:get_param](param_name, def)
2020
end
2121
catch ex
2222
throw(KeyError(pycall(pybuiltin("str"), PyAny, ex.val)[2:end-1]))
2323
end
2424
end
25-
set_param(param_name::String, val) = __rospy__.set_param(param_name, val)
26-
has_param(param_name::String) = __rospy__.has_param(param_name)
25+
set_param(param_name::String, val) = __rospy__[:set_param](param_name, val)
26+
has_param(param_name::String) = __rospy__[:has_param](param_name)
2727
delete_param(param_name::String) = begin
2828
try
29-
__rospy__.delete_param(param_name)
29+
__rospy__[:delete_param](param_name)
3030
catch ex
3131
throw(KeyError(pycall(pybuiltin("str"), PyAny, ex.val)[2:end-1]))
3232
end
3333
end
3434
#Doesn't work for some reason
35-
#rospy_search_param(param_name::String) = __rospy__.rospy_search_param(param_name)
36-
get_param_names() = __rospy__.get_param_names()
35+
#rospy_search_param(param_name::String) = __rospy__[:rospy_search_param](param_name)
36+
get_param_names() = __rospy__[:get_param_names]()
3737

3838
#Logging API
39-
logdebug(msg, args...) = __rospy__.logdebug(msg, args...)
40-
loginfo(msg, args...) = __rospy__.loginfo(msg, args...)
41-
logwarn(msg, args...) = __rospy__.logwarn(msg, args...)
42-
logerr(msg, args...) = __rospy__.logerr(msg, args...)
43-
logfatal(msg, args...) = __rospy__.logfatal(msg, args...)
39+
logdebug(msg, args...) = __rospy__[:logdebug](msg, args...)
40+
loginfo(msg, args...) = __rospy__[:loginfo](msg, args...)
41+
logwarn(msg, args...) = __rospy__[:logwarn](msg, args...)
42+
logerr(msg, args...) = __rospy__[:logerr](msg, args...)
43+
logfatal(msg, args...) = __rospy__[:logfatal](msg, args...)
4444

4545
#Node information
46-
get_name() = __rospy__.get_name()
47-
get_namespace() = __rospy__.get_namespace()
48-
get_node_uri() = __rospy__.get_node_uri()
49-
get_caller_id() = __rospy__.get_caller_id()
46+
get_name() = __rospy__[:get_name]()
47+
get_namespace() = __rospy__[:get_namespace]()
48+
get_node_uri() = __rospy__[:get_node_uri]()
49+
get_caller_id() = __rospy__[:get_caller_id]()

src/services.jl

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@ type ServiceProxy{SrvType <: ServiceDefinition}
1313
function ServiceProxy(name::String; kwargs...)
1414
@debug("Creating <$SrvType> service proxy for '$name'")
1515
rospycls = _get_rospy_class(SrvType)
16-
new(__rospy__.ServiceProxy(name, rospycls; kwargs...))
16+
new(__rospy__[:ServiceProxy](name, rospycls; kwargs...))
1717
end
1818
end
1919
function ServiceProxy{SrvType<:ServiceDefinition}(
@@ -48,7 +48,7 @@ type Service{SrvType <: ServiceDefinition}
4848
jl_handler(req::PyObject) =
4949
convert(PyObject, handler(convert(ReqType,req)))
5050
try
51-
new(__rospy__.Service(name, rospycls, jl_handler; kwargs...),
51+
new(__rospy__[:Service](name, rospycls, jl_handler; kwargs...),
5252
jl_handler
5353
)
5454
catch err
@@ -71,7 +71,7 @@ end
7171

7272
function wait_for_service(service::String; kwargs...)
7373
try
74-
__rospy__.wait_for_service(service; kwargs...)
74+
__rospy__[:wait_for_service](service; kwargs...)
7575
catch ex
7676
error("Timeout exceeded waiting for service '$service'")
7777
end

src/time.jl

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -54,8 +54,8 @@ end
5454
#PyObject conversions
5555
convert(::Type{Time}, o::PyObject) = Time( o[:secs],o[:nsecs])
5656
convert(::Type{Duration}, o::PyObject) = Duration(o[:secs],o[:nsecs])
57-
convert(::Type{PyObject}, t::Time) = __rospy__.Time( t.secs,t.nsecs)
58-
convert(::Type{PyObject}, t::Duration) = __rospy__.Duration(t.secs,t.nsecs)
57+
convert(::Type{PyObject}, t::Time) = __rospy__[:Time]( t.secs,t.nsecs)
58+
convert(::Type{PyObject}, t::Duration) = __rospy__[:Duration](t.secs,t.nsecs)
5959

6060
#Real number conversions
6161
to_sec{T<:TVal}(t::T) = t.secs + 1e-9*t.nsecs
@@ -73,7 +73,7 @@ isless{T<:TVal}(t1::T, t2::T) = to_nsec(t1) < to_nsec(t2)
7373
type Rate
7474
o::PyObject
7575
end
76-
Rate(hz::Real) = Rate(__rospy__.Rate(hz))
76+
Rate(hz::Real) = Rate(__rospy__[:Rate](hz))
7777
Rate(d::Duration) = Rate(1.0/to_sec(d))
7878

7979
type Timer
@@ -90,16 +90,16 @@ end
9090

9191
function get_rostime()
9292
t = try
93-
__rospy__.get_rostime()
93+
__rospy__[:get_rostime]()
9494
catch ex
9595
error(pycall(pybuiltin("str"), PyAny, ex.val))
9696
end
9797
convert(Time, t)
9898
end
9999
now() = get_rostime()
100100

101-
rossleep(t::Real) = __rospy__.sleep(t)
102-
rossleep(t::Duration) = __rospy__.sleep(convert(PyObject, t))
101+
rossleep(t::Real) = __rospy__[:sleep](t)
102+
rossleep(t::Duration) = __rospy__[:sleep](convert(PyObject, t))
103103
rossleep(r::Rate) = pycall(r.o["sleep"], PyAny)
104104
sleep(t::Duration) = rossleep(t)
105105
sleep(t::Rate) = rossleep(t)

0 commit comments

Comments
 (0)