Skip to content

Commit

Permalink
Improve systemtests (#378)
Browse files Browse the repository at this point in the history
* clean processes automatically at exit; replaced custom Waiter class with Popen.wait() function
* cleanup
  • Loading branch information
julienthevenoz committed Dec 7, 2023
1 parent 9050b37 commit 5bd08d8
Show file tree
Hide file tree
Showing 2 changed files with 61 additions and 46 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/systemtests.yml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ name: System Tests

on:
push:
branches: [ "feature_systemtests" ]
branches: [ "feature-systemtests-better" ]
# manual trigger
workflow_dispatch:

Expand Down
105 changes: 60 additions & 45 deletions systemtests/run_test.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/usr/bin/env python3
#!/usr/bin/env python3
from subprocess import Popen, PIPE
from subprocess import Popen, PIPE, TimeoutExpired
import time
import os
import signal
Expand All @@ -12,45 +12,58 @@
import atexit


class Waiter:
'''A helper class which sleeps the amount of seconds it is instanciated with. If the user interrupts with ^C during the waiting time (zB if the drone crashes), it will stop sleeping and continue
to the end of the program where all child processes are terminated correctly. All subsequent Waiter() calls will be ignored'''
wait=True
def clean_process(process:Popen) -> int :
'''Kills process and its children on exit if they aren't already terminated (called with atexit). Returns 0 on success, 1 on failure'''

if process.poll() == None:
group_id = os.getpgid(process.pid)
print(f"cleaning process {group_id}")
os.killpg(group_id, signal.SIGTERM)
time.sleep(0.01) #necessary delay before first poll
i=0
while i < 10 and process.poll() == None: #in case the process termination is lazy and takes some time, we wait up to 0.5 sec per process
if process.poll() != None:
return 0 #if we have a returncode-> it terminated
time.sleep(0.05) #if not wait a bit longer
if(i == 9):
print(f"Process group {process} with groupID {group_id} didn't terminate correctly")
return 1 #after 0.5s we stop waiting and consider it did not terminate correctly
return 0
else:
return 0 #process already terminated

def __init__(self, seconds):
if seconds > 0 :
self.sleep(seconds)

def sleep(self, seconds):
start=time.time()
while Waiter.wait and time.time()<(start+seconds):
try:
time.sleep(1)
except KeyboardInterrupt:
Waiter.wait = False

def record_start_and_terminate(testname:str, testduration:int, bagfolder:str):
'''Helper function that starts recording the /tf topic in a rosbag, starts the test, waits, closes the rosbag and terminate all processes

def record_start_and_clean(testname:str, max_wait:int, bagfolder:str):
'''Starts recording the /tf topic in a rosbag, starts the test, waits, closes the rosbag and terminate all processes. max_wait is the max amount of time you want to wait
before forcefully terminating the test flight script (in case it never finishes correctly).
NB the testname must be the name of the crayzflie_examples executable (ie the CLI grammar "ros2 run crazyflie_examples testname" must be valid)'''

index = bagfolder.find("bag_")
bagname = bagfolder[index:]


src = "source " + bagfolder[:index-9] + "install/setup.bash" # -> "source /home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/install/setup.bash"

command = f"{src} && ros2 bag record -s mcap -o {testname}_{bagname} /tf"
record_bag = Popen(command, shell=True, cwd=bagfolder, stderr=PIPE, stdout=True,
start_new_session=True, text=True, executable="/bin/bash")

command = f"{src} && ros2 run crazyflie_examples {testname}"
start_flight_test = Popen(command, shell=True, stderr=True, stdout=True,
start_new_session=True, text=True, executable="/bin/bash")

try:
command = f"{src} && ros2 bag record -s mcap -o {testname}_{bagname} /tf"
record_bag = Popen(command, shell=True, cwd=bagfolder, stderr=PIPE, stdout=True,
start_new_session=True, text=True, executable="/bin/bash")
atexit.register(clean_process, record_bag)

command = f"{src} && ros2 run crazyflie_examples {testname}"
start_flight_test = Popen(command, shell=True, stderr=True, stdout=True,
start_new_session=True, text=True, executable="/bin/bash")
atexit.register(clean_process, start_flight_test)

Waiter(testduration) #wait x seconds for the crazyflie to fly the test
start_flight_test.wait(timeout=max_wait) #raise Timeoutexpired after max_wait seconds if start_flight_test didn't finish by itself
clean_process(start_flight_test)
clean_process(record_bag)

os.killpg(os.getpgid(start_flight_test.pid), signal.SIGTERM) #kill flight test and all of its child processes
os.killpg(os.getpgid(record_bag.pid), signal.SIGTERM) #kill rosbag
except TimeoutExpired: #if max_wait is exceeded
clean_process(start_flight_test)
clean_process(record_bag)

except KeyboardInterrupt: #if drone crashes, user can ^C to skip the waiting
clean_process(start_flight_test)
clean_process(record_bag)

#if something went wrong with the bash command lines in Popen, print the error
if record_bag.stderr != None:
Expand All @@ -59,9 +72,9 @@ def record_start_and_terminate(testname:str, testduration:int, bagfolder:str):
print(testname," start_flight flight stderr: ", start_flight_test.stderr.readlines())



def translate_and_plot(testname:str, bagfolder:str):
'''Helper function that translates rosbag .mcap format to .csv, then uses that csv to plot a pdf '''
'''Translates rosbag .mcap format to .csv, then uses that csv to plot a pdf '''

index = bagfolder.find("bag_")
bagname = bagfolder[index:]
# NB : the mcap filename is almost the same as the folder name but has _0 at the end
Expand All @@ -81,15 +94,18 @@ def translate_and_plot(testname:str, bagfolder:str):
plotter.create_figures(test_file, rosbag_csv, output_pdf) #plot the data



if __name__ == "__main__":

path = Path(__file__) #Path(__file__) should be "/home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/src/crazyswarm2/systemtests/newsub.py" ; path.parents[0]=.../systemstests
path = Path(__file__) #Path(__file__) in this case "/home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/src/crazyswarm2/systemtests/newsub.py" ; path.parents[0]=.../systemstests

#delete results, logs and bags of previous experiments
shutil.rmtree(path.parents[3].joinpath("bagfiles"))
shutil.rmtree(path.parents[3].joinpath("results"))
shutil.rmtree(Path.home() / ".ros/log")

#delete results, logs and bags of previous experiments if they exist
if(Path(path.parents[3].joinpath("bagfiles")).exists()):
shutil.rmtree(path.parents[3].joinpath("bagfiles"))
if(Path(path.parents[3].joinpath("results")).exists()):
shutil.rmtree(path.parents[3].joinpath("results"))
if(Path(Path.home() / ".ros/log").exists()):
shutil.rmtree(Path.home() / ".ros/log")

#create the folder where we will record the different bags and the folder where the results pdf will be saved
now = datetime.now().strftime('%d_%m_%Y-%H_%M_%S')
Expand All @@ -102,14 +118,13 @@ def translate_and_plot(testname:str, bagfolder:str):
command = f"{src} && ros2 launch crazyflie launch.py"
launch_crazyswarm = Popen(command, shell=True, stderr=True, stdout=True, text=True,
start_new_session=True, executable="/bin/bash")
atexit.register(clean_process, launch_crazyswarm) #atexit helps us to make sure processes are cleaned even if script exits unexpectedly

time.sleep(1)
print("f8")
record_start_and_terminate("figure8", 20, bagfolder)
print("multi")
record_start_and_terminate("multi_trajectory", 80, bagfolder)
record_start_and_clean("figure8", 20, bagfolder)
record_start_and_clean("multi_trajectory", 80, bagfolder)

os.killpg(os.getpgid(launch_crazyswarm.pid), signal.SIGTERM) #kill crazyswarm and all of its child processes
clean_process(launch_crazyswarm) #kill crazyswarm and all of its child processes


#test done, now we create the results pdf
Expand Down

0 comments on commit 5bd08d8

Please sign in to comment.