Skip to content

Commit ea82349

Browse files
committed
Updated time API to not conflict with Base
1 parent 3a7c47c commit ea82349

File tree

5 files changed

+21
-23
lines changed

5 files changed

+21
-23
lines changed

README.md

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -69,11 +69,9 @@ regenerated, the first version will remain.
6969

7070
## Usage: ROS API
7171

72-
In general, the ROS api functions directly match those provided in rospy, with
73-
few cosmetic differences. The API functions can reviewed here:
74-
[http://wiki.ros.org/rospy/Overview](http://wiki.ros.org/rospy/Overview) The
75-
only large differences are the current lack of services, and custom ROS
76-
exceptions.
72+
In general, the API functions provided directly match those provided in rospy,
73+
with few cosmetic differences. The rospy API functions can reviewed here:
74+
[http://wiki.ros.org/rospy/Overview](http://wiki.ros.org/rospy/Overview)
7775

7876
### General Functions
7977

@@ -92,12 +90,13 @@ for the rospy Rate, which keeps loops running on a near fixed time interval. It
9290
can be constructed with a `Duration` object, or a floating-point value,
9391
specifying the loop rate in Hz. Other functions are:
9492

95-
- `get_rostime()`, `now()` : Current time as `Time` object.
93+
- `get_rostime()`, `RobotOS.now()` : Current time as `Time` object.
9694
- `to_sec(time_obj)`, `convert(Float64, time_obj)` : Convert `Time` or
9795
`Duration` object to floating-point number of seconds.
9896
- `to_nsec(time_obj)` : Convert object to integral number of nanoseconds.
99-
- `sleep(t::Duration)`, `sleep(t::FloatingPoint)`, `sleep(t::Rate)` : Sleep the
100-
amount implied by type and value of the `t` parameter.
97+
- `rossleep(t)` with `t` of type `Duration`, `Rate`, `Real`. Also
98+
`sleep(t::Duration)` and `sleep(t::Rate)` : Sleep the amount implied by type
99+
and value of the `t` parameter.
101100

102101
### Publishing Messages
103102

src/time.jl

Lines changed: 8 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
#All time related types and functions
22

3-
import Base: convert, isless
4-
export Time, Duration, Rate, to_sec, to_nsec, get_rostime
3+
import Base: convert, isless, sleep
4+
export Time, Duration, Rate, to_sec, to_nsec, get_rostime, rossleep
55

66
#Time type definitions
77
abstract TVal
@@ -59,8 +59,7 @@ convert(::Type{PyObject}, t::Duration) = __rospy__.Duration(t.secs,t.nsecs)
5959
#Real number conversions
6060
to_sec{T<:TVal}(t::T) = float64(t.secs) + 1e-9*float64(t.nsecs)
6161
to_nsec{T<:TVal}(t::T) = 1_000_000_000*t.secs + t.nsecs
62-
#seems to be broken
63-
#convert{T<:TVal}(::Type{Float64}, t::T) = to_sec(t)
62+
convert{T<:TVal}(::Type{Float64}, t::T) = to_sec(t)
6463

6564
#Comparisons
6665
=={T<:TVal}(t1::T, t2::T) = (t1.secs == t2.secs) && (t1.nsecs == t2.nsecs)
@@ -98,6 +97,8 @@ function get_rostime()
9897
end
9998
now() = get_rostime()
10099

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

test/pubsub.jl

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -30,14 +30,14 @@ const ros_sub = Subscriber{PoseStamped}("poses", pose_cb, (msgs,), queue_size =
3030

3131
#First message doesn't go out for some reason
3232
publish(ros_pub, Vector3(1.1,2.2,3.3))
33-
RobotOS.sleep(1.0)
33+
rossleep(Duration(1.0))
3434

3535
const r = Rate(20.0)
3636
for i=1:Nmsgs
3737
publish(ros_pub, refs[i])
38-
RobotOS.sleep(r)
38+
rossleep(r)
3939
end
40-
RobotOS.sleep(1.0)
40+
rossleep(Duration(1.0))
4141
println("Received ",length(msgs)," / ",Nmsgs)
4242

4343
@test length(msgs) == Nmsgs

test/services.jl

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -36,14 +36,14 @@ call(srvcall, EmptyRequest())
3636
#Wait for call from echo
3737
println("Waiting for service call from echo..")
3838
while ! (flag[1] || is_shutdown())
39-
RobotOS.sleep(Duration(0.1))
39+
rossleep(Duration(0.1))
4040
end
4141
println("Response sent")
4242

4343
#Listen for message replies caught by the geomety_msgs/PoseStamped subscriber
4444
#in pubsub.jl which populates the msgs global variable
4545
if flag[1]
46-
RobotOS.sleep(Duration(2.0))
46+
rossleep(Duration(2.0))
4747
@test length(msgs) == Nposes
4848
for i=1:Nposes
4949
@test_approx_eq(msgs[i].pose.position.z, i)

test/typegeneration.jl

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@ using Compat
66
@rosimport geometry_msgs.msg: PoseStamped, Vector3
77
@rosimport std_srvs.srv.Empty
88
@rosimport nav_msgs.srv.GetPlan
9-
@rosimport std_msgs.msg: Float64, String, Int8MultiArray
9+
@rosimport std_msgs.msg: Float64, String
1010
rostypegen()
1111

1212
@test isdefined(:geometry_msgs)
@@ -67,5 +67,3 @@ emptymsg = std_msgs.msg.Empty()
6767
#Issue #7 - Renaming conflicting message types
6868
@test isdefined(std_msgs.msg, :Float64Msg)
6969
@test isdefined(std_msgs.msg, :StringMsg)
70-
intarr = std_msgs.msg.Int8MultiArray()
71-
@test typeof(intarr.data) == Vector{Int8}

0 commit comments

Comments
 (0)