Skip to content

Commit c95543c

Browse files
committed
Added docstrings to rospy functions
1 parent a42bd54 commit c95543c

File tree

1 file changed

+51
-1
lines changed

1 file changed

+51
-1
lines changed

src/rospy.jl

Lines changed: 51 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,13 +3,30 @@ export init_node, is_shutdown, spin,
33
get_param, has_param, set_param, delete_param,
44
logdebug, loginfo, logwarn, logerr, logfatal
55

6-
#General rospy functions
6+
"""
7+
init_node(name; args...)
8+
9+
Initialize this node, registering it with the ROS master. All arguments are passed on directly to
10+
the rospy init_node function.
11+
"""
712
init_node(name::AbstractString; args...) =
813
__rospy__[:init_node](ascii(name); args...)
14+
15+
"""
16+
is_shutdown()
17+
18+
Return the shutdown status of the node.
19+
"""
920
is_shutdown() = __rospy__[:is_shutdown]()
21+
1022
get_published_topics() = __rospy__[:get_published_topics]()
1123
get_ros_root() = __rospy__[:get_ros_root]()
1224

25+
"""
26+
spin()
27+
28+
Block execution and only process callbacks/service calls until the node is shut down.
29+
"""
1330
function spin()
1431
#Have to make sure both Julia tasks and python threads can wake up so
1532
#can't just call rospy's spin
@@ -19,6 +36,12 @@ function spin()
1936
end
2037

2138
#Parameter server API
39+
"""
40+
get_param(param_name, default=nothing)
41+
42+
Request the value of a parameter from the parameter server, with optional default value. If no
43+
default is given, throws a `KeyError` if the parameter cannot be found.
44+
"""
2245
function get_param(param_name::AbstractString, def=nothing)
2346
try
2447
if def == nothing
@@ -30,17 +53,36 @@ function get_param(param_name::AbstractString, def=nothing)
3053
throw(KeyError(pycall(pybuiltin("str"), PyAny, ex.val)[2:end-1]))
3154
end
3255
end
56+
57+
"""
58+
set_param(param_name, val)
59+
60+
Set the value of a parameter on the parameter server.
61+
"""
3362
set_param(param_name::AbstractString, val) =
3463
__rospy__[:set_param](ascii(param_name), val)
64+
65+
"""
66+
has_param(param_name)
67+
68+
Return a boolean specifying if a parameter exists on the parameter server.
69+
"""
3570
has_param(param_name::AbstractString) =
3671
__rospy__[:has_param](ascii(param_name))
72+
73+
"""
74+
delete_param(param_name)
75+
76+
Delete a parameter from the parameter server. Throws a `KeyError` if no such parameter exists.
77+
"""
3778
function delete_param(param_name::AbstractString)
3879
try
3980
__rospy__[:delete_param](ascii(param_name))
4081
catch ex
4182
throw(KeyError(pycall(pybuiltin("str"), PyAny, ex.val)[2:end-1]))
4283
end
4384
end
85+
4486
#Doesn't work for some reason
4587
#rospy_search_param(param_name::AbstractString) =
4688
# __rospy__[:rospy_search_param](ascii(param_name))
@@ -53,6 +95,14 @@ logwarn(msg, args...) = __rospy__[:logwarn](msg, args...)
5395
logerr(msg, args...) = __rospy__[:logerr](msg, args...)
5496
logfatal(msg, args...) = __rospy__[:logfatal](msg, args...)
5597

98+
"""
99+
logdebug, loginfo, logwarn, logerr, logfatal
100+
101+
Call the rospy logging system at the corresponding message level, passing a message and other
102+
arguments directly.
103+
"""
104+
logdebug, loginfo, logwarn, logerr, logfatal
105+
56106
#Node information
57107
get_name() = __rospy__[:get_name]()
58108
get_namespace() = __rospy__[:get_namespace]()

0 commit comments

Comments
 (0)