Skip to content

Commit ccd77dd

Browse files
committed
Disable features making use of julia callbacks in 0.5 until #15 is resolved
1 parent 01c88ed commit ccd77dd

File tree

6 files changed

+104
-34
lines changed

6 files changed

+104
-34
lines changed

src/pubsub.jl

Lines changed: 14 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -17,13 +17,21 @@ function publish{MsgType<:MsgT}(p::Publisher{MsgType}, msg::MsgType)
1717
pycall(p.o["publish"], PyAny, convert(PyObject, msg))
1818
end
1919

20+
if VERSION >= v"0.5.0-dev+3692" #callbacks are broken
21+
22+
type Subscriber{T}
23+
end
24+
Subscriber(args...) = error(
25+
"""Subscribing to a topic is currently broken on julia v0.5 and above. See
26+
https://github.com/jdlangs/RobotOS.jl/issues/15 for ongoing efforts to fix this.""")
27+
28+
else #callbacks not broken
29+
2030
type Subscriber{MsgType<:MsgT}
2131
o::PyObject
2232
callback
2333

24-
function Subscriber(
25-
topic::AbstractString, cb, cb_args::Tuple=(); kwargs...
26-
)
34+
function Subscriber(topic::AbstractString, cb, cb_args::Tuple=(); kwargs...)
2735
@debug("Creating <$(string(MsgType))> subscriber on topic: '$topic'")
2836
rospycls = _get_rospy_class(MsgType)
2937
jl_cb(msg::PyObject) = cb(convert(MsgType, msg), cb_args...)
@@ -33,10 +41,13 @@ type Subscriber{MsgType<:MsgT}
3341
)
3442
end
3543
end
44+
3645
Subscriber{MsgType<:MsgT}(
3746
topic::AbstractString,
3847
::Type{MsgType},
3948
cb,
4049
cb_args::Tuple=();
4150
kwargs...
4251
) = Subscriber{MsgType}(ascii(topic), cb, cb_args; kwargs...)
52+
53+
end #version check

src/services.jl

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,17 @@ end
3232
resp
3333
end
3434

35+
if VERSION >= v"0.5.0-dev+3692" #callbacks are broken
36+
37+
type Service{T}
38+
end
39+
40+
Service(args...) = error(
41+
"""Providing a service is currently broken on julia v0.5 and above. See
42+
https://github.com/jdlangs/RobotOS.jl/issues/15 for ongoing efforts to fix this.""")
43+
44+
else #callbacks not broken
45+
3546
type Service{SrvType <: ServiceDefinition}
3647
o::PyObject
3748
jl_handler
@@ -64,6 +75,8 @@ function Service{SrvType<:ServiceDefinition}(
6475
Service{SrvType}(ascii(name), handler; kwargs...)
6576
end
6677

78+
end #version check
79+
6780
function wait_for_service(service::AbstractString; kwargs...)
6881
try
6982
__rospy__[:wait_for_service](ascii(service); kwargs...)

test/echonode.py

Lines changed: 11 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -4,16 +4,18 @@
44
import rospy
55
from geometry_msgs.msg import PoseStamped, Vector3
66

7-
from std_srvs.srv import Empty, EmptyResponse
7+
from std_srvs.srv import SetBool, SetBoolRequest, SetBoolResponse
88
from nav_msgs.srv import GetPlan, GetPlanRequest, GetPlanResponse
99

1010
class Echo(object):
1111
def __init__(self):
1212
self._pub = rospy.Publisher("poses", PoseStamped, queue_size=10)
1313
self._sub = rospy.Subscriber("vectors", Vector3, self.msg_cb, queue_size=10)
14+
self._nrecv = 0
1415

15-
self._srvlisten = rospy.Service("callme", Empty, self.srv_cb)
16+
self._srvlisten = rospy.Service("callme", SetBool, self.srv_cb)
1617
self._srvcall = rospy.ServiceProxy("getplan", GetPlan)
18+
rospy.set_param("/received_service_call", False)
1719

1820
#Translate a Vector3 message to a PoseStamped and republish
1921
def msg_cb(self, msg):
@@ -24,9 +26,14 @@ def msg_cb(self, msg):
2426
pmsg.pose.position.z = msg.z
2527
self._pub.publish(pmsg)
2628

29+
self._nrecv += 1
30+
rospy.set_param("/num_received_messages", self._nrecv)
31+
2732
def srv_cb(self, req):
28-
self._calltimer = rospy.Timer(rospy.Duration(2.0), self.callsrv, oneshot=True)
29-
return EmptyResponse()
33+
if req.data:
34+
self._calltimer = rospy.Timer(rospy.Duration(2.0), self.callsrv, oneshot=True)
35+
rospy.set_param("/received_service_call", True)
36+
return SetBoolResponse(True, "")
3037

3138
def callsrv(self, ev):
3239
req = GetPlanRequest()

test/pubsub.jl

Lines changed: 32 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -14,29 +14,48 @@ for i=1:Nmsgs
1414
refs[i] = Vector3(rand(3)...)
1515
end
1616

17+
const ros_pub = Publisher("vectors", Vector3, queue_size = 10)
18+
rossleep(Duration(3.0))
19+
20+
function publish_messages(pubobj, msgs, rate_hz)
21+
const r = Rate(rate_hz)
22+
for msg in msgs
23+
publish(pubobj, msg)
24+
rossleep(r)
25+
end
26+
rossleep(Duration(1.0))
27+
end
28+
1729
function pose_cb(msg::PoseStamped, msgs::Vector{PoseStamped})
1830
mtime = to_nsec(msg.header.stamp) - t0
19-
println("Message received, time: ",mtime," nanoseconds")
20-
if msg.header.stamp.secs > 1.
31+
mtime > 0 && println("Message received, time: ",mtime," nanoseconds")
32+
if msg.header.stamp.secs > 1.0
2133
push!(msgs, msg)
2234
println("Got message #",msg.header.seq)
2335
end
2436
end
25-
pose_cb(PoseStamped(), msgs)
37+
pose_cb(PoseStamped(), msgs) #warm up run
38+
39+
if VERSION >= v"0.5.0-dev+3692" #callbacks are broken
40+
41+
warn("Not testing subscriber!")
42+
43+
publish_messages(ros_pub, refs, 20.0)
44+
rossleep(Duration(5.0))
45+
Nreceived = get_param("/num_received_messages")
46+
@test Nreceived == length(refs)
47+
set_param("/num_received_messages", 0)
48+
49+
else #callbacks not broken
2650

27-
const ros_pub = Publisher("vectors", Vector3, queue_size = 10)
2851
const ros_sub = Subscriber("poses", PoseStamped, pose_cb, (msgs,), queue_size = 10)
2952

3053
#First message doesn't go out for some reason
3154
publish(ros_pub, Vector3(1.1,2.2,3.3))
3255
rossleep(Duration(1.0))
33-
34-
const r = Rate(20.0)
35-
for i=1:Nmsgs
36-
publish(ros_pub, refs[i])
37-
rossleep(r)
38-
end
56+
publish_messages(ros_pub, refs, 20.0)
3957
rossleep(Duration(1.0))
58+
4059
println("Received ",length(msgs)," / ",Nmsgs)
4160

4261
@test length(msgs) == Nmsgs
@@ -45,3 +64,6 @@ for i=1:Nmsgs
4564
@test_approx_eq msgs[i].pose.position.y refs[i].y
4665
@test_approx_eq msgs[i].pose.position.z refs[i].z
4766
end
67+
empty!(msgs)
68+
69+
end #version check

test/services.jl

Lines changed: 29 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -3,11 +3,11 @@
33
using std_srvs.srv
44
using nav_msgs.srv
55

6-
const flag = Bool[false]
7-
const Nposes = 5
8-
empty!(msgs)
9-
106
#Set up services
7+
const srvcall = ServiceProxy("callme", SetBool)
8+
println("Waiting for 'callme' service...")
9+
wait_for_service("callme")
10+
1111
function srv_cb(req::GetPlanRequest)
1212
println("GetPlan call received")
1313
@test_approx_eq(req.start.pose.position.x, 1.0)
@@ -24,14 +24,27 @@ function srv_cb(req::GetPlanRequest)
2424
return resp
2525
end
2626

27-
const srvcall = ServiceProxy("callme", Empty)
27+
if VERSION >= v"0.5.0-dev+3692" #callbacks are broken
28+
29+
warn("Not testing service provider!")
30+
31+
println("Calling service...")
32+
srvcall(SetBoolRequest(false))
33+
rossleep(Duration(5.0))
34+
35+
didcall = get_param("/received_service_call")
36+
@test didcall
37+
set_param("/received_service_call", false)
38+
39+
else #callbacks not broken
40+
41+
const flag = Bool[false]
42+
const Nposes = 5
43+
2844
const srvlisten = Service("getplan", GetPlan, srv_cb)
2945

30-
#Call echo's Empty service
31-
println("Waiting for 'callme' service...")
32-
wait_for_service("callme")
33-
println("Calling service now")
34-
srvcall(EmptyRequest())
46+
println("Calling service...")
47+
srvcall(SetBoolRequest(true))
3548

3649
#Wait for call from echo
3750
println("Waiting for service call from echo..")
@@ -40,16 +53,19 @@ while ! (flag[1] || is_shutdown())
4053
end
4154
println("Response sent")
4255

43-
#Listen for message replies caught by the geomety_msgs/PoseStamped subscriber
44-
#in pubsub.jl which populates the msgs global variable
56+
#Check the message replies caught by the geomety_msgs/PoseStamped subscriber in pubsub.jl which
57+
#populates the msgs global variable
4558
if flag[1]
4659
rossleep(Duration(2.0))
4760
@test length(msgs) == Nposes
4861
for i=1:Nposes
4962
@test_approx_eq(msgs[i].pose.position.z, i)
5063
end
5164
end
65+
empty!(msgs)
66+
67+
end #version check
5268

5369
#Test error handling
5470
@test_throws ErrorException wait_for_service("fake_srv", timeout=1.0)
55-
@test_throws ArgumentError srvcall(EmptyResponse())
71+
@test_throws ArgumentError srvcall(SetBoolResponse())

test/typegeneration.jl

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@ using Compat
44

55
@rosimport geometry_msgs.msg: PoseStamped, Vector3
66
@rosimport visualization_msgs.msg: Marker
7-
@rosimport std_srvs.srv.Empty
7+
@rosimport std_srvs.srv: Empty, SetBool
88
@rosimport nav_msgs.srv.GetPlan
99
@rosimport std_msgs.msg: Empty
1010
@rosimport std_msgs.msg: Float64, String
@@ -35,8 +35,8 @@ posestamp = geometry_msgs.msg.PoseStamped()
3535
@test typeof(posestamp.pose.position) == geometry_msgs.msg.Point
3636

3737
#service creation
38-
emptyreq = std_srvs.srv.EmptyRequest()
39-
emptyresp = std_srvs.srv.EmptyResponse()
38+
boolreq = std_srvs.srv.SetBoolRequest()
39+
boolresp = std_srvs.srv.SetBoolResponse(true, "message")
4040
planreq = nav_msgs.srv.GetPlanRequest()
4141
planresp = nav_msgs.srv.GetPlanResponse()
4242
@test typeof(planreq) == nav_msgs.srv.GetPlanRequest
@@ -77,4 +77,5 @@ emptymsg = std_msgs.msg.Empty()
7777
@test isdefined(std_msgs.msg, :Float64Msg)
7878
@test isdefined(std_msgs.msg, :StringMsg)
7979
@test Publisher{std_msgs.msg.Float64Msg}("x", queue_size=10) != nothing
80-
@test Subscriber{std_msgs.msg.Float64Msg}("x", x->x, queue_size=10) != nothing
80+
VERSION < v"0.5.0-dev+3692" &&
81+
@test Subscriber{std_msgs.msg.Float64Msg}("x", x->x, queue_size=10) != nothing

0 commit comments

Comments
 (0)