You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
No errors are printed to stdout. Roslaunch is configured with output="screen". Here's an example (note the tools calls to error() in callback and main:
#!/usr/bin/env julia
using RobotOS
@rosimport geometry_msgs.msg: Point, Pose2D
rostypegen()
using geometry_msgs.msg
function callback(msg::Pose2D, pub_obj::Publisher{Point})
pt_msg = Point(msg.x, msg.y, 0.0)
error("this does not throw an error, and instead fails silently (we never reach the next line)")
publish(pub_obj, pt_msg)
end
function loop(pub_obj)
loop_rate = Rate(5.0)
while ! is_shutdown()
npt = Point(rand(), rand(), 0.0)
publish(pub_obj, npt)
rossleep(loop_rate)
end
end
function main()
init_node("rosjl_example")
error("This correctly throws an error")
pub = Publisher{Point}("pts", queue_size=10)
sub = Subscriber{Pose2D}("pose", callback, (pub,), queue_size=10)
loop(pub)
end
if ! isinteractive()
main()
end
Is there any way to to have these errors raised so that the process exits? Having them fail silently makes debugging far more difficult. Thanks!
The text was updated successfully, but these errors were encountered:
The callbacks are run in a separate julia process which will die if there's an uncaught error. One possible solution is to try/catch any errors using standard Julia control flow (e.g., as done here) and do whatever logic you'd like (shutting down the program, printing the error and stack trace and continuing on, etc.).
Makes sense! I put together a little macro that has proved to be very useful if you (or anyone else) finds a need for it:
macro debugtask(ex)
quote
try
$(esc(ex))
catch e
bt = stacktrace(catch_backtrace())
io = IOBuffer()
showerror(io, e, bt)
errstr = String(take!(io))
RobotOS.logfatal("Error: $errstr")
exit()
end
end
end
function foo_callback(msg)
@debugtask begin
error("whoops")
end
end
Now when the error is thrown it shuts down the node and causes the error message to be logged to stderr and /rosout as one would expect in Python.
No errors are printed to stdout. Roslaunch is configured with output="screen". Here's an example (note the tools calls to error() in callback and main:
Is there any way to to have these errors raised so that the process exits? Having them fail silently makes debugging far more difficult. Thanks!
The text was updated successfully, but these errors were encountered: