diff --git a/.editorconfig b/.editorconfig index 9dd330ea..8db9e725 100644 --- a/.editorconfig +++ b/.editorconfig @@ -10,7 +10,7 @@ insert_final_newline = true trim_trailing_whitespace = true [*.py] -max_line_length = 80 +max_line_length = 88 indent_size = 4 [*.md] diff --git a/.flake8 b/.flake8 index 042f2345..6c032f36 100644 --- a/.flake8 +++ b/.flake8 @@ -1,7 +1,3 @@ [flake8] -exclude= code/planning/src/behavior_agent/behavior_tree.py, - code/planning/src/behavior_agent/behaviours/__init__.py, - code/planning/src/behavior_agent/behaviours, - code/planning/__init__.py, - doc/development/templates/template_class_no_comments.py, - doc/development/templates/template_class.py \ No newline at end of file +max-line-length = 88 +extend-ignore = E203,E701 \ No newline at end of file diff --git a/.github/workflows/add-to-project.yml b/.github/workflows/add-to-project.yml index dcced1c4..52f9bcf6 100644 --- a/.github/workflows/add-to-project.yml +++ b/.github/workflows/add-to-project.yml @@ -1,4 +1,4 @@ -name: Add bugs to bugs project +name: Add issue to project on: issues: diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index fa07e68f..ac3b7276 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -1,9 +1,10 @@ -name: Build, publish and run tests +name: Build and push image on: - push: - branches: [ 'main' ] - pull_request: + workflow_run: + workflows: ["Check code format", "Linter markdown and code"] + types: + - completed env: REGISTRY: ghcr.io @@ -38,19 +39,6 @@ jobs: username: ${{ github.actor }} password: ${{ secrets.GITHUB_TOKEN }} - - name: Bump version and push tag - # only run on push to main - if: github.event_name == 'push' && github.ref == 'refs/heads/main' - id: tag - uses: mathieudutour/github-tag-action@v6.1 - with: - github_token: ${{ secrets.GITHUB_TOKEN }} - release_branches: main - - - name: Get commit hash - id: hash - run: echo "hash=$(git rev-parse --short HEAD)" >> $GITHUB_OUTPUT - - name: Build and push Docker image id: build uses: docker/build-push-action@v3 @@ -59,72 +47,6 @@ jobs: file: ./build/docker/build/Dockerfile push: true # tag 'latest' and version on push to main, otherwise use the commit hash - tags: | - ${{ env.REGISTRY }}/${{ env.IMAGE_NAME }}:${{ steps.tag.outputs.new_version == '' && steps.hash.outputs.hash || steps.tag.outputs.new_version }} - ${{ env.REGISTRY }}/${{ env.IMAGE_NAME }}:${{ github.event_name == 'push' && github.ref == 'refs/heads/main' && 'latest' || steps.hash.outputs.hash }} + tags: ${{ env.REGISTRY }}/${{ env.IMAGE_NAME }}:latest cache-from: type=gha cache-to: type=gha,mode=max - - - name: Output version - id: version - # take either the created tag or the commit hash - run: echo "version=${{ steps.tag.outputs.new_version == '' && steps.hash.outputs.hash || steps.tag.outputs.new_version }}" >> $GITHUB_OUTPUT - drive: - runs-on: self-hosted - needs: build-and-push-image - # run only on pull request for now - if: github.event_name == 'pull_request' - env: - AGENT_VERSION: ${{ needs.build-and-push-image.outputs.version }} - COMPOSE_FILE: ./build/docker-compose.cicd.yaml - steps: - - name: Checkout repository - uses: actions/checkout@v3 - - name: Print environment variables (DEBUG) - run: | - echo "AGENT_VERSION=${AGENT_VERSION}" - echo "COMPOSE_FILE=${COMPOSE_FILE}" - - name: Get commit hash - id: hash - run: echo "hash=$(git rev-parse --short HEAD)" >> $GITHUB_OUTPUT - - name: Set AGENT_VERSION from hash (workaround) - run: echo "AGENT_VERSION=${{ steps.hash.outputs.hash }}" >> $GITHUB_ENV - - name: Run docker-compose - run: docker compose up --quiet-pull --exit-code-from agent - - name: Copy results - run: docker compose cp agent:/tmp/simulation_results.json . - - name: Stop docker-compose - # always run this step, to clean up even on error - if: always() - run: docker compose down -v - # add rendered JSON as comment to the pull request - - name: Add simulation results as comment - if: github.event_name == 'pull_request' - uses: actions/github-script@v6 - with: - github-token: ${{ secrets.GITHUB_TOKEN }} - # this script reads the simulation_results.json and creates a comment on the pull request with the results. - script: | - const fs = require('fs'); - // read the simulation results - const results = fs.readFileSync('./simulation_results.json', 'utf8'); - let resultsJson = JSON.parse(results); - // create a markdown table of the results - let resultsTable = resultsJson.values.map((values, i) => { - return `| ${resultsJson.labels[i]} | ${values} |`; - }); - // create a markdown table header - let resultsTableHeader = `| Metric | Value |`; - // create a markdown table divider - let resultsTableDivider = `| --- | --- |`; - // add everything to the resultsTable - resultsTable = resultsTableHeader + '\n' + resultsTableDivider + '\n' + resultsTable.join('\n'); - // add the results as a comment to the pull request - github.rest.issues.createComment({ - issue_number: context.issue.number, - owner: context.repo.owner, - repo: context.repo.repo, - body: "## Simulation results\n" + resultsTable - }); - - name: Prune all images older than 30 days from self-hosted runner - run: docker image prune -a --force --filter "until=720h" diff --git a/.github/workflows/drive.yaml b/.github/workflows/drive.yaml new file mode 100644 index 00000000..629acba7 --- /dev/null +++ b/.github/workflows/drive.yaml @@ -0,0 +1,63 @@ +name: Evaluate agent + +on: + workflow_run: + workflows: ["Build and push image"] + types: + - completed + +jobs: + drive: + runs-on: self-hosted + needs: build-and-push-image + # run only on pull request for now + if: github.event_name == 'pull_request' + env: + AGENT_VERSION: latest + COMPOSE_FILE: ./build/docker-compose.cicd.yaml + steps: + - name: Checkout repository + uses: actions/checkout@v3 + - name: Print environment variables (DEBUG) + run: | + echo "AGENT_VERSION=${AGENT_VERSION}" + echo "COMPOSE_FILE=${COMPOSE_FILE}" + - name: Run docker-compose + run: docker compose up --quiet-pull --exit-code-from agent + - name: Copy results + run: docker compose cp agent:/tmp/simulation_results.json . + - name: Stop docker-compose + # always run this step, to clean up even on error + if: always() + run: docker compose down -v + # add rendered JSON as comment to the pull request + - name: Add simulation results as comment + if: github.event_name == 'pull_request' + uses: actions/github-script@v6 + with: + github-token: ${{ secrets.GITHUB_TOKEN }} + # this script reads the simulation_results.json and creates a comment on the pull request with the results. + script: | + const fs = require('fs'); + // read the simulation results + const results = fs.readFileSync('./simulation_results.json', 'utf8'); + let resultsJson = JSON.parse(results); + // create a markdown table of the results + let resultsTable = resultsJson.values.map((values, i) => { + return `| ${resultsJson.labels[i]} | ${values} |`; + }); + // create a markdown table header + let resultsTableHeader = `| Metric | Value |`; + // create a markdown table divider + let resultsTableDivider = `| --- | --- |`; + // add everything to the resultsTable + resultsTable = resultsTableHeader + '\n' + resultsTableDivider + '\n' + resultsTable.join('\n'); + // add the results as a comment to the pull request + github.rest.issues.createComment({ + issue_number: context.issue.number, + owner: context.repo.owner, + repo: context.repo.repo, + body: "## Simulation results\n" + resultsTable + }); + - name: Prune all images older than 30 days from self-hosted runner + run: docker image prune -a --force --filter "until=720h" \ No newline at end of file diff --git a/.github/workflows/format.yaml b/.github/workflows/format.yaml new file mode 100644 index 00000000..58a1947e --- /dev/null +++ b/.github/workflows/format.yaml @@ -0,0 +1,21 @@ +name: Check code format + +on: + pull_request: + branches: + - "main" + +jobs: + format: + name: Check code files format + runs-on: ubuntu-latest + steps: + - name: Check out the repo + uses: actions/checkout@v2 + # Execute the python formatter + - name: Run the python formatter + uses: addnab/docker-run-action@v3 + with: + image: pyfound/black + options: -v ${{ github.workspace}}:/apps + run: black --check ./apps/ diff --git a/.github/workflows/linter.yml b/.github/workflows/linter.yml index d20a1b54..630ad725 100644 --- a/.github/workflows/linter.yml +++ b/.github/workflows/linter.yml @@ -1,6 +1,9 @@ -name: linter +name: Linter markdown and code -on: pull_request +on: + pull_request: + branches: + - "main" jobs: linter: @@ -13,16 +16,13 @@ jobs: - name: Run the markdown linter uses: addnab/docker-run-action@v3 with: - image: peterdavehello/markdownlint:0.32.2 - options: -v ${{ github.workspace }}:/md - run: | - markdownlint . + image: peterdavehello/markdownlint:0.32.2 + options: -v ${{ github.workspace }}:/md + run: markdownlint . # Execute the python linter (executes even if the previous step failed) - name: Run the python linter - if: always() uses: addnab/docker-run-action@v3 with: image: alpine/flake8 options: -v ${{ github.workspace }}:/apps - run: | - flake8 code + run: flake8 . diff --git a/.vscode/extensions.json b/.vscode/extensions.json index 6e4fc554..c27bbad5 100644 --- a/.vscode/extensions.json +++ b/.vscode/extensions.json @@ -11,6 +11,7 @@ "bierner.markdown-mermaid", "richardkotze.git-mob", "ms-vscode-remote.remote-containers", - "valentjn.vscode-ltex" + "valentjn.vscode-ltex", + "ms-python.black-formatter" ] } \ No newline at end of file diff --git a/.vscode/settings.json b/.vscode/settings.json index 8d42024f..260ba70c 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -1,7 +1,6 @@ { "githubIssues.issueBranchTitle": "${issueNumber}-${sanitizedIssueTitle}", "githubIssues.queries": [ - { "label": "My Issues", "query": "default" @@ -23,8 +22,9 @@ "docker.commands.composeUp": [ { "label": "Compose Up", - "template": "xhost +local: && ${composeCommand} ${configurationFile} up" + "template": "xhost +local: && USERNAME=$(whoami) USER_UID=$(id -u) USER_GID=$(id -g) ${composeCommand} ${configurationFile} up" } ], - "workbench.iconTheme": "vscode-icons" + "workbench.iconTheme": "vscode-icons", + "editor.formatOnSave": true } \ No newline at end of file diff --git a/build/agent_service.yaml b/build/agent_service.yaml index 6362983b..13d8bab1 100644 --- a/build/agent_service.yaml +++ b/build/agent_service.yaml @@ -2,10 +2,11 @@ services: agent: build: dockerfile: build/docker/agent/Dockerfile - args: - - USER_UID=${DOCKER_HOST_UNIX_UID:-1000} - - USER_GID=${DOCKER_HOST_UNIX_GID:-1000} context: ../ + args: + USERNAME: ${USERNAME} + USER_UID: ${USER_UID} + USER_GID: ${USER_GID} init: true tty: true shm_size: 2gb diff --git a/build/docker-compose.dev.yaml b/build/docker-compose.dev.yaml index 0e3fe39a..ab21bf03 100644 --- a/build/docker-compose.dev.yaml +++ b/build/docker-compose.dev.yaml @@ -1,13 +1,17 @@ # compose file for the development without a driving vehicle # "interactive" development without a car +include: + - roscore_service.yaml + services: agent-dev: build: dockerfile: build/docker/agent-dev/Dockerfile context: ../ args: - - USER_UID=${DOCKER_HOST_UNIX_UID:-1000} - - USER_GID=${DOCKER_HOST_UNIX_GID:-1000} + USERNAME: ${USERNAME} + USER_UID: ${USER_UID} + USER_GID: ${USER_GID} init: true tty: true shm_size: 2gb @@ -23,6 +27,4 @@ services: - DISPLAY=${DISPLAY} network_mode: host privileged: true - entrypoint: ["/dev_entrypoint.sh"] - command: bash - \ No newline at end of file + command: bash -c "sudo chown -R ${USER_UID}:${USER_GID} ../ && sudo chmod -R a+w ../ && bash" diff --git a/build/docker-compose.devroute-distributed.yaml b/build/docker-compose.devroute-distributed.yaml index e8ed7e9f..cc9f429c 100644 --- a/build/docker-compose.devroute-distributed.yaml +++ b/build/docker-compose.devroute-distributed.yaml @@ -8,7 +8,7 @@ services: extends: file: agent_service.yaml service: agent - command: bash -c "sleep 10 && roslaunch agent/launch/dev.launch" + command: bash -c "sleep 10 && sudo chown -R ${USER_UID}:${USER_GID} ../ && sudo chmod -R a+w ../ && roslaunch agent/launch/dev.launch" environment: - CARLA_SIM_HOST= - ROUTE=/workspace/code/routes/routes_simple.xml diff --git a/build/docker-compose.devroute.yaml b/build/docker-compose.devroute.yaml index 6f04d601..4510f0a2 100644 --- a/build/docker-compose.devroute.yaml +++ b/build/docker-compose.devroute.yaml @@ -12,4 +12,4 @@ services: service: agent environment: - ROUTE=/workspace/code/routes/routes_simple.xml - command: bash -c "sleep 10 && sudo chown -R carla:carla ../code/ && sudo chmod -R a+w ../code/ && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=$${ROUTE} --agent=/workspace/code/agent/src/agent/agent.py --host=$${CARLA_SIM_HOST} --track=MAP" + command: bash -c "sleep 10 && sudo chown -R ${USER_UID}:${USER_GID} ../ && sudo chmod -R a+w ../ && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=$${ROUTE} --agent=/workspace/code/agent/src/agent/agent.py --host=$${CARLA_SIM_HOST} --track=MAP" diff --git a/build/docker-compose.leaderboard-distributed.yaml b/build/docker-compose.leaderboard-distributed.yaml index 464c1aa6..1bcb9949 100644 --- a/build/docker-compose.leaderboard-distributed.yaml +++ b/build/docker-compose.leaderboard-distributed.yaml @@ -7,7 +7,7 @@ services: extends: file: agent_service.yaml service: agent - command: bash -c "sleep 10 && sudo chown -R carla:carla ../code/ && sudo chmod -R a+w ../code/ && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=$${ROUTE} --agent=/workspace/code/agent/src/agent/agent.py --host=$${CARLA_SIM_HOST} --track=MAP" + command: bash -c "sleep 10 && sudo chown -R ${USER_UID}:${USER_GID} ../ && sudo chmod -R a+w ../ && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=$${ROUTE} --agent=/workspace/code/agent/src/agent/agent.py --host=$${CARLA_SIM_HOST} --track=MAP" environment: - CARLA_SIM_HOST= diff --git a/build/docker-compose.leaderboard.yaml b/build/docker-compose.leaderboard.yaml index 93a669fc..32fc98fc 100644 --- a/build/docker-compose.leaderboard.yaml +++ b/build/docker-compose.leaderboard.yaml @@ -8,4 +8,4 @@ services: extends: file: agent_service.yaml service: agent - command: bash -c "sleep 10 && sudo chown -R carla:carla ../code/ && sudo chmod -R a+w ../code/ && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=$${ROUTE} --agent=/workspace/code/agent/src/agent/agent.py --host=$${CARLA_SIM_HOST} --track=MAP" + command: bash -c "sleep 10 && sudo chown -R ${USER_UID}:${USER_GID} ../ && sudo chmod -R a+w ../ && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=$${ROUTE} --agent=/workspace/code/agent/src/agent/agent.py --host=$${CARLA_SIM_HOST} --track=MAP" diff --git a/build/docker-compose.linter.yaml b/build/docker-compose.linter.yaml index 0816aaab..d184141d 100644 --- a/build/docker-compose.linter.yaml +++ b/build/docker-compose.linter.yaml @@ -5,6 +5,12 @@ services: volumes: - ../:/apps + black: + image: pyfound/black + command: black --check ./apps/ + volumes: + - ../:/apps + mdlint: image: peterdavehello/markdownlint:0.32.2 command: markdownlint . diff --git a/build/docker/agent-dev/dev_entrypoint.sh b/build/docker/agent-dev/dev_entrypoint.sh index 14f912e3..2626fcb9 100755 --- a/build/docker/agent-dev/dev_entrypoint.sh +++ b/build/docker/agent-dev/dev_entrypoint.sh @@ -1,19 +1,7 @@ #!/bin/bash +set -e -# Source ROS setup source /opt/ros/noetic/setup.bash - -# Source the catkin workspace setup source /catkin_ws/devel/setup.bash -# Set up any additional environment variables if needed -export CARLA_ROOT=/opt/carla -export SCENARIO_RUNNER_ROOT=/opt/scenario_runner -export LEADERBOARD_ROOT=/opt/leaderboard - -# Execute the command passed to the script, or start a bash session if no command was given -if [ $# -eq 0 ]; then - exec bash -else - exec "$@" -fi \ No newline at end of file +exec "$@" diff --git a/build/docker/agent/Dockerfile b/build/docker/agent/Dockerfile index 1917b372..dff54814 100644 --- a/build/docker/agent/Dockerfile +++ b/build/docker/agent/Dockerfile @@ -12,14 +12,14 @@ FROM osrf/ros:noetic-desktop-full-focal # COPY --from=carla /home/carla/PythonAPI /opt/carla/PythonAPI -ARG USERNAME=carla -ARG USER_UID=999 -ARG USER_GID=$USER_UID +ARG USERNAME +ARG USER_UID +ARG USER_GID ARG DEBIAN_FRONTEND=noninteractive # install rendering dependencies for rviz / rqt RUN apt-get update \ - && apt-get install -y -qq --no-install-recommends \ + && apt-get install -y -qq --no-install-recommends \ libxext6 libx11-6 libglvnd0 libgl1 \ libglx0 libegl1 freeglut3-dev apt-utils \ fprintd libfprint-2-2 libpam-fprintd @@ -30,10 +30,10 @@ RUN apt-get install wget unzip # Download Carla PythonAPI (alternative to getting it from the Carla-Image, which is commented out above) # If the PythonAPI/Carla version changes, either update the link, or refer to the comment at the top of this file. RUN wget https://github.com/una-auxme/paf/releases/download/v0.0.1/PythonAPI_Leaderboard-2.0.zip -O PythonAPI.zip \ - && unzip PythonAPI.zip \ - && rm PythonAPI.zip \ - && mkdir -p /opt/carla \ - && mv PythonAPI /opt/carla/PythonAPI + && unzip PythonAPI.zip \ + && rm PythonAPI.zip \ + && mkdir -p /opt/carla \ + && mv PythonAPI /opt/carla/PythonAPI # Workaround/fix for using dpkg for cuda installation # Only required for the lab PCs @@ -65,12 +65,12 @@ ENV PYTHONPATH=$PYTHONPATH:/opt/carla/PythonAPI/carla/dist/carla-0.9.14-py3.7-li # install mlocate, pip, wget, git and some ROS dependencies for building the CARLA ROS bridge RUN apt-get update && apt-get install -y \ - mlocate python3-pip wget git python-is-python3 \ - ros-noetic-ackermann-msgs ros-noetic-derived-object-msgs \ - ros-noetic-carla-msgs ros-noetic-pcl-conversions \ - ros-noetic-rviz ros-noetic-rqt ros-noetic-pcl-ros ros-noetic-rosbridge-suite ros-noetic-rosbridge-server \ - ros-noetic-robot-pose-ekf ros-noetic-ros-numpy \ - ros-noetic-py-trees-ros ros-noetic-rqt-py-trees ros-noetic-rqt-reconfigure + mlocate python3-pip wget git python-is-python3 \ + ros-noetic-ackermann-msgs ros-noetic-derived-object-msgs \ + ros-noetic-carla-msgs ros-noetic-pcl-conversions \ + ros-noetic-rviz ros-noetic-rqt ros-noetic-pcl-ros ros-noetic-rosbridge-suite ros-noetic-rosbridge-server \ + ros-noetic-robot-pose-ekf ros-noetic-ros-numpy \ + ros-noetic-py-trees-ros ros-noetic-rqt-py-trees ros-noetic-rqt-reconfigure SHELL ["/bin/bash", "-c"] @@ -105,9 +105,9 @@ ENV CARLA_ROS_BRIDGE_ROOT=/catkin_ws/src/ros-bridge # (as we're not running as root, pip installs into ~/.local/bin) ENV PATH=$PATH:/home/$USERNAME/.local/bin -# install simple_pid +# install pip packages RUN python -m pip install pip --upgrade \ - && python -m pip install simple_pid pygame transformations roslibpy lxml + && python -m pip install simple_pid pygame transformations roslibpy lxml black # install the scenario runner from GitHub leaderboard-2.0 branch ENV CARLA_ROOT=/opt/carla @@ -170,20 +170,19 @@ RUN source /opt/ros/noetic/setup.bash && catkin_make ADD ./build/docker/agent/entrypoint.sh /entrypoint.sh - - # set the default working directory to the code WORKDIR /workspace/code RUN echo "source /opt/ros/noetic/setup.bash" >> ~/.bashrc +RUN echo "source /catkin_ws/devel/setup.bash" >> ~/.bashrc ENTRYPOINT ["/entrypoint.sh"] CMD ["bash", "-c", "sleep 10 && \ -python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py \ ---debug=${DEBUG_CHALLENGE} \ ---repetitions=${REPETITIONS} \ ---checkpoint=${CHECKPOINT_ENDPOINT} \ ---track=${CHALLENGE_TRACK} \ ---agent=${TEAM_AGENT} \ ---routes=${ROUTES} \ ---host=${CARLA_SIM_HOST}"] + python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py \ + --debug=${DEBUG_CHALLENGE} \ + --repetitions=${REPETITIONS} \ + --checkpoint=${CHECKPOINT_ENDPOINT} \ + --track=${CHALLENGE_TRACK} \ + --agent=${TEAM_AGENT} \ + --routes=${ROUTES} \ + --host=${CARLA_SIM_HOST}"] diff --git a/build/docker/agent/Dockerfile_Submission b/build/docker/agent/Dockerfile_Submission index 128a8bd8..8128266e 100644 --- a/build/docker/agent/Dockerfile_Submission +++ b/build/docker/agent/Dockerfile_Submission @@ -19,7 +19,7 @@ ARG DEBIAN_FRONTEND=noninteractive # install rendering dependencies for rviz / rqt RUN apt-get update \ - && apt-get install -y -qq --no-install-recommends \ + && apt-get install -y -qq --no-install-recommends \ libxext6 libx11-6 libglvnd0 libgl1 \ libglx0 libegl1 freeglut3-dev @@ -27,10 +27,10 @@ RUN apt-get update \ RUN apt-get install wget unzip RUN wget https://github.com/una-auxme/paf/releases/download/v0.0.1/PythonAPI_Leaderboard-2.0.zip -O PythonAPI.zip \ - && unzip PythonAPI.zip \ - && rm PythonAPI.zip \ - && mkdir -p /opt/carla \ - && mv PythonAPI /opt/carla/PythonAPI + && unzip PythonAPI.zip \ + && rm PythonAPI.zip \ + && mkdir -p /opt/carla \ + && mv PythonAPI /opt/carla/PythonAPI # build libgit2 RUN wget https://github.com/libgit2/libgit2/archive/refs/tags/v1.5.0.tar.gz -O libgit2-1.5.0.tar.gz \ @@ -67,12 +67,12 @@ ENV PYTHONPATH=$PYTHONPATH:/opt/carla/PythonAPI/carla/dist/carla-0.9.14-py3.7-li # install mlocate, pip, wget, git and some ROS dependencies for building the CARLA ROS bridge RUN apt-get update && apt-get install -y \ - mlocate python3-pip wget git python-is-python3 \ - ros-noetic-ackermann-msgs ros-noetic-derived-object-msgs \ - ros-noetic-carla-msgs ros-noetic-pcl-conversions \ - ros-noetic-rviz ros-noetic-rqt ros-noetic-pcl-ros ros-noetic-rosbridge-suite ros-noetic-rosbridge-server \ - ros-noetic-robot-pose-ekf ros-noetic-ros-numpy \ - ros-noetic-py-trees-ros ros-noetic-rqt-py-trees ros-noetic-rqt-reconfigure + mlocate python3-pip wget git python-is-python3 \ + ros-noetic-ackermann-msgs ros-noetic-derived-object-msgs \ + ros-noetic-carla-msgs ros-noetic-pcl-conversions \ + ros-noetic-rviz ros-noetic-rqt ros-noetic-pcl-ros ros-noetic-rosbridge-suite ros-noetic-rosbridge-server \ + ros-noetic-robot-pose-ekf ros-noetic-ros-numpy \ + ros-noetic-py-trees-ros ros-noetic-rqt-py-trees ros-noetic-rqt-reconfigure SHELL ["/bin/bash", "-c"] @@ -178,12 +178,13 @@ ADD ./build/docker/agent/entrypoint.sh /entrypoint.sh WORKDIR /workspace/code RUN echo "source /opt/ros/noetic/setup.bash" >> ~/.bashrc +RUN echo "source /catkin_ws/devel/setup.bash" >> ~/.bashrc ENTRYPOINT ["/entrypoint.sh"] CMD ["bash", "-c", "sleep 10 && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=${DEBUG_CHALLENGE} \ ---repetitions=${REPETITIONS} \ ---checkpoint=${CHECKPOINT_ENDPOINT} \ ---track=${CHALLENGE_TRACK} \ ---agent=${TEAM_AGENT} \ ---routes=${ROUTES} \ ---host=${CARLA_SIM_HOST}"] + --repetitions=${REPETITIONS} \ + --checkpoint=${CHECKPOINT_ENDPOINT} \ + --track=${CHALLENGE_TRACK} \ + --agent=${TEAM_AGENT} \ + --routes=${ROUTES} \ + --host=${CARLA_SIM_HOST}"] diff --git a/build/docker/agent/entrypoint.sh b/build/docker/agent/entrypoint.sh index 61e51dc4..2626fcb9 100755 --- a/build/docker/agent/entrypoint.sh +++ b/build/docker/agent/entrypoint.sh @@ -1,7 +1,7 @@ #!/bin/bash set -e -source "/opt/ros/noetic/setup.bash" -source "/catkin_ws/devel/setup.bash" +source /opt/ros/noetic/setup.bash +source /catkin_ws/devel/setup.bash exec "$@" diff --git a/code/__init__.py b/code/__init__.py deleted file mode 100644 index e69de29b..00000000 diff --git a/code/acting/setup.py b/code/acting/setup.py index e2665b1f..773f1357 100644 --- a/code/acting/setup.py +++ b/code/acting/setup.py @@ -2,6 +2,5 @@ from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup -setup_args = generate_distutils_setup(packages=['acting'], - package_dir={'': 'src'}) +setup_args = generate_distutils_setup(packages=["acting"], package_dir={"": "src"}) setup(**setup_args) diff --git a/code/acting/src/acting/Acting_Debug_Node.py b/code/acting/src/acting/Acting_Debug_Node.py index 99839e18..b3289747 100755 --- a/code/acting/src/acting/Acting_Debug_Node.py +++ b/code/acting/src/acting/Acting_Debug_Node.py @@ -71,35 +71,33 @@ def __init__(self): Constructor of the class :return: """ - super(Acting_Debug_Node, self).__init__('dummy_trajectory_pub') - self.loginfo('Acting_Debug_Node node started') - self.role_name = self.get_param('role_name', 'ego_vehicle') - self.control_loop_rate = self.get_param('control_loop_rate', 0.05) + super(Acting_Debug_Node, self).__init__("dummy_trajectory_pub") + self.loginfo("Acting_Debug_Node node started") + self.role_name = self.get_param("role_name", "ego_vehicle") + self.control_loop_rate = self.get_param("control_loop_rate", 0.05) # Publisher for Dummy Trajectory self.trajectory_pub: Publisher = self.new_publisher( - Path, - "/paf/" + self.role_name + "/trajectory", - qos_profile=1) + Path, "/paf/" + self.role_name + "/trajectory", qos_profile=1 + ) # Publisher for Dummy Velocity self.velocity_pub: Publisher = self.new_publisher( - Float32, - f"/paf/{self.role_name}/target_velocity", - qos_profile=1) + Float32, f"/paf/{self.role_name}/target_velocity", qos_profile=1 + ) # PurePursuit: Publisher for Dummy PP-Steer self.pure_pursuit_steer_pub: Publisher = self.new_publisher( - Float32, - f"/paf/{self.role_name}/pure_pursuit_steer", - qos_profile=1) + Float32, f"/paf/{self.role_name}/pure_pursuit_steer", qos_profile=1 + ) # Subscriber of current_pos, used for Steering Debugging self.current_pos_sub: Subscriber = self.new_subscription( msg_type=PoseStamped, topic="/paf/" + self.role_name + "/current_pos", callback=self.__current_position_callback, - qos_profile=1) + qos_profile=1, + ) # ---> EVALUATION/TUNING: Subscribers for plotting # Subscriber for target_velocity for plotting @@ -107,55 +105,61 @@ def __init__(self): Float32, f"/paf/{self.role_name}/target_velocity", self.__get_target_velocity, - qos_profile=1) + qos_profile=1, + ) # Subscriber for current_heading self.heading_sub: Subscriber = self.new_subscription( Float32, f"/paf/{self.role_name}/current_heading", self.__get_heading, - qos_profile=1) + qos_profile=1, + ) # Subscriber for current_velocity self.current_velocity_sub: Subscriber = self.new_subscription( CarlaSpeedometer, f"/carla/{self.role_name}/Speed", self.__get_current_velocity, - qos_profile=1) + qos_profile=1, + ) # Subscriber for current_throttle self.current_throttle_sub: Subscriber = self.new_subscription( Float32, f"/paf/{self.role_name}/throttle", self.__get_throttle, - qos_profile=1) + qos_profile=1, + ) # Subscriber for Stanley_steer self.stanley_steer_sub: Subscriber = self.new_subscription( Float32, f"/paf/{self.role_name}/stanley_steer", self.__get_stanley_steer, - qos_profile=1) + qos_profile=1, + ) # Subscriber for PurePursuit_steer self.pure_pursuit_steer_sub: Subscriber = self.new_subscription( Float32, f"/paf/{self.role_name}/pure_pursuit_steer", self.__get_purepursuit_steer, - qos_profile=1) + qos_profile=1, + ) # Subscriber for vehicle_steer self.vehicle_steer_sub: Subscriber = self.new_subscription( CarlaEgoVehicleControl, - f'/carla/{self.role_name}/vehicle_control_cmd', + f"/carla/{self.role_name}/vehicle_control_cmd", self.__get_vehicle_steer, - qos_profile=10) + qos_profile=10, + ) # Publisher for emergency brake testing self.emergency_pub: Publisher = self.new_publisher( - Bool, - f"/paf/{self.role_name}/emergency", - qos_profile=1) + Bool, f"/paf/{self.role_name}/emergency", qos_profile=1 + ) # Initialize all needed "global" variables here self.current_trajectory = [] @@ -181,16 +185,12 @@ def __init__(self): # Spawncoords at the simulationstart startx = 984.5 starty = -5442.0 - if (TRAJECTORY_TYPE == 0): # Straight trajectory - self.current_trajectory = [ - (startx, starty), - (startx, starty-200) - ] + if TRAJECTORY_TYPE == 0: # Straight trajectory + self.current_trajectory = [(startx, starty), (startx, starty - 200)] - elif (TRAJECTORY_TYPE == 1): # straight into 90° Curve + elif TRAJECTORY_TYPE == 1: # straight into 90° Curve self.current_trajectory = [ (984.5, -5442.0), - (984.5, -5563.5), (985.0, -5573.2), (986.3, -5576.5), @@ -198,12 +198,11 @@ def __init__(self): (988.7, -5579.0), (990.5, -5579.8), (1000.0, -5580.2), - (1040.0, -5580.0), - (1070.0, -5580.0) + (1070.0, -5580.0), ] - elif (TRAJECTORY_TYPE == 2): # Sinewave Serpentines trajectory + elif TRAJECTORY_TYPE == 2: # Sinewave Serpentines trajectory # Generate a sine-wave with the global Constants to # automatically generate a trajectory with serpentine waves cycles = 4 # how many sine cycles @@ -224,53 +223,50 @@ def __init__(self): traj_y -= 2 trajectory_wave.append((traj_x, traj_y)) # back to the middle of the road - trajectory_wave.append((startx, traj_y-2)) + trajectory_wave.append((startx, traj_y - 2)) # add a long straight path after the serpentines - trajectory_wave.append((startx, starty-200)) + trajectory_wave.append((startx, starty - 200)) self.current_trajectory = trajectory_wave - elif (TRAJECTORY_TYPE == 3): # 2 Lane Switches + elif TRAJECTORY_TYPE == 3: # 2 Lane Switches self.current_trajectory = [ (startx, starty), - (startx-0.5, starty-10), - (startx-0.5, starty-20), - - (startx-0.4, starty-21), - (startx-0.3, starty-22), - (startx-0.2, starty-23), - (startx-0.1, starty-24), - (startx, starty-25), - (startx+0.1, starty-26), - (startx+0.2, starty-27), - (startx+0.3, starty-28), - (startx+0.4, starty-29), - (startx+0.5, starty-30), - (startx+0.6, starty-31), - (startx+0.7, starty-32), - (startx+0.8, starty-33), - (startx+0.9, starty-34), - (startx+1.0, starty-35), - (startx+1.0, starty-50), - - (startx+1.0, starty-51), - (startx+0.9, starty-52), - (startx+0.8, starty-53), - (startx+0.7, starty-54), - (startx+0.6, starty-55), - (startx+0.5, starty-56), - (startx+0.4, starty-57), - (startx+0.3, starty-58), - (startx+0.2, starty-59), - (startx+0.1, starty-60), - (startx, starty-61), - (startx-0.1, starty-62), - (startx-0.2, starty-63), - (startx-0.3, starty-64), - (startx-0.4, starty-65), - (startx-0.5, starty-66), - - (startx-0.5, starty-100), - ] + (startx - 0.5, starty - 10), + (startx - 0.5, starty - 20), + (startx - 0.4, starty - 21), + (startx - 0.3, starty - 22), + (startx - 0.2, starty - 23), + (startx - 0.1, starty - 24), + (startx, starty - 25), + (startx + 0.1, starty - 26), + (startx + 0.2, starty - 27), + (startx + 0.3, starty - 28), + (startx + 0.4, starty - 29), + (startx + 0.5, starty - 30), + (startx + 0.6, starty - 31), + (startx + 0.7, starty - 32), + (startx + 0.8, starty - 33), + (startx + 0.9, starty - 34), + (startx + 1.0, starty - 35), + (startx + 1.0, starty - 50), + (startx + 1.0, starty - 51), + (startx + 0.9, starty - 52), + (startx + 0.8, starty - 53), + (startx + 0.7, starty - 54), + (startx + 0.6, starty - 55), + (startx + 0.5, starty - 56), + (startx + 0.4, starty - 57), + (startx + 0.3, starty - 58), + (startx + 0.2, starty - 59), + (startx + 0.1, starty - 60), + (startx, starty - 61), + (startx - 0.1, starty - 62), + (startx - 0.2, starty - 63), + (startx - 0.3, starty - 64), + (startx - 0.4, starty - 65), + (startx - 0.5, starty - 66), + (startx - 0.5, starty - 100), + ] self.updated_trajectory(self.current_trajectory) def updated_trajectory(self, target_trajectory): @@ -347,21 +343,21 @@ def loop(timer_event=None): depending on the selected TEST_TYPE """ # Drive const. velocity on fixed straight steering - if (TEST_TYPE == 0): + if TEST_TYPE == 0: self.driveVel = TARGET_VELOCITY_1 self.pure_pursuit_steer_pub.publish(FIXED_STEERING) self.velocity_pub.publish(self.driveVel) # Drive alternating velocities on fixed straight steering - elif (TEST_TYPE == 1): + elif TEST_TYPE == 1: if not self.time_set: self.drive_Vel = TARGET_VELOCITY_1 self.switch_checkpoint_time = rospy.get_time() self.switch_time_set = True - if (self.switch_checkpoint_time < rospy.get_time() - 10): + if self.switch_checkpoint_time < rospy.get_time() - 10: self.switch_checkpoint_time = rospy.get_time() self.switchVelocity = not self.switchVelocity - if (self.switchVelocity): + if self.switchVelocity: self.driveVel = TARGET_VELOCITY_2 else: self.driveVel = TARGET_VELOCITY_1 @@ -369,7 +365,7 @@ def loop(timer_event=None): self.velocity_pub.publish(self.driveVel) # drive const. velocity on trajectoy with steering controller - elif (TEST_TYPE == 2): + elif TEST_TYPE == 2: # Continuously update path and publish it self.drive_Vel = TARGET_VELOCITY_1 self.updated_trajectory(self.current_trajectory) @@ -378,13 +374,13 @@ def loop(timer_event=None): # drive const. velocity on fixed straight steering and # trigger an emergency brake after 15 secs - elif (TEST_TYPE == 3): + elif TEST_TYPE == 3: # Continuously update path and publish it self.drive_Vel = TARGET_VELOCITY_1 if not self.time_set: self.checkpoint_time = rospy.get_time() self.time_set = True - if (self.checkpoint_time < rospy.get_time() - 15.0): + if self.checkpoint_time < rospy.get_time() - 15.0: self.checkpoint_time = rospy.get_time() self.emergency_pub.publish(True) self.pure_pursuit_steer_pub.publish(FIXED_STEERING) @@ -402,7 +398,7 @@ def loop(timer_event=None): print(">>>>>>>>>>>> TRAJECTORY <<<<<<<<<<<<<<") # Uncomment the prints of the data you want to plot - if (self.checkpoint_time < rospy.get_time() - PRINT_AFTER_TIME): + if self.checkpoint_time < rospy.get_time() - PRINT_AFTER_TIME: self.checkpoint_time = rospy.get_time() print(">>>>>>>>>>>> DATA <<<<<<<<<<<<<<") if PRINT_VELOCITY_DATA: @@ -420,6 +416,7 @@ def loop(timer_event=None): print(">> ACTUAL POSITIONS <<") print(self.positions) print(">>>>>>>>>>>> DATA <<<<<<<<<<<<<<") + self.new_timer(self.control_loop_rate, loop) self.spin() diff --git a/code/acting/src/acting/MainFramePublisher.py b/code/acting/src/acting/MainFramePublisher.py index 0ba4783d..a34240e8 100755 --- a/code/acting/src/acting/MainFramePublisher.py +++ b/code/acting/src/acting/MainFramePublisher.py @@ -19,11 +19,11 @@ def __init__(self): ego vehicle does. The hero frame is used by sensors like the lidar. Rviz also uses the hero frame. The main frame is used for planning. """ - super(MainFramePublisher, self).__init__('main_frame_publisher') - self.loginfo('MainFramePublisher node started') + super(MainFramePublisher, self).__init__("main_frame_publisher") + self.loginfo("MainFramePublisher node started") - self.control_loop_rate = self.get_param('control_loop_rate', 0.05) - self.role_name = self.get_param('role_name', 'ego_vehicle') + self.control_loop_rate = self.get_param("control_loop_rate", 0.05) + self.role_name = self.get_param("role_name", "ego_vehicle") self.current_pos: PoseStamped = PoseStamped() self.current_heading: float = 0 @@ -31,16 +31,18 @@ def __init__(self): PoseStamped, "/paf/" + self.role_name + "/current_pos", self.get_current_pos, - qos_profile=1) + qos_profile=1, + ) self.current_heading_subscriber = self.new_subscription( Float32, f"/paf/{self.role_name}/current_heading", self.get_current_heading, - qos_profile=1) + qos_profile=1, + ) def run(self): - self.loginfo('MainFramePublisher node running') + self.loginfo("MainFramePublisher node running") br = tf.TransformBroadcaster() def loop(timer_event=None): @@ -49,22 +51,26 @@ def loop(timer_event=None): return rot = -self.current_heading pos = [0, 0, 0] - pos[0] = cos(rot) * \ - self.current_pos.pose.position.x - \ - sin(rot) * self.current_pos.pose.position.y - pos[1] = sin(rot) * \ - self.current_pos.pose.position.x + \ - cos(rot) * self.current_pos.pose.position.y + pos[0] = ( + cos(rot) * self.current_pos.pose.position.x + - sin(rot) * self.current_pos.pose.position.y + ) + pos[1] = ( + sin(rot) * self.current_pos.pose.position.x + + cos(rot) * self.current_pos.pose.position.y + ) pos[2] = -self.current_pos.pose.position.z - rot_quat = R.from_euler("xyz", [0, 0, -self.current_heading+pi], - degrees=False).as_quat() - - br.sendTransform(pos, - rot_quat, - rospy.Time.now(), - "global", - "hero", - ) + rot_quat = R.from_euler( + "xyz", [0, 0, -self.current_heading + pi], degrees=False + ).as_quat() + + br.sendTransform( + pos, + rot_quat, + rospy.Time.now(), + "global", + "hero", + ) self.new_timer(self.control_loop_rate, loop) self.spin() @@ -81,7 +87,7 @@ def main(args=None): Main function starts the node :param args: """ - roscomp.init('main_frame_publisher', args=args) + roscomp.init("main_frame_publisher", args=args) try: node = MainFramePublisher() @@ -92,5 +98,5 @@ def main(args=None): roscomp.shutdown() -if __name__ == '__main__': +if __name__ == "__main__": main() diff --git a/code/acting/src/acting/helper_functions.py b/code/acting/src/acting/helper_functions.py index 072e9aa2..8dc2c6d8 100755 --- a/code/acting/src/acting/helper_functions.py +++ b/code/acting/src/acting/helper_functions.py @@ -106,10 +106,10 @@ def calc_path_yaw(path: Path, idx: int) -> float: point_current = path.poses[idx] point_next: PoseStamped point_next = path.poses[idx + 1] - angle = math.atan2(point_next.pose.position.y - - point_current.pose.position.y, - point_next.pose.position.x - - point_current.pose.position.x) + angle = math.atan2( + point_next.pose.position.y - point_current.pose.position.y, + point_next.pose.position.x - point_current.pose.position.x, + ) return normalize_angle(angle) @@ -134,14 +134,19 @@ def calc_egocar_yaw(pose: PoseStamped) -> float: :param pose: The current pose of the ego vehicle :return: normalized yaw of the vehicle """ - quaternion = (pose.pose.orientation.x, pose.pose.orientation.y, - pose.pose.orientation.z, pose.pose.orientation.w) + quaternion = ( + pose.pose.orientation.x, + pose.pose.orientation.y, + pose.pose.orientation.z, + pose.pose.orientation.w, + ) _, _, yaw = euler_from_quaternion(quaternion) return normalize_angle(yaw) -def points_to_vector(p_1: Tuple[float, float], - p_2: Tuple[float, float]) -> Tuple[float, float]: +def points_to_vector( + p_1: Tuple[float, float], p_2: Tuple[float, float] +) -> Tuple[float, float]: """ Create the vector starting at p1 and ending at p2 :param p_1: Start point @@ -157,11 +162,12 @@ def vector_len(vec: Tuple[float, float]) -> float: :param vec: vector v as a tuple (x, y) :return: length of vector v """ - return sqrt(vec[0]**2 + vec[1]**2) + return sqrt(vec[0] ** 2 + vec[1] ** 2) -def add_vector(v_1: Tuple[float, float], - v_2: Tuple[float, float]) -> Tuple[float, float]: +def add_vector( + v_1: Tuple[float, float], v_2: Tuple[float, float] +) -> Tuple[float, float]: """ Add the two given vectors :param v_1: first vector @@ -172,20 +178,22 @@ def add_vector(v_1: Tuple[float, float], return v_1[0] + v_2[0], v_1[1] + v_2[1] -def rotate_vector(vector: Tuple[float, float], - angle_rad: float) -> Tuple[float, float]: +def rotate_vector(vector: Tuple[float, float], angle_rad: float) -> Tuple[float, float]: """ Rotate the given vector by an angle :param vector: vector :param angle_rad: angle of rotation :return: rotated angle """ - return (cos(angle_rad) * vector[0] - sin(angle_rad) * vector[1], - sin(angle_rad) * vector[0] + cos(angle_rad) * vector[1]) + return ( + cos(angle_rad) * vector[0] - sin(angle_rad) * vector[1], + sin(angle_rad) * vector[0] + cos(angle_rad) * vector[1], + ) -def linear_interpolation(start: Tuple[float, float], end: Tuple[float, float], - interval_m: float) -> List[Tuple[float, float]]: +def linear_interpolation( + start: Tuple[float, float], end: Tuple[float, float], interval_m: float +) -> List[Tuple[float, float]]: """ Interpolate linearly between start and end, with a minimal distance of interval_m between points. @@ -200,21 +208,23 @@ def linear_interpolation(start: Tuple[float, float], end: Tuple[float, float], steps = max(1, floor(distance / interval_m)) exceeds_interval_cap = distance > interval_m - step_vector = (vector[0] / steps if exceeds_interval_cap else vector[0], - vector[1] / steps if exceeds_interval_cap else vector[1]) + step_vector = ( + vector[0] / steps if exceeds_interval_cap else vector[0], + vector[1] / steps if exceeds_interval_cap else vector[1], + ) lin_points = [(start[0], start[1])] for i in range(1, steps): lin_points.append( - (start[0] + step_vector[0] * i, - start[1] + step_vector[1] * i) + (start[0] + step_vector[0] * i, start[1] + step_vector[1] * i) ) return lin_points -def _clean_route_duplicates(route: List[Tuple[float, float]], - min_dist: float) -> List[Tuple[float, float]]: +def _clean_route_duplicates( + route: List[Tuple[float, float]], min_dist: float +) -> List[Tuple[float, float]]: """ Remove duplicates in the given List of tuples, if the distance between them is less than min_dist. @@ -243,8 +253,9 @@ def interpolate_route(orig_route: List[Tuple[float, float]], interval_m=0.5): orig_route = _clean_route_duplicates(orig_route, 0.1) route = [] for index in range(len(orig_route) - 1): - waypoints = linear_interpolation(orig_route[index], - orig_route[index + 1], interval_m) + waypoints = linear_interpolation( + orig_route[index], orig_route[index + 1], interval_m + ) route.extend(waypoints) route = route + [orig_route[-1]] diff --git a/code/acting/src/acting/pure_pursuit_controller.py b/code/acting/src/acting/pure_pursuit_controller.py index 04740418..4259fe78 100755 --- a/code/acting/src/acting/pure_pursuit_controller.py +++ b/code/acting/src/acting/pure_pursuit_controller.py @@ -26,45 +26,44 @@ class PurePursuitController(CompatibleNode): def __init__(self): - super(PurePursuitController, self).__init__('pure_pursuit_controller') - self.loginfo('PurePursuitController node started') + super(PurePursuitController, self).__init__("pure_pursuit_controller") + self.loginfo("PurePursuitController node started") - self.control_loop_rate = self.get_param('control_loop_rate', 0.05) - self.role_name = self.get_param('role_name', 'ego_vehicle') + self.control_loop_rate = self.get_param("control_loop_rate", 0.05) + self.role_name = self.get_param("role_name", "ego_vehicle") self.position_sub: Subscriber = self.new_subscription( - Path, - f"/paf/{self.role_name}/trajectory", - self.__set_path, - qos_profile=1) + Path, f"/paf/{self.role_name}/trajectory", self.__set_path, qos_profile=1 + ) self.path_sub: Subscriber = self.new_subscription( PoseStamped, f"/paf/{self.role_name}/current_pos", self.__set_position, - qos_profile=1) + qos_profile=1, + ) self.velocity_sub: Subscriber = self.new_subscription( CarlaSpeedometer, f"/carla/{self.role_name}/Speed", self.__set_velocity, - qos_profile=1) + qos_profile=1, + ) self.heading_sub: Subscriber = self.new_subscription( Float32, f"/paf/{self.role_name}/current_heading", self.__set_heading, - qos_profile=1) + qos_profile=1, + ) self.pure_pursuit_steer_pub: Publisher = self.new_publisher( - Float32, - f"/paf/{self.role_name}/pure_pursuit_steer", - qos_profile=1) + Float32, f"/paf/{self.role_name}/pure_pursuit_steer", qos_profile=1 + ) self.debug_msg_pub: Publisher = self.new_publisher( - Debug, - f"/paf/{self.role_name}/pure_p_debug", - qos_profile=1) + Debug, f"/paf/{self.role_name}/pure_p_debug", qos_profile=1 + ) self.__position: tuple[float, float] = None # x, y self.__path: Path = None @@ -77,7 +76,7 @@ def run(self): Starts the main loop of the node :return: """ - self.loginfo('PurePursuitController node running') + self.loginfo("PurePursuitController node running") def loop(timer_event=None): """ @@ -86,26 +85,34 @@ def loop(timer_event=None): :return: """ if self.__path is None: - self.logdebug("PurePursuitController hasn't received a path " - "yet and can therefore not publish steering") + self.logdebug( + "PurePursuitController hasn't received a path " + "yet and can therefore not publish steering" + ) return if self.__position is None: - self.logdebug("PurePursuitController hasn't received the " - "position of the vehicle yet " - "and can therefore not publish steering") + self.logdebug( + "PurePursuitController hasn't received the " + "position of the vehicle yet " + "and can therefore not publish steering" + ) return if self.__heading is None: - self.logdebug("PurePursuitController hasn't received the " - "heading of the vehicle yet and " - "can therefore not publish steering") + self.logdebug( + "PurePursuitController hasn't received the " + "heading of the vehicle yet and " + "can therefore not publish steering" + ) return if self.__velocity is None: - self.logdebug("PurePursuitController hasn't received the " - "velocity of the vehicle yet " - "and can therefore not publish steering") + self.logdebug( + "PurePursuitController hasn't received the " + "velocity of the vehicle yet " + "and can therefore not publish steering" + ) return self.pure_pursuit_steer_pub.publish(self.__calculate_steer()) @@ -119,16 +126,17 @@ def __calculate_steer(self) -> float: :return: """ # la_dist = MIN_LA_DISTANCE <= K_LAD * velocity <= MAX_LA_DISTANCE - look_ahead_dist = np.clip(K_LAD * self.__velocity, - MIN_LA_DISTANCE, MAX_LA_DISTANCE) + look_ahead_dist = np.clip( + K_LAD * self.__velocity, MIN_LA_DISTANCE, MAX_LA_DISTANCE + ) # Get the target position on the trajectory in look_ahead distance self.__tp_idx = self.__get_target_point_index(look_ahead_dist) target_wp: PoseStamped = self.__path.poses[self.__tp_idx] # Get the vector from the current position to the target position - target_v_x, target_v_y = points_to_vector((self.__position[0], - self.__position[1]), - (target_wp.pose.position.x, - target_wp.pose.position.y)) + target_v_x, target_v_y = points_to_vector( + (self.__position[0], self.__position[1]), + (target_wp.pose.position.x, target_wp.pose.position.y), + ) # Get the target heading from that vector target_vector_heading = vector_angle(target_v_x, target_v_y) # Get the error between current heading and target heading @@ -181,7 +189,7 @@ def __dist_to(self, pos: Point) -> float: y_current = self.__position[1] x_target = pos.x y_target = pos.y - d = (x_target - x_current)**2 + (y_target - y_current)**2 + d = (x_target - x_current) ** 2 + (y_target - y_current) ** 2 return math.sqrt(d) def __set_position(self, data: PoseStamped, min_diff=0.001): @@ -206,9 +214,11 @@ def __set_position(self, data: PoseStamped, min_diff=0.001): # if new position is to close to current, do not accept it # too close = closer than min_diff = 0.001 meters # for debugging purposes: - self.logdebug("New position disregarded, " - f"as dist ({round(dist, 3)}) to current pos " - f"< min_diff ({round(min_diff, 3)})") + self.logdebug( + "New position disregarded, " + f"as dist ({round(dist, 3)}) to current pos " + f"< min_diff ({round(min_diff, 3)})" + ) return new_x = data.pose.position.x new_y = data.pose.position.y @@ -230,10 +240,10 @@ def __set_velocity(self, data: CarlaSpeedometer): def main(args=None): """ - main function starts the pure pursuit controller node - :param args: + main function starts the pure pursuit controller node + :param args: """ - roscomp.init('pure_pursuit_controller', args=args) + roscomp.init("pure_pursuit_controller", args=args) try: node = PurePursuitController() @@ -244,5 +254,5 @@ def main(args=None): roscomp.shutdown() -if __name__ == '__main__': +if __name__ == "__main__": main() diff --git a/code/acting/src/acting/stanley_controller.py b/code/acting/src/acting/stanley_controller.py index e0cbc190..3463e90e 100755 --- a/code/acting/src/acting/stanley_controller.py +++ b/code/acting/src/acting/stanley_controller.py @@ -20,46 +20,45 @@ class StanleyController(CompatibleNode): def __init__(self): - super(StanleyController, self).__init__('stanley_controller') - self.loginfo('StanleyController node started') + super(StanleyController, self).__init__("stanley_controller") + self.loginfo("StanleyController node started") - self.control_loop_rate = self.get_param('control_loop_rate', 0.05) - self.role_name = self.get_param('role_name', 'ego_vehicle') + self.control_loop_rate = self.get_param("control_loop_rate", 0.05) + self.role_name = self.get_param("role_name", "ego_vehicle") # Subscribers self.position_sub: Subscriber = self.new_subscription( - Path, - f"/paf/{self.role_name}/trajectory", - self.__set_path, - qos_profile=1) + Path, f"/paf/{self.role_name}/trajectory", self.__set_path, qos_profile=1 + ) self.path_sub: Subscriber = self.new_subscription( PoseStamped, f"/paf/{self.role_name}/current_pos", self.__set_position, - qos_profile=1) + qos_profile=1, + ) self.velocity_sub: Subscriber = self.new_subscription( CarlaSpeedometer, f"/carla/{self.role_name}/Speed", self.__set_velocity, - qos_profile=1) + qos_profile=1, + ) self.heading_sub: Subscriber = self.new_subscription( Float32, f"/paf/{self.role_name}/current_heading", self.__set_heading, - qos_profile=1) + qos_profile=1, + ) self.stanley_steer_pub: Publisher = self.new_publisher( - Float32, - f"/paf/{self.role_name}/stanley_steer", - qos_profile=1) + Float32, f"/paf/{self.role_name}/stanley_steer", qos_profile=1 + ) self.debug_publisher: Publisher = self.new_publisher( - StanleyDebug, - f"/paf/{self.role_name}/stanley_debug", - qos_profile=1) + StanleyDebug, f"/paf/{self.role_name}/stanley_debug", qos_profile=1 + ) self.__position: tuple[float, float] = None # x , y self.__path: Path = None @@ -71,7 +70,7 @@ def run(self): Starts the main loop of the node :return: """ - self.loginfo('StanleyController node running') + self.loginfo("StanleyController node running") def loop(timer_event=None): """ @@ -80,25 +79,33 @@ def loop(timer_event=None): :return: """ if self.__path is None: - self.logwarn("StanleyController hasn't received a path yet " - "and can therefore not publish steering") + self.logwarn( + "StanleyController hasn't received a path yet " + "and can therefore not publish steering" + ) return if self.__position is None: - self.logwarn("StanleyController hasn't received the" - "position of the vehicle yet " - "and can therefore not publish steering") + self.logwarn( + "StanleyController hasn't received the" + "position of the vehicle yet " + "and can therefore not publish steering" + ) return if self.__heading is None: - self.logwarn("StanleyController hasn't received the" - "heading of the vehicle yet and" - "can therefore not publish steering") + self.logwarn( + "StanleyController hasn't received the" + "heading of the vehicle yet and" + "can therefore not publish steering" + ) return if self.__velocity is None: - self.logwarn("StanleyController hasn't received the " - "velocity of the vehicle yet " - "and can therefore not publish steering") + self.logwarn( + "StanleyController hasn't received the " + "velocity of the vehicle yet " + "and can therefore not publish steering" + ) return self.stanley_steer_pub.publish(self.__calculate_steer()) @@ -125,8 +132,9 @@ def __calculate_steer(self) -> float: closest_point: PoseStamped = self.__path.poses[closest_point_idx] cross_err = self.__get_cross_err(closest_point.pose.position) # * -1 because it is inverted compared to PurePursuit - steering_angle = 1 * (heading_err + atan((K_CROSSERR * cross_err) - / current_velocity)) + steering_angle = 1 * ( + heading_err + atan((K_CROSSERR * cross_err) / current_velocity) + ) # -> for debugging debug_msg = StanleyDebug() debug_msg.heading = self.__heading @@ -174,10 +182,11 @@ def __get_path_heading(self, index: int) -> float: if index > 0: # Calculate heading from the previous point on the trajectory - prv_point: Point = self.__path.poses[index-1].pose.position + prv_point: Point = self.__path.poses[index - 1].pose.position - prv_v_x, prv_v_y = points_to_vector((prv_point.x, prv_point.y), - (cur_pos.x, cur_pos.y)) + prv_v_x, prv_v_y = points_to_vector( + (prv_point.x, prv_point.y), (cur_pos.x, cur_pos.y) + ) heading_sum += vector_angle(prv_v_x, prv_v_y) heading_sum_args += 1 @@ -186,8 +195,9 @@ def __get_path_heading(self, index: int) -> float: # Calculate heading to the following point on the trajectory aft_point: Point = self.__path.poses[index + 1].pose.position - aft_v_x, aft_v_y = points_to_vector((aft_point.x, aft_point.y), - (cur_pos.x, cur_pos.y)) + aft_v_x, aft_v_y = points_to_vector( + (aft_point.x, aft_point.y), (cur_pos.x, cur_pos.y) + ) heading_sum += vector_angle(aft_v_x, aft_v_y) heading_sum_args += 1 @@ -210,8 +220,10 @@ def __get_cross_err(self, pos: Point) -> float: if self.__heading is not None: alpha = self.__heading + (math.pi / 2) v_e_0 = (0, 1) - v_e = (cos(alpha)*v_e_0[0] - sin(alpha)*v_e_0[1], - sin(alpha)*v_e_0[0] + cos(alpha)*v_e_0[1]) + v_e = ( + cos(alpha) * v_e_0[0] - sin(alpha) * v_e_0[1], + sin(alpha) * v_e_0[0] + cos(alpha) * v_e_0[1], + ) # define a vector (v_ab) with length 10 centered on the cur pos # of the vehicle, with a heading parallel to that of the vehicle @@ -221,8 +233,7 @@ def __get_cross_err(self, pos: Point) -> float: v_ab = (b[0] - a[0], b[1] - a[1]) v_am = (pos.x - a[0], pos.y - a[1]) - c = np.array([[v_ab[0], v_am[0]], - [v_ab[1], v_am[1]]]) + c = np.array([[v_ab[0], v_am[0]], [v_ab[1], v_am[1]]]) temp_sign = np.linalg.det(c) min_sign = 0.01 # to avoid rounding errors @@ -268,9 +279,11 @@ def __set_position(self, data: PoseStamped, min_diff=0.001): # check if the new position is valid dist = self.__dist_to(data.pose.position) if dist < min_diff: - self.logdebug("New position disregarded, " - f"as dist ({round(dist, 3)}) to current pos " - f"< min_diff ({round(min_diff, 3)})") + self.logdebug( + "New position disregarded, " + f"as dist ({round(dist, 3)}) to current pos " + f"< min_diff ({round(min_diff, 3)})" + ) return new_x = data.pose.position.x @@ -296,7 +309,7 @@ def main(args=None): Main function starts the node :param args: """ - roscomp.init('stanley_controller', args=args) + roscomp.init("stanley_controller", args=args) try: node = StanleyController() @@ -307,5 +320,5 @@ def main(args=None): roscomp.shutdown() -if __name__ == '__main__': +if __name__ == "__main__": main() diff --git a/code/acting/src/acting/vehicle_controller.py b/code/acting/src/acting/vehicle_controller.py index e97bc1c8..90aa0f68 100755 --- a/code/acting/src/acting/vehicle_controller.py +++ b/code/acting/src/acting/vehicle_controller.py @@ -21,41 +21,45 @@ class VehicleController(CompatibleNode): """ def __init__(self): - super(VehicleController, self).__init__('vehicle_controller') - self.loginfo('VehicleController node started') - self.control_loop_rate = self.get_param('control_loop_rate', 0.05) - self.role_name = self.get_param('role_name', 'ego_vehicle') + super(VehicleController, self).__init__("vehicle_controller") + self.loginfo("VehicleController node started") + self.control_loop_rate = self.get_param("control_loop_rate", 0.05) + self.role_name = self.get_param("role_name", "ego_vehicle") self.__curr_behavior = None # only unstuck behavior is relevant here # Publisher for Carla Vehicle Control Commands self.control_publisher: Publisher = self.new_publisher( CarlaEgoVehicleControl, - f'/carla/{self.role_name}/vehicle_control_cmd', - qos_profile=10) + f"/carla/{self.role_name}/vehicle_control_cmd", + qos_profile=10, + ) # Publisher for Status TODO: Maybe unneccessary self.status_pub: Publisher = self.new_publisher( Bool, f"/carla/{self.role_name}/status", qos_profile=QoSProfile( - depth=1, - durability=DurabilityPolicy.TRANSIENT_LOCAL)) + depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL + ), + ) # Publisher for which steering-controller is mainly used # 1 = PurePursuit and 2 = Stanley self.controller_pub: Publisher = self.new_publisher( Float32, f"/paf/{self.role_name}/controller", - qos_profile=QoSProfile(depth=10, - durability=DurabilityPolicy.TRANSIENT_LOCAL) + qos_profile=QoSProfile( + depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL + ), ) self.emergency_pub: Publisher = self.new_publisher( Bool, f"/paf/{self.role_name}/emergency", - qos_profile=QoSProfile(depth=10, - durability=DurabilityPolicy.TRANSIENT_LOCAL) + qos_profile=QoSProfile( + depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL + ), ) # Subscribers @@ -63,51 +67,53 @@ def __init__(self): String, f"/paf/{self.role_name}/curr_behavior", self.__set_curr_behavior, - qos_profile=1) + qos_profile=1, + ) self.emergency_sub: Subscriber = self.new_subscription( Bool, f"/paf/{self.role_name}/emergency", self.__set_emergency, - qos_profile=QoSProfile(depth=10, - durability=DurabilityPolicy.TRANSIENT_LOCAL) + qos_profile=QoSProfile( + depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL + ), ) self.velocity_sub: Subscriber = self.new_subscription( CarlaSpeedometer, f"/carla/{self.role_name}/Speed", self.__get_velocity, - qos_profile=1) + qos_profile=1, + ) self.throttle_sub: Subscriber = self.new_subscription( Float32, f"/paf/{self.role_name}/throttle", self.__set_throttle, - qos_profile=1) + qos_profile=1, + ) self.brake_sub: Subscriber = self.new_subscription( - Float32, - f"/paf/{self.role_name}/brake", - self.__set_brake, - qos_profile=1) + Float32, f"/paf/{self.role_name}/brake", self.__set_brake, qos_profile=1 + ) self.reverse_sub: Subscriber = self.new_subscription( - Bool, - f"/paf/{self.role_name}/reverse", - self.__set_reverse, - qos_profile=1) + Bool, f"/paf/{self.role_name}/reverse", self.__set_reverse, qos_profile=1 + ) self.pure_pursuit_steer_sub: Subscriber = self.new_subscription( Float32, f"/paf/{self.role_name}/pure_pursuit_steer", self.__set_pure_pursuit_steer, - qos_profile=1) + qos_profile=1, + ) self.stanley_sub: Subscriber = self.new_subscription( Float32, f"/paf/{self.role_name}/stanley_steer", self.__set_stanley_steer, - qos_profile=1) + qos_profile=1, + ) self.__reverse: bool = False self.__emergency: bool = False @@ -123,7 +129,7 @@ def run(self): :return: """ self.status_pub.publish(True) - self.loginfo('VehicleController node running') + self.loginfo("VehicleController node running") def loop(timer_event=None) -> None: """ @@ -143,8 +149,10 @@ def loop(timer_event=None) -> None: steer = self._s_steer else: # while doing the unstuck routine we don't want to steer - if self.__curr_behavior == "us_unstuck" or \ - self.__curr_behavior == "us_stop": + if ( + self.__curr_behavior == "us_unstuck" + or self.__curr_behavior == "us_stop" + ): steer = 0 else: steer = self._p_steer @@ -157,8 +165,7 @@ def loop(timer_event=None) -> None: message.throttle = self.__throttle message.brake = self.__brake message.steer = steer - message.header.stamp = roscomp.ros_timestamp(self.get_time(), - from_sec=True) + message.header.stamp = roscomp.ros_timestamp(self.get_time(), from_sec=True) self.control_publisher.publish(message) self.new_timer(self.control_loop_rate, loop) @@ -204,8 +211,7 @@ def __emergency_brake(self, active) -> None: message.reverse = True message.hand_brake = True message.manual_gear_shift = False - message.header.stamp = roscomp.ros_timestamp(self.get_time(), - from_sec=True) + message.header.stamp = roscomp.ros_timestamp(self.get_time(), from_sec=True) else: self.__emergency = False message.throttle = 0 @@ -214,8 +220,7 @@ def __emergency_brake(self, active) -> None: message.reverse = False message.hand_brake = False message.manual_gear_shift = False - message.header.stamp = roscomp.ros_timestamp(self.get_time(), - from_sec=True) + message.header.stamp = roscomp.ros_timestamp(self.get_time(), from_sec=True) self.control_publisher.publish(message) def __get_velocity(self, data: CarlaSpeedometer) -> None: @@ -230,11 +235,12 @@ def __get_velocity(self, data: CarlaSpeedometer) -> None: return if data.speed < 0.1: # vehicle has come to a stop self.__emergency_brake(False) - self.loginfo("Emergency breaking disengaged " - "(Emergency breaking has been executed successfully)") + self.loginfo( + "Emergency breaking disengaged " + "(Emergency breaking has been executed successfully)" + ) for _ in range(7): # publish 7 times just to be safe - self.emergency_pub.publish( - Bool(False)) + self.emergency_pub.publish(Bool(False)) def __set_throttle(self, data): self.__throttle = data.data @@ -246,12 +252,12 @@ def __set_reverse(self, data): self.__reverse = data.data def __set_pure_pursuit_steer(self, data: Float32): - r = (math.pi / 2) # convert from RAD to [-1;1] - self._p_steer = (data.data / r) + r = math.pi / 2 # convert from RAD to [-1;1] + self._p_steer = data.data / r def __set_stanley_steer(self, data: Float32): - r = (math.pi / 2) # convert from RAD to [-1;1] - self._s_steer = (data.data / r) + r = math.pi / 2 # convert from RAD to [-1;1] + self._s_steer = data.data / r def main(args=None): @@ -259,7 +265,7 @@ def main(args=None): Main function starts the node :param args: """ - roscomp.init('vehicle_controller', args=args) + roscomp.init("vehicle_controller", args=args) try: node = VehicleController() @@ -270,5 +276,5 @@ def main(args=None): roscomp.shutdown() -if __name__ == '__main__': +if __name__ == "__main__": main() diff --git a/code/acting/src/acting/velocity_controller.py b/code/acting/src/acting/velocity_controller.py index bf43ab41..db1f53aa 100755 --- a/code/acting/src/acting/velocity_controller.py +++ b/code/acting/src/acting/velocity_controller.py @@ -15,38 +15,37 @@ class VelocityController(CompatibleNode): """ def __init__(self): - super(VelocityController, self).__init__('velocity_controller') - self.loginfo('VelocityController node started') + super(VelocityController, self).__init__("velocity_controller") + self.loginfo("VelocityController node started") - self.control_loop_rate = self.get_param('control_loop_rate', 0.05) - self.role_name = self.get_param('role_name', 'ego_vehicle') + self.control_loop_rate = self.get_param("control_loop_rate", 0.05) + self.role_name = self.get_param("role_name", "ego_vehicle") self.target_velocity_sub: Subscriber = self.new_subscription( Float32, f"/paf/{self.role_name}/target_velocity", self.__get_target_velocity, - qos_profile=1) + qos_profile=1, + ) self.velocity_sub: Subscriber = self.new_subscription( CarlaSpeedometer, f"/carla/{self.role_name}/Speed", self.__get_current_velocity, - qos_profile=1) + qos_profile=1, + ) self.throttle_pub: Publisher = self.new_publisher( - Float32, - f"/paf/{self.role_name}/throttle", - qos_profile=1) + Float32, f"/paf/{self.role_name}/throttle", qos_profile=1 + ) self.brake_pub: Publisher = self.new_publisher( - Float32, - f"/paf/{self.role_name}/brake", - qos_profile=1) + Float32, f"/paf/{self.role_name}/brake", qos_profile=1 + ) self.reverse_pub: Publisher = self.new_publisher( - Bool, - f"/paf/{self.role_name}/reverse", - qos_profile=1) + Bool, f"/paf/{self.role_name}/reverse", qos_profile=1 + ) self.__current_velocity: float = None self.__target_velocity: float = None @@ -56,7 +55,7 @@ def run(self): Starts the main loop of the node :return: """ - self.loginfo('VelocityController node running') + self.loginfo("VelocityController node running") # PID for throttle pid_t = PID(0.60, 0.00076, 0.63) # since we use this for braking aswell, allow -1 to 0. @@ -71,15 +70,19 @@ def loop(timer_event=None): :return: """ if self.__target_velocity is None: - self.logdebug("VelocityController hasn't received target" - "_velocity yet. target_velocity has been set to" - "default value 0") + self.logdebug( + "VelocityController hasn't received target" + "_velocity yet. target_velocity has been set to" + "default value 0" + ) self.__target_velocity = 0 if self.__current_velocity is None: - self.logdebug("VelocityController hasn't received " - "current_velocity yet and can therefore not" - "publish a throttle value") + self.logdebug( + "VelocityController hasn't received " + "current_velocity yet and can therefore not" + "publish a throttle value" + ) return if self.__target_velocity < 0: @@ -135,7 +138,7 @@ def main(args=None): Main function starts the node :param args: """ - roscomp.init('velocity_controller', args=args) + roscomp.init("velocity_controller", args=args) try: node = VelocityController() @@ -146,5 +149,5 @@ def main(args=None): roscomp.shutdown() -if __name__ == '__main__': +if __name__ == "__main__": main() diff --git a/code/agent/setup.py b/code/agent/setup.py index ad7850df..0b6d7399 100644 --- a/code/agent/setup.py +++ b/code/agent/setup.py @@ -2,6 +2,5 @@ from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup -setup_args = generate_distutils_setup(packages=['agent'], - package_dir={'': 'src'}) +setup_args = generate_distutils_setup(packages=["agent"], package_dir={"": "src"}) setup(**setup_args) diff --git a/code/agent/src/agent/agent.py b/code/agent/src/agent/agent.py index 5a97786b..a57f2d6a 100755 --- a/code/agent/src/agent/agent.py +++ b/code/agent/src/agent/agent.py @@ -4,7 +4,7 @@ def get_entry_point(): - return 'PAFAgent' + return "PAFAgent" class PAFAgent(ROS1Agent): @@ -14,76 +14,102 @@ def setup(self, path_to_conf_file): def get_ros_entrypoint(self): return { - 'package': 'agent', - 'launch_file': 'agent.launch', - 'parameters': { - 'role_name': 'hero', - } + "package": "agent", + "launch_file": "agent.launch", + "parameters": { + "role_name": "hero", + }, } def sensors(self): sensors = [ { - 'type': 'sensor.camera.rgb', - 'id': 'Center', - 'x': 0.0, 'y': 0.0, 'z': 1.70, - 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, - 'width': 1280, 'height': 720, 'fov': 100 - }, + "type": "sensor.camera.rgb", + "id": "Center", + "x": 0.0, + "y": 0.0, + "z": 1.70, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0, + "width": 1280, + "height": 720, + "fov": 100, + }, { - 'type': 'sensor.camera.rgb', - 'id': 'Back', - 'x': 0.0, 'y': 0.0, 'z': 1.70, - 'roll': 0.0, 'pitch': 0.0, 'yaw': math.radians(180.0), - 'width': 1280, 'height': 720, 'fov': 100 - }, + "type": "sensor.camera.rgb", + "id": "Back", + "x": 0.0, + "y": 0.0, + "z": 1.70, + "roll": 0.0, + "pitch": 0.0, + "yaw": math.radians(180.0), + "width": 1280, + "height": 720, + "fov": 100, + }, { - 'type': 'sensor.camera.rgb', - 'id': 'Left', - 'x': 0.0, 'y': 0.0, 'z': 1.70, - 'roll': 0.0, 'pitch': 0.0, 'yaw': math.radians(-90.0), - 'width': 1280, 'height': 720, 'fov': 100 - }, + "type": "sensor.camera.rgb", + "id": "Left", + "x": 0.0, + "y": 0.0, + "z": 1.70, + "roll": 0.0, + "pitch": 0.0, + "yaw": math.radians(-90.0), + "width": 1280, + "height": 720, + "fov": 100, + }, { - 'type': 'sensor.camera.rgb', - 'id': 'Right', - 'x': 0.0, 'y': 0.0, 'z': 1.70, - 'roll': 0.0, 'pitch': 0.0, 'yaw': math.radians(90.0), - 'width': 1280, 'height': 720, 'fov': 100 - }, + "type": "sensor.camera.rgb", + "id": "Right", + "x": 0.0, + "y": 0.0, + "z": 1.70, + "roll": 0.0, + "pitch": 0.0, + "yaw": math.radians(90.0), + "width": 1280, + "height": 720, + "fov": 100, + }, { - 'type': 'sensor.lidar.ray_cast', - 'id': 'LIDAR', - 'x': 0.0, 'y': 0.0, 'z': 1.70, - 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0 - }, + "type": "sensor.lidar.ray_cast", + "id": "LIDAR", + "x": 0.0, + "y": 0.0, + "z": 1.70, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0, + }, { - 'type': 'sensor.other.radar', - 'id': 'RADAR', - 'x': 2.0, 'y': 0.0, 'z': 0.7, - 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, - 'horizontal_fov': 30, 'vertical_fov': 30 - }, + "type": "sensor.other.radar", + "id": "RADAR", + "x": 2.0, + "y": 0.0, + "z": 0.7, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0, + "horizontal_fov": 30, + "vertical_fov": 30, + }, + {"type": "sensor.other.gnss", "id": "GPS", "x": 0.0, "y": 0.0, "z": 0.0}, { - 'type': 'sensor.other.gnss', - 'id': 'GPS', - 'x': 0.0, 'y': 0.0, 'z': 0.0 - }, - { - 'type': 'sensor.other.imu', - 'id': 'IMU', - 'x': 0.0, 'y': 0.0, 'z': 0.0, - 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0 - }, - { - 'type': 'sensor.opendrive_map', - 'id': 'OpenDRIVE', - 'reading_frequency': 1 - }, - { - 'type': 'sensor.speedometer', - 'id': 'Speed' - } + "type": "sensor.other.imu", + "id": "IMU", + "x": 0.0, + "y": 0.0, + "z": 0.0, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0, + }, + {"type": "sensor.opendrive_map", "id": "OpenDRIVE", "reading_frequency": 1}, + {"type": "sensor.speedometer", "id": "Speed"}, ] return sensors diff --git a/code/mock/setup.py b/code/mock/setup.py index 8f232a1f..bf698614 100755 --- a/code/mock/setup.py +++ b/code/mock/setup.py @@ -1,6 +1,5 @@ from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup -setup_args = generate_distutils_setup(packages=['mock'], - package_dir={'': 'src'}) +setup_args = generate_distutils_setup(packages=["mock"], package_dir={"": "src"}) setup(**setup_args) diff --git a/code/mock/src/mock_intersection_clear.py b/code/mock/src/mock_intersection_clear.py index df7cea62..bb584941 100755 --- a/code/mock/src/mock_intersection_clear.py +++ b/code/mock/src/mock_intersection_clear.py @@ -10,18 +10,17 @@ class MockIntersectionClearPublisher(CompatibleNode): This node publishes intersection clear information. It can be used for testing. """ + def __init__(self): - super(MockIntersectionClearPublisher, self).\ - __init__('intersectionClearMock') + super(MockIntersectionClearPublisher, self).__init__("intersectionClearMock") - self.control_loop_rate = self.get_param('control_loop_rate', 10) - self.role_name = self.get_param('role_name', 'ego_vehicle') + self.control_loop_rate = self.get_param("control_loop_rate", 10) + self.role_name = self.get_param("role_name", "ego_vehicle") # self.enabled = self.get_param('enabled', False) self.stop_sign_pub: Publisher = self.new_publisher( - Bool, - f"/paf/{self.role_name}/intersection_clear", - qos_profile=1) + Bool, f"/paf/{self.role_name}/intersection_clear", qos_profile=1 + ) self.delta = 0.2 self.distance = 75.0 self.isClear = False @@ -33,7 +32,7 @@ def run(self): """ # if not self.enabled: # return - self.loginfo('Stopsignmock node running') + self.loginfo("Stopsignmock node running") def loop(timer_event=None): """ @@ -47,6 +46,7 @@ def loop(timer_event=None): if self.distance < 0.0: self.isClear = True self.stop_sign_pub.publish(msg) + self.new_timer(self.control_loop_rate, loop) self.spin() @@ -56,7 +56,7 @@ def main(args=None): Main function starts the node :param args: """ - roscomp.init('velocity_publisher_dummy', args=args) + roscomp.init("velocity_publisher_dummy", args=args) try: node = MockIntersectionClearPublisher() @@ -67,5 +67,5 @@ def main(args=None): roscomp.shutdown() -if __name__ == '__main__': +if __name__ == "__main__": main() diff --git a/code/mock/src/mock_stop_sign.py b/code/mock/src/mock_stop_sign.py index a5ec4691..f85f6344 100755 --- a/code/mock/src/mock_stop_sign.py +++ b/code/mock/src/mock_stop_sign.py @@ -2,6 +2,7 @@ import ros_compatibility as roscomp from ros_compatibility.node import CompatibleNode from rospy import Publisher + # from std_msgs.msg import Float32 from mock.msg import Stop_sign @@ -11,18 +12,17 @@ class MockStopSignPublisher(CompatibleNode): This node publishes stop sign light information. It can be used for testing. """ + def __init__(self): - super(MockStopSignPublisher, self).\ - __init__('stopSignMock') + super(MockStopSignPublisher, self).__init__("stopSignMock") - self.control_loop_rate = self.get_param('control_loop_rate', 10) - self.role_name = self.get_param('role_name', 'ego_vehicle') + self.control_loop_rate = self.get_param("control_loop_rate", 10) + self.role_name = self.get_param("role_name", "ego_vehicle") # self.enabled = self.get_param('enabled', False) self.stop_sign_pub: Publisher = self.new_publisher( - Stop_sign, - f"/paf/{self.role_name}/stop_sign", - qos_profile=1) + Stop_sign, f"/paf/{self.role_name}/stop_sign", qos_profile=1 + ) self.delta = 0.2 self.distance = 20.0 self.isStop = False @@ -34,7 +34,7 @@ def run(self): """ # if not self.enabled: # return - self.loginfo('Stopsignmock node running') + self.loginfo("Stopsignmock node running") def loop(timer_event=None): """ @@ -50,6 +50,7 @@ def loop(timer_event=None): self.distance = 20.0 msg.distance = self.distance self.stop_sign_pub.publish(msg) + self.new_timer(self.control_loop_rate, loop) self.spin() @@ -59,7 +60,7 @@ def main(args=None): Main function starts the node :param args: """ - roscomp.init('velocity_publisher_dummy', args=args) + roscomp.init("velocity_publisher_dummy", args=args) try: node = MockStopSignPublisher() @@ -70,5 +71,5 @@ def main(args=None): roscomp.shutdown() -if __name__ == '__main__': +if __name__ == "__main__": main() diff --git a/code/mock/src/mock_traffic_light.py b/code/mock/src/mock_traffic_light.py index 13852e03..63ff289a 100755 --- a/code/mock/src/mock_traffic_light.py +++ b/code/mock/src/mock_traffic_light.py @@ -2,6 +2,7 @@ import ros_compatibility as roscomp from ros_compatibility.node import CompatibleNode from rospy import Publisher + # from std_msgs.msg import Float32 from mock.msg import Traffic_light @@ -10,18 +11,17 @@ class MockTrafficLightPublisher(CompatibleNode): """ This node publishes traffic light information. It can be used for testing. """ + def __init__(self): - super(MockTrafficLightPublisher, self).\ - __init__('trafficLightMock') + super(MockTrafficLightPublisher, self).__init__("trafficLightMock") - self.control_loop_rate = self.get_param('control_loop_rate', 10) - self.role_name = self.get_param('role_name', 'ego_vehicle') + self.control_loop_rate = self.get_param("control_loop_rate", 10) + self.role_name = self.get_param("role_name", "ego_vehicle") # self.enabled = self.get_param('enabled', False) self.traffic_light_pub: Publisher = self.new_publisher( - Traffic_light, - f"/paf/{self.role_name}/traffic_light", - qos_profile=1) + Traffic_light, f"/paf/{self.role_name}/traffic_light", qos_profile=1 + ) self.delta = 0.2 self.distance = 20.0 self.color = "green" @@ -33,7 +33,7 @@ def run(self): """ # if not self.enabled: # return - self.loginfo('TrafficLightmock node running') + self.loginfo("TrafficLightmock node running") def loop(timer_event=None): """ @@ -54,6 +54,7 @@ def loop(timer_event=None): self.distance = 20.0 msg.distance = self.distance self.traffic_light_pub.publish(msg) + self.new_timer(self.control_loop_rate, loop) self.spin() @@ -63,7 +64,7 @@ def main(args=None): Main function starts the node :param args: """ - roscomp.init('traffic_light_publisher_dummy', args=args) + roscomp.init("traffic_light_publisher_dummy", args=args) try: node = MockTrafficLightPublisher() @@ -74,5 +75,5 @@ def main(args=None): roscomp.shutdown() -if __name__ == '__main__': +if __name__ == "__main__": main() diff --git a/code/perception/launch/perception.launch b/code/perception/launch/perception.launch index 45d970be..8d6072e7 100644 --- a/code/perception/launch/perception.launch +++ b/code/perception/launch/perception.launch @@ -41,8 +41,8 @@