From 473a6e25756a61eafe054ff0d8de0724d7b8c94b Mon Sep 17 00:00:00 2001 From: Jakub Delicat Date: Mon, 11 Sep 2023 12:30:17 +0200 Subject: [PATCH 01/12] added scan test Signed-off-by: Jakub Delicat --- rosbot_gazebo/test/simulation_test_node.py | 16 +++++++++++++++- 1 file changed, 15 insertions(+), 1 deletion(-) diff --git a/rosbot_gazebo/test/simulation_test_node.py b/rosbot_gazebo/test/simulation_test_node.py index f21a1788..f2ba5c16 100644 --- a/rosbot_gazebo/test/simulation_test_node.py +++ b/rosbot_gazebo/test/simulation_test_node.py @@ -14,6 +14,7 @@ # limitations under the License. import rclpy +import tf_transformations from threading import Event from threading import Thread @@ -22,10 +23,11 @@ from geometry_msgs.msg import Twist from nav_msgs.msg import Odometry -import tf_transformations +from sensor_msgs.msg import LaserScan class SimulationTestNode(Node): + MINIMAL_LASER_SCAN_RANGE = 0.1 __test__ = False def __init__(self, name="test_node"): @@ -37,6 +39,7 @@ def __init__(self, name="test_node"): self.goal_x_event = Event() self.goal_y_event = Event() self.goal_theta_event = Event() + self.scan_event = Event() def set_and_publish_velocities( self, goal_x_distance, goal_y_distance, goal_theta_angle @@ -52,6 +55,11 @@ def create_test_subscribers_and_publishers(self): self.odom_sub = self.create_subscription( Odometry, "/odometry/filtered", self.odometry_callback, 10 ) + + self.scan_sub = self.create_subscription( + LaserScan, "/scan", self.scan_callback, 10 + ) + self.timer = None def start_node_thread(self): @@ -83,6 +91,12 @@ def odometry_callback(self, data: Odometry): if yaw > self.goal_theta_angle: self.goal_theta_event.set() + def scan_callback(self, data: LaserScan): + if min(data.ranges) < self.MINIMAL_LASER_SCAN_RANGE: + print(f"Ranges: {data.ranges}") + return + self.scan_event.set() + def publish_cmd_vel_messages(self): twist_msg = Twist() twist_msg.linear.x = self.goal_x_distance From a704d1454fd96bf2d58e6f964dc49b8080e1af40 Mon Sep 17 00:00:00 2001 From: Jakub Delicat Date: Tue, 10 Oct 2023 11:41:17 +0200 Subject: [PATCH 02/12] Configurated workspace Signed-off-by: Jakub Delicat --- .gitignore | 5 +++-- .vscode/extensions.json | 9 +++++++++ .vscode/settings.json | 11 +++++++++++ .wordlist.txt | 4 +++- 4 files changed, 26 insertions(+), 3 deletions(-) create mode 100644 .vscode/extensions.json create mode 100644 .vscode/settings.json diff --git a/.gitignore b/.gitignore index 929fbf49..b09c4ff1 100644 --- a/.gitignore +++ b/.gitignore @@ -1,8 +1,9 @@ -.vscode +*.pyc + +# ROS 2 build folders build install log -*.pyc # ROSbots submodules rosbot_hardware_interfaces/ diff --git a/.vscode/extensions.json b/.vscode/extensions.json new file mode 100644 index 00000000..dd34646d --- /dev/null +++ b/.vscode/extensions.json @@ -0,0 +1,9 @@ +{ + "recommendations": [ + "ms-iot.vscode-ros", + "ms-python.black-formatter", + "streetsidesoftware.code-spell-checker", + "kevinrose.vsc-python-indent", + "ms-python.python" + ] +} \ No newline at end of file diff --git a/.vscode/settings.json b/.vscode/settings.json new file mode 100644 index 00000000..c7b8cf91 --- /dev/null +++ b/.vscode/settings.json @@ -0,0 +1,11 @@ +{ + "cSpell.customDictionaries": { + "project-words": { + "name": "Workspace Dictionary for Github Action", + "path": "${workspaceRoot}/.wordlist.txt", + "addWords": true + }, + "custom": true, + "internal-terms": false + } +} \ No newline at end of file diff --git a/.wordlist.txt b/.wordlist.txt index a0da9633..887d1027 100644 --- a/.wordlist.txt +++ b/.wordlist.txt @@ -117,4 +117,6 @@ Delicat Jakub Bence Palacios -env \ No newline at end of file +env +pids +pgrep \ No newline at end of file From c278c06d8b5ff7d690a0f4cb2e8ecbf37f1027ed Mon Sep 17 00:00:00 2001 From: Jakub Delicat Date: Thu, 19 Oct 2023 03:12:01 +0200 Subject: [PATCH 03/12] added white spaces extention recommendation | added EOF new line setting Signed-off-by: Jakub Delicat --- .vscode/extensions.json | 3 ++- .vscode/settings.json | 5 +++-- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/.vscode/extensions.json b/.vscode/extensions.json index dd34646d..12b10b51 100644 --- a/.vscode/extensions.json +++ b/.vscode/extensions.json @@ -4,6 +4,7 @@ "ms-python.black-formatter", "streetsidesoftware.code-spell-checker", "kevinrose.vsc-python-indent", - "ms-python.python" + "ms-python.python", + "shardulm94.trailing-spaces" ] } \ No newline at end of file diff --git a/.vscode/settings.json b/.vscode/settings.json index c7b8cf91..67d4694f 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -7,5 +7,6 @@ }, "custom": true, "internal-terms": false - } -} \ No newline at end of file + }, + "files.insertFinalNewline": true +} From f2824c62e892c334b24c8b8a1d69901a7b23ed2a Mon Sep 17 00:00:00 2001 From: Jakub Delicat Date: Thu, 19 Oct 2023 03:43:08 +0200 Subject: [PATCH 04/12] added EOF new line Signed-off-by: Jakub Delicat --- .pyspelling.yaml | 2 +- .wordlist.txt | 2 +- README.md | 2 +- rosbot/CMakeLists.txt | 2 +- rosbot/rosbot_hardware.repos | 2 +- rosbot_controller/config/mecanum_drive_controller.yaml | 2 +- rosbot_controller/package.xml | 2 +- rosbot_description/CMakeLists.txt | 2 +- rosbot_description/package.xml | 2 +- rosbot_description/urdf/body.urdf.xacro | 2 +- rosbot_description/urdf/components/vl53lox.urdf.xacro | 2 +- rosbot_description/urdf/rosbot.urdf.xacro | 2 +- rosbot_description/urdf/rosbot_macro.urdf.xacro | 2 +- rosbot_description/urdf/wheel.urdf.xacro | 2 +- rosbot_gazebo/package.xml | 2 +- 15 files changed, 15 insertions(+), 15 deletions(-) diff --git a/.pyspelling.yaml b/.pyspelling.yaml index 92205887..df8259ca 100644 --- a/.pyspelling.yaml +++ b/.pyspelling.yaml @@ -50,4 +50,4 @@ matrix: - .wordlist.txt pipeline: - - pyspelling.filters.xml \ No newline at end of file + - pyspelling.filters.xml diff --git a/.wordlist.txt b/.wordlist.txt index 887d1027..5a21da62 100644 --- a/.wordlist.txt +++ b/.wordlist.txt @@ -119,4 +119,4 @@ Bence Palacios env pids -pgrep \ No newline at end of file +pgrep diff --git a/README.md b/README.md index b9ed442e..8fd6767c 100644 --- a/README.md +++ b/README.md @@ -113,7 +113,7 @@ ros2 launch rosbot_gazebo simulation.launch.py colcon test ``` -> [!NOTE] +> [!NOTE] > Command `colcon test` does not build the code. Remember to build your code after changes. If tests finish with errors print logs: diff --git a/rosbot/CMakeLists.txt b/rosbot/CMakeLists.txt index 39350741..a6c2f3cf 100644 --- a/rosbot/CMakeLists.txt +++ b/rosbot/CMakeLists.txt @@ -3,4 +3,4 @@ project(rosbot) find_package(ament_cmake REQUIRED) -ament_package() \ No newline at end of file +ament_package() diff --git a/rosbot/rosbot_hardware.repos b/rosbot/rosbot_hardware.repos index b63efad9..27f4a344 100644 --- a/rosbot/rosbot_hardware.repos +++ b/rosbot/rosbot_hardware.repos @@ -10,4 +10,4 @@ repositories: rosbot_controllers: type: git url: https://github.com/husarion/rosbot_controllers - version: main \ No newline at end of file + version: main diff --git a/rosbot_controller/config/mecanum_drive_controller.yaml b/rosbot_controller/config/mecanum_drive_controller.yaml index 4f4df446..f0c21c1b 100644 --- a/rosbot_controller/config/mecanum_drive_controller.yaml +++ b/rosbot_controller/config/mecanum_drive_controller.yaml @@ -101,4 +101,4 @@ rosbot_base_controller: # min_velocity - When unspecified, -max_velocity is used max_acceleration: 4.0 # rad/s^2 # min_acceleration - When unspecified, -max_acceleration is used. - max_jerk: 0.0 # rad/s^3 \ No newline at end of file + max_jerk: 0.0 # rad/s^3 diff --git a/rosbot_controller/package.xml b/rosbot_controller/package.xml index 218e6df7..e9b36aa2 100644 --- a/rosbot_controller/package.xml +++ b/rosbot_controller/package.xml @@ -53,4 +53,4 @@ ament_python - \ No newline at end of file + diff --git a/rosbot_description/CMakeLists.txt b/rosbot_description/CMakeLists.txt index 8b8dfc0e..da0671ea 100644 --- a/rosbot_description/CMakeLists.txt +++ b/rosbot_description/CMakeLists.txt @@ -9,4 +9,4 @@ install(DIRECTORY DESTINATION share/${PROJECT_NAME} ) -ament_package() \ No newline at end of file +ament_package() diff --git a/rosbot_description/package.xml b/rosbot_description/package.xml index 4c0cbfa8..e42f73f1 100644 --- a/rosbot_description/package.xml +++ b/rosbot_description/package.xml @@ -20,4 +20,4 @@ ament_cmake - \ No newline at end of file + diff --git a/rosbot_description/urdf/body.urdf.xacro b/rosbot_description/urdf/body.urdf.xacro index 955fd01d..53505b58 100644 --- a/rosbot_description/urdf/body.urdf.xacro +++ b/rosbot_description/urdf/body.urdf.xacro @@ -85,4 +85,4 @@ - \ No newline at end of file + diff --git a/rosbot_description/urdf/components/vl53lox.urdf.xacro b/rosbot_description/urdf/components/vl53lox.urdf.xacro index 6ae8e3cd..bcbe6ec6 100644 --- a/rosbot_description/urdf/components/vl53lox.urdf.xacro +++ b/rosbot_description/urdf/components/vl53lox.urdf.xacro @@ -49,4 +49,4 @@ - \ No newline at end of file + diff --git a/rosbot_description/urdf/rosbot.urdf.xacro b/rosbot_description/urdf/rosbot.urdf.xacro index 81d14180..d3b27224 100644 --- a/rosbot_description/urdf/rosbot.urdf.xacro +++ b/rosbot_description/urdf/rosbot.urdf.xacro @@ -24,4 +24,4 @@ rpy="0.0 0.0 0.0" simulation_engine="$(arg simulation_engine)" /> - \ No newline at end of file + diff --git a/rosbot_description/urdf/rosbot_macro.urdf.xacro b/rosbot_description/urdf/rosbot_macro.urdf.xacro index eddd2c46..4f3d8613 100644 --- a/rosbot_description/urdf/rosbot_macro.urdf.xacro +++ b/rosbot_description/urdf/rosbot_macro.urdf.xacro @@ -206,4 +206,4 @@ - \ No newline at end of file + diff --git a/rosbot_description/urdf/wheel.urdf.xacro b/rosbot_description/urdf/wheel.urdf.xacro index 167468d0..5fe9e7c2 100644 --- a/rosbot_description/urdf/wheel.urdf.xacro +++ b/rosbot_description/urdf/wheel.urdf.xacro @@ -105,4 +105,4 @@ - \ No newline at end of file + diff --git a/rosbot_gazebo/package.xml b/rosbot_gazebo/package.xml index 307c4bd9..d58bfa30 100644 --- a/rosbot_gazebo/package.xml +++ b/rosbot_gazebo/package.xml @@ -40,4 +40,4 @@ ament_python - \ No newline at end of file + From 7eb716d225508e6a063320dd669a9998e2ab8f79 Mon Sep 17 00:00:00 2001 From: Jakub Delicat Date: Thu, 19 Oct 2023 03:43:45 +0200 Subject: [PATCH 05/12] added EOF new line Signed-off-by: Jakub Delicat --- .github/pull_request_template.md | 2 +- .github/workflows/bump_version.yaml | 2 +- .github/workflows/industrial_ci.yaml | 2 +- .github/workflows/spellcheck.yaml | 2 +- .vscode/extensions.json | 2 +- 5 files changed, 5 insertions(+), 5 deletions(-) diff --git a/.github/pull_request_template.md b/.github/pull_request_template.md index 9e3e216e..f84855b9 100644 --- a/.github/pull_request_template.md +++ b/.github/pull_request_template.md @@ -1,3 +1,3 @@ # TODO: specify bump command and remove this description -Bump version workflow is triggered when PR is closed, it bumps version and triggers docker build that will be tagged with version number. To use it you have to specify bump type, available commands: `bump::patch`, `bump::minor` and `bump::major` (simply leave one of them in PR description and remove this description). \ No newline at end of file +Bump version workflow is triggered when PR is closed, it bumps version and triggers docker build that will be tagged with version number. To use it you have to specify bump type, available commands: `bump::patch`, `bump::minor` and `bump::major` (simply leave one of them in PR description and remove this description). diff --git a/.github/workflows/bump_version.yaml b/.github/workflows/bump_version.yaml index ba6d3ccc..c766f278 100644 --- a/.github/workflows/bump_version.yaml +++ b/.github/workflows/bump_version.yaml @@ -61,4 +61,4 @@ jobs: -H "Accept: application/vnd.github+json" -H "Authorization: Bearer ${{ secrets.GH_PAT }}" https://api.github.com/repos/husarion/rosbot-docker/dispatches - -d '{"event_type":"ros-package-update"}' \ No newline at end of file + -d '{"event_type":"ros-package-update"}' diff --git a/.github/workflows/industrial_ci.yaml b/.github/workflows/industrial_ci.yaml index c77dad06..c1c025f5 100644 --- a/.github/workflows/industrial_ci.yaml +++ b/.github/workflows/industrial_ci.yaml @@ -19,4 +19,4 @@ jobs: vcs import . < ./rosbot/rosbot_simulation.repos - uses: ros-industrial/industrial_ci@master env: - ROS_DISTRO: ${{matrix.ROS_DISTRO}} \ No newline at end of file + ROS_DISTRO: ${{matrix.ROS_DISTRO}} diff --git a/.github/workflows/spellcheck.yaml b/.github/workflows/spellcheck.yaml index 77473bdd..a35fb0c1 100644 --- a/.github/workflows/spellcheck.yaml +++ b/.github/workflows/spellcheck.yaml @@ -11,4 +11,4 @@ jobs: steps: - uses: actions/checkout@v3 - uses: rojopolis/spellcheck-github-actions@0.33.1 - name: Spellcheck \ No newline at end of file + name: Spellcheck diff --git a/.vscode/extensions.json b/.vscode/extensions.json index 12b10b51..62d443f5 100644 --- a/.vscode/extensions.json +++ b/.vscode/extensions.json @@ -7,4 +7,4 @@ "ms-python.python", "shardulm94.trailing-spaces" ] -} \ No newline at end of file +} From d978d4204934b8bf00692914d4b5df3de7806c49 Mon Sep 17 00:00:00 2001 From: Jakub Delicat Date: Fri, 20 Oct 2023 14:40:50 +0200 Subject: [PATCH 06/12] Add and apply precommit hooks Signed-off-by: Jakub Delicat --- .github/workflows/black.yaml | 11 +- .github/workflows/bump_version.yaml | 111 +++++++++--------- .github/workflows/industrial_ci.yaml | 35 +++--- .github/workflows/spellcheck.yaml | 19 +-- .pre-commit-config.yaml | 70 +++++++++++ rosbot/rosbot_simulation.repos | 2 +- rosbot_bringup/launch/bringup.launch.py | 3 +- rosbot_bringup/setup.py | 14 +++ rosbot_bringup/test/test_diff_drive_ekf.py | 2 +- rosbot_bringup/test/test_flake8.py | 4 +- rosbot_bringup/test/test_mecanum_ekf.py | 2 +- .../{bringup_test_node.py => test_utils.py} | 8 +- rosbot_controller/launch/controller.launch.py | 13 +- rosbot_controller/setup.py | 14 +++ .../test/test_diff_drive_controllers.py | 6 +- rosbot_controller/test/test_flake8.py | 4 +- .../test/test_mecanum_controllers.py | 6 +- ...controllers_test_node.py => test_utils.py} | 12 +- rosbot_controller/test/test_xacro.py | 4 +- rosbot_description/meshes/mecanum_a.dae | 2 +- rosbot_description/meshes/mecanum_b.dae | 2 +- rosbot_description/meshes/wheel_a.dae | 2 +- rosbot_description/meshes/wheel_b.dae | 2 +- rosbot_gazebo/launch/simulation.launch.py | 3 +- rosbot_gazebo/setup.py | 14 +++ .../test/test_diff_drive_simulation.py | 4 +- rosbot_gazebo/test/test_flake8.py | 4 +- .../{kill_ign.py => test_ign_kill_utils.py} | 0 rosbot_gazebo/test/test_mecanum_simulation.py | 4 +- ...{simulation_test_node.py => test_utils.py} | 8 +- 30 files changed, 233 insertions(+), 152 deletions(-) create mode 100644 .pre-commit-config.yaml rename rosbot_bringup/test/{bringup_test_node.py => test_utils.py} (92%) rename rosbot_controller/test/{controllers_test_node.py => test_utils.py} (88%) rename rosbot_gazebo/test/{kill_ign.py => test_ign_kill_utils.py} (100%) rename rosbot_gazebo/test/{simulation_test_node.py => test_utils.py} (93%) diff --git a/.github/workflows/black.yaml b/.github/workflows/black.yaml index a170ee47..6bba432c 100644 --- a/.github/workflows/black.yaml +++ b/.github/workflows/black.yaml @@ -1,3 +1,4 @@ +--- name: Black python lint on: @@ -5,8 +6,8 @@ on: push: jobs: - lint: - runs-on: ubuntu-latest - steps: - - uses: actions/checkout@v3 - - uses: psf/black@stable + lint: + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v3 + - uses: psf/black@stable diff --git a/.github/workflows/bump_version.yaml b/.github/workflows/bump_version.yaml index c766f278..69d5b39d 100644 --- a/.github/workflows/bump_version.yaml +++ b/.github/workflows/bump_version.yaml @@ -1,64 +1,63 @@ +--- name: Trigger rosbot-docker to build an image and bump version on: - workflow_dispatch: - inputs: - name: - description: "Version to bump (major, minor, patch)" - default: "patch" - required: true - pull_request: - branches: humble - types: [closed] + workflow_dispatch: + inputs: + name: + description: Version to bump (major, minor, patch) + default: patch + required: true + pull_request: + branches: humble + types: [closed] jobs: - get-bump: - if: github.event_name == 'pull_request' && github.event.action == 'closed' && github.event.pull_request.merged == true - name: Get version bump - runs-on: ubuntu-22.04 - outputs: - bump: ${{ env.BUMP }} - steps: - - if: github.event_name == 'pull_request' && github.event.pull_request.merged == true + get-bump: + if: github.event_name == 'pull_request' && github.event.action == 'closed' && github.event.pull_request.merged == true name: Get version bump - id: get-version-bump - uses: husarion-ci/action-get-version-bump@v0.3.0 - - if: github.event_name == 'pull_request' && github.event.pull_request.merged == true - run: echo "BUMP=${{ steps.get-version-bump.outputs.bump }}" >> $GITHUB_ENV - - if: github.event_name == 'workflow_dispatch' - run: echo "BUMP=${{ github.event.inputs.name }}" >> $GITHUB_ENV + runs-on: ubuntu-22.04 + outputs: + bump: ${{ env.BUMP }} + steps: + - if: github.event_name == 'pull_request' && github.event.pull_request.merged == true + name: Get version bump + id: get-version-bump + uses: husarion-ci/action-get-version-bump@v0.3.0 + - if: github.event_name == 'pull_request' && github.event.pull_request.merged == true + run: echo "BUMP=${{ steps.get-version-bump.outputs.bump }}" >> $GITHUB_ENV + - if: github.event_name == 'workflow_dispatch' + run: echo "BUMP=${{ github.event.inputs.name }}" >> $GITHUB_ENV - catkin-release: - if: github.event_name == 'pull_request' && github.event.action == 'closed' && github.event.pull_request.merged == true - name: Bump version - runs-on: ubuntu-22.04 - needs: get-bump - outputs: - new_version: ${{ steps.catkin-release.outputs.new_version }} - steps: - - - name: Checkout - uses: actions/checkout@v2 - - - name: Catkin release - id: catkin-release - uses: husarion-ci/action-catkin-release@v0.1.4 - with: - bump: ${{ needs.get-bump.outputs.bump }} - github_token: ${{ secrets.GH_PAT }} - git_user: action-bot - git_email: action-bot@action-bot.com + catkin-release: + if: github.event_name == 'pull_request' && github.event.action == 'closed' && github.event.pull_request.merged == true + name: Bump version + runs-on: ubuntu-22.04 + needs: get-bump + outputs: + new_version: ${{ steps.catkin-release.outputs.new_version }} + steps: + - name: Checkout + uses: actions/checkout@v2 + - name: Catkin release + id: catkin-release + uses: husarion-ci/action-catkin-release@v0.1.4 + with: + bump: ${{ needs.get-bump.outputs.bump }} + github_token: ${{ secrets.GH_PAT }} + git_user: action-bot + git_email: action-bot@action-bot.com - build-and-push-docker-image: - if: github.event_name == 'pull_request' && github.event.action == 'closed' && github.event.pull_request.merged == true - name: Create new docker image - runs-on: ubuntu-22.04 - needs: catkin-release - steps: - - name: trigger the endpoint - run: > - curl -X POST - -H "Accept: application/vnd.github+json" - -H "Authorization: Bearer ${{ secrets.GH_PAT }}" - https://api.github.com/repos/husarion/rosbot-docker/dispatches - -d '{"event_type":"ros-package-update"}' + build-and-push-docker-image: + if: github.event_name == 'pull_request' && github.event.action == 'closed' && github.event.pull_request.merged == true + name: Create new docker image + runs-on: ubuntu-22.04 + needs: catkin-release + steps: + - name: trigger the endpoint + run: > + curl -X POST + -H "Accept: application/vnd.github+json" + -H "Authorization: Bearer ${{ secrets.GH_PAT }}" + https://api.github.com/repos/husarion/rosbot-docker/dispatches + -d '{"event_type":"ros-package-update"}' diff --git a/.github/workflows/industrial_ci.yaml b/.github/workflows/industrial_ci.yaml index c1c025f5..a3701751 100644 --- a/.github/workflows/industrial_ci.yaml +++ b/.github/workflows/industrial_ci.yaml @@ -1,22 +1,21 @@ +--- name: Industrial CI on: - workflow_call: - push: + workflow_call: + push: jobs: - industrial_ci: - strategy: - fail-fast: false - matrix: - ROS_DISTRO: [humble] - runs-on: ubuntu-latest - steps: - - uses: actions/checkout@v3 - - name: Clone installation requirements - shell: bash - run : python3 -m pip install -U vcstool && - vcs import . < ./rosbot/rosbot_hardware.repos && - vcs import . < ./rosbot/rosbot_simulation.repos - - uses: ros-industrial/industrial_ci@master - env: - ROS_DISTRO: ${{matrix.ROS_DISTRO}} + industrial_ci: + strategy: + fail-fast: false + matrix: + ROS_DISTRO: [humble] + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v3 + - name: Clone installation requirements + shell: bash + run: python3 -m pip install -U vcstool && vcs import . < ./rosbot/rosbot_hardware.repos && vcs import . < ./rosbot/rosbot_simulation.repos + - uses: ros-industrial/industrial_ci@master + env: + ROS_DISTRO: ${{matrix.ROS_DISTRO}} diff --git a/.github/workflows/spellcheck.yaml b/.github/workflows/spellcheck.yaml index a35fb0c1..36f304fe 100644 --- a/.github/workflows/spellcheck.yaml +++ b/.github/workflows/spellcheck.yaml @@ -1,14 +1,15 @@ +--- name: Spellcheck Action on: - workflow_call: - push: + workflow_call: + push: jobs: - build: - name: Spellcheck - runs-on: ubuntu-latest - steps: - - uses: actions/checkout@v3 - - uses: rojopolis/spellcheck-github-actions@0.33.1 - name: Spellcheck + build: + name: Spellcheck + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v3 + - uses: rojopolis/spellcheck-github-actions@0.33.1 + name: Spellcheck diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml new file mode 100644 index 00000000..d3522021 --- /dev/null +++ b/.pre-commit-config.yaml @@ -0,0 +1,70 @@ +--- +repos: + - repo: https://github.com/pre-commit/pre-commit-hooks + rev: v4.5.0 + hooks: + - id: check-merge-conflict + - id: trailing-whitespace + - id: end-of-file-fixer + - id: check-yaml + - id: check-xml + - id: check-added-large-files + - id: check-ast + - id: check-json + - id: name-tests-test + files: ^.*\/test\/.*$ + args: [--pytest-test-first] + + - repo: https://github.com/codespell-project/codespell + rev: v1.16.0 + hooks: + - id: codespell + name: codespell + description: Checks for common misspellings in text files. + entry: codespell * + language: python + types: [text] + + - repo: https://github.com/jumanjihouse/pre-commit-hook-yamlfmt + rev: 0.2.1 + hooks: + - id: yamlfmt + files: ^.github|./\.yaml + + - repo: https://github.com/psf/black + rev: 22.12.0 + hooks: + - id: black + args: ["--line-length=99"] + + - repo: https://github.com/PyCQA/flake8 + rev: 6.1.0 + hooks: + - id: flake8 + args: ["--ignore=E501"] # ignore too long line, black checks it + + - repo: local + hooks: + - id: ament_lint_cmake + name: ament_lint_cmake + description: Check format of CMakeLists.txt files. + entry: ament_lint_cmake + language: system + files: CMakeLists\.txt$ + + - repo: local + hooks: + - id: ament_copyright + name: ament_copyright + description: Check if copyright notice is available in all files. + stages: [commit] + entry: ament_copyright + language: system + + # Docs - RestructuredText hooks + - repo: https://github.com/PyCQA/doc8 + rev: v1.1.1 + hooks: + - id: doc8 + args: ['--max-line-length=100', '--ignore=D001'] + exclude: ^.*\/CHANGELOG\.rst/.*$ diff --git a/rosbot/rosbot_simulation.repos b/rosbot/rosbot_simulation.repos index 4c6dcf5a..a4014f93 100644 --- a/rosbot/rosbot_simulation.repos +++ b/rosbot/rosbot_simulation.repos @@ -3,7 +3,7 @@ repositories: type: git url: https://github.com/ros-controls/gz_ros2_control.git # on branch humble hardware isn't activated - # recently on master API breaking change was introduced, it is necessay to use commit before this change + # recently on master API breaking change was introduced, it is necessary to use commit before this change version: b296ff2f5c3758b637a70bd496fe6ed875ab03ce husarion/husarion_office_gz: diff --git a/rosbot_bringup/launch/bringup.launch.py b/rosbot_bringup/launch/bringup.launch.py index d1c8114b..787ef679 100644 --- a/rosbot_bringup/launch/bringup.launch.py +++ b/rosbot_bringup/launch/bringup.launch.py @@ -51,8 +51,7 @@ def generate_launch_description(): "mecanum", default_value="False", description=( - "Whether to use mecanum drive controller " - "(otherwise diff drive controller is used)" + "Whether to use mecanum drive controller " "(otherwise diff drive controller is used)" ), ) diff --git a/rosbot_bringup/setup.py b/rosbot_bringup/setup.py index b31703b9..bf5e8ba5 100644 --- a/rosbot_bringup/setup.py +++ b/rosbot_bringup/setup.py @@ -1,3 +1,17 @@ +# Copyright 2023 Husarion +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import os from glob import glob from setuptools import find_packages, setup diff --git a/rosbot_bringup/test/test_diff_drive_ekf.py b/rosbot_bringup/test/test_diff_drive_ekf.py index aef6d8e7..1c72b8b8 100644 --- a/rosbot_bringup/test/test_diff_drive_ekf.py +++ b/rosbot_bringup/test/test_diff_drive_ekf.py @@ -23,7 +23,7 @@ from launch.actions import IncludeLaunchDescription from launch.substitutions import PathJoinSubstitution from launch.launch_description_sources import PythonLaunchDescriptionSource -from bringup_test_node import BringupTestNode +from rosbot_bringup.test.test_utils import BringupTestNode @launch_pytest.fixture diff --git a/rosbot_bringup/test/test_flake8.py b/rosbot_bringup/test/test_flake8.py index ee79f31a..49c1644f 100644 --- a/rosbot_bringup/test/test_flake8.py +++ b/rosbot_bringup/test/test_flake8.py @@ -20,6 +20,4 @@ @pytest.mark.linter def test_flake8(): rc, errors = main_with_errors(argv=[]) - assert rc == 0, "Found %d code style errors / warnings:\n" % len( - errors - ) + "\n".join(errors) + assert rc == 0, "Found %d code style errors / warnings:\n" % len(errors) + "\n".join(errors) diff --git a/rosbot_bringup/test/test_mecanum_ekf.py b/rosbot_bringup/test/test_mecanum_ekf.py index ab473e08..7b78d901 100644 --- a/rosbot_bringup/test/test_mecanum_ekf.py +++ b/rosbot_bringup/test/test_mecanum_ekf.py @@ -23,7 +23,7 @@ from launch.actions import IncludeLaunchDescription from launch.substitutions import PathJoinSubstitution from launch.launch_description_sources import PythonLaunchDescriptionSource -from bringup_test_node import BringupTestNode +from rosbot_bringup.test.test_utils import BringupTestNode @launch_pytest.fixture diff --git a/rosbot_bringup/test/bringup_test_node.py b/rosbot_bringup/test/test_utils.py similarity index 92% rename from rosbot_bringup/test/bringup_test_node.py rename to rosbot_bringup/test/test_utils.py index d40cb4a1..36ff36f4 100644 --- a/rosbot_bringup/test/bringup_test_node.py +++ b/rosbot_bringup/test/test_utils.py @@ -38,9 +38,7 @@ def __init__(self, name="test_node"): def create_test_subscribers_and_publishers(self): self.imu_publisher = self.create_publisher(Imu, "_imu/data_raw", 10) - self.joint_states_publisher = self.create_publisher( - JointState, "_motors_response", 10 - ) + self.joint_states_publisher = self.create_publisher(JointState, "_motors_response", 10) self.tf_buffer = Buffer() self.tf_listener = TransformListener(self.tf_buffer, self) @@ -55,9 +53,7 @@ def lookup_transform_odom(self): self.get_logger().error(f"Could not transform odom to base_link: {ex}") def start_node_thread(self): - self.ros_spin_thread = Thread( - target=lambda node: rclpy.spin(node), args=(self,) - ) + self.ros_spin_thread = Thread(target=lambda node: rclpy.spin(node), args=(self,)) self.ros_spin_thread.start() def start_publishing_fake_hardware(self): diff --git a/rosbot_controller/launch/controller.launch.py b/rosbot_controller/launch/controller.launch.py index 93620931..8d745de3 100644 --- a/rosbot_controller/launch/controller.launch.py +++ b/rosbot_controller/launch/controller.launch.py @@ -35,8 +35,7 @@ def generate_launch_description(): "mecanum", default_value="False", description=( - "Whether to use mecanum drive controller " - "(otherwise diff drive controller is used)" + "Whether to use mecanum drive controller " "(otherwise diff drive controller is used)" ), ) @@ -154,12 +153,10 @@ def generate_launch_description(): ) # Delay start of robot_controller after joint_state_broadcaster - delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = ( - RegisterEventHandler( - event_handler=OnProcessExit( - target_action=joint_state_broadcaster_spawner, - on_exit=[robot_controller_spawner], - ) + delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=joint_state_broadcaster_spawner, + on_exit=[robot_controller_spawner], ) ) diff --git a/rosbot_controller/setup.py b/rosbot_controller/setup.py index 20164df8..3812e353 100644 --- a/rosbot_controller/setup.py +++ b/rosbot_controller/setup.py @@ -1,3 +1,17 @@ +# Copyright 2023 Husarion +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import os from glob import glob from setuptools import find_packages, setup diff --git a/rosbot_controller/test/test_diff_drive_controllers.py b/rosbot_controller/test/test_diff_drive_controllers.py index 49fe6185..f2065729 100644 --- a/rosbot_controller/test/test_diff_drive_controllers.py +++ b/rosbot_controller/test/test_diff_drive_controllers.py @@ -23,7 +23,7 @@ from launch.actions import IncludeLaunchDescription from launch.substitutions import PathJoinSubstitution from launch.launch_description_sources import PythonLaunchDescriptionSource -from controllers_test_node import ControllersTestNode +from rosbot_controller.test.test_utils import ControllersTestNode @launch_pytest.fixture @@ -66,9 +66,7 @@ def test_controllers_startup_fail(): not msgs_received_flag ), "Expected Odom message not received. Check rosbot_base_controller!" msgs_received_flag = node.imu_msg_event.wait(timeout=10.0) - assert ( - not msgs_received_flag - ), "Expected Imu message not received. Check imu_broadcaster!" + assert not msgs_received_flag, "Expected Imu message not received. Check imu_broadcaster!" finally: rclpy.shutdown() diff --git a/rosbot_controller/test/test_flake8.py b/rosbot_controller/test/test_flake8.py index ee79f31a..49c1644f 100644 --- a/rosbot_controller/test/test_flake8.py +++ b/rosbot_controller/test/test_flake8.py @@ -20,6 +20,4 @@ @pytest.mark.linter def test_flake8(): rc, errors = main_with_errors(argv=[]) - assert rc == 0, "Found %d code style errors / warnings:\n" % len( - errors - ) + "\n".join(errors) + assert rc == 0, "Found %d code style errors / warnings:\n" % len(errors) + "\n".join(errors) diff --git a/rosbot_controller/test/test_mecanum_controllers.py b/rosbot_controller/test/test_mecanum_controllers.py index 4832da88..998557e1 100644 --- a/rosbot_controller/test/test_mecanum_controllers.py +++ b/rosbot_controller/test/test_mecanum_controllers.py @@ -23,7 +23,7 @@ from launch.actions import IncludeLaunchDescription from launch.substitutions import PathJoinSubstitution from launch.launch_description_sources import PythonLaunchDescriptionSource -from controllers_test_node import ControllersTestNode +from rosbot_controller.test.test_utils import ControllersTestNode @launch_pytest.fixture @@ -66,9 +66,7 @@ def test_controllers_startup_fail(): not msgs_received_flag ), "Expected Odom message not received. Check rosbot_base_controller!" msgs_received_flag = node.imu_msg_event.wait(timeout=10.0) - assert ( - not msgs_received_flag - ), "Expected Imu message not received. Check imu_broadcaster!" + assert not msgs_received_flag, "Expected Imu message not received. Check imu_broadcaster!" finally: rclpy.shutdown() diff --git a/rosbot_controller/test/controllers_test_node.py b/rosbot_controller/test/test_utils.py similarity index 88% rename from rosbot_controller/test/controllers_test_node.py rename to rosbot_controller/test/test_utils.py index ef9835eb..db48c06a 100644 --- a/rosbot_controller/test/controllers_test_node.py +++ b/rosbot_controller/test/test_utils.py @@ -44,22 +44,16 @@ def create_test_subscribers_and_publishers(self): Odometry, "/rosbot_base_controller/odom", self.odometry_callback, 10 ) - self.imu_sub = self.create_subscription( - Imu, "/imu_broadcaster/imu", self.imu_callback, 10 - ) + self.imu_sub = self.create_subscription(Imu, "/imu_broadcaster/imu", self.imu_callback, 10) self.imu_publisher = self.create_publisher(Imu, "_imu/data_raw", 10) - self.joint_states_publisher = self.create_publisher( - JointState, "_motors_response", 10 - ) + self.joint_states_publisher = self.create_publisher(JointState, "_motors_response", 10) self.timer = None def start_node_thread(self): - self.ros_spin_thread = Thread( - target=lambda node: rclpy.spin(node), args=(self,) - ) + self.ros_spin_thread = Thread(target=lambda node: rclpy.spin(node), args=(self,)) self.ros_spin_thread.start() def joint_states_callback(self, data): diff --git a/rosbot_controller/test/test_xacro.py b/rosbot_controller/test/test_xacro.py index c8ae93ca..17216c75 100644 --- a/rosbot_controller/test/test_xacro.py +++ b/rosbot_controller/test/test_xacro.py @@ -25,9 +25,7 @@ def test_rosbot_description_parsing(): simulation_engine_values = ["ignition-gazebo", "webots"] # 'gazebo-classic' all_combinations = list( - itertools.product( - mecanum_values, use_sim_values, use_gpu_values, simulation_engine_values - ) + itertools.product(mecanum_values, use_sim_values, use_gpu_values, simulation_engine_values) ) for combination in all_combinations: diff --git a/rosbot_description/meshes/mecanum_a.dae b/rosbot_description/meshes/mecanum_a.dae index 04f2202b..e81b5ad1 100644 --- a/rosbot_description/meshes/mecanum_a.dae +++ b/rosbot_description/meshes/mecanum_a.dae @@ -170,4 +170,4 @@ - \ No newline at end of file + diff --git a/rosbot_description/meshes/mecanum_b.dae b/rosbot_description/meshes/mecanum_b.dae index 0e839aed..2f3b1341 100644 --- a/rosbot_description/meshes/mecanum_b.dae +++ b/rosbot_description/meshes/mecanum_b.dae @@ -170,4 +170,4 @@ - \ No newline at end of file + diff --git a/rosbot_description/meshes/wheel_a.dae b/rosbot_description/meshes/wheel_a.dae index f49e5032..ecad5e4d 100644 --- a/rosbot_description/meshes/wheel_a.dae +++ b/rosbot_description/meshes/wheel_a.dae @@ -228,4 +228,4 @@ - \ No newline at end of file + diff --git a/rosbot_description/meshes/wheel_b.dae b/rosbot_description/meshes/wheel_b.dae index e5eb8af0..94cde797 100644 --- a/rosbot_description/meshes/wheel_b.dae +++ b/rosbot_description/meshes/wheel_b.dae @@ -159,4 +159,4 @@ - \ No newline at end of file + diff --git a/rosbot_gazebo/launch/simulation.launch.py b/rosbot_gazebo/launch/simulation.launch.py index 85508098..a3b534f1 100644 --- a/rosbot_gazebo/launch/simulation.launch.py +++ b/rosbot_gazebo/launch/simulation.launch.py @@ -35,8 +35,7 @@ def generate_launch_description(): "mecanum", default_value="False", description=( - "Whether to use mecanum drive controller " - "(otherwise diff drive controller is used)" + "Whether to use mecanum drive controller " "(otherwise diff drive controller is used)" ), ) diff --git a/rosbot_gazebo/setup.py b/rosbot_gazebo/setup.py index 06ca4476..0d432bd4 100644 --- a/rosbot_gazebo/setup.py +++ b/rosbot_gazebo/setup.py @@ -1,3 +1,17 @@ +# Copyright 2023 Husarion +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import os from glob import glob from setuptools import find_packages, setup diff --git a/rosbot_gazebo/test/test_diff_drive_simulation.py b/rosbot_gazebo/test/test_diff_drive_simulation.py index 25dc7ed7..090ab89d 100644 --- a/rosbot_gazebo/test/test_diff_drive_simulation.py +++ b/rosbot_gazebo/test/test_diff_drive_simulation.py @@ -24,8 +24,8 @@ from launch.substitutions import PathJoinSubstitution from launch.launch_description_sources import PythonLaunchDescriptionSource -from simulation_test_node import SimulationTestNode -from kill_ign import kill_ign_linux_processes +from rosbot_gazebo.test.test_utils import SimulationTestNode +from rosbot_gazebo.test.test_ign_kill_utils import kill_ign_linux_processes @launch_pytest.fixture diff --git a/rosbot_gazebo/test/test_flake8.py b/rosbot_gazebo/test/test_flake8.py index ee79f31a..49c1644f 100644 --- a/rosbot_gazebo/test/test_flake8.py +++ b/rosbot_gazebo/test/test_flake8.py @@ -20,6 +20,4 @@ @pytest.mark.linter def test_flake8(): rc, errors = main_with_errors(argv=[]) - assert rc == 0, "Found %d code style errors / warnings:\n" % len( - errors - ) + "\n".join(errors) + assert rc == 0, "Found %d code style errors / warnings:\n" % len(errors) + "\n".join(errors) diff --git a/rosbot_gazebo/test/kill_ign.py b/rosbot_gazebo/test/test_ign_kill_utils.py similarity index 100% rename from rosbot_gazebo/test/kill_ign.py rename to rosbot_gazebo/test/test_ign_kill_utils.py diff --git a/rosbot_gazebo/test/test_mecanum_simulation.py b/rosbot_gazebo/test/test_mecanum_simulation.py index f4c425ea..061d6b1c 100644 --- a/rosbot_gazebo/test/test_mecanum_simulation.py +++ b/rosbot_gazebo/test/test_mecanum_simulation.py @@ -24,8 +24,8 @@ from launch.substitutions import PathJoinSubstitution from launch.launch_description_sources import PythonLaunchDescriptionSource -from simulation_test_node import SimulationTestNode -from kill_ign import kill_ign_linux_processes +from rosbot_gazebo.test.test_utils import SimulationTestNode +from rosbot_gazebo.test.test_ign_kill_utils import kill_ign_linux_processes @launch_pytest.fixture diff --git a/rosbot_gazebo/test/simulation_test_node.py b/rosbot_gazebo/test/test_utils.py similarity index 93% rename from rosbot_gazebo/test/simulation_test_node.py rename to rosbot_gazebo/test/test_utils.py index 7fb5a4ac..ac0b7912 100644 --- a/rosbot_gazebo/test/simulation_test_node.py +++ b/rosbot_gazebo/test/test_utils.py @@ -64,18 +64,14 @@ def create_test_subscribers_and_publishers(self): Odometry, "/odometry/filtered", self.odometry_callback, 10 ) - self.scan_sub = self.create_subscription( - LaserScan, "/scan", self.scan_callback, 10 - ) + self.scan_sub = self.create_subscription(LaserScan, "/scan", self.scan_callback, 10) self.tf_buffer = Buffer() self.tf_listener = TransformListener(self.tf_buffer, self) self.timer = None def start_node_thread(self): - self.ros_spin_thread = Thread( - target=lambda node: rclpy.spin(node), args=(self,) - ) + self.ros_spin_thread = Thread(target=lambda node: rclpy.spin(node), args=(self,)) self.ros_spin_thread.start() self.timer = self.create_timer(1.0 / 10.0, self.timer_callback) From 2a272bd2e3988f4e414dbbe1f7687a9b1d1a28b7 Mon Sep 17 00:00:00 2001 From: Jakub Delicat Date: Fri, 20 Oct 2023 14:54:42 +0200 Subject: [PATCH 07/12] change line length to 99 for gh action Signed-off-by: Jakub Delicat --- .github/workflows/black.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/black.yaml b/.github/workflows/black.yaml index 6bba432c..f087223e 100644 --- a/.github/workflows/black.yaml +++ b/.github/workflows/black.yaml @@ -11,3 +11,4 @@ jobs: steps: - uses: actions/checkout@v3 - uses: psf/black@stable + black_args: --line-length=99 From 9a5946dbe942fbb5a698822498d50fc8cb7888e6 Mon Sep 17 00:00:00 2001 From: Jakub Delicat Date: Fri, 20 Oct 2023 14:58:02 +0200 Subject: [PATCH 08/12] fix black action Signed-off-by: Jakub Delicat --- .github/workflows/black.yaml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/workflows/black.yaml b/.github/workflows/black.yaml index f087223e..0e1c54a4 100644 --- a/.github/workflows/black.yaml +++ b/.github/workflows/black.yaml @@ -11,4 +11,5 @@ jobs: steps: - uses: actions/checkout@v3 - uses: psf/black@stable - black_args: --line-length=99 + with: + black_args: --line-length=99 From 00eb5d0112ff9e29d159147d8d9aaeb225d5b93f Mon Sep 17 00:00:00 2001 From: Jakub Delicat Date: Fri, 20 Oct 2023 14:58:54 +0200 Subject: [PATCH 09/12] fix black action Signed-off-by: Jakub Delicat --- .github/workflows/black.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/black.yaml b/.github/workflows/black.yaml index 0e1c54a4..ab5e1b3f 100644 --- a/.github/workflows/black.yaml +++ b/.github/workflows/black.yaml @@ -12,4 +12,4 @@ jobs: - uses: actions/checkout@v3 - uses: psf/black@stable with: - black_args: --line-length=99 + options: --line-length=99 From 77df36c8395c72d1685dab74db3a3ac56cf4f41c Mon Sep 17 00:00:00 2001 From: Jakub Delicat Date: Fri, 20 Oct 2023 15:13:46 +0200 Subject: [PATCH 10/12] fixed importing Signed-off-by: Jakub Delicat --- rosbot_bringup/test/test_diff_drive_ekf.py | 2 +- rosbot_bringup/test/test_mecanum_ekf.py | 2 +- rosbot_controller/test/test_diff_drive_controllers.py | 2 +- rosbot_controller/test/test_mecanum_controllers.py | 2 +- rosbot_gazebo/test/test_diff_drive_simulation.py | 4 ++-- rosbot_gazebo/test/test_mecanum_simulation.py | 4 ++-- 6 files changed, 8 insertions(+), 8 deletions(-) diff --git a/rosbot_bringup/test/test_diff_drive_ekf.py b/rosbot_bringup/test/test_diff_drive_ekf.py index 1c72b8b8..c9b1bea8 100644 --- a/rosbot_bringup/test/test_diff_drive_ekf.py +++ b/rosbot_bringup/test/test_diff_drive_ekf.py @@ -23,7 +23,7 @@ from launch.actions import IncludeLaunchDescription from launch.substitutions import PathJoinSubstitution from launch.launch_description_sources import PythonLaunchDescriptionSource -from rosbot_bringup.test.test_utils import BringupTestNode +from test_utils import BringupTestNode @launch_pytest.fixture diff --git a/rosbot_bringup/test/test_mecanum_ekf.py b/rosbot_bringup/test/test_mecanum_ekf.py index 7b78d901..d46b29cc 100644 --- a/rosbot_bringup/test/test_mecanum_ekf.py +++ b/rosbot_bringup/test/test_mecanum_ekf.py @@ -23,7 +23,7 @@ from launch.actions import IncludeLaunchDescription from launch.substitutions import PathJoinSubstitution from launch.launch_description_sources import PythonLaunchDescriptionSource -from rosbot_bringup.test.test_utils import BringupTestNode +from test_utils import BringupTestNode @launch_pytest.fixture diff --git a/rosbot_controller/test/test_diff_drive_controllers.py b/rosbot_controller/test/test_diff_drive_controllers.py index f2065729..4f0c8f5d 100644 --- a/rosbot_controller/test/test_diff_drive_controllers.py +++ b/rosbot_controller/test/test_diff_drive_controllers.py @@ -23,7 +23,7 @@ from launch.actions import IncludeLaunchDescription from launch.substitutions import PathJoinSubstitution from launch.launch_description_sources import PythonLaunchDescriptionSource -from rosbot_controller.test.test_utils import ControllersTestNode +from test_utils import ControllersTestNode @launch_pytest.fixture diff --git a/rosbot_controller/test/test_mecanum_controllers.py b/rosbot_controller/test/test_mecanum_controllers.py index 998557e1..b45f3729 100644 --- a/rosbot_controller/test/test_mecanum_controllers.py +++ b/rosbot_controller/test/test_mecanum_controllers.py @@ -23,7 +23,7 @@ from launch.actions import IncludeLaunchDescription from launch.substitutions import PathJoinSubstitution from launch.launch_description_sources import PythonLaunchDescriptionSource -from rosbot_controller.test.test_utils import ControllersTestNode +from test_utils import ControllersTestNode @launch_pytest.fixture diff --git a/rosbot_gazebo/test/test_diff_drive_simulation.py b/rosbot_gazebo/test/test_diff_drive_simulation.py index 090ab89d..34a8019c 100644 --- a/rosbot_gazebo/test/test_diff_drive_simulation.py +++ b/rosbot_gazebo/test/test_diff_drive_simulation.py @@ -24,8 +24,8 @@ from launch.substitutions import PathJoinSubstitution from launch.launch_description_sources import PythonLaunchDescriptionSource -from rosbot_gazebo.test.test_utils import SimulationTestNode -from rosbot_gazebo.test.test_ign_kill_utils import kill_ign_linux_processes +from test_utils import SimulationTestNode +from test_ign_kill_utils import kill_ign_linux_processes @launch_pytest.fixture diff --git a/rosbot_gazebo/test/test_mecanum_simulation.py b/rosbot_gazebo/test/test_mecanum_simulation.py index 061d6b1c..3ade723a 100644 --- a/rosbot_gazebo/test/test_mecanum_simulation.py +++ b/rosbot_gazebo/test/test_mecanum_simulation.py @@ -24,8 +24,8 @@ from launch.substitutions import PathJoinSubstitution from launch.launch_description_sources import PythonLaunchDescriptionSource -from rosbot_gazebo.test.test_utils import SimulationTestNode -from rosbot_gazebo.test.test_ign_kill_utils import kill_ign_linux_processes +from test_utils import SimulationTestNode +from test_ign_kill_utils import kill_ign_linux_processes @launch_pytest.fixture From c1043bdbc3d4a8fc35c06a94098289d56581d8ba Mon Sep 17 00:00:00 2001 From: Jakub Delicat Date: Fri, 20 Oct 2023 15:30:07 +0200 Subject: [PATCH 11/12] added pre-commit to readme Signed-off-by: Jakub Delicat --- .vscode/extensions.json | 10 ---------- .vscode/settings.json | 12 ------------ README.md | 16 ++++++++++++++++ 3 files changed, 16 insertions(+), 22 deletions(-) delete mode 100644 .vscode/extensions.json delete mode 100644 .vscode/settings.json diff --git a/.vscode/extensions.json b/.vscode/extensions.json deleted file mode 100644 index 62d443f5..00000000 --- a/.vscode/extensions.json +++ /dev/null @@ -1,10 +0,0 @@ -{ - "recommendations": [ - "ms-iot.vscode-ros", - "ms-python.black-formatter", - "streetsidesoftware.code-spell-checker", - "kevinrose.vsc-python-indent", - "ms-python.python", - "shardulm94.trailing-spaces" - ] -} diff --git a/.vscode/settings.json b/.vscode/settings.json deleted file mode 100644 index 67d4694f..00000000 --- a/.vscode/settings.json +++ /dev/null @@ -1,12 +0,0 @@ -{ - "cSpell.customDictionaries": { - "project-words": { - "name": "Workspace Dictionary for Github Action", - "path": "${workspaceRoot}/.wordlist.txt", - "addWords": true - }, - "custom": true, - "internal-terms": false - }, - "files.insertFinalNewline": true -} diff --git a/README.md b/README.md index 8fd6767c..419f5fef 100644 --- a/README.md +++ b/README.md @@ -108,6 +108,22 @@ ros2 launch rosbot_gazebo simulation.launch.py ## Testing package +### pre-commit +[pre-commit configuration](.pre-commit-config.yaml) prepares plenty of tests helping for developing and contributing. Usage: + +```bash +# install pre-commit +pip install pre-commit + +# initialize pre-commit workspace +pre-commit install + +# manually run tests +pre-commit run -a +``` + +After initialization [pre-commit configuration](.pre-commit-config.yaml) will applied on every commit. + ### Industrial CI ``` colcon test From eb43c989b2905229cec4b5e1c2e80366169912ff Mon Sep 17 00:00:00 2001 From: Jakub Delicat Date: Tue, 24 Oct 2023 09:36:07 +0200 Subject: [PATCH 12/12] added .vscode to .gitignore | removed separate strings Signed-off-by: Jakub Delicat --- .gitignore | 1 + rosbot_bringup/launch/bringup.launch.py | 2 +- rosbot_controller/launch/controller.launch.py | 2 +- rosbot_gazebo/launch/simulation.launch.py | 2 +- 4 files changed, 4 insertions(+), 3 deletions(-) diff --git a/.gitignore b/.gitignore index b09c4ff1..f044df5f 100644 --- a/.gitignore +++ b/.gitignore @@ -1,3 +1,4 @@ +.vscode *.pyc # ROS 2 build folders diff --git a/rosbot_bringup/launch/bringup.launch.py b/rosbot_bringup/launch/bringup.launch.py index 787ef679..30b85f65 100644 --- a/rosbot_bringup/launch/bringup.launch.py +++ b/rosbot_bringup/launch/bringup.launch.py @@ -51,7 +51,7 @@ def generate_launch_description(): "mecanum", default_value="False", description=( - "Whether to use mecanum drive controller " "(otherwise diff drive controller is used)" + "Whether to use mecanum drive controller (otherwise diff drive controller is used)" ), ) diff --git a/rosbot_controller/launch/controller.launch.py b/rosbot_controller/launch/controller.launch.py index 8d745de3..f6382f6b 100644 --- a/rosbot_controller/launch/controller.launch.py +++ b/rosbot_controller/launch/controller.launch.py @@ -35,7 +35,7 @@ def generate_launch_description(): "mecanum", default_value="False", description=( - "Whether to use mecanum drive controller " "(otherwise diff drive controller is used)" + "Whether to use mecanum drive controller (otherwise diff drive controller is used)" ), ) diff --git a/rosbot_gazebo/launch/simulation.launch.py b/rosbot_gazebo/launch/simulation.launch.py index a3b534f1..47e272cc 100644 --- a/rosbot_gazebo/launch/simulation.launch.py +++ b/rosbot_gazebo/launch/simulation.launch.py @@ -35,7 +35,7 @@ def generate_launch_description(): "mecanum", default_value="False", description=( - "Whether to use mecanum drive controller " "(otherwise diff drive controller is used)" + "Whether to use mecanum drive controller (otherwise diff drive controller is used)" ), )