From dd04af86de672ae02f86831727e412d78a004922 Mon Sep 17 00:00:00 2001 From: George Stavrinos Date: Sat, 26 Dec 2020 13:35:42 +0200 Subject: [PATCH] CI testing and code coverage --- .travis.yml | 23 ++++++++++++--- test/actionlib_client.jl | 26 +++++++++++++++++ test/actionlib_server.jl | 49 +++++++++++++++++++++++++++++++ test/nodehandle.jl | 36 +++++++++++++++++++++++ test/package.jl | 6 ++++ test/publisher.jl | 23 +++++++++++++++ test/roscpp.jl | 18 ++++++++++++ test/runtests.jl | 34 ++++++++++++++++++++++ test/serviceClient.jl | 28 ++++++++++++++++++ test/serviceServer.jl | 31 ++++++++++++++++++++ test/subscriber.jl | 28 ++++++++++++++++++ test/tf.jl | 62 ++++++++++++++++++++++++++++++++++++++++ test/time.jl | 40 ++++++++++++++++++++++++++ 13 files changed, 400 insertions(+), 4 deletions(-) create mode 100644 test/actionlib_client.jl create mode 100644 test/actionlib_server.jl create mode 100644 test/nodehandle.jl create mode 100644 test/package.jl create mode 100644 test/publisher.jl create mode 100644 test/roscpp.jl create mode 100644 test/runtests.jl create mode 100644 test/serviceClient.jl create mode 100644 test/serviceServer.jl create mode 100644 test/subscriber.jl create mode 100644 test/tf.jl create mode 100644 test/time.jl diff --git a/.travis.yml b/.travis.yml index 9b90432..996e291 100644 --- a/.travis.yml +++ b/.travis.yml @@ -4,7 +4,7 @@ julia: dist: focal -# codecov: true +codecov: true sudo: required @@ -13,16 +13,31 @@ before_install: - sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' - sudo apt-key adv --keyserver 'hkp://keyserver.ubuntu.com:80' --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654 - sudo apt-get update - - sudo apt-get install -y python3-rosdep ros-noetic-ros-base ros-noetic-geometry2 + - sudo apt-get install -y python3-rosdep ros-noetic-ros-base ros-noetic-geometry2 ros-noetic-std-msgs ros-noetic-std-srvs ros-noetic-actionlib-tutorials - source /opt/ros/noetic/setup.bash - sudo rosdep init - rosdep update - sudo cp /usr/lib/x86_64-linux-gnu/libstdc++.so.6 ~/julia/lib/julia/libstdc++.so.6 -# TODO tests - jobs: include: + - stage: "Tests" + julia: 1.3 + os: linux + script: + - julia --project -e 'using Pkg; + ENV["JULIA_CXX_RTTI"]=1; + Pkg.add("Cxx"); + Pkg.build("Cxx"); + Pkg.add("Documenter"); + Pkg.add("Libdl"); + using Cxx; + Pkg.instantiate();' + - source /opt/ros/noetic/setup.bash && roscore & + - JULIA_NUM_THREADS=4 julia --code-coverage test/runtests.jl + after_success: + - rm src/gen/!(__*) + - julia -e 'using Pkg; cd(Pkg.dir("ROS")); Pkg.add("Coverage"); using Coverage; Codecov.submit(Codecov.process_folder())' - stage: "Documentation" julia: 1.3 os: linux diff --git a/test/actionlib_client.jl b/test/actionlib_client.jl new file mode 100644 index 0000000..1c901be --- /dev/null +++ b/test/actionlib_client.jl @@ -0,0 +1,26 @@ +ROS.@include actionlib_tutorials: FibonacciAction, FibonacciFeedback, FibonacciResult, FibonacciGoal + +function testActionClient() + ROS.init("testActionlibClient") + nh = ROS.NodeHandle() + + action_client = ROS.actionlib.SimpleActionClient("test_action_server", ROS.actionlib_tutorials_FibonacciAction, true) + # ROS.actionlib.waitForServer(action_client) + ROS.actionlib.waitForServer(action_client, ROS.Duration(120)) + ROS.actionlib.sendGoal(action_client, ROS.actionlib_tutorials_FibonacciGoal()) + ROS.actionlib.waitForResult(action_client, ROS.Duration(3)) + ROS.actionlib.sendGoalAndWait(action_client, ROS.actionlib_tutorials_FibonacciGoal(), ROS.Duration(3), ROS.Duration(5)) + + action_result_called = ROS.actionlib.getResult(action_client) + ROS.actionlib.cancelAllGoals(action_client) + ROS.actionlib.cancelGoal(action_client) + state = ROS.actionlib.getState(action_client) + ROS.actionlib.getText(state) + ROS.actionlib.isDone(state) + ROS.actionlib.toString(state) + ROS.actionlib.isServerConnected(action_client) + + ROS.actionlib.stopTrackingGoal(action_client) + println("All $(basename(@__FILE__)) tests passed.") +end + diff --git a/test/actionlib_server.jl b/test/actionlib_server.jl new file mode 100644 index 0000000..d853b82 --- /dev/null +++ b/test/actionlib_server.jl @@ -0,0 +1,49 @@ +ROS.@include actionlib_tutorials: FibonacciAction, FibonacciFeedback, FibonacciResult, FibonacciGoal + +action_server = nothing +callback_enabled = false + +function execute_cb() + goal = ROS.actionlib.acceptNewGoal(action_server) + action_feedback = ROS.actionlib_tutorials_FibonacciFeedback() + f::Vector{Number} = [] + for i in 1:100 + push!(f,i) + action_feedback.sequence = f + ROS.actionlib.publishFeedback(action_server, action_feedback) + end + action_result = ROS.actionlib_tutorials_FibonacciResult() + action_result.sequence = f + ROS.actionlib.setSucceeded(action_server, action_result, ":)") + ROS.actionlib.setAborted(action_server, ROS.actionlib_tutorials_FibonacciResult(), "result") + ROS.actionlib.setAborted(action_server) + ROS.actionlib.setPreempted(action_server, ROS.actionlib_tutorials_FibonacciResult(), "result") + ROS.actionlib.setPreempted(action_server) + ROS.actionlib.setSucceeded(action_server) + global callback_enabled = true + return nothing +end + +function testActionServer() + ROS.init("testActionlibServer") + nh = ROS.NodeHandle() + + global action_server = ROS.actionlib.SimpleActionServer("test_action_server", ROS.actionlib_tutorials_FibonacciAction) + ROS.actionlib.start(action_server) + @test ! ROS.actionlib.isActive(action_server) + ROS.actionlib.registerGoalCallback(action_server, execute_cb) + ROS.actionlib.registerPreemptCallback(action_server, execute_cb) + ROS.actionlib.isNewGoalAvailable(action_server) + ROS.actionlib.isPreemptRequested(action_server) + + loop = 500 + while loop > 0 && !callback_enabled + loop -= 1 + ROS.sleep(ROS.Rate(10)) + ROS.spinOnce() + end + @test callback_enabled + ROS.actionlib.shutdown(action_server) + println("All $(basename(@__FILE__)) tests passed.") +end + diff --git a/test/nodehandle.jl b/test/nodehandle.jl new file mode 100644 index 0000000..1bb4c49 --- /dev/null +++ b/test/nodehandle.jl @@ -0,0 +1,36 @@ + +ROS.init("testNodeHandle") +nh = ROS.NodeHandle() + +@test ROS.param(nh, "float_param", 16.7) == 16.7 +@test ROS.param(nh, "int_param", Int32(16)) == 16 +@test ROS.param(nh, "int_param", 16) == 16 +@test ROS.param(nh, "string_param", "s") == "s" +@test ROS.param(nh, "bool_param", true) +@test !ROS.hasParam(nh, "float_param") +@test !ROS.hasParam(nh, "int_param") +@test !ROS.hasParam(nh, "string_param") +@test !ROS.hasParam(nh, "bool_param") +ROS.setParam(nh, "float_param", 16.7) +ROS.setParam(nh, "int_param", Int32(16)) +ROS.setParam(nh, "int_param", 16) +ROS.setParam(nh, "string_param", "s") +ROS.setParam(nh, "bool_param", true) +@test ROS.hasParam(nh, "float_param") +@test ROS.hasParam(nh, "int_param") +@test ROS.hasParam(nh, "string_param") +@test ROS.hasParam(nh, "bool_param") + +ROS.deleteParam(nh, "float_param") +ROS.deleteParam(nh, "int_param") +ROS.deleteParam(nh, "string_param") +ROS.deleteParam(nh, "bool_param") + +@test !ROS.hasParam(nh, "float_param") +@test !ROS.hasParam(nh, "int_param") +@test !ROS.hasParam(nh, "string_param") +@test !ROS.hasParam(nh, "bool_param") + +ROS.shutdown(nh) + +println("All $(basename(@__FILE__)) tests passed.") diff --git a/test/package.jl b/test/package.jl new file mode 100644 index 0000000..a476bbc --- /dev/null +++ b/test/package.jl @@ -0,0 +1,6 @@ + +@test !isempty(ROS.package.command("list")) +@test !isempty(ROS.package.getAll()) +@test !isempty(ROS.package.getPath("std_msgs")) + +println("All $(basename(@__FILE__)) tests passed.") diff --git a/test/publisher.jl b/test/publisher.jl new file mode 100644 index 0000000..82b54eb --- /dev/null +++ b/test/publisher.jl @@ -0,0 +1,23 @@ +ROS.@include std_msgs: Float64MultiArray + +function testPublisher() + ROS.init("testPub") + nh = ROS.NodeHandle() + + pub = ROS.advertise(nh, "test_sub", ROS.std_msgs_Float64MultiArray, 1) + + ROS.getNumSubscribers(pub) + @test ROS.getTopic(pub) == "/test_sub" + @test ! ROS.isLatched(pub) + + loop = 50 + while loop > 0 + loop -= 1 + ROS.sleep(ROS.Rate(10)) + ROS.publish(pub, ROS.std_msgs_Float64MultiArray()) + ROS.spinOnce() + end + ROS.shutdown(pub) + println("All $(basename(@__FILE__)) tests passed.") +end + diff --git a/test/roscpp.jl b/test/roscpp.jl new file mode 100644 index 0000000..565a389 --- /dev/null +++ b/test/roscpp.jl @@ -0,0 +1,18 @@ + +ROS.init("testBase") +nh = ROS.NodeHandle() + +@test ROS.ok() +ROS.spinOnce() +ROS.info("j") +ROS.info_stream(3.2) +ROS.warn("u") +ROS.warn_stream(2) +ROS.error("l") +ROS.error_stream(16.07) +ROS.fatal("i") +ROS.fatal_stream(true) +ROS.debug("a") +ROS.debug_stream("!") + +println("All $(basename(@__FILE__)) tests passed.") diff --git a/test/runtests.jl b/test/runtests.jl new file mode 100644 index 0000000..194190d --- /dev/null +++ b/test/runtests.jl @@ -0,0 +1,34 @@ +ENV["JULIA_CXX_RTTI"]=1 +using Cxx +using Test +include("../src/ROS.jl") +# using ROS + +ROS.@genNew +ROS.@updateAll + +include("publisher.jl") +include("subscriber.jl") +include("serviceServer.jl") +include("serviceClient.jl") +include("actionlib_client.jl") +include("actionlib_server.jl") + +as = Threads.@spawn testActionServer() +ac = Threads.@spawn testActionClient() +wait(ac) +wait(as) +s = Threads.@spawn testSubscriber() +p = Threads.@spawn testPublisher() +wait(p) +wait(s) +sc = Threads.@spawn testServiceClient() +ss = Threads.@spawn testServiceServer() +wait(sc) +wait(ss) + +include("tf.jl") +include("time.jl") +include("roscpp.jl") +include("package.jl") +include("nodehandle.jl") diff --git a/test/serviceClient.jl b/test/serviceClient.jl new file mode 100644 index 0000000..36a2cd9 --- /dev/null +++ b/test/serviceClient.jl @@ -0,0 +1,28 @@ +ROS.@include std_srvs: SetBool + + +function testServiceClient() + ROS.init("testSC") + nh = ROS.NodeHandle() + + srvc = ROS.serviceClient(nh, "test_srv", ROS.std_srvs_SetBool) + + @test ROS.getService(srvc) == "/test_srv" + @test ROS.isValid(srvc) + + loop = 500 + while loop > 0 + if ROS.exists(srvc) + ROS.call(srvc, ROS.std_srvs_SetBool()) + break + end + loop -= 1 + ROS.sleep(ROS.Rate(10)) + ROS.spinOnce() + end + @test loop > 0 + @test !ROS.isPersistent(srvc) + + println("All $(basename(@__FILE__)) tests passed.") +end + diff --git a/test/serviceServer.jl b/test/serviceServer.jl new file mode 100644 index 0000000..cfc23d7 --- /dev/null +++ b/test/serviceServer.jl @@ -0,0 +1,31 @@ +ROS.@include std_srvs: SetBool + +callback_enabled = false + +function testServiceServer() + ROS.init("testSS") + nh = ROS.NodeHandle() + + srv = ROS.advertiseService(nh, "test_srv", ROS.std_srvs_SetBool_Request, ROS.std_srvs_SetBool_Response, srv_callback) + + @test ROS.getService(srv) == "/test_srv" + + loop = 500 + while loop > 0 && !callback_enabled + loop -= 1 + ROS.sleep(ROS.Rate(10)) + ROS.spinOnce() + end + @test callback_enabled + + ROS.shutdown(srv) + + println("All $(basename(@__FILE__)) tests passed.") +end + +function srv_callback(req,res) + res.success = true + res.message = ":D" + global callback_enabled = true + return true +end diff --git a/test/subscriber.jl b/test/subscriber.jl new file mode 100644 index 0000000..ecf9318 --- /dev/null +++ b/test/subscriber.jl @@ -0,0 +1,28 @@ +ROS.@include std_msgs: Float64MultiArray + +callback_enabled = false + +function testSubscriber() + ROS.init("testSub") + nh = ROS.NodeHandle() + + sub = ROS.subscribe(nh, "test_sub", 1, ROS.std_msgs_Float64MultiArray, callback) + + ROS.getNumPublishers(sub) + @test ROS.getTopic(sub) == "/test_sub" + + loop = 100 + while loop > 0 && !callback_enabled + loop -= 1 + ROS.sleep(ROS.Rate(10)) + ROS.spinOnce() + end + @test callback_enabled + ROS.shutdown(sub) + println("All $(basename(@__FILE__)) tests passed.") +end + +function callback(t) + t.data = [1,2,3,4] + global callback_enabled = true +end diff --git a/test/tf.jl b/test/tf.jl new file mode 100644 index 0000000..2171c96 --- /dev/null +++ b/test/tf.jl @@ -0,0 +1,62 @@ + +ROS.@include geometry_msgs: TransformStamped, PoseStamped, PointStamped, Vector3Stamped + +ROS.init("testTF") +nh = ROS.NodeHandle() + +b = ROS.tf.TransformBroadcaster() +sb = ROS.tf.StaticTransformBroadcaster() +bf = ROS.tf.Buffer() +tl = ROS.tf.TransformListener(bf) + +ts = ROS.geometry_msgs_TransformStamped() +ts.header.stamp = ROS.now() +ts.header.frame_id = "base_link" +ts.child_frame_id = "gps_link" +ts.transform.translation.y = 1.6 +ts.transform.rotation.w = 1 +ts2 = ROS.geometry_msgs_TransformStamped() +ts2.header.stamp = ROS.now() +ts2.header.frame_id = "base_link" +ts2.child_frame_id = "camera_link" +ts2.transform.translation.x = 0.3 +ts2.transform.rotation.w = 1 +tss = [ts,ts2] + +ROS.tf.sendTransform(b, ts) +ROS.tf.sendTransform(b, tss) +ROS.tf.sendTransform(sb, ts) +ROS.tf.sendTransform(sb, tss) + +@test ROS.tf.canTransform(bf, "base_link", "camera_link", ROS.Time(0), ROS.Duration(1)) +@test ROS.tf.canTransform(bf, "gps_link", ROS.Time(0), "camera_link", ROS.Time(0), "base_link", ROS.Duration(1)) + +ROS.tf.lookupTransform(bf, "base_link", "camera_link", ROS.Time(0), ROS.Duration(1)) +ROS.tf.lookupTransform(bf, "gps_link", ROS.Time(0), "camera_link", ROS.Time(0), "base_link", ROS.Duration(1)) + +p = ROS.geometry_msgs_PoseStamped() +p.header.frame_id = "camera_link" +p.pose.position.x = 1 +p.pose.position.y = 0.6 +p.pose.orientation.w = 1 + +ROS.tf.transform(bf, p, "gps_link", ROS.Time(0), "base_link", ROS.Duration(2)) +ROS.tf.transform(bf, p, "base_link", ROS.Duration(2)) + +p = ROS.geometry_msgs_PointStamped() +p.header.frame_id = "camera_link" +p.point.x = 1 +p.point.y = 0.6 + +ROS.tf.transform(bf, p, "gps_link", ROS.Time(0), "base_link", ROS.Duration(2)) +ROS.tf.transform(bf, p, "base_link", ROS.Duration(2)) + +p = ROS.geometry_msgs_Vector3Stamped() +p.header.frame_id = "camera_link" +p.vector.x = 1 +p.vector.y = 0.6 + +ROS.tf.transform(bf, p, "gps_link", ROS.Time(0), "base_link", ROS.Duration(2)) +ROS.tf.transform(bf, p, "base_link", ROS.Duration(2)) + +println("All $(basename(@__FILE__)) tests passed.") diff --git a/test/time.jl b/test/time.jl new file mode 100644 index 0000000..a548320 --- /dev/null +++ b/test/time.jl @@ -0,0 +1,40 @@ + +ROS.init("testTime") +nh = ROS.NodeHandle() +r = ROS.Rate(2) +d = ROS.Duration(2) +t = ROS.Time(2) +ROS.Rate(d) +ROS.reset(r) +ROS.sleep(r) +ROS.cycleTime(r) +ROS.expectedCycleTime(r) + +ROS.Duration() +ROS.Duration(r) +ROS.Duration(2,3) +ROS.sleep(d) +@test ROS.toSec(d) == 2 + +ROS.Time() +ROS.Time(2,3) +@test ROS.toSec(t) == 2 +ROS.init(t) +@test !ROS.isSimTime(t) +@test ROS.isSystemTime(t) +@test ROS.isValid(t) +ROS.now(t) +ROS.setNow(t, ROS.now()) +ROS.setNow(t, ROS.Time(0)) +ROS.sleepUntil(t, ROS.now()) +ROS.useSystemTime(t) +ROS.shutdown(t) +t1 = ROS.now() +t.sec = t1.sec + 2 +t.nsec = 0 +ROS.toSec(t1 + d) +@test ROS.toSec(d + d) == 4 +@test ROS.toSec(d - d) == 0 +ROS.waitForValid(t) + +println("All $(basename(@__FILE__)) tests passed.")