|
| 1 | +# RobotOS.jl Documentation |
| 2 | + |
| 3 | + |
| 4 | +## Overview |
| 5 | + |
| 6 | +### Description |
| 7 | + |
| 8 | +This package enables interfacing Julia code with a ROS ([Robot Operating |
| 9 | +System](http://wiki.ros.org)) system. It works by generating native Julia types |
| 10 | +for ROS types, the same as in C++ or Python, and then wrapping rospy through |
| 11 | +the PyCall package to get communication through topics, services, and |
| 12 | +parameters. |
| 13 | + |
| 14 | +### Installation |
| 15 | + |
| 16 | + Pkg.add("RobotOS") |
| 17 | + using RobotOS |
| 18 | + |
| 19 | +### Contributing |
| 20 | + |
| 21 | +The package will hopefully continue to undergo substantial improvement. Please |
| 22 | +feel free to submit either an issue or pull request through github if you want |
| 23 | +to fix something or suggest a needed improvment, even if it's just to add an |
| 24 | +extra sentence in this README. |
| 25 | + |
| 26 | +#### Testing |
| 27 | + |
| 28 | +Currently, `Pkg.test("RobotOS")` requires some bootstrapping to work properly. |
| 29 | +Before running Julia, make sure a ROS master is running and start the helper |
| 30 | +node by running the `test/echonode.py` file. |
| 31 | + |
| 32 | +## Usage: Type Generation |
| 33 | + |
| 34 | +ROS types are brought into your program with the `@rosimport` macro which |
| 35 | +specifies a package and one or more types. The three valid syntax forms can be |
| 36 | +seen in these examples: |
| 37 | + |
| 38 | + @rosimport std_msgs.msg.Header |
| 39 | + @rosimport nav_msgs.srv: GetPlan |
| 40 | + @rosimport geometry_msgs.msg: PoseStamped, Vector3 |
| 41 | + |
| 42 | +`@rosimport` will import the python modules for the requested type and all |
| 43 | +its dependencies but the native Julia types are not created yet since any |
| 44 | +inter-module dependencies have to be resolved first. After the final |
| 45 | +`@rosimport` call, initiate the type generation with: |
| 46 | + |
| 47 | + rostypegen() |
| 48 | + |
| 49 | +The new types will be placed in newly created modules in `Main`, corresponding |
| 50 | +to the packages requested. For example, `"std_msgs/Header" => |
| 51 | +std_msgs.msg.Header`. After calling `rostypegen()` they can be interacted with |
| 52 | +just like regular modules with `import` and `using` statements bringing the |
| 53 | +generated type names into the local namespace. |
| 54 | + |
| 55 | + using nav_msgs.msg |
| 56 | + import geometry_msgs.msg: Pose, Vector3 |
| 57 | + p = Path() |
| 58 | + v = Vector3(1.1,2.2,3.3) |
| 59 | + |
| 60 | +There is one special case, where the ROS type name conflicts with a built-in |
| 61 | +Julia type name (e.g., `std_msgs/Float64` or `std_msgs/String`). In these |
| 62 | +cases, the generated Julia type will have "Msg" appended to the name for |
| 63 | +disambiguation (e.g., `std_msgs.msg.Float64Msg` and `std_msgs.msg.StringMsg`). |
| 64 | + |
| 65 | +An additional function, `rostypereset()`, resets the type generation process, |
| 66 | +possibly useful for development in the REPL. When invoked, new `@rosimport` |
| 67 | +calls will be needed to generate the same or different types, and previously |
| 68 | +generated modules will be overwritten after `rostypegen()` is called again. Keep |
| 69 | +in mind that names cannot be cleared once defined so if a module is not |
| 70 | +regenerated, the first version will remain. |
| 71 | + |
| 72 | +## Usage: ROS API |
| 73 | + |
| 74 | +In general, the API functions provided directly match those provided in rospy, |
| 75 | +with few cosmetic differences. The rospy API functions can reviewed here: |
| 76 | +[http://wiki.ros.org/rospy/Overview](http://wiki.ros.org/rospy/Overview) |
| 77 | + |
| 78 | +### General Functions |
| 79 | + |
| 80 | +- `init_node(name::String; kwargs...)` : Initialize node. Passes keyword |
| 81 | +arguments on to rospy directly. (Required) |
| 82 | +- `is_shutdown()` : Check for ROS shutdown state. |
| 83 | +- `spin()` : Wait for callbacks until shutdown happens. |
| 84 | +- `logdebug`,`loginfo`,`logwarn`,`logerr`,`logfatal` all work as in rospy. |
| 85 | + |
| 86 | +### Time |
| 87 | + |
| 88 | +Native Julia types `Time` and `Duration` are defined, both as a composite of an |
| 89 | +integral number of seconds and nanoseconds, as in rospy. Arithmetic and |
| 90 | +comparison operators are also defined. A `Rate` type is defined as a wrapper |
| 91 | +for the rospy Rate, which keeps loops running on a near fixed time interval. It |
| 92 | +can be constructed with a `Duration` object, or a floating-point value, |
| 93 | +specifying the loop rate in Hz. Other functions are: |
| 94 | + |
| 95 | +- `get_rostime()`, `RobotOS.now()` : Current time as `Time` object. |
| 96 | +- `to_sec(time_obj)`, `convert(Float64, time_obj)` : Convert `Time` or |
| 97 | +`Duration` object to floating-point number of seconds. |
| 98 | +- `to_nsec(time_obj)` : Convert object to integral number of nanoseconds. |
| 99 | +- `rossleep(t)` with `t` of type `Duration`, `Rate`, `Real`. Also |
| 100 | +`sleep(t::Duration)` and `sleep(t::Rate)` : Sleep the amount implied by type |
| 101 | +and value of the `t` parameter. |
| 102 | + |
| 103 | +### Publishing Messages |
| 104 | + |
| 105 | +Publishing messages is the same as in rospy, except use the `publish` method, |
| 106 | +paired with a Publisher object. For example: |
| 107 | + |
| 108 | + using geometry_msgs.msg |
| 109 | + pub = Publisher{PointStamped}("topic", queue_size = 10) #or... |
| 110 | + #pub = Publisher("topic", PointStamped, queue_size = 10) |
| 111 | + msg = PointStamped() |
| 112 | + msg.header.stamp = now() |
| 113 | + msg.point.x = 1.1 |
| 114 | + publish(pub, msg) |
| 115 | + |
| 116 | +The keyword arguments in the `Publisher` constructor are passed directly on to |
| 117 | +rospy so anything it accepts will be valid. |
| 118 | + |
| 119 | +### Subscribing to a Topic |
| 120 | + |
| 121 | +Subscribing to a topic is the same as in rospy. When creating a `Subscriber`, |
| 122 | +an optional `callback_args` parameter can be given to forward on whenever the |
| 123 | +callback is invoked. Note that it must be passed as a tuple, even if there is |
| 124 | +only a single argument. And again, keyword arguments are directly forwarded. An |
| 125 | +example: |
| 126 | + |
| 127 | + using sensor_msgs.msg |
| 128 | + cb1(msg::Imu, a::String) = println(a,": ",msg.linear_acceleration.x) |
| 129 | + cb2(msg::Imu) = println(msg.angular_velocity.z) |
| 130 | + sub1 = Subscriber{Imu}("topic", cb1, ("accel",), queue_size = 10) #or... |
| 131 | + #sub1 = Subscriber("topic", Imu, cb1, ("accel",), queue_size = 10) |
| 132 | + sub2 = Subscriber{Imu}("topic", cb2, queue_size = 10) |
| 133 | + spin() |
| 134 | + |
| 135 | +### Using services |
| 136 | + |
| 137 | +ROS services are fully supported, including automatic request and response type |
| 138 | +generation. For the `@rosimport` call, use the plain service type name. After |
| 139 | +`rostypegen()`, the generated `.srv` submodule will contain 3 types: the plain |
| 140 | +type, a request type, and a response type. For example `@rosimport |
| 141 | +nav_msgs.srv.GetPlan` will create `GetPlan`, `GetPlanRequest`, and |
| 142 | +`GetPlanResponse`. To provide the service to other nodes, you would create a |
| 143 | +`Service{GetPlan}` object. To call it, a `ServiceProxy{GetPlan}` object. The |
| 144 | +syntax exactly matches rospy to construct and use these objects. For example, |
| 145 | +if `myproxy` is a `ServiceProxy` object, it can be called with |
| 146 | +`myproxy(my_request)`. |
| 147 | + |
| 148 | +### Parameter Server |
| 149 | + |
| 150 | +`get_param`, `set_param`, `has_param`, and `delete_param` are all implemented |
| 151 | +in the `RobotOS` module with the same syntax as in rospy. |
| 152 | + |
| 153 | +### Message Constants |
| 154 | +Message constants may be accessed using `getindex` syntax. For example for |
| 155 | +[visualization_msgs/Marker.msg](http://docs.ros.org/api/visualization_msgs/html/msg/Marker.html) |
| 156 | +we have: |
| 157 | + |
| 158 | + import visualization_msgs.msg: Marker |
| 159 | + Marker[:SPHERE] == getindex(Marker, :SPHERE) == 2 # true |
| 160 | + |
| 161 | +## ROS Integration |
| 162 | + |
| 163 | +Since Julia code needs no prior compilation, it is possible to integrate very |
| 164 | +tightly and natively with a larger ROS system. Just make sure you: |
| 165 | + |
| 166 | +- Keep your code inside your ROS packages as usual. |
| 167 | +- Ensure your .jl script is executable (e.g., `chmod a+x script.jl`) and has |
| 168 | +the hint to the Julia binary as the first line (`#!/usr/bin/env julia`). |
| 169 | + |
| 170 | +Now your Julia code will run exactly like any python script that gets invoked |
| 171 | +through `rosrun` or `roslaunch`. And since `include` takes paths relative to |
| 172 | +the location of the calling file, you can bring in whatever other modules or |
| 173 | +functions reside in your package from the single executable script. |
| 174 | + |
| 175 | + #!/usr/bin/env julia |
| 176 | + #main.jl in thebot_pkg/src |
| 177 | + using RobotOS |
| 178 | + |
| 179 | + include("BotSrc/Bot.jl") |
| 180 | + using Bot |
| 181 | + #... |
| 182 | + |
| 183 | +## Full example |
| 184 | + |
| 185 | +This example demonstrates publishing a random `geometry_msgs/Point` message at |
| 186 | +5 Hz. It also listens for incoming `geometry_msgs/Pose2D` messages and |
| 187 | +republishes them as Points. |
| 188 | + |
| 189 | + #!/usr/bin/env julia |
| 190 | + |
| 191 | + using RobotOS |
| 192 | + @rosimport geometry_msgs.msg: Point, Pose2D |
| 193 | + rostypegen() |
| 194 | + using geometry_msgs.msg |
| 195 | + |
| 196 | + function callback(msg::Pose2D, pub_obj::Publisher{Point}) |
| 197 | + pt_msg = Point(msg.x, msg.y, 0.0) |
| 198 | + publish(pub_obj, pt_msg) |
| 199 | + end |
| 200 | + |
| 201 | + function loop(pub_obj) |
| 202 | + loop_rate = Rate(5.0) |
| 203 | + while ! is_shutdown() |
| 204 | + npt = Point(rand(), rand(), 0.0) |
| 205 | + publish(pub_obj, npt) |
| 206 | + rossleep(loop_rate) |
| 207 | + end |
| 208 | + end |
| 209 | + |
| 210 | + function main() |
| 211 | + init_node("rosjl_example") |
| 212 | + pub = Publisher{Point}("pts", queue_size=10) |
| 213 | + sub = Subscriber{Pose2D}("pose", callback, (pub,), queue_size=10) |
| 214 | + loop(pub) |
| 215 | + end |
| 216 | + |
| 217 | + if ! isinteractive() |
| 218 | + main() |
| 219 | + end |
| 220 | + |
| 221 | +## Versions |
| 222 | + |
| 223 | +- `0.1` : Initial release |
| 224 | +- `0.2` : Changed type gen API and moved generated modules to Main |
| 225 | +- `0.3` : Added service type generation and API |
| 226 | +- `0.4` : Julia v0.4+ support only |
0 commit comments