The .test files launch the corresponding Python tests defined in integrationtests/python_src/px4_it/mavros/
Write a New MAVROS Test (Python)
This section explains how to write a new python test using ROS(1)/MAVROS, test it, and add it to the PX4 test suite.
We recommend you review the existing tests as examples/inspiration (integrationtests/python_src/px4_it/mavros/). The official ROS documentation also contains information on how to use unittest (on which this test suite is based).
To write a new test:
Create a new test script by copying the empty test skeleton below:
#!/usr/bin/env python# [... LICENSE ...]## @author Example Author <author@example.com>#PKG ='px4'import unittestimport rospyimport rosbagfrom sensor_msgs.msg import NavSatFixclassMavrosNewTest(unittest.TestCase):""" Test description """defsetUp(self): rospy.init_node('test_node', anonymous=True) rospy.wait_for_service('mavros/cmd/arming', 30) rospy.Subscriber("mavros/global_position/global", NavSatFix, self.global_position_callback) self.rate = rospy.Rate(10)# 10hz self.has_global_pos =FalsedeftearDown(self):pass## General callback functions used in tests#defglobal_position_callback(self,data): self.has_global_pos =Truedeftest_method(self):"""Test method description"""# FIXME: hack to wait for simulation to be readywhilenot self.has_global_pos: self.rate.sleep()# TODO: execute testif__name__=='__main__':import rostest rostest.rosrun(PKG, 'mavros_new_test', MavrosNewTest)
Run the new test only
Start the simulator:
cd <PX4-Autopilot_clone>
source Tools/setup_gazebo.bash
roslaunch launch/mavros_posix_sitl.launch
Run test (in a new shell):
cd <PX4-Autopilot_clone>
source Tools/setup_gazebo.bash
rosrun px4 mavros_new_test.py
Add new test node to a launch file
In test/ create a new <test_name>.test ROS launch file.
Call the test file using one of the base scripts rostest_px4_run.sh or rostest_avoidance_run.sh