Skip to content

Commit

Permalink
CI testing and code coverage
Browse files Browse the repository at this point in the history
  • Loading branch information
gstavrinos committed Dec 26, 2020
1 parent d92cfed commit dd04af8
Show file tree
Hide file tree
Showing 13 changed files with 400 additions and 4 deletions.
23 changes: 19 additions & 4 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ julia:

dist: focal

# codecov: true
codecov: true

sudo: required

Expand All @@ -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
Expand Down
26 changes: 26 additions & 0 deletions test/actionlib_client.jl
Original file line number Diff line number Diff line change
@@ -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

49 changes: 49 additions & 0 deletions test/actionlib_server.jl
Original file line number Diff line number Diff line change
@@ -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

36 changes: 36 additions & 0 deletions test/nodehandle.jl
Original file line number Diff line number Diff line change
@@ -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.")
6 changes: 6 additions & 0 deletions test/package.jl
Original file line number Diff line number Diff line change
@@ -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.")
23 changes: 23 additions & 0 deletions test/publisher.jl
Original file line number Diff line number Diff line change
@@ -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

18 changes: 18 additions & 0 deletions test/roscpp.jl
Original file line number Diff line number Diff line change
@@ -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.")
34 changes: 34 additions & 0 deletions test/runtests.jl
Original file line number Diff line number Diff line change
@@ -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")
28 changes: 28 additions & 0 deletions test/serviceClient.jl
Original file line number Diff line number Diff line change
@@ -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

31 changes: 31 additions & 0 deletions test/serviceServer.jl
Original file line number Diff line number Diff line change
@@ -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
28 changes: 28 additions & 0 deletions test/subscriber.jl
Original file line number Diff line number Diff line change
@@ -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
62 changes: 62 additions & 0 deletions test/tf.jl
Original file line number Diff line number Diff line change
@@ -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.")
Loading

0 comments on commit dd04af8

Please sign in to comment.