diff --git a/en/SUMMARY.md b/en/SUMMARY.md index 6cc692a573bb..b1c4bb3649c2 100644 --- a/en/SUMMARY.md +++ b/en/SUMMARY.md @@ -690,8 +690,10 @@ * [Test MC_05 - Indoor Flight (Manual Modes)](test_cards/mc_05_indoor_flight_manual_modes.md) * [Unit Tests](test_and_ci/unit_tests.md) * [Continuous Integration](test_and_ci/continous_integration.md) - * [MAVSDK Integration Testing](test_and_ci/integration_testing_mavsdk.md) - * [ROS Integration Testing](test_and_ci/integration_testing.md) + * [Integration Testing](test_and_ci/integration_testing.md) + * [MAVSDK Integration Testing](test_and_ci/integration_testing_mavsdk.md) + * [PX4 ROS2 Interface Library Integration Testing](test_and_ci/integration_testing_px4_ros2_interface.md) + * [ROS 1 Integration Testing](test_and_ci/integration_testing_ros1_mavros.md) * [Docker Containers](test_and_ci/docker.md) * [Maintenance](test_and_ci/maintenance.md) * [Drone Apps & APIs](robotics/README.md) diff --git a/en/ros2/px4_ros2_interface_lib.md b/en/ros2/px4_ros2_interface_lib.md index 4212ef16c5c1..a5b481d599f5 100644 --- a/en/ros2/px4_ros2_interface_lib.md +++ b/en/ros2/px4_ros2_interface_lib.md @@ -50,20 +50,4 @@ To get started using the library within an existing ROS 2 workspace: When opening a pull request to PX4, CI runs the library integration tests. These test that mode registration, failsafes, and mode replacement, work as expected. -The tests can also be run locally from PX4: - -```sh -./test/ros_test_runner.py -``` - -And to run only a single case: - -```sh -./test/ros_test_runner.py --verbose --case -``` - -You can list the available test cases with: - -```sh -./test/ros_test_runner.py --list-cases -``` +For more information see [PX4 ROS2 Interface Library Integration Testing](../test_and_ci/integration_testing_px4_ros2_interface.md). diff --git a/en/simulation/README.md b/en/simulation/README.md index 8e26cf40ea9c..8352089f3a50 100644 --- a/en/simulation/README.md +++ b/en/simulation/README.md @@ -155,9 +155,8 @@ make px4_sitl none_iris The simulation can be further configured via environment variables: -- `PX4_ESTIMATOR`: This variable configures which estimator to use. - Possible options are: `ekf2` (default), `lpe` (deprecated). - It can be set via `export PX4_ESTIMATOR=lpe` before running the simulation. +- Any of the [PX4 parameters](../advanced_config/parameter_reference.md) can be overridden via `export PX4_PARAM_{name}={value}`. + For example changing the estimator: `export PX4_PARAM_SYS_MC_EST_GROUP=3`. The syntax described here is simplified, and there are many other options that you can configure via _make_ - for example, to set that you wish to connect to an IDE or debugger. For more information see: [Building the Code > PX4 Make Build Targets](../dev_setup/building_px4.md#px4-make-build-targets). diff --git a/en/test_and_ci/README.md b/en/test_and_ci/README.md index fc17ee848621..dbb1aa7c11f3 100644 --- a/en/test_and_ci/README.md +++ b/en/test_and_ci/README.md @@ -8,7 +8,9 @@ Test topics include: - [Test Flights](../test_and_ci/test_flights.md) - How to make test flights (e.g. to [test PRs](../contribute/code.md#pull-requests)) - [Unit Tests](../test_and_ci/unit_tests.md) - [Continuous Integration (CI)](../test_and_ci/continous_integration.md) -- [ROS Integration Testing](../test_and_ci/integration_testing.md) -- [MAVSDK Integration Testing](../test_and_ci/integration_testing_mavsdk.md) +- [Integration Testing](../test_and_ci/integration_testing.md) + - [MAVSDK Integration Testing](../test_and_ci/integration_testing_mavsdk.md) + - [PX4 ROS2 Interface Library Integration Testing](../test_and_ci/integration_testing_px4_ros2_interface.md) + - [ROS 1 Integration Testing](../test_and_ci/integration_testing_ros1_mavros.md) (Deprecated) - [Docker](../test_and_ci/docker.md) - [Maintenance](../test_and_ci/maintenance.md) diff --git a/en/test_and_ci/integration_testing.md b/en/test_and_ci/integration_testing.md index 6ca74940f3c0..e8ee3cd54a84 100644 --- a/en/test_and_ci/integration_testing.md +++ b/en/test_and_ci/integration_testing.md @@ -1,152 +1,13 @@ -# Integration Testing using ROS +# Integration Testing -This topic explains how to run (and extend) PX4's ROS-based integration tests. +Integration tests are used to verify how well larger parts of a system work together. +In PX4 this generally means testing whole features of a vehicle, usually running in simulation. +The tests are run in [Continuous Integration (CI)](../test_and_ci/continous_integration.md) on every pull request. -:::note -[MAVSDK Integration Testing](../test_and_ci/integration_testing_mavsdk.md) is preferred when writing new tests. -Use the ROS-based integration test framework for use cases that _require_ ROS (e.g. object avoidance). +- [MAVSDK Integration Testing](../test_and_ci/integration_testing_mavsdk.md) - MAVSDK-based test framework for PX4. + This is the recommended framework for writing new Integration tests is MAVSDK. +- [PX4 ROS2 Interface Library Integration Testing](../test_and_ci/integration_testing_px4_ros2_interface.md) - Integration Tests for the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md). -All PX4 integraton tests are executed automatically by our [Continuous Integration](../test_and_ci/continous_integration.md) system. -::: +The following framework should only be used for tests that require ROS 1: -## Prerequisites: - -- [jMAVSim Simulator](../sim_jmavsim/README.md) -- [Gazebo Classic Simulator](../sim_gazebo_classic/README.md) -- [ROS and MAVROS](../simulation/ros_interface.md) - -## Execute Tests - -To run the MAVROS tests: - -```sh -source /devel/setup.bash -cd -make px4_sitl_default sitl_gazebo -make -``` - -`test_target` is a makefile targets from the set: _tests_mission_, _tests_mission_coverage_, _tests_offboard_ and _tests_avoidance_. - -Test can also be executed directly by running the test scripts, located under `test/`: - -```sh -source /devel/setup.bash -cd -make px4_sitl_default sitl_gazebo -./test/ -``` - -For example: - -```sh -./test/rostest_px4_run.sh mavros_posix_tests_offboard_posctl.test -``` - -Tests can also be run with a GUI to see what's happening (by default the tests run "headless"): - -```sh -./test/rostest_px4_run.sh mavros_posix_tests_offboard_posctl.test gui:=true headless:=false -``` - -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/](https://github.com/PX4/PX4-Autopilot/tree/main/integrationtests/python_src/px4_it/mavros)). -The official ROS documentation also contains information on how to use [unittest](http://wiki.ros.org/unittest) (on which this test suite is based). - -To write a new test: - -1. Create a new test script by copying the empty test skeleton below: - - ```python - #!/usr/bin/env python - # [... LICENSE ...] - - # - # @author Example Author - # - PKG = 'px4' - - import unittest - import rospy - import rosbag - - from sensor_msgs.msg import NavSatFix - - class MavrosNewTest(unittest.TestCase): - """ - Test description - """ - - def setUp(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 = False - - def tearDown(self): - pass - - # - # General callback functions used in tests - # - def global_position_callback(self, data): - self.has_global_pos = True - - def test_method(self): - """Test method description""" - - # FIXME: hack to wait for simulation to be ready - while not self.has_global_pos: - self.rate.sleep() - - # TODO: execute test - - if __name__ == '__main__': - import rostest - rostest.rosrun(PKG, 'mavros_new_test', MavrosNewTest) - ``` - -1. Run the new test only - - - Start the simulator: - - ```sh - cd - source Tools/simulation/gazebo/setup_gazebo.bash - roslaunch launch/mavros_posix_sitl.launch - ``` - - - Run test (in a new shell): - - ```sh - cd - source Tools/simulation/gazebo/setup_gazebo.bash - rosrun px4 mavros_new_test.py - ``` - -1. Add new test node to a launch file - - - In `test/` create a new `.test` ROS launch file. - - Call the test file using one of the base scripts _rostest_px4_run.sh_ or _rostest_avoidance_run.sh_ - -1. (Optional) Create a new target in the Makefile - - - Open the Makefile - - Search the _Testing_ section - - Add a new target name and call the test - - For example: - - ```sh - tests_: rostest - @"$(SRC_DIR)"/test/rostest_px4_run.sh mavros_posix_tests_.test - ``` - -Run the tests as described above. +- [ROS 1 Integration Testing](../test_and_ci/integration_testing_ros1_mavros.md) (Deprecated) diff --git a/en/test_and_ci/integration_testing_mavsdk.md b/en/test_and_ci/integration_testing_mavsdk.md index afc92caedb98..adc93035bab4 100644 --- a/en/test_and_ci/integration_testing_mavsdk.md +++ b/en/test_and_ci/integration_testing_mavsdk.md @@ -7,6 +7,10 @@ In future we plan to generalise them for any platform/hardware. The instructions below explain how to setup and run the tests locally. +:::note +This is the recommended integration test framework for PX4. +::: + ## Prerequisites ### Setup Developer Environment @@ -47,21 +51,20 @@ To run all SITL tests as defined in [sitl.json](https://github.com/PX4/PX4-Autop test/mavsdk_tests/mavsdk_test_runner.py test/mavsdk_tests/configs/sitl.json --speed-factor 10 ``` -This will list all of the tests and then run them sequentially. +This will list all the tests and then run them sequentially. To see all possible command line arguments use the `-h` argument: ```sh -test/mavsdk_tests/mavsdk_test_runner.py -h - -usage: mavsdk_test_runner.py [-h] [--log-dir LOG_DIR] [--speed-factor SPEED_FACTOR] [--iterations ITERATIONS] [--abort-early] [--gui] [--model MODEL] - [--case CASE] [--debugger DEBUGGER] [--verbose] +usage: mavsdk_test_runner.py [-h] [--log-dir LOG_DIR] [--speed-factor SPEED_FACTOR] [--iterations ITERATIONS] [--abort-early] + [--gui] [--model MODEL] [--case CASE] [--debugger DEBUGGER] [--upload] [--force-color] + [--verbose] [--build-dir BUILD_DIR] config_file positional arguments: config_file JSON config file to use -optional arguments: +options: -h, --help show this help message and exit --log-dir LOG_DIR Directory for log files --speed-factor SPEED_FACTOR @@ -71,9 +74,13 @@ optional arguments: --abort-early abort on first unsuccessful test --gui display the visualization for a simulation --model MODEL only run tests for one model - --case CASE only run tests for one case + --case CASE only run tests for one case (or multiple cases with wildcard '*') --debugger DEBUGGER choice from valgrind, callgrind, gdb, lldb + --upload Upload logs to logs.px4.io + --force-color Force colorized output --verbose enable more verbose output + --build-dir BUILD_DIR + relative path where the built files are stored ``` ## Run a Single Test diff --git a/en/test_and_ci/integration_testing_px4_ros2_interface.md b/en/test_and_ci/integration_testing_px4_ros2_interface.md new file mode 100644 index 000000000000..1c967e89f6c5 --- /dev/null +++ b/en/test_and_ci/integration_testing_px4_ros2_interface.md @@ -0,0 +1,29 @@ +# Integration Testing for the PX4 ROS 2 Interface Library + +This topic outlines the integration tests for the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md). + +These test that mode registration, failsafes, and mode replacement, work as expected. + +## CI Testing + +When opening a pull request to PX4, CI runs the library integration tests. + +## Running Tests Locally + +The tests can also be run locally from PX4: + +```sh +./test/ros_test_runner.py +``` + +And to run only a single case: + +```sh +./test/ros_test_runner.py --verbose --case +``` + +You can list the available test cases with: + +```sh +./test/ros_test_runner.py --list-cases +``` diff --git a/en/test_and_ci/integration_testing_ros1_mavros.md b/en/test_and_ci/integration_testing_ros1_mavros.md new file mode 100644 index 000000000000..13bdb3f6bde7 --- /dev/null +++ b/en/test_and_ci/integration_testing_ros1_mavros.md @@ -0,0 +1,155 @@ +# Integration Testing using ROS 1 + +This topic explains how to run (and extend) PX4's ROS (1) and MAVROS -based integration tests. + +:::warning This test framework is deprecated. +It should be used only for new test cases that _require_ ROS 1. + +[MAVSDK Integration Testing](../test_and_ci/integration_testing_mavsdk.md) is preferred when writing new tests. +::: + +:::note +All PX4 integration tests are executed automatically by our [Continuous Integration](../test_and_ci/continous_integration.md) system. +::: + +## Prerequisites + +- [jMAVSim Simulator](../sim_jmavsim/README.md) +- [Gazebo Classic Simulator](../sim_gazebo_classic/README.md) +- [ROS and MAVROS](../simulation/ros_interface.md) + +## Execute Tests + +To run the MAVROS tests: + +```sh +source /devel/setup.bash +cd +make px4_sitl_default sitl_gazebo +make +``` + +`test_target` is a makefile targets from the set: _tests_mission_, _tests_mission_coverage_, _tests_offboard_ and _tests_avoidance_. + +Test can also be executed directly by running the test scripts, located under `test/`: + +```sh +source /devel/setup.bash +cd +make px4_sitl_default sitl_gazebo +./test/ +``` + +For example: + +```sh +./test/rostest_px4_run.sh mavros_posix_tests_offboard_posctl.test +``` + +Tests can also be run with a GUI to see what's happening (by default the tests run "headless"): + +```sh +./test/rostest_px4_run.sh mavros_posix_tests_offboard_posctl.test gui:=true headless:=false +``` + +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/](https://github.com/PX4/PX4-Autopilot/tree/main/integrationtests/python_src/px4_it/mavros)). +The official ROS documentation also contains information on how to use [unittest](http://wiki.ros.org/unittest) (on which this test suite is based). + +To write a new test: + +1. Create a new test script by copying the empty test skeleton below: + + ```python + #!/usr/bin/env python + # [... LICENSE ...] + + # + # @author Example Author + # + PKG = 'px4' + + import unittest + import rospy + import rosbag + + from sensor_msgs.msg import NavSatFix + + class MavrosNewTest(unittest.TestCase): + """ + Test description + """ + + def setUp(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 = False + + def tearDown(self): + pass + + # + # General callback functions used in tests + # + def global_position_callback(self, data): + self.has_global_pos = True + + def test_method(self): + """Test method description""" + + # FIXME: hack to wait for simulation to be ready + while not self.has_global_pos: + self.rate.sleep() + + # TODO: execute test + + if __name__ == '__main__': + import rostest + rostest.rosrun(PKG, 'mavros_new_test', MavrosNewTest) + ``` + +1. Run the new test only + + - Start the simulator: + + ```sh + cd + source Tools/simulation/gazebo/setup_gazebo.bash + roslaunch launch/mavros_posix_sitl.launch + ``` + + - Run test (in a new shell): + + ```sh + cd + source Tools/simulation/gazebo/setup_gazebo.bash + rosrun px4 mavros_new_test.py + ``` + +1. Add new test node to a launch file + + - In `test/` create a new `.test` ROS launch file. + - Call the test file using one of the base scripts _rostest_px4_run.sh_ or _rostest_avoidance_run.sh_ + +1. (Optional) Create a new target in the Makefile + + - Open the Makefile + - Search the _Testing_ section + - Add a new target name and call the test + + For example: + + ```sh + tests_: rostest + @"$(SRC_DIR)"/test/rostest_px4_run.sh mavros_posix_tests_.test + ``` + +Run the tests as described above.