From 92352acc572976b39c30fe77cb9dcb83acea4313 Mon Sep 17 00:00:00 2001 From: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> Date: Sun, 15 Jun 2025 10:17:57 -0700 Subject: [PATCH 01/16] Fix `wb_speaker_play_sound` Request Message (#6843) * fix speaker_play_sound message * update changelog * changelog clarification --- docs/reference/changelog-r2025.md | 1 + src/controller/c/speaker.c | 20 ++++++++++---------- 2 files changed, 11 insertions(+), 10 deletions(-) diff --git a/docs/reference/changelog-r2025.md b/docs/reference/changelog-r2025.md index 8dcb0004235..99dd770f49c 100644 --- a/docs/reference/changelog-r2025.md +++ b/docs/reference/changelog-r2025.md @@ -3,6 +3,7 @@ ## Webots R2025b - Bug Fixes - Fixed a bug preventing the `webots-controller` executable from running on arm-based mac devices ([#6806](https://github.com/cyberbotics/webots/pull/6806)). + - Fixed a bug causing Webots to crash when multiple sounds were used with a [Speaker](speaker.md) node ([#6843](https://github.com/cyberbotics/webots/pull/6843)). ## Webots R2025a Released on January 31st, 2025. diff --git a/src/controller/c/speaker.c b/src/controller/c/speaker.c index cd11ce8e3c6..32e02cd1118 100644 --- a/src/controller/c/speaker.c +++ b/src/controller/c/speaker.c @@ -258,17 +258,17 @@ static void speaker_write_request(WbDevice *d, WbRequest *r) { request_write_char(r, 1); else request_write_char(r, 0); - } - request_write_int32(r, sound->upload_size); - if (sound->upload_size) { - /* Sound data available to stream, send it one time and discard it. - * Webots will cache the data inside the device. - */ - request_write_data(r, sound->upload_data, sound->upload_size); - free(sound->upload_data); - sound->upload_data = NULL; - sound->upload_size = 0; + request_write_int32(r, sound->upload_size); + if (sound->upload_size) { + /* Sound data available to stream, send it one time and discard it. + * Webots will cache the data inside the device. + */ + request_write_data(r, sound->upload_data, sound->upload_size); + free(sound->upload_data); + sound->upload_data = NULL; + sound->upload_size = 0; + } } sound->need_update = false; From 5e8942c0993e49e19b42ef8ebefcc2c346ab7b4a Mon Sep 17 00:00:00 2001 From: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> Date: Sun, 15 Jun 2025 22:47:13 -0700 Subject: [PATCH 02/16] Fix Checking of Reload/Reset Selection in WbBuildEditor (#6844) * fix reload button checking in WbBuildEditor popup * update changelog * fix pointer syntax * use const-pointers where applicable --- docs/reference/changelog-r2025.md | 1 + src/webots/editor/WbBuildEditor.cpp | 15 ++++++++++----- 2 files changed, 11 insertions(+), 5 deletions(-) diff --git a/docs/reference/changelog-r2025.md b/docs/reference/changelog-r2025.md index 99dd770f49c..114982338d7 100644 --- a/docs/reference/changelog-r2025.md +++ b/docs/reference/changelog-r2025.md @@ -4,6 +4,7 @@ - Bug Fixes - Fixed a bug preventing the `webots-controller` executable from running on arm-based mac devices ([#6806](https://github.com/cyberbotics/webots/pull/6806)). - Fixed a bug causing Webots to crash when multiple sounds were used with a [Speaker](speaker.md) node ([#6843](https://github.com/cyberbotics/webots/pull/6843)). + - Fixed a bug causing the "Reload/Reset" buttons in the controller recompilation popup to not work on Windows ([#6844](https://github.com/cyberbotics/webots/pull/6844)). ## Webots R2025a Released on January 31st, 2025. diff --git a/src/webots/editor/WbBuildEditor.cpp b/src/webots/editor/WbBuildEditor.cpp index 51da84d4b93..9bc52adda9d 100644 --- a/src/webots/editor/WbBuildEditor.cpp +++ b/src/webots/editor/WbBuildEditor.cpp @@ -28,6 +28,7 @@ #include "../../../include/controller/c/webots/utils/ansi_codes.h" #include +#include #include #include @@ -268,12 +269,16 @@ void WbBuildEditor::reloadMessageBoxIfNeeded() { if (WbMessageBox::enabled()) { QMessageBox messageBox(QMessageBox::Question, tr("Compilation successful"), tr("Do you want to reset or reload the world?"), QMessageBox::Cancel, this); - messageBox.addButton(tr("Reload"), QMessageBox::AcceptRole); - messageBox.setDefaultButton(messageBox.addButton(tr("Reset"), QMessageBox::AcceptRole)); - const int ret = messageBox.exec(); - if (ret == 0) + const QPushButton *reloadButton = messageBox.addButton(tr("Reload"), QMessageBox::AcceptRole); + QPushButton *resetButton = messageBox.addButton(tr("Reset"), QMessageBox::AcceptRole); + messageBox.setDefaultButton(resetButton); + + messageBox.exec(); + + const QAbstractButton *clickedButton = messageBox.clickedButton(); + if (clickedButton == reloadButton) emit reloadRequested(); - else if (ret == 1) + else if (clickedButton == resetButton) emit resetRequested(); } } else From ee34f4e2d1eb936ccf32e3e2c38f55940374d4c8 Mon Sep 17 00:00:00 2001 From: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> Date: Tue, 24 Jun 2025 12:14:50 -0700 Subject: [PATCH 03/16] use QImage::flipped instead of QImage::mirrored in WbWrenTextureOverlay (#6850) --- src/webots/wren/WbWrenTextureOverlay.cpp | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/src/webots/wren/WbWrenTextureOverlay.cpp b/src/webots/wren/WbWrenTextureOverlay.cpp index b8647c2b78a..80aa032dc2c 100644 --- a/src/webots/wren/WbWrenTextureOverlay.cpp +++ b/src/webots/wren/WbWrenTextureOverlay.cpp @@ -272,7 +272,15 @@ WrTexture2d *WbWrenTextureOverlay::createIconTexture(QString filePath) { return imageTexture; QImageReader imageReader(filePath); - QImage image = imageReader.read().mirrored(false, true); // account for inverted Y axis in OpenGL + QImage image = imageReader.read(); + + // account for inverted Y axis in OpenGL +#ifdef _WIN32 // Windows builds against a newer version of Qt, which deprecates `mirrored` + image = image.flipped(Qt::Vertical); +#else + image = image.mirrored(false, true); +#endif + const bool isTranslucent = image.pixelFormat().alphaUsage() == QPixelFormat::UsesAlpha; imageTexture = wr_texture_2d_new(); From ec05c25bbddb4e34b19132828686e63b30004ab0 Mon Sep 17 00:00:00 2001 From: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> Date: Wed, 25 Jun 2025 23:00:38 -0700 Subject: [PATCH 04/16] use stdbool instead of boolean.h (#6853) --- .../controllers/contest_manager/boolean.h | 28 ------------------- .../contest_manager/maze_definition.h | 2 +- .../contest_manager/round_manager.c | 2 +- .../contest_manager/texture_generator.c | 2 +- 4 files changed, 3 insertions(+), 31 deletions(-) delete mode 100644 projects/samples/contests/ratslife/controllers/contest_manager/boolean.h diff --git a/projects/samples/contests/ratslife/controllers/contest_manager/boolean.h b/projects/samples/contests/ratslife/controllers/contest_manager/boolean.h deleted file mode 100644 index 6959f499ac4..00000000000 --- a/projects/samples/contests/ratslife/controllers/contest_manager/boolean.h +++ /dev/null @@ -1,28 +0,0 @@ -/* - * Copyright 1996-2024 Cyberbotics Ltd. - * - * 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 - * - * https://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. - */ - -/* - * Description: Boolean type - */ - -#ifndef BOOLEAN_H -#define BOOLEAN_H - -#if !defined(bool) && !defined(true) && !defined(false) -typedef enum { false, true } bool; -#endif - -#endif diff --git a/projects/samples/contests/ratslife/controllers/contest_manager/maze_definition.h b/projects/samples/contests/ratslife/controllers/contest_manager/maze_definition.h index bc7ab74ea16..d255852cc7f 100644 --- a/projects/samples/contests/ratslife/controllers/contest_manager/maze_definition.h +++ b/projects/samples/contests/ratslife/controllers/contest_manager/maze_definition.h @@ -21,7 +21,7 @@ #ifndef MAZE_DEFINITION_H #define MAZE_DEFINITION_H -#include "boolean.h" +#include #include "linked_list.h" // enum typedef enum { North, South, East, West, None } Orientation; diff --git a/projects/samples/contests/ratslife/controllers/contest_manager/round_manager.c b/projects/samples/contests/ratslife/controllers/contest_manager/round_manager.c index 62fd710bd7e..ad2ea940b7b 100644 --- a/projects/samples/contests/ratslife/controllers/contest_manager/round_manager.c +++ b/projects/samples/contests/ratslife/controllers/contest_manager/round_manager.c @@ -20,7 +20,7 @@ #include "round_manager.h" -#include "boolean.h" +#include #include "helper.h" #include diff --git a/projects/samples/contests/ratslife/controllers/contest_manager/texture_generator.c b/projects/samples/contests/ratslife/controllers/contest_manager/texture_generator.c index e6c9ad58dbe..f1b9a7f923a 100644 --- a/projects/samples/contests/ratslife/controllers/contest_manager/texture_generator.c +++ b/projects/samples/contests/ratslife/controllers/contest_manager/texture_generator.c @@ -22,7 +22,7 @@ #include #include -#include "boolean.h" +#include #include "helper.h" #include "parameters.h" #include "texture_generator.h" From 8e7d814fbbc2aef8680e86d9f9df1cc7873093b9 Mon Sep 17 00:00:00 2001 From: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> Date: Sun, 6 Jul 2025 20:51:31 -0700 Subject: [PATCH 05/16] use windows-2022 in sources tests (#6858) --- .github/workflows/tests_sources.yml | 6 +++--- .github/workflows/tests_sources_with_latest_cppcheck.yml | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/.github/workflows/tests_sources.yml b/.github/workflows/tests_sources.yml index ba6318f4b4d..e4e648de51e 100644 --- a/.github/workflows/tests_sources.yml +++ b/.github/workflows/tests_sources.yml @@ -34,14 +34,14 @@ jobs: strategy: fail-fast: false matrix: - os: [ubuntu-22.04, macos-14, windows-2019] + os: [ubuntu-22.04, macos-14, windows-2022] python: [3.9] include: - os: ubuntu-22.04 DEPENDENCIES_INSTALLATION: "wget https://github.com/danmar/cppcheck/archive/refs/tags/2.14.2.tar.gz; tar -xf 2.14.2.tar.gz -C ~/; mkdir -p ~/cppcheck-2.14.2/build; cd ~/cppcheck-2.14.2/build; cmake -DCMAKE_BUILD_TYPE=RelWithDebInfo ..; cmake --build . --config RelWithDebInfo; export PATH=~/cppcheck-2.14.2/build/bin:$PATH" - os: macos-14 DEPENDENCIES_INSTALLATION: "brew tap-new --no-git $USER/local-cppcheck; brew extract --version=2.14.2 cppcheck $USER/local-cppcheck; brew install cppcheck@2.14.2; brew tap-new --no-git $USER/local-clang-format; brew extract --version=14.0.0 clang-format $USER/local-clang-format; brew install clang-format@14.0.0" - - os: windows-2019 + - os: windows-2022 DEPENDENCIES_INSTALLATION: "curl -LJO https://github.com/danmar/cppcheck/releases/download/2.14.1/cppcheck-2.14.1-x64-Setup.msi; powershell 'Start-Process msiexec -ArgumentList \"/quiet\",\"/passive\",\"/qn\",\"/i\",\"cppcheck-2.14.1-x64-Setup.msi\" -Wait'; choco uninstall -y llvm; choco install -y llvm --version=14.0.0; export PATH=$PATH:\"/c/Program Files/Cppcheck:/c/Program Files/LLVM/bin\"" runs-on: ${{ matrix.os }} if: needs.job-skipper.outputs.should_skip != 'true' @@ -52,7 +52,7 @@ jobs: echo "job_needed=true" >> "$GITHUB_OUTPUT" id: os_check - name: Set git to use LF - if: matrix.os == 'windows-2019' + if: matrix.os == 'windows-2022' run: | git config --global core.autocrlf false git config --global core.eol lf diff --git a/.github/workflows/tests_sources_with_latest_cppcheck.yml b/.github/workflows/tests_sources_with_latest_cppcheck.yml index fbef60e4d70..c57f3d4d067 100644 --- a/.github/workflows/tests_sources_with_latest_cppcheck.yml +++ b/.github/workflows/tests_sources_with_latest_cppcheck.yml @@ -30,14 +30,14 @@ jobs: strategy: fail-fast: false matrix: - os: [ubuntu-22.04, macos-14, windows-2019] + os: [ubuntu-22.04, macos-14, windows-2022] python: [3.9] include: - os: ubuntu-22.04 DEPENDENCIES_INSTALLATION: "sudo apt -y install cppcheck" - os: macos-14 DEPENDENCIES_INSTALLATION: "brew install cppcheck; brew tap-new --no-git $USER/local-clang-format; brew extract --version=14.0.0 clang-format $USER/local-clang-format; brew install clang-format@14.0.0" - - os: windows-2019 + - os: windows-2022 DEPENDENCIES_INSTALLATION: "choco install -y cppcheck || true; choco uninstall -y llvm; choco install -y llvm --version=14.0.0; export PATH=$PATH:\"/c/Program Files/Cppcheck:/c/Program Files/LLVM/bin\"" runs-on: ${{ matrix.os }} if: needs.job-skipper.outputs.should_skip != 'true' @@ -48,7 +48,7 @@ jobs: echo "job_needed=true" >> "$GITHUB_OUTPUT" id: os_check - name: Set git to use LF - if: matrix.os == 'windows-2019' + if: matrix.os == 'windows-2022' run: | git config --global core.autocrlf false git config --global core.eol lf From 474fd9fee1c626eb1945ad461293201352c642ca Mon Sep 17 00:00:00 2001 From: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> Date: Sun, 6 Jul 2025 22:47:58 -0700 Subject: [PATCH 06/16] Set `mIsBeingDeleted` before emitting `isBeingDestroyed` in `WbNode` (#6857) * set mIsBeingDeleted before emitting isBeingDestroyed * update changelog * disable debug symbols in release builds (revert unnecessary changes) * fix casts --- docs/reference/changelog-r2025.md | 1 + src/webots/app/WbSelection.cpp | 4 ++-- src/webots/gui/WbMainWindow.cpp | 2 +- src/webots/gui/WbRenderingDeviceWindowFactory.cpp | 4 ++-- src/webots/nodes/WbBaseNode.cpp | 1 - src/webots/nodes/WbBaseNode.hpp | 1 - src/webots/nodes/WbRobot.cpp | 4 ++-- src/webots/vrml/WbNode.cpp | 1 + src/webots/vrml/WbNode.hpp | 2 ++ 9 files changed, 11 insertions(+), 9 deletions(-) diff --git a/docs/reference/changelog-r2025.md b/docs/reference/changelog-r2025.md index 114982338d7..54ded549a84 100644 --- a/docs/reference/changelog-r2025.md +++ b/docs/reference/changelog-r2025.md @@ -5,6 +5,7 @@ - Fixed a bug preventing the `webots-controller` executable from running on arm-based mac devices ([#6806](https://github.com/cyberbotics/webots/pull/6806)). - Fixed a bug causing Webots to crash when multiple sounds were used with a [Speaker](speaker.md) node ([#6843](https://github.com/cyberbotics/webots/pull/6843)). - Fixed a bug causing the "Reload/Reset" buttons in the controller recompilation popup to not work on Windows ([#6844](https://github.com/cyberbotics/webots/pull/6844)). + - Fixed a bug causing Webots to occasionally crash when unloading a world ([#6857](https://github.com/cyberbotics/webots/pull/6857)). ## Webots R2025a Released on January 31st, 2025. diff --git a/src/webots/app/WbSelection.cpp b/src/webots/app/WbSelection.cpp index 02ec637f709..90a93d52ab9 100644 --- a/src/webots/app/WbSelection.cpp +++ b/src/webots/app/WbSelection.cpp @@ -72,7 +72,7 @@ void WbSelection::selectNode(WbBaseNode *n, bool handlesDisabled) { if (mSelectedAbstractPose && poseChanged) { mSelectedAbstractPose->detachTranslateRotateManipulator(); - disconnect(mSelectedAbstractPose->baseNode(), &WbBaseNode::isBeingDestroyed, this, &WbSelection::clear); + disconnect(mSelectedAbstractPose->baseNode(), &WbNode::isBeingDestroyed, this, &WbSelection::clear); } } } @@ -88,7 +88,7 @@ void WbSelection::selectNode(WbBaseNode *n, bool handlesDisabled) { updateMatterSelection(true); if (mSelectedAbstractPose && poseChanged) { - connect(mSelectedNode, &WbBaseNode::isBeingDestroyed, this, &WbSelection::clear, Qt::UniqueConnection); + connect(mSelectedNode, &WbNode::isBeingDestroyed, this, &WbSelection::clear, Qt::UniqueConnection); if (!handlesDisabled && !mSelectedNode->isUseNode() && !WbNodeUtilities::isNodeOrAncestorLocked(mSelectedAbstractPose->baseNode())) mSelectedAbstractPose->attachTranslateRotateManipulator(); diff --git a/src/webots/gui/WbMainWindow.cpp b/src/webots/gui/WbMainWindow.cpp index 55e5f8afad6..d2db2ee2363 100644 --- a/src/webots/gui/WbMainWindow.cpp +++ b/src/webots/gui/WbMainWindow.cpp @@ -2181,7 +2181,7 @@ void WbMainWindow::showHtmlRobotWindow(WbRobot *robot, bool manualTrigger) { currentRobotWindow = new WbRobotWindow(robot); mRobotWindows << currentRobotWindow; connect(mTcpServer, &WbTcpServer::sendRobotWindowClientID, currentRobotWindow, &WbRobotWindow::setClientID); - connect(robot, &WbBaseNode::isBeingDestroyed, this, [this, robot]() { deleteRobotWindow(robot); }); + connect(robot, &WbNode::isBeingDestroyed, this, [this, robot]() { deleteRobotWindow(robot); }); connect(robot, &WbMatter::matterNameChanged, this, [this, robot]() { showHtmlRobotWindow(robot, false); }); connect(robot, &WbRobot::controllerChanged, this, [this, robot]() { showHtmlRobotWindow(robot, false); }); connect(robot, &WbRobot::externControllerChanged, this, [this, robot]() { showHtmlRobotWindow(robot, false); }); diff --git a/src/webots/gui/WbRenderingDeviceWindowFactory.cpp b/src/webots/gui/WbRenderingDeviceWindowFactory.cpp index 130e3aa8923..7face847f8f 100644 --- a/src/webots/gui/WbRenderingDeviceWindowFactory.cpp +++ b/src/webots/gui/WbRenderingDeviceWindowFactory.cpp @@ -116,7 +116,7 @@ WbRenderingDeviceWindow *WbRenderingDeviceWindowFactory::getWindowForDevice(WbRe return NULL; WbRenderingDeviceWindow *window = new WbRenderingDeviceWindow(device); - connect(device, &WbRenderingDevice::isBeingDestroyed, this, &WbRenderingDeviceWindowFactory::deleteWindow); + connect(device, &WbNode::isBeingDestroyed, this, &WbRenderingDeviceWindowFactory::deleteWindow); mWindowsList.append(window); return window; } @@ -140,7 +140,7 @@ void WbRenderingDeviceWindowFactory::setWindowsEnabled(bool enabled) { } void WbRenderingDeviceWindowFactory::deleteWindow() { - WbBaseNode *node = dynamic_cast(sender()); + WbNode *node = dynamic_cast(sender()); assert(node); for (int i = 0; i < mWindowsList.size(); ++i) { if (mWindowsList[i]->deviceId() == node->uniqueId()) { diff --git a/src/webots/nodes/WbBaseNode.cpp b/src/webots/nodes/WbBaseNode.cpp index 3cd4cccd769..6db657847a7 100644 --- a/src/webots/nodes/WbBaseNode.cpp +++ b/src/webots/nodes/WbBaseNode.cpp @@ -72,7 +72,6 @@ WbBaseNode::WbBaseNode(const QString &modelName) : WbNode(modelName) { } WbBaseNode::~WbBaseNode() { - emit isBeingDestroyed(this); if (mPostFinalizeCalled && !defName().isEmpty() && !WbWorld::instance()->isCleaning() && !WbTemplateManager::isRegenerating()) WbDictionary::instance()->removeNodeFromDictionary(this); } diff --git a/src/webots/nodes/WbBaseNode.hpp b/src/webots/nodes/WbBaseNode.hpp index f0d855d7324..f927257ffbb 100644 --- a/src/webots/nodes/WbBaseNode.hpp +++ b/src/webots/nodes/WbBaseNode.hpp @@ -129,7 +129,6 @@ class WbBaseNode : public WbNode { QString documentationUrl() const; signals: - void isBeingDestroyed(WbBaseNode *node); void visibleHandlesChanged(bool resizeHandlesEnabled); void finalizationCompleted(WbBaseNode *node); diff --git a/src/webots/nodes/WbRobot.cpp b/src/webots/nodes/WbRobot.cpp index dbfb47c6434..ce41d37bd2c 100644 --- a/src/webots/nodes/WbRobot.cpp +++ b/src/webots/nodes/WbRobot.cpp @@ -284,7 +284,7 @@ void WbRobot::addDevices(WbNode *node) { WbRenderingDevice *renderingDevice = dynamic_cast(node); if (renderingDevice) { - connect(renderingDevice, &WbBaseNode::isBeingDestroyed, this, &WbRobot::removeRenderingDevice, Qt::UniqueConnection); + connect(renderingDevice, &WbNode::isBeingDestroyed, this, &WbRobot::removeRenderingDevice, Qt::UniqueConnection); mRenderingDevices.append(renderingDevice); WbAbstractCamera *camera = dynamic_cast(renderingDevice); if (camera) { @@ -632,7 +632,7 @@ void WbRobot::updateBattery(bool itemInserted) { } void WbRobot::removeRenderingDevice() { - mRenderingDevices.removeOne(static_cast(sender())); + mRenderingDevices.removeOne(dynamic_cast(sender())); } void WbRobot::assignDeviceTags(bool reset) { diff --git a/src/webots/vrml/WbNode.cpp b/src/webots/vrml/WbNode.cpp index 17f0639efab..5648120bdd9 100644 --- a/src/webots/vrml/WbNode.cpp +++ b/src/webots/vrml/WbNode.cpp @@ -250,6 +250,7 @@ WbNode::WbNode(const WbNode &other) : WbNode::~WbNode() { mIsBeingDeleted = true; + emit isBeingDestroyed(this); // Delete fields backwards to always delete USE nodes before DEF nodes int n = mFields.size() - 1; diff --git a/src/webots/vrml/WbNode.hpp b/src/webots/vrml/WbNode.hpp index c76e5dee527..db1bc282f3e 100644 --- a/src/webots/vrml/WbNode.hpp +++ b/src/webots/vrml/WbNode.hpp @@ -281,6 +281,8 @@ class WbNode : public QObject { virtual const bool isRobot() const { return false; }; signals: + void isBeingDestroyed(WbNode *node); + // emitted when any value has changed void fieldChanged(WbField *field); void parameterChanged(WbField *field); From 78755a40fae545a4057e72313fee185b792722f9 Mon Sep 17 00:00:00 2001 From: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> Date: Sun, 13 Jul 2025 13:08:03 -0700 Subject: [PATCH 07/16] Clarify Robot Window HTML Test (#6755) * fix race condition * run test on all platforms * fix test message to reference correct controller * use non-snap firefox * copy previous commit to main CI script * define UBUNTU_VERSION * add sudo to scripts * use correct formatting in apt preferences * specify apt repo in command instead of preferences * debugging * clarify logic * revert firefox changes * revert test-suite change * Revert "debugging" This reverts commit eb1458669856968dc764f72d6d47977718819fec. * clarify variable initializations * disable robot_window_html test in CI * reenable test on non-linux platforms * cleanup --- .../robot_window_html/robot_window_html.c | 21 +++++++++---------- tests/test_suite.py | 6 ++++-- 2 files changed, 14 insertions(+), 13 deletions(-) diff --git a/tests/api/controllers/robot_window_html/robot_window_html.c b/tests/api/controllers/robot_window_html/robot_window_html.c index 9e38f6c3c37..be050015a19 100644 --- a/tests/api/controllers/robot_window_html/robot_window_html.c +++ b/tests/api/controllers/robot_window_html/robot_window_html.c @@ -7,27 +7,26 @@ #define TIME_STEP 32 int main(int argc, char **argv) { - bool configured = false, received = false; ts_setup(argv[0]); - while (!configured) { // receive message sent by the robot window. + for (;;) { // receive message sent by the robot window. wb_robot_step(TIME_STEP); - const char *configure_message; - while ((configure_message = wb_robot_wwi_receive_text())) { + const char *configure_message = wb_robot_wwi_receive_text(); + if (configure_message) { if (strcmp(configure_message, "configure") == 0) { - configured = true; - wb_robot_wwi_send_text("test wwi functions from complete_test controller."); + wb_robot_wwi_send_text("test wwi functions from robot_window_html controller."); + break; } else ts_send_error_and_exit("Wrong configure message received from the HTML robot-window: %s", configure_message); } } - while (!received) { // receive message sent by Webots. + for (;;) { // receive message sent by Webots. wb_robot_step(TIME_STEP); - const char *test_message; - while ((test_message = wb_robot_wwi_receive_text())) { - if (strcmp(test_message, "Answer: test wwi functions from complete_test controller.") == 0) - received = true; + const char *test_message = wb_robot_wwi_receive_text(); + if (test_message) { + if (strcmp(test_message, "Answer: test wwi functions from robot_window_html controller.") == 0) + break; else ts_send_error_and_exit("Wrong test message received from the HTML robot-window: %s", test_message); } diff --git a/tests/test_suite.py b/tests/test_suite.py index 6362c27fe67..68b7ba0a7c2 100755 --- a/tests/test_suite.py +++ b/tests/test_suite.py @@ -199,17 +199,19 @@ def generateWorldsList(groupName): # to file for filename in filenames: # speaker test not working on github action because of missing sound drivers - # robot window and movie recording test not working on BETA Ubuntu 22.04 GitHub Action environment + # robot window test cannot open a browser for the robot window in a headless environment + # on non-mac operating systems + # movie recording test not working on BETA Ubuntu 22.04 GitHub Action environment # billboard test not working in macos GitHub Action environment # billboard and robot window not working on windows GitHub Action environment. if (not filename.endswith('_temp.wbt') and not ('GITHUB_ACTIONS' in os.environ and ( filename.endswith('speaker.wbt') or filename.endswith('local_proto_with_texture.wbt') or - (filename.endswith('robot_window_html.wbt') and is_ubuntu_22_04) or (filename.endswith('supervisor_start_stop_movie.wbt') and is_ubuntu_22_04) or (filename.endswith('billboard.wbt') and sys.platform == 'darwin') or (filename.endswith('billboard.wbt') and sys.platform == 'win32') or + (filename.endswith('robot_window_html.wbt') and sys.platform == 'linux') or (filename.endswith('robot_window_html.wbt') and sys.platform == 'win32') ))): worldsList.append(filename) From 6e8f7f3d8725b4c64ddf5365763810176adacbae Mon Sep 17 00:00:00 2001 From: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> Date: Sun, 13 Jul 2025 13:21:27 -0700 Subject: [PATCH 08/16] Decouple MATLAB Functions Test from `Controller.def` (#6752) * test matlab functions against controller headers * fix MATLAB capitalization * fix typo * print stderr on subprocess failure --- include/controller/c/webots/supervisor.h | 4 +- tests/sources/test_matlab_functions.py | 88 ++++++++++++++++-------- 2 files changed, 63 insertions(+), 29 deletions(-) mode change 100755 => 100644 tests/sources/test_matlab_functions.py diff --git a/include/controller/c/webots/supervisor.h b/include/controller/c/webots/supervisor.h index 092c02cba71..fdae974cb7e 100644 --- a/include/controller/c/webots/supervisor.h +++ b/include/controller/c/webots/supervisor.h @@ -224,10 +224,10 @@ void wb_supervisor_simulation_revert() WB_DEPRECATED; // please us void wb_supervisor_load_world(const char *filename) WB_DEPRECATED; // please use wb_supervisor_world_load() instead bool wb_supervisor_save_world(const char *filename) WB_DEPRECATED; // please use wb_supervisor_world_save() instead -// deprecated since Webots 8.6.0, plesae use wb_supervisor_field_remove_mf_item() instead +// deprecated since Webots 8.6.0, please use wb_supervisor_field_remove_mf() instead void wb_supervisor_field_remove_mf_node(WbFieldRef field, int position) WB_DEPRECATED; -// deprecated since Webots 8.0.0, plesae use wb_supervisor_simulation_reset_physics() instead +// deprecated since Webots 8.0.0, please use wb_supervisor_simulation_reset_physics() instead void wb_supervisor_simulation_physics_reset() WB_DEPRECATED; // deprecated since Webots 8.4.0 please use wb_supervisor_movie_is_ready and wb_supervisor_movie_failed diff --git a/tests/sources/test_matlab_functions.py b/tests/sources/test_matlab_functions.py old mode 100755 new mode 100644 index 5c3ff2f59f1..4b65b4d2544 --- a/tests/sources/test_matlab_functions.py +++ b/tests/sources/test_matlab_functions.py @@ -14,54 +14,88 @@ # See the License for the specific language governing permissions and # limitations under the License. -"""Test that all the required Matlab functions are defined.""" +"""Test that all the required MATLAB functions are defined.""" import unittest +import glob import os +import re +import subprocess import sys + WEBOTS_HOME = os.path.normpath(os.environ['WEBOTS_HOME']) sys.path.append(os.path.join(WEBOTS_HOME, 'src', 'controller', 'matlab')) import mgenerate # noqa: E402 class TestMatlabFunctions(unittest.TestCase): - """Unit test for checking that all the required Matlab functions are defined.""" + """Unit test for checking that all the required MATLAB functions are defined.""" def setUp(self): if sys.version_info[0] >= 3: mgenerate.UPDATE = False mgenerate.main() - """Get all the required function.""" + """Get all the required functions.""" skippedLines = [ - 'wbr', - 'microphone', - 'remote_control', - 'robot', - 'wb_device_get_type', - 'wb_node_get_name', - 'wbu_string', - 'lookup_table_size', - 'EXPORTS' + # Patterns + '.*_H', # Header Guards + '.*_', # Some comments use the ..._* pattern to refer to a group of functions ; + # grep will filter the *, but no function should end with _ + 'wb_camera_image_get_.*', # The MATLAB API exposes the image data as a multidimensional array, + # so these functions are not needed + 'wb_(microphone|radio)_.*', # Experimental Node Types + 'wb_remote_control_.*', 'wbr_.*', # Remote Control Plugin + 'wb_robot_.*', # Many robot functions are used internally by the C API (e.x. wb_robot_mutex_*) + '.*_lookup_table_size', # MATLAB lets you get the size of an array, so these functions are not needed + 'wbu_string_.*', # String manipulation functions are not needed + + # Specific Functions + + # Non-Function Macros + 'WB_ALLOW_MIXING_C_AND_CPP_API', + 'WB_DEPRECATED', + 'WB_MATLAB_LOADLIBRARY', + 'WB_USING_C(PP)?_API', + + # These functions are used internally by the MATLAB API + 'wb_camera_recognition_get_object', + 'wb_lidar_get_point', + 'wb_mouse_get_state_pointer', + 'wb_radar_get_target', + + 'wb_device_get_type', # Deprecated since 8.0.0 + 'wb_node_get_name', # C API Only + + # Not Yet Implemented + 'wbu_system_tmpdir', + 'wbu_system_webots_instance_path', ] self.functions = [] - filename = os.path.join(WEBOTS_HOME, 'src', 'controller', 'c', 'Controller.def') - self.assertTrue( - os.path.isfile(filename), - msg='Missing "%s" file.' % filename - ) - with open(filename) as file: - for line in file: - if not any(skippedLine in line for skippedLine in skippedLines) and not line[3:].isupper(): - self.functions.append(line.replace('\n', '')) + + symbolSearch = subprocess.run([ + # Search for webots definitions + 'grep', '-Ehio', r'\bwb_\w+\b', + # In the controller headers + *glob.glob(os.path.join(WEBOTS_HOME, 'include', 'controller', 'c', 'webots', '*.h')), + *glob.glob(os.path.join(WEBOTS_HOME, 'include', 'controller', 'c', 'webots', 'utils', '*.h')) + ], capture_output=True, text=True) + if symbolSearch.returncode != 0: + self.fail(f'Failed to generate function list:\n{symbolSearch.stdout}\n{symbolSearch.stderr}') + + for line in symbolSearch.stdout.splitlines(): + if not any(re.match(f'^{skippedLine}$', line) for skippedLine in skippedLines) and line not in self.functions: + self.functions.append(line) @unittest.skipIf(sys.version_info[0] < 3, "not supported by Python 2.7") def test_matlab_function_exists(self): """Test that the function file exists.""" - for function in self.functions: - filename = os.path.join(WEBOTS_HOME, 'lib', 'controller', 'matlab', function + '.m') - self.assertTrue( - os.path.isfile(filename), - msg='Missing "%s" file.' % filename - ) + expectedFiles = (os.path.join(WEBOTS_HOME, 'lib', 'controller', 'matlab', function + '.m') + for function in self.functions) + missingFiles = [file for file in expectedFiles if not os.path.isfile(file)] + + self.assertTrue( + not missingFiles, + msg='Missing files: %s' % ', '.join(missingFiles) + ) if __name__ == '__main__': From 34e7ddeec502c0215e652b34eb92618bb6e9a0cb Mon Sep 17 00:00:00 2001 From: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> Date: Mon, 14 Jul 2025 01:34:14 -0700 Subject: [PATCH 09/16] Build lib Files with gcc on Windows (#6753) * build lib files with gcc * remove references to Visual Studio * remove unneeded def files * include lib files in distribution * update the changelog * fix test step names * missing change from previous commit --- .github/workflows/test_suite_windows.yml | 14 +- .../workflows/test_suite_windows_develop.yml | 7 +- docs/reference/changelog-r2025.md | 5 + .../default/libraries/vehicle/c/car/car.def | 28 - .../libraries/vehicle/c/driver/driver.def | 30 - .../youbot_control/youbot_control.def | 34 - resources/Makefile.include | 39 +- scripts/install/bash_profile.windows | 1 - scripts/packaging/files_core.txt | 6 +- src/controller/c/Controller.def | 643 ----------------- src/controller/c/Makefile | 34 +- src/controller/cpp/Makefile | 4 +- src/ode/ode.def | 649 ------------------ 13 files changed, 23 insertions(+), 1471 deletions(-) delete mode 100644 projects/default/libraries/vehicle/c/car/car.def delete mode 100644 projects/default/libraries/vehicle/c/driver/driver.def delete mode 100644 projects/robots/kuka/youbot/libraries/youbot_control/youbot_control.def delete mode 100644 src/controller/c/Controller.def delete mode 100644 src/ode/ode.def diff --git a/.github/workflows/test_suite_windows.yml b/.github/workflows/test_suite_windows.yml index eec6a99632c..df7b819e089 100644 --- a/.github/workflows/test_suite_windows.yml +++ b/.github/workflows/test_suite_windows.yml @@ -59,18 +59,15 @@ jobs: - uses: actions/setup-python@v4 with: python-version: '3.11' - - name: Install Visual Studio 10 and OpenJDK 18 + - name: Install OpenJDK 18 shell: powershell - run: | - choco install -y openjdk --version=18.0.2 - choco install -y visualcpp-build-tools + run: choco install -y openjdk --version=18.0.2 - name: Install Webots Compilation Dependencies run: | export PYTHON_INSTALLATION_FOLDER=/C/hostedtoolcache/windows/Python export PYTHON_HOME=$PYTHON_INSTALLATION_FOLDER/3.11.`ls $PYTHON_INSTALLATION_FOLDER | grep '^3\.11\.[0-9]\+$' | cut -c6- | sort -n | tail -n1`/x64 echo 'export JAVA_HOME=/C/Program\ Files/OpenJDK/`ls /C/Program\ Files/OpenJDK`' >> ~/.bash_profile echo 'export PYTHON_HOME='$PYTHON_HOME >> ~/.bash_profile - echo 'export VISUAL_STUDIO_PATH="/C/Program Files (x86)/Microsoft Visual Studio/2017"' >> ~/.bash_profile echo 'export INNO_SETUP_HOME="/C/Program Files (x86)/Inno Setup 6"' >> ~/.bash_profile echo 'export PATH=$PYTHON_HOME:$PYTHON_HOME/Scripts:$GITHUB_WORKSPACE/msys64/mingw64/bin:$GITHUB_WORKSPACE/bin/node:/mingw64/bin:/usr/bin:$JAVA_HOME/bin:$PATH' >> ~/.bash_profile export WEBOTS_HOME=$GITHUB_WORKSPACE @@ -110,18 +107,15 @@ jobs: - uses: msys2/setup-msys2@v2 with: update: false - - name: Install Visual Studio 10 and OpenJDK 18 + - name: Install OpenJDK 18 shell: powershell - run: | - choco install -y openjdk --version=18.0.2 - choco install -y visualcpp-build-tools + run: choco install -y openjdk --version=18.0.2 - name: Install Webots Compilation Dependencies run: | export PYTHON_INSTALLATION_FOLDER=/C/hostedtoolcache/windows/Python export PYTHON_HOME=$PYTHON_INSTALLATION_FOLDER/3.11.`ls $PYTHON_INSTALLATION_FOLDER | grep '^3\.11\.[0-9]\+$' | cut -c6- | sort -n | tail -n1`/x64 echo 'export JAVA_HOME=/C/Program\ Files/OpenJDK/`ls /C/Program\ Files/OpenJDK`' >> ~/.bash_profile echo 'export PYTHON_HOME='$PYTHON_HOME >> ~/.bash_profile - echo 'export VISUAL_STUDIO_PATH="/C/Program Files (x86)/Microsoft Visual Studio/2017"' >> ~/.bash_profile echo 'export INNO_SETUP_HOME="/C/Program Files (x86)/Inno Setup 6"' >> ~/.bash_profile echo 'export PATH=$PYTHON_HOME:$PYTHON_HOME/Scripts:$GITHUB_WORKSPACE/msys64/mingw64/bin:$GITHUB_WORKSPACE/bin/node:/mingw64/bin:/usr/bin:$JAVA_HOME/bin:$PATH' >> ~/.bash_profile export WEBOTS_HOME=$GITHUB_WORKSPACE diff --git a/.github/workflows/test_suite_windows_develop.yml b/.github/workflows/test_suite_windows_develop.yml index cb24a23dc81..434fa79326b 100644 --- a/.github/workflows/test_suite_windows_develop.yml +++ b/.github/workflows/test_suite_windows_develop.yml @@ -55,18 +55,15 @@ jobs: - uses: actions/setup-python@v4 with: python-version: '3.11' - - name: Install Visual Studio 10 and OpenJDK 18 + - name: Install OpenJDK 18 shell: powershell - run: | - choco install -y openjdk --version=18.0.2 - choco install -y visualcpp-build-tools + run: choco install -y openjdk --version=18.0.2 - name: Install Webots Compilation Dependencies run: | export PYTHON_INSTALLATION_FOLDER=/C/hostedtoolcache/windows/Python export PYTHON_HOME=$PYTHON_INSTALLATION_FOLDER/3.11.`ls $PYTHON_INSTALLATION_FOLDER | grep '^3\.11\.[0-9]\+$' | cut -c6- | sort -n | tail -n1`/x64 echo 'export JAVA_HOME=/C/Program\ Files/OpenJDK/`ls /C/Program\ Files/OpenJDK`' >> ~/.bash_profile echo 'export PYTHON_HOME='$PYTHON_HOME >> ~/.bash_profile - echo 'export VISUAL_STUDIO_PATH="/C/Program Files (x86)/Microsoft Visual Studio/2017"' >> ~/.bash_profile echo 'export INNO_SETUP_HOME="/C/Program Files (x86)/Inno Setup 6"' >> ~/.bash_profile echo 'export PATH=$PYTHON_HOME:$PYTHON_HOME/Scripts:$GITHUB_WORKSPACE/msys64/mingw64/bin:$GITHUB_WORKSPACE/bin/node:/mingw64/bin:/usr/bin:$JAVA_HOME/bin:$PATH' >> ~/.bash_profile export WEBOTS_HOME=$GITHUB_WORKSPACE diff --git a/docs/reference/changelog-r2025.md b/docs/reference/changelog-r2025.md index 54ded549a84..3c1bb676478 100644 --- a/docs/reference/changelog-r2025.md +++ b/docs/reference/changelog-r2025.md @@ -1,6 +1,11 @@ # Webots R2025 Change Log ## Webots R2025b + - Enhancements + - Added missing import libraries on Windows ([#6753](https://github.com/cyberbotics/webots/pull/6753)). + - Added some missing function definitions to the existing Windows libraries ([#6753](https://github.com/cyberbotics/webots/pull/6753)). + - Cleanup + - **Removed `libController.a` and `libCppController.a` libraries on Windows. Please use `Controller.lib` and `CppController.lib` instead ([#6753](https://github.com/cyberbotics/webots/pull/6753)).** - Bug Fixes - Fixed a bug preventing the `webots-controller` executable from running on arm-based mac devices ([#6806](https://github.com/cyberbotics/webots/pull/6806)). - Fixed a bug causing Webots to crash when multiple sounds were used with a [Speaker](speaker.md) node ([#6843](https://github.com/cyberbotics/webots/pull/6843)). diff --git a/projects/default/libraries/vehicle/c/car/car.def b/projects/default/libraries/vehicle/c/car/car.def deleted file mode 100644 index 1c3e82018d5..00000000000 --- a/projects/default/libraries/vehicle/c/car/car.def +++ /dev/null @@ -1,28 +0,0 @@ -EXPORTS -wbu_car_init -wbu_car_cleanup -wbu_car_get_type -wbu_car_get_engine_type -wbu_car_set_indicator_period -wbu_car_get_indicator_period -wbu_car_get_backwards_lights -wbu_car_get_brake_lights -wbu_car_get_track_front -wbu_car_get_track_rear -wbu_car_get_wheelbase -wbu_car_get_front_wheel_radius -wbu_car_get_rear_wheel_radius -wbu_car_get_wheel_encoder -wbu_car_get_wheel_speed -wbu_car_set_right_steering_angle -wbu_car_get_right_steering_angle -wbu_car_set_left_steering_angle -wbu_car_get_left_steering_angle -wbu_car_enable_limited_slip_differential -wbu_car_enable_indicator_auto_disabling -_wbu_car_get_instance -_wbu_car_set_led_state_if_exist -_wbu_car_get_led_state_if_exist -_wbu_car_check_initialisation -_wbu_car_initialization_is_possible - diff --git a/projects/default/libraries/vehicle/c/driver/driver.def b/projects/default/libraries/vehicle/c/driver/driver.def deleted file mode 100644 index 20a14276f50..00000000000 --- a/projects/default/libraries/vehicle/c/driver/driver.def +++ /dev/null @@ -1,30 +0,0 @@ -EXPORTS -wbu_driver_init -wbu_driver_initialization_is_possible -wbu_driver_cleanup -wbu_driver_step -wbu_driver_set_steering_angle -wbu_driver_get_steering_angle -wbu_driver_set_cruising_speed -wbu_driver_get_target_cruising_speed -wbu_driver_get_current_speed -wbu_driver_set_throttle -wbu_driver_get_throttle -wbu_driver_set_brake_intensity -wbu_driver_get_brake_intensity -wbu_driver_set_indicator -wbu_driver_set_hazard_flashers -wbu_driver_get_indicator -wbu_driver_get_hazard_flashers -wbu_driver_set_dipped_beams -wbu_driver_set_antifog_lights -wbu_driver_get_dipped_beams -wbu_driver_get_antifog_lights -wbu_driver_get_rpm -wbu_driver_get_gear -wbu_driver_set_gear -wbu_driver_get_gear_number -wbu_driver_get_control_mode -wbu_driver_set_wiper_mode -wbu_driver_get_wiper_mode - diff --git a/projects/robots/kuka/youbot/libraries/youbot_control/youbot_control.def b/projects/robots/kuka/youbot/libraries/youbot_control/youbot_control.def deleted file mode 100644 index c31e921477d..00000000000 --- a/projects/robots/kuka/youbot/libraries/youbot_control/youbot_control.def +++ /dev/null @@ -1,34 +0,0 @@ -EXPORTS -arm_init -arm_reset -arm_set_height -arm_increase_height -arm_decrease_height -arm_set_orientation -arm_increase_orientation -arm_decrease_orientation -arm_set_sub_arm_rotation -arm_get_sub_arm_length -arm_ik -base_init -base_reset -base_forwards -base_backwards -base_turn_left -base_turn_right -base_strafe_left -base_strafe_right -base_forwards_increment -base_backwards_increment -base_turn_left_increment -base_turn_right_increment -base_strafe_left_increment -base_strafe_right_increment -base_goto_init -base_goto_set_target -base_goto_run -base_goto_reached -gripper_init -gripper_grip -gripper_release -gripper_set_gap diff --git a/resources/Makefile.include b/resources/Makefile.include index 461793b164e..c961d1f74e7 100644 --- a/resources/Makefile.include +++ b/resources/Makefile.include @@ -391,18 +391,6 @@ ifdef BUILD_STATIC_LIBRARY STATIC_LINK_FLAGS += rvs endif -# Visual Studio -ifeq ($(OSTYPE),windows) - ifdef BUILD_SHARED_LIBRARY - ifndef USE_CXX - ifneq ($(wildcard /C/Program\ Files\ */Microsoft\ Visual\ Studio/2017),) - VISUAL_STUDIO_PATH?=/C/Program Files (x86)/Microsoft Visual Studio/2017 - endif - VS_DEF_NAME = $(NAME).def - endif - endif -endif - ifeq ($(OSTYPE),darwin) ifdef WEBOTS_LIBRARY INSTALL_NAME ?= @rpath/Contents/lib/controller/$(MAIN_TARGET) @@ -486,6 +474,7 @@ MAIN_TARGET_COPY ?= $(MAIN_TARGET) MAIN_TARGET_WINDOWS64_LIB = $(MAIN_TARGET:.dll=.lib) endif ifeq ($(OSTYPE),windows) +DYNAMIC_LINK_FLAGS += -Wl,--out-implib,$(MAIN_TARGET_WINDOWS64_LIB) FILES_TO_REMOVE += $(MAIN_TARGET_WINDOWS64_LIB) endif @@ -506,19 +495,6 @@ endif ifdef TARGET_LIB_DIR $(MAIN_TARGET): $(TARGET_LIB_DIR)/$(MAIN_TARGET) -ifdef VS_DEF_NAME - @# Generate the .lib libraries to facilitate the integration with Visual Studio - @# if the .def file is existing. - @if [ -f $(VS_DEF_NAME) ]; then \ - if [ -d "$(VISUAL_STUDIO_PATH)" ]; then \ - PATH="$(VISUAL_STUDIO_PATH)/BuildTools/VC/Tools/MSVC/14.16.27023/bin/Hostx64/x64":$PATH lib /machine:X64 /def:$(VS_DEF_NAME) /out:out.lib > /dev/null; \ - mv out.lib $(MAIN_TARGET_WINDOWS64_LIB); \ - rm -f *.exp; \ - else \ - $(ECHO) "\033[0;33m'VISUAL_STUDIO_PATH' environmental variable not set or Microsoft Visual Studio not installed, skipping $(NAME).lib\033[0m"; \ - fi \ - fi -endif else @@ -528,19 +504,6 @@ $(MAIN_TARGET): $(BUILD_GOAL_DIR)/$(MAIN_TARGET) @# This new version will be executed only when the process restarts. @# Note: this binary may be an executable (e.g., a controller) or shared library (e.g., a physics plug-in). @rm -f $(MAIN_TARGET) > /dev/null 2>&1 && echo "# copying to" $(MAIN_TARGET_COPY) && cp $(BUILD_GOAL_DIR)/$(MAIN_TARGET) $(MAIN_TARGET_COPY) > /dev/null 2>&1 -ifdef VS_DEF_NAME - @# Generate the .lib libraries to facilitate the integration with Visual Studio - @# if the .def file is existing. - @if [ -f $(VS_DEF_NAME) ]; then \ - if [ -d "$(VISUAL_STUDIO_PATH)" ]; then \ - PATH="$(VISUAL_STUDIO_PATH)/BuildTools/VC/Tools/MSVC/14.16.27023/bin/Hostx64/x64":$PATH lib /machine:X64 /def:$(VS_DEF_NAME) /out:out.lib > /dev/null; \ - mv out.lib $(MAIN_TARGET_WINDOWS64_LIB); \ - rm -f *.exp; \ - else \ - $(ECHO) "\033[0;33m'VISUAL_STUDIO_PATH' environmental variable not set or Microsoft Visual Studio not installed, skipping $(NAME).lib\033[0m"; \ - fi \ - fi -endif endif diff --git a/scripts/install/bash_profile.windows b/scripts/install/bash_profile.windows index 1fe3d69a16f..ab0c3e5dfe2 100644 --- a/scripts/install/bash_profile.windows +++ b/scripts/install/bash_profile.windows @@ -6,7 +6,6 @@ # export PYTHON_HOME="C:\Program Files\Python310" # Optionally defines the path to Python home. # export JAVA_HOME=/C/Program\ Files/OpenJDK/`ls /C/Program\ Files/OpenJDK` # Optionally defines the path to Java home. # export MATLAB_HOME=/C/Program\ Files/MATLAB/R2018b # Optionally defines the path to MATLAB home. -# export VISUAL_STUDIO_PATH="/C/Program Files (x86)/Microsoft Visual Studio/2017" # Optionally defines the path to Microsoft Visual Studio home. # export INNO_SETUP_HOME="/C/Program Files (x86)/Inno Setup 6" # Optionally defines the path to Inno Setup home. diff --git a/scripts/packaging/files_core.txt b/scripts/packaging/files_core.txt index 473d8c9cc97..a20ad7c69c9 100644 --- a/scripts/packaging/files_core.txt +++ b/scripts/packaging/files_core.txt @@ -64,10 +64,9 @@ lib/controller/ [windows,linux] lib/controller/Controller [dll,windows,linux] lib/controller/Controller.lib [windows] -lib/controller/libController.a [windows] lib/controller/CppController [dll,windows,linux] -lib/controller/libCppController.a [windows] +lib/controller/CppController.lib [windows] lib/controller/java/ [windows,linux] lib/controller/java/*.jar [windows,linux] @@ -81,8 +80,11 @@ lib/controller/CppDriver [dll,windows,linux] lib/controller/driver [dll,windows,linux] lib/controller/car.lib [windows] lib/controller/driver.lib [windows] +lib/controller/CppCar.lib [windows] +lib/controller/CppDriver.lib [windows] lib/controller/generic_robot_window [dll,windows,linux] +lib/controller/generic_robot_window.lib [windows] lib/controller/python/ [windows,linux] lib/controller/python/controller/ [windows,linux] diff --git a/src/controller/c/Controller.def b/src/controller/c/Controller.def deleted file mode 100644 index d7fc80bbe2b..00000000000 --- a/src/controller/c/Controller.def +++ /dev/null @@ -1,643 +0,0 @@ -EXPORTS -wb_ANSI_RESET -wb_ANSI_BOLD -wb_ANSI_UNDERLINE -wb_ANSI_BLACK_BACKGROUND -wb_ANSI_RED_BACKGROUND -wb_ANSI_GREEN_BACKGROUND -wb_ANSI_YELLOW_BACKGROUND -wb_ANSI_BLUE_BACKGROUND -wb_ANSI_MAGENTA_BACKGROUND -wb_ANSI_CYAN_BACKGROUND -wb_ANSI_WHITE_BACKGROUND -wb_ANSI_BLACK_FOREGROUND -wb_ANSI_RED_FOREGROUND -wb_ANSI_GREEN_FOREGROUND -wb_ANSI_YELLOW_FOREGROUND -wb_ANSI_BLUE_FOREGROUND -wb_ANSI_MAGENTA_FOREGROUND -wb_ANSI_CYAN_FOREGROUND -wb_ANSI_WHITE_FOREGROUND -wb_ANSI_CLEAR_SCREEN -wb_KEYBOARD_END -wb_KEYBOARD_HOME -wb_KEYBOARD_LEFT -wb_KEYBOARD_UP -wb_KEYBOARD_RIGHT -wb_KEYBOARD_DOWN -wb_KEYBOARD_PAGEUP -wb_KEYBOARD_PAGEDOWN -wb_KEYBOARD_NUMPAD_HOME -wb_KEYBOARD_NUMPAD_LEFT -wb_KEYBOARD_NUMPAD_UP -wb_KEYBOARD_NUMPAD_RIGHT -wb_KEYBOARD_NUMPAD_DOWN -wb_KEYBOARD_NUMPAD_END -wb_KEYBOARD_KEY -wb_KEYBOARD_SHIFT -wb_KEYBOARD_CONTROL -wb_KEYBOARD_ALT -wb_LINEAR -wb_MF -wb_MF_BOOL -wb_MF_INT32 -wb_MF_FLOAT -wb_MF_VEC2F -wb_MF_VEC3F -wb_MF_ROTATION -wb_MF_COLOR -wb_MF_STRING -wb_MF_NODE -wb_NODE_NO_NODE -wb_NODE_APPEARANCE -wb_NODE_BACKGROUND -wb_NODE_BILLBOARD -wb_NODE_BOX -wb_NODE_CAD_SHAPE -wb_NODE_CAPSULE -wb_NODE_COLOR -wb_NODE_CONE -wb_NODE_COORDINATE -wb_NODE_CYLINDER -wb_NODE_DIRECTIONAL_LIGHT -wb_NODE_ELEVATION_GRID -wb_NODE_FOG -wb_NODE_GROUP -wb_NODE_IMAGE_TEXTURE -wb_NODE_INDEXED_FACE_SET -wb_NODE_INDEXED_LINE_SET -wb_NODE_MATERIAL -wb_NODE_MESH -wb_NODE_MUSCLE -wb_NODE_NORMAL -wb_NODE_PBR_APPEARANCE -wb_NODE_PLANE -wb_NODE_POINT_LIGHT -wb_NODE_POINT_SET -wb_NODE_POSE -wb_NODE_SHAPE -wb_NODE_SPHERE -wb_NODE_SPOT_LIGHT -wb_NODE_TEXTURE_COORDINATE -wb_NODE_TEXTURE_TRANSFORM -wb_NODE_TRANSFORM -wb_NODE_VIEWPOINT -wb_NODE_ROBOT -wb_NODE_ACCELEROMETER -wb_NODE_ALTIMETER -wb_NODE_BRAKE -wb_NODE_CAMERA -wb_NODE_COMPASS -wb_NODE_CONNECTOR -wb_NODE_DISPLAY -wb_NODE_DISTANCE_SENSOR -wb_NODE_EMITTER -wb_NODE_GPS -wb_NODE_GYRO -wb_NODE_INERTIAL_UNIT -wb_NODE_LED -wb_NODE_LIDAR -wb_NODE_LIGHT_SENSOR -wb_NODE_LINEAR_MOTOR -wb_NODE_PEN -wb_NODE_POSITION_SENSOR -wb_NODE_PROPELLER -wb_NODE_RADAR -wb_NODE_RANGE_FINDER -wb_NODE_RECEIVER -wb_NODE_ROTATIONAL_MOTOR -wb_NODE_SKIN -wb_NODE_SPEAKER -wb_NODE_TOUCH_SENSOR -wb_NODE_VACUUM_GRIPPER -wb_NODE_BALL_JOINT -wb_NODE_BALL_JOINT_PARAMETERS -wb_NODE_CHARGER -wb_NODE_CONTACT_PROPERTIES -wb_NODE_DAMPING -wb_NODE_FLUID -wb_NODE_FOCUS -wb_NODE_HINGE_JOINT -wb_NODE_HINGE_JOINT_PARAMETERS -wb_NODE_HINGE_2_JOINT -wb_NODE_IMMERSION_PROPERTIES -wb_NODE_JOINT_PARAMETERS -wb_NODE_LENS -wb_NODE_LENS_FLARE -wb_NODE_PHYSICS -wb_NODE_RECOGNITION -wb_NODE_SLIDER_JOINT -wb_NODE_SLOT -wb_NODE_SOLID -wb_NODE_SOLID_REFERENCE -wb_NODE_TRACK -wb_NODE_TRACK_WHEEL -wb_NODE_WORLD_INFO -wb_NODE_ZOOM -wb_NODE_MICROPHONE -wb_NODE_RADIO -wb_ROTATIONAL -wb_SF_BOOL -wb_SF_INT32 -wb_SF_FLOAT -wb_SF_VEC2F -wb_SF_VEC3F -wb_SF_ROTATION -wb_SF_COLOR -wb_SF_STRING -wb_SF_NODE -wb_accelerometer_disable -wb_accelerometer_enable -wb_accelerometer_get_sampling_period -wb_accelerometer_get_values -wb_accelerometer_get_lookup_table_size -wb_accelerometer_get_lookup_table -wb_altimeter_disable -wb_altimeter_enable -wb_altimeter_get_sampling_period -wb_altimeter_get_value -wb_brake_get_motor -wb_brake_get_position_sensor -wb_brake_get_type -wb_brake_set_damping_constant -wb_camera_disable -wb_camera_enable -wb_camera_get_exposure -wb_camera_get_focal_distance -wb_camera_get_focal_length -wb_camera_get_fov -wb_camera_get_height -wb_camera_get_image -wb_camera_get_max_focal_distance -wb_camera_get_max_fov -wb_camera_get_min_focal_distance -wb_camera_get_min_fov -wb_camera_get_near -wb_camera_get_sampling_period -wb_camera_get_width -wb_camera_has_recognition -wb_camera_recognition_disable -wb_camera_recognition_disable_segmentation -wb_camera_recognition_enable -wb_camera_recognition_enable_segmentation -wb_camera_recognition_get_number_of_objects -wb_camera_recognition_get_objects -wb_camera_recognition_get_sampling_period -wb_camera_recognition_get_segmentation_image -wb_camera_recognition_has_segmentation -wb_camera_recognition_is_segmentation_enabled -wb_camera_recognition_save_segmentation_image -wb_camera_save_image -wb_camera_set_exposure -wb_camera_set_focal_distance -wb_camera_set_fov -wb_compass_disable -wb_compass_enable -wb_compass_get_sampling_period -wb_compass_get_values -wb_compass_get_lookup_table_size -wb_compass_get_lookup_table -wb_connector_disable_presence -wb_connector_enable_presence -wb_connector_get_presence -wb_connector_get_presence_sampling_period -wb_connector_is_locked -wb_connector_lock -wb_connector_unlock -wb_console_print -wb_device_get_model -wb_device_get_name -wb_device_get_type -wb_device_get_node_type -wb_display_attach_camera -wb_display_detach_camera -wb_display_draw_line -wb_display_draw_oval -wb_display_draw_pixel -wb_display_draw_polygon -wb_display_draw_rectangle -wb_display_draw_text -wb_display_fill_oval -wb_display_fill_polygon -wb_display_fill_rectangle -wb_display_get_height -wb_display_get_width -wb_display_image_copy -wb_display_image_delete -wb_display_image_load -wb_display_image_new -wb_display_image_paste -wb_display_image_save -wb_display_set_alpha -wb_display_set_color -wb_display_set_font -wb_display_set_opacity -wb_distance_sensor_disable -wb_distance_sensor_enable -wb_distance_sensor_get_aperture -wb_distance_sensor_get_max_value -wb_distance_sensor_get_min_value -wb_distance_sensor_get_sampling_period -wb_distance_sensor_get_type -wb_distance_sensor_get_value -wb_distance_sensor_get_lookup_table_size -wb_distance_sensor_get_lookup_table -wb_emitter_get_buffer_size -wb_emitter_get_channel -wb_emitter_get_range -wb_emitter_send -wb_emitter_set_channel -wb_emitter_set_range -wb_gps_disable -wb_gps_convert_to_degrees_minutes_seconds -wb_gps_enable -wb_gps_get_coordinate_system -wb_gps_get_sampling_period -wb_gps_get_speed -wb_gps_get_speed_vector -wb_gps_get_values -wb_gyro_disable -wb_gyro_enable -wb_gyro_get_sampling_period -wb_gyro_get_values -wb_gyro_get_lookup_table_size -wb_gyro_get_lookup_table -wb_inertial_unit_disable -wb_inertial_unit_enable -wb_inertial_unit_get_roll_pitch_yaw -wb_inertial_unit_get_quaternion -wb_inertial_unit_get_sampling_period -wb_inertial_unit_get_noise -wb_joystick_disable -wb_joystick_enable -wb_joystick_get_axis_value -wb_joystick_get_model -wb_joystick_get_number_of_axes -wb_joystick_get_number_of_povs -wb_joystick_get_pov_value -wb_joystick_get_pressed_button -wb_joystick_get_sampling_period -wb_joystick_is_connected -wb_joystick_set_auto_centering_gain -wb_joystick_set_constant_force -wb_joystick_set_constant_force_duration -wb_joystick_set_force_axis -wb_joystick_set_resistance_gain -wb_keyboard_disable -wb_keyboard_enable -wb_keyboard_get_key -wb_keyboard_get_sampling_period -wb_led_get -wb_led_set -wb_lidar_disable -wb_lidar_disable_point_cloud -wb_lidar_enable -wb_lidar_enable_point_cloud -wb_lidar_get_fov -wb_lidar_get_frequency -wb_lidar_get_horizontal_resolution -wb_lidar_get_layer_point_cloud -wb_lidar_get_layer_range_image -wb_lidar_get_max_frequency -wb_lidar_get_max_range -wb_lidar_get_min_frequency -wb_lidar_get_min_range -wb_lidar_get_number_of_layers -wb_lidar_get_number_of_points -wb_lidar_get_point_cloud -wb_lidar_get_range_image -wb_lidar_get_sampling_period -wb_lidar_get_vertical_fov -wb_lidar_is_point_cloud_enabled -wb_lidar_set_frequency -wb_light_sensor_disable -wb_light_sensor_enable -wb_light_sensor_get_sampling_period -wb_light_sensor_get_value -wb_light_sensor_get_lookup_table_size -wb_light_sensor_get_lookup_table -wb_microphone_enable -wb_microphone_get_sample_data -wb_microphone_get_sample_size -wb_microphone_get_sampling_period -wb_motor_disable_force_feedback -wb_motor_disable_torque_feedback -wb_motor_enable_force_feedback -wb_motor_enable_torque_feedback -wb_motor_get_acceleration -wb_motor_get_available_force -wb_motor_get_available_torque -wb_motor_get_force_feedback -wb_motor_get_force_feedback_sampling_period -wb_motor_get_max_force -wb_motor_get_max_torque -wb_motor_get_max_position -wb_motor_get_max_velocity -wb_motor_get_min_position -wb_motor_get_multiplier -wb_motor_get_target_position -wb_motor_get_torque_feedback -wb_motor_get_torque_feedback_sampling_period -wb_motor_get_type -wb_motor_get_velocity -wb_motor_get_brake -wb_motor_get_position_sensor -wb_motor_set_acceleration -wb_motor_set_available_force -wb_motor_set_available_torque -wb_motor_set_control_pid -wb_motor_set_force -wb_motor_set_position -wb_motor_set_torque -wb_motor_set_velocity -wb_mouse_disable -wb_mouse_disable_3d_position -wb_mouse_enable -wb_mouse_enable_3d_position -wb_mouse_get_sampling_period -wb_mouse_get_state -wb_mouse_is_3d_position_enabled -wb_node_get_name -wb_pen_set_ink_color -wb_pen_write -wb_position_sensor_enable -wb_position_sensor_disable -wb_position_sensor_get_value -wb_position_sensor_get_sampling_period -wb_position_sensor_get_type -wb_position_sensor_get_brake -wb_position_sensor_get_motor -wb_radar_disable -wb_radar_enable -wb_radar_get_horizontal_fov -wb_radar_get_max_range -wb_radar_get_min_range -wb_radar_get_number_of_targets -wb_radar_get_sampling_period -wb_radar_get_targets -wb_radar_get_vertical_fov -wb_range_finder_enable -wb_range_finder_disable -wb_range_finder_get_sampling_period -wb_range_finder_get_range_image -wb_range_finder_get_width -wb_range_finder_get_height -wb_range_finder_get_fov -wb_range_finder_get_min_range -wb_range_finder_get_max_range -wb_range_finder_save_image -wb_range_finder_image_get_depth -wb_remote_control_custom_function -wb_receiver_disable -wb_receiver_enable -wb_receiver_get_channel -wb_receiver_get_data -wb_receiver_get_data_size -wb_receiver_get_emitter_direction -wb_receiver_get_queue_length -wb_receiver_get_sampling_period -wb_receiver_get_signal_strength -wb_receiver_next_packet -wb_receiver_set_channel -wb_robot_battery_sensor_disable -wb_robot_battery_sensor_enable -wb_robot_battery_sensor_get_value -wb_robot_battery_sensor_get_sampling_period -wb_robot_cleanup -wb_robot_get_basic_time_step -wb_robot_get_controller_name -wb_robot_get_custom_data -wb_robot_get_data -wb_robot_get_device -wb_robot_get_device_by_index -wb_robot_get_mode -wb_robot_get_model -wb_robot_get_name -wb_robot_get_number_of_devices -wb_robot_get_project_path -wb_robot_get_supervisor -wb_robot_get_synchronization -wb_robot_get_time -wb_robot_get_urdf -wb_robot_get_world_path -wb_robot_init -wb_robot_init_msvc -wb_robot_mutex_delete -wb_robot_mutex_lock -wb_robot_mutex_new -wb_robot_mutex_unlock -wb_robot_pin_to_static_environment -wb_robot_set_custom_data -wb_robot_set_data -wb_robot_set_mode -wb_robot_step -wb_robot_step_begin -wb_robot_step_end -wb_robot_task_new -wb_robot_wait_for_user_input_event -wb_robot_window_custom_function -wb_robot_wwi_send -wb_robot_wwi_receive -wb_robot_wwi_receive_text -wb_skin_get_bone_count -wb_skin_get_bone_name -wb_skin_get_bone_orientation -wb_skin_get_bone_position -wb_skin_set_bone_orientation -wb_skin_set_bone_position -wb_speaker_get_engine -wb_speaker_get_language -wb_speaker_is_sound_playing -wb_speaker_is_speaking -wb_speaker_play_sound -wb_speaker_set_engine -wb_speaker_set_language -wb_speaker_speak -wb_speaker_stop -wb_supervisor_node_add_force -wb_supervisor_node_add_force_with_offset -wb_supervisor_node_add_torque -wb_supervisor_animation_start_recording -wb_supervisor_animation_stop_recording -wb_supervisor_export_image -wb_supervisor_field_disable_sf_tracking -wb_supervisor_field_enable_sf_tracking -wb_supervisor_field_get_actual_field -wb_supervisor_field_get_count -wb_supervisor_field_get_name -wb_supervisor_field_get_mf_bool -wb_supervisor_field_get_mf_color -wb_supervisor_field_get_mf_float -wb_supervisor_field_get_mf_int32 -wb_supervisor_field_get_mf_node -wb_supervisor_field_get_mf_rotation -wb_supervisor_field_get_mf_string -wb_supervisor_field_get_mf_vec2f -wb_supervisor_field_get_mf_vec3f -wb_supervisor_field_get_sf_bool -wb_supervisor_field_get_sf_color -wb_supervisor_field_get_sf_float -wb_supervisor_field_get_sf_int32 -wb_supervisor_field_get_sf_node -wb_supervisor_field_get_sf_rotation -wb_supervisor_field_get_sf_string -wb_supervisor_field_get_sf_vec2f -wb_supervisor_field_get_sf_vec3f -wb_supervisor_field_get_type -wb_supervisor_field_get_type_name -wb_supervisor_field_import_mf_node_from_string -wb_supervisor_field_import_sf_node_from_string -wb_supervisor_field_insert_mf_bool -wb_supervisor_field_insert_mf_color -wb_supervisor_field_insert_mf_float -wb_supervisor_field_insert_mf_int32 -wb_supervisor_field_insert_mf_rotation -wb_supervisor_field_insert_mf_string -wb_supervisor_field_insert_mf_vec2f -wb_supervisor_field_insert_mf_vec3f -wb_supervisor_field_remove_mf -wb_supervisor_field_remove_mf_node -wb_supervisor_field_remove_sf -wb_supervisor_field_set_mf_bool -wb_supervisor_field_set_mf_color -wb_supervisor_field_set_mf_float -wb_supervisor_field_set_mf_int32 -wb_supervisor_field_set_mf_rotation -wb_supervisor_field_set_mf_string -wb_supervisor_field_set_mf_vec2f -wb_supervisor_field_set_mf_vec3f -wb_supervisor_field_set_sf_bool -wb_supervisor_field_set_sf_color -wb_supervisor_field_set_sf_float -wb_supervisor_field_set_sf_int32 -wb_supervisor_field_set_sf_rotation -wb_supervisor_field_set_sf_string -wb_supervisor_field_set_sf_vec2f -wb_supervisor_field_set_sf_vec3f -wb_supervisor_movie_failed -wb_supervisor_movie_is_ready -wb_supervisor_movie_start_recording -wb_supervisor_movie_stop_recording -wb_supervisor_movie_get_status -wb_supervisor_node_disable_contact_point_tracking -wb_supervisor_node_disable_contact_points_tracking -wb_supervisor_node_disable_pose_tracking -wb_supervisor_node_enable_contact_point_tracking -wb_supervisor_node_enable_contact_points_tracking -wb_supervisor_node_enable_pose_tracking -wb_supervisor_node_export_string -wb_supervisor_node_get_base_node_field -wb_supervisor_node_get_base_node_field_by_index -wb_supervisor_node_get_base_type_name -wb_supervisor_node_get_def -wb_supervisor_node_get_field -wb_supervisor_node_get_field_by_index -wb_supervisor_node_get_from_def -wb_supervisor_node_get_from_id -wb_supervisor_node_get_from_proto_def -wb_supervisor_node_get_from_device -wb_supervisor_node_get_center_of_mass -wb_supervisor_node_get_contact_point -wb_supervisor_node_get_contact_points -wb_supervisor_node_get_contact_point_node -wb_supervisor_node_get_id -wb_supervisor_node_get_number_of_base_node_fields -wb_supervisor_node_get_number_of_contact_points -wb_supervisor_node_get_number_of_fields -wb_supervisor_node_get_orientation -wb_supervisor_node_get_parent_node -wb_supervisor_node_get_pose -wb_supervisor_node_get_position -wb_supervisor_node_get_proto -wb_supervisor_node_get_root -wb_supervisor_node_get_selected -wb_supervisor_node_get_self -wb_supervisor_node_get_static_balance -wb_supervisor_node_get_type -wb_supervisor_node_get_type_name -wb_supervisor_node_get_velocity -wb_supervisor_node_is_proto -wb_supervisor_node_load_state -wb_supervisor_node_move_viewpoint -wb_supervisor_node_remove -wb_supervisor_node_reset_physics -wb_supervisor_node_restart_controller -wb_supervisor_node_save_state -wb_supervisor_node_set_joint_position -wb_supervisor_node_set_velocity -wb_supervisor_node_set_visibility -wb_supervisor_proto_get_field -wb_supervisor_proto_get_field_by_index -wb_supervisor_proto_get_number_of_fields -wb_supervisor_proto_get_parent -wb_supervisor_proto_get_type_name -wb_supervisor_proto_is_derived -wb_supervisor_set_label -wb_supervisor_simulation_get_mode -wb_supervisor_simulation_physics_reset -wb_supervisor_simulation_quit -wb_supervisor_simulation_reset -wb_supervisor_simulation_reset_physics -wb_supervisor_simulation_revert -wb_supervisor_simulation_set_mode -wb_supervisor_start_movie -wb_supervisor_stop_movie -wb_supervisor_get_movie_status -wb_supervisor_virtual_reality_headset_get_position -wb_supervisor_virtual_reality_headset_get_orientation -wb_supervisor_virtual_reality_headset_is_used -wb_supervisor_world_load -wb_supervisor_world_save -wb_supervisor_world_reload -wb_touch_sensor_disable -wb_touch_sensor_enable -wb_touch_sensor_get_sampling_period -wb_touch_sensor_get_type -wb_touch_sensor_get_value -wb_touch_sensor_get_values -wb_touch_sensor_get_lookup_table_size -wb_touch_sensor_get_lookup_table -wb_vacuum_gripper_disable_presence -wb_vacuum_gripper_enable_presence -wb_vacuum_gripper_get_presence -wb_vacuum_gripper_get_presence_sampling_period -wb_vacuum_gripper_is_on -wb_vacuum_gripper_turn_on -wb_vacuum_gripper_turn_off -wbr_accelerometer_set_values -wbr_camera_get_image_buffer -wbr_camera_set_image -wbr_camera_set_focal_distance -wbr_camera_set_fov -wbr_compass_set_values -wbr_display_save_image -wbr_distance_sensor_set_value -wbr_gps_set_values -wbr_gyro_set_values -wbr_light_sensor_set_value -wbr_microphone_set_buffer -wbr_motor_set_force_feedback -wbr_motor_set_torque_feedback -wbr_position_sensor_set_value -wbr_robot_battery_sensor_set_value -wbr_touch_sensor_set_value -wbr_touch_sensor_set_values -wbu_default_robot_window_configure -wbu_default_robot_window_update -wbu_default_robot_window_set_images_max_size -wbu_motion_delete -wbu_motion_get_duration -wbu_motion_get_time -wbu_motion_is_over -wbu_motion_new -wbu_motion_play -wbu_motion_set_loop -wbu_motion_set_reverse -wbu_motion_set_time -wbu_motion_stop -wbu_robot_window_configure -wbu_robot_window_update -wbu_string_replace -wbu_string_strsep -wbu_system_getenv -wbu_system_short_path diff --git a/src/controller/c/Makefile b/src/controller/c/Makefile index 14a32c751b5..d9c04e3206d 100644 --- a/src/controller/c/Makefile +++ b/src/controller/c/Makefile @@ -61,10 +61,10 @@ endif ifeq ($(OSTYPE),windows) CFLAGS = -Wall -mwindows -frandom-seed=0 -D LIBCONTROLLER_VERSION='$(LIBCONTROLLER_VERSION)' INCLUDE = -I$(WEBOTS_HOME_PATH)/include/controller/c -I$(WEBOTS_HOME_PATH)/include -I/mingw64/include -LD_FLAGS = -shared -mwindows --def Controller.def -lws2_32 -PLATFORM = win32 +LD_FLAGS = -shared -mwindows -Wl,--out-implib,$(WEBOTS_CONTROLLER_LIB_PATH)/Controller.lib +SHARED_LIBS = -lws2_32 CC = gcc -TARGET = $(WEBOTS_CONTROLLER_LIB_PATH)/Controller.dll $(WEBOTS_CONTROLLER_LIB_PATH)/Controller.lib +TARGET = $(WEBOTS_CONTROLLER_LIB_PATH)/Controller.dll endif ifeq ($(MAKECMDGOALS),debug) @@ -122,27 +122,6 @@ endif debug profile release: $(TARGET) -ifeq ($(OSTYPE),windows) - -MINGW64_OBJECTS = $(addprefix $(OBJDIR)/, $(OBJECTS)) - -$(WEBOTS_CONTROLLER_LIB_PATH)/Controller.dll: $(MINGW64_OBJECTS) Controller.def - @echo "# linking "$@ - @echo "# linking "$(WEBOTS_CONTROLLER_LIB_PATH)"/libController.a" - @$(CC) -o $@ $(addprefix $(OBJDIR)/, $(OBJECTS)) $(LD_FLAGS) -Wl,--out-implib,$(WEBOTS_CONTROLLER_LIB_PATH)/libController.a - -$(WEBOTS_CONTROLLER_LIB_PATH)/Controller.lib: $(WEBOTS_CONTROLLER_LIB_PATH)/Controller.dll Controller.def -ifeq ($(VISUAL_STUDIO_PATH),) - @$(ECHO) "# \033[0;33m'VISUAL_STUDIO_PATH' not set, skipping Controller.lib\033[0m" -else - @echo "# creating "$@ - @PATH="$(VISUAL_STUDIO_PATH)/BuildTools/VC/Tools/MSVC/14.16.27023/bin/Hostx64/x64":$PATH lib /machine:X64 /def:Controller.def /out:Controller.lib > /dev/null - @mv Controller.lib "$(WEBOTS_CONTROLLER_LIB_PATH)" - @rm Controller.exp -endif - -endif - ifeq ($(OSTYPE),darwin) X86_64_OBJECTS = $(addprefix $(OBJDIR)/x86_64/, $(OBJECTS)) ARM64_OBJECTS = $(addprefix $(OBJDIR)/arm64/, $(OBJECTS)) @@ -163,9 +142,7 @@ $(OBJDIR)/arm64/libController.dylib: $(ARM64_OBJECTS) @$(CC) $(LD_FLAGS) -target arm64-apple-macos12 -o $@ $(ARM64_OBJECTS) $(SHARED_LIBS) @chmod a-x $@ -endif - -ifeq ($(OSTYPE),linux) +else $(TARGET): $(OBJECTS) @echo "# linking "$@ @$(CC) $(LD_FLAGS) -o $(TARGET) $(addprefix $(OBJDIR)/, $(OBJECTS)) $(SHARED_LIBS) @@ -193,5 +170,4 @@ $(OBJDIR)/%.d:%.c @$(CC) $(CFLAGS) -MM -w $(INCLUDE) $< >> $(OBJDIR)/$(notdir $@) FILES_TO_REMOVE = $(TARGET) -FILES_TO_REMOVE += $(WEBOTS_CONTROLLER_LIB_PATH)/libController.a -FILES_TO_REMOVE += $(WEBOTS_CONTROLLER_LIB_PATH)/libController.lib +FILES_TO_REMOVE += $(WEBOTS_CONTROLLER_LIB_PATH)/Controller.lib diff --git a/src/controller/cpp/Makefile b/src/controller/cpp/Makefile index dde0a6e9794..88d9d604877 100644 --- a/src/controller/cpp/Makefile +++ b/src/controller/cpp/Makefile @@ -86,7 +86,7 @@ ifneq (,$(filter $(MAKECMDGOALS),debug release profile)) # if $(MAKECMDGOALS) is endif ifeq ($(OSTYPE),windows) -LDFLAGS = -frandom-seed=0 -shared -Wl,--out-implib,$(WEBOTS_CONTROLLER_LIB_PATH)/libCppController.a +LDFLAGS = -frandom-seed=0 -shared -Wl,--out-implib,$(WEBOTS_CONTROLLER_LIB_PATH)/CppController.lib LIBCONTROLLER = $(WEBOTS_CONTROLLER_LIB_PATH)/Controller.dll SHAREDLIBS = $(LIBCONTROLLER) CPPFLAGS = -c -Wall -mwindows @@ -168,7 +168,7 @@ $(OBJDIR)/%.d:%.cpp @$(CXX) $(CPPINCLUDES) -MM $< >> $@ ifeq ($(OSTYPE),windows) -FILES_TO_REMOVE = $(WEBOTS_CONTROLLER_LIB_PATH)/CppController.dll $(WEBOTS_CONTROLLER_LIB_PATH)/libCppController.a *.def *.exp +FILES_TO_REMOVE = $(WEBOTS_CONTROLLER_LIB_PATH)/CppController.dll $(WEBOTS_CONTROLLER_LIB_PATH)/CppController.lib *.exp else FILES_TO_REMOVE = $(WEBOTS_CONTROLLER_LIB_PATH)/*Cpp* endif diff --git a/src/ode/ode.def b/src/ode/ode.def deleted file mode 100644 index 17ba86a738d..00000000000 --- a/src/ode/ode.def +++ /dev/null @@ -1,649 +0,0 @@ -EXPORTS -dAlloc -dAllocateODEDataForThread -dAreConnected -dAreConnectedExcluding -dAreGeomsSame -dAreLinked -dBodyAddForce -dBodyAddForceAtPos -dBodyAddForceAtRelPos -dBodyAddRelForce -dBodyAddRelForceAtPos -dBodyAddRelForceAtRelPos -dBodyAddRelTorque -dBodyAddTorque -dBodyCopyPosition -dBodyCopyQuaternion -dBodyCopyRotation -dBodyCreate -dBodyDestroy -dBodyDisable -dBodyEnable -dBodyGetAngularDamping -dBodyGetAngularDampingThreshold -dBodyGetAngularVel -dBodyGetAutoDisableAngularThreshold -dBodyGetAutoDisableAverageSamplesCount -dBodyGetAutoDisableFlag -dBodyGetAutoDisableLinearThreshold -dBodyGetAutoDisableSteps -dBodyGetAutoDisableTime -dBodyGetData -dBodyGetFiniteRotationAxis -dBodyGetFiniteRotationMode -dBodyGetFirstGeom -dBodyGetForce -dBodyGetGravityMode -dBodyGetGyroscopicMode -dBodyGetImmersionLink -dBodyGetJoint -dBodyGetLinearDamping -dBodyGetLinearDampingThreshold -dBodyGetLinearVel -dBodyGetMass -dBodyGetMaxAngularSpeed -dBodyGetNextGeom -dBodyGetNumImmersionLinks -dBodyGetNumJoints -dBodyGetPointVel -dBodyGetPosRelPoint -dBodyGetPosition -dBodyGetQuaternion -dBodyGetRelPointPos -dBodyGetRelPointVel -dBodyGetRotation -dBodyGetTorque -dBodyGetWorld -dBodyIsEnabled -dBodyIsKinematic -dBodySetAngularDamping -dBodySetAngularDampingThreshold -dBodySetAngularVel -dBodySetAutoDisableAngularThreshold -dBodySetAutoDisableAverageSamplesCount -dBodySetAutoDisableDefaults -dBodySetAutoDisableFlag -dBodySetAutoDisableLinearThreshold -dBodySetAutoDisableSteps -dBodySetAutoDisableTime -dBodySetDamping -dBodySetDampingDefaults -dBodySetData -dBodySetDynamic -dBodySetFiniteRotationAxis -dBodySetFiniteRotationMode -dBodySetForce -dBodySetGravityMode -dBodySetGyroscopicMode -dBodySetKinematic -dBodySetLinearDamping -dBodySetLinearDampingThreshold -dBodySetLinearVel -dBodySetMass -dBodySetMaxAngularSpeed -dBodySetMovedCallback -dBodySetPosition -dBodySetQuaternion -dBodySetRotation -dBodySetTorque -dBodyVectorFromWorld -dBodyVectorToWorld -dBoxBox -dBoxTouchesBox -dCheckConfiguration -dCleanupODEAllDataForThread -dClearUpperTriangle -dCloseODE -dClosestLineSegmentPoints -dClusterGetCenter -dClusterGetClusterAABBs -dClusterGetCount -dClusterGetGridStep -dCollide -dConnectingJoint -dConnectingJointList -dCreateBox -dCreateCapsule -dCreateConvex -dCreateCylinder -dCreateGeom -dCreateGeomClass -dCreateGeomTransform -dCreateHeightfield -dCreatePlane -dCreateRay -dCreateSphere -dCreateTriMesh -dDQfromW -dDebug -dDot -dError -dFactorCholesky -dFactorLDLT -dFluidCreate -dFluidDestroy -dFluidDisable -dFluidDynamicsStep -dFluidEnable -dFluidGetData -dFluidGetDensity -dFluidGetFirstGeom -dFluidGetImmersionLink -dFluidGetNextGeom -dFluidGetNumImmersionLinks -dFluidGetStreamVel -dFluidGetViscosity -dFluidGetWorld -dFluidIsEnabled -dFluidSetData -dFluidSetDensity -dFluidSetStreamVel -dFluidSetViscosity -dFree -dGeomBoxGetArea -dGeomBoxGetFacePlane -dGeomBoxGetImmersionPlane -dGeomBoxGetLengths -dGeomBoxGetTangentPlane -dGeomBoxGetVolume -dGeomBoxPointDepth -dGeomBoxSetLengths -dGeomCapsuleGetArea -dGeomCapsuleGetImmersionPlane -dGeomCapsuleGetParams -dGeomCapsuleGetTangentPlane -dGeomCapsuleGetVolume -dGeomCapsulePointDepth -dGeomCapsuleSetParams -dGeomClearOffset -dGeomCopyOffsetPosition -dGeomCopyOffsetRotation -dGeomCopyPosition -dGeomCopyRotation -dGeomCylinderGetArea -dGeomCylinderGetDiskPlane -dGeomCylinderGetImmersionPlane -dGeomCylinderGetParams -dGeomCylinderGetTangentPlane -dGeomCylinderGetVolume -dGeomCylinderPointDepth -dGeomCylinderSetParams -dGeomDestroy -dGeomDisable -dGeomEnable -dGeomGetAABB -dGeomGetArea -dGeomGetBody -dGeomGetBodyNext -dGeomGetCategoryBits -dGeomGetClass -dGeomGetClassData -dGeomGetCollideBits -dGeomGetData -dGeomGetFlags -dGeomGetFluid -dGeomGetFluidNext -dGeomGetImmersionPlane -dGeomGetOffsetPosition -dGeomGetOffsetQuaternion -dGeomGetOffsetRotation -dGeomGetPosRelPoint -dGeomGetPosition -dGeomGetQuaternion -dGeomGetRelPointPos -dGeomGetRotation -dGeomGetSpace -dGeomGetVolume -dGeomHeightfieldDataBuildByte -dGeomHeightfieldDataBuildCallback -dGeomHeightfieldDataBuildDouble -dGeomHeightfieldDataBuildShort -dGeomHeightfieldDataBuildSingle -dGeomHeightfieldDataCreate -dGeomHeightfieldDataDestroy -dGeomHeightfieldDataSetBounds -dGeomHeightfieldGetHeightfieldData -dGeomHeightfieldSetHeightfieldData -dGeomIsBelowImmersionPlane -dGeomIsEnabled -dGeomIsInside -dGeomIsOffset -dGeomIsSpace -dGeomLowLevelControl -dGeomMoved -dGeomPlaneGetParams -dGeomPlanePointDepth -dGeomPlaneSetParams -dGeomRayGet -dGeomRayGetClosestHit -dGeomRayGetLength -dGeomRayGetParams -dGeomRaySet -dGeomRaySetClosestHit -dGeomRaySetLength -dGeomRaySetParams -dGeomSetBody -dGeomSetCategoryBits -dGeomSetCollideBits -dGeomSetConvex -dGeomSetData -dGeomSetDynamicFlag -dGeomSetFluid -dGeomSetOffsetPosition -dGeomSetOffsetQuaternion -dGeomSetOffsetRotation -dGeomSetOffsetWorldPosition -dGeomSetOffsetWorldQuaternion -dGeomSetOffsetWorldRotation -dGeomSetPosition -dGeomSetQuaternion -dGeomSetRotation -dGeomSphereGetArea -dGeomSphereGetImmersionPlane -dGeomSphereGetRadius -dGeomSphereGetTangentPlane -dGeomSphereGetVolume -dGeomSpherePointDepth -dGeomSphereSetRadius -dGeomTransformGetCleanup -dGeomTransformGetGeom -dGeomTransformGetInfo -dGeomTransformSetCleanup -dGeomTransformSetGeom -dGeomTransformSetInfo -dGeomTriMeshClearTCCache -dGeomTriMeshDataBuildDouble -dGeomTriMeshDataBuildDouble1 -dGeomTriMeshDataBuildSimple -dGeomTriMeshDataBuildSimple1 -dGeomTriMeshDataBuildSingle -dGeomTriMeshDataBuildSingle1 -dGeomTriMeshDataCreate -dGeomTriMeshDataDestroy -dGeomTriMeshDataGet -dGeomTriMeshDataGetBuffer -dGeomTriMeshDataPreprocess -dGeomTriMeshDataSet -dGeomTriMeshDataSetBuffer -dGeomTriMeshDataUpdate -dGeomTriMeshEnableTC -dGeomTriMeshGetArea -dGeomTriMeshGetArrayCallback -dGeomTriMeshGetBoundingPlane -dGeomTriMeshGetCallback -dGeomTriMeshGetCenterOfMass -dGeomTriMeshGetData -dGeomTriMeshGetImmersionPlane -dGeomTriMeshGetInertiaMatrix -dGeomTriMeshGetLastTransform -dGeomTriMeshGetPoint -dGeomTriMeshGetRayCallback -dGeomTriMeshGetRelCenterOfMass -dGeomTriMeshGetTriMergeCallback -dGeomTriMeshGetTriMeshDataID -dGeomTriMeshGetTriangle -dGeomTriMeshGetTriangleCount -dGeomTriMeshGetVolume -dGeomTriMeshIsTCEnabled -dGeomTriMeshPointDepth -dGeomTriMeshSetArrayCallback -dGeomTriMeshSetCallback -dGeomTriMeshSetData -dGeomTriMeshSetLastTransform -dGeomTriMeshSetRayCallback -dGeomTriMeshSetTriMergeCallback -dGeomVectorFromWorld -dGeomVectorToWorld -dGetAllocHandler -dGetConfiguration -dGetDebugHandler -dGetErrorHandler -dGetFreeHandler -dGetMessageHandler -dGetReallocHandler -dHashSpaceCreate -dHashSpaceGetLevels -dHashSpaceSetLevels -dImmerse -dImmersionLinkAttach -dImmersionLinkCreate -dImmersionLinkDestroy -dImmersionLinkDisable -dImmersionLinkEnable -dImmersionLinkGroupCreate -dImmersionLinkGroupDestroy -dImmersionLinkGroupEmpty -dImmersionLinkSetData -dImmersionOutlineCreate -dImmersionOutlineDestroy -dImmersionOutlineGetCurvedEdge -dImmersionOutlineGetCurvedEdgesSize -dImmersionOutlineGetStraightEdge -dImmersionOutlineGetStraightEdgeEnd -dImmersionOutlineGetStraightEdgeOrigin -dImmersionOutlineGetStraightEdgesSize -dInfiniteAABB -dInitODE -dInitODE2 -dInvertPDMatrix -dIsPositiveDefinite -dJointAddAMotorTorques -dJointAddHinge2Torques -dJointAddHingeTorque -dJointAddPRTorque -dJointAddPistonForce -dJointAddSliderForce -dJointAddUniversalTorques -dJointAttach -dJointCreateAMotor -dJointCreateBall -dJointCreateContact -dJointCreateFixed -dJointCreateHinge -dJointCreateHinge2 -dJointCreateLMotor -dJointCreateNull -dJointCreatePR -dJointCreatePU -dJointCreatePiston -dJointCreatePlane2D -dJointCreateSlider -dJointCreateUniversal -dJointDestroy -dJointDisable -dJointEnable -dJointGetAMotorAngle -dJointGetAMotorAngleRate -dJointGetAMotorAxis -dJointGetAMotorAxisRel -dJointGetAMotorMode -dJointGetAMotorNumAxes -dJointGetAMotorParam -dJointGetBallAnchor -dJointGetBallAnchor2 -dJointGetBallParam -dJointGetBody -dJointGetData -dJointGetFeedback -dJointGetFixedParam -dJointGetHinge2Anchor -dJointGetHinge2Anchor2 -dJointGetHinge2Angle1 -dJointGetHinge2Angle1Rate -dJointGetHinge2Angle2 -dJointGetHinge2Angle2Rate -dJointGetHinge2Axis1 -dJointGetHinge2Axis2 -dJointGetHinge2Param -dJointGetHinge2SuspensionAxis -dJointGetHingeAnchor -dJointGetHingeAnchor2 -dJointGetHingeAngle -dJointGetHingeAngleRate -dJointGetHingeAxis -dJointGetHingeParam -dJointGetHingeSuspensionAxis -dJointGetLMotorAxis -dJointGetLMotorNumAxes -dJointGetLMotorParam -dJointGetLMotorPosition -dJointGetNumBodies -dJointGetPRAnchor -dJointGetPRAngle -dJointGetPRAngleRate -dJointGetPRAxis1 -dJointGetPRAxis2 -dJointGetPRParam -dJointGetPRPosition -dJointGetPRPositionRate -dJointGetPUAnchor -dJointGetPUAngle1 -dJointGetPUAngle1Rate -dJointGetPUAngle2 -dJointGetPUAngle2Rate -dJointGetPUAngles -dJointGetPUAxis1 -dJointGetPUAxis2 -dJointGetPUAxis3 -dJointGetPUAxisP -dJointGetPUParam -dJointGetPUPosition -dJointGetPUPositionRate -dJointGetPistonAnchor -dJointGetPistonAnchor2 -dJointGetPistonAngle -dJointGetPistonAngleRate -dJointGetPistonAxis -dJointGetPistonParam -dJointGetPistonPosition -dJointGetPistonPositionRate -dJointGetSliderAxis -dJointGetSliderParam -dJointGetSliderPosition -dJointGetSliderPositionRate -dJointGetType -dJointGetUniversalAnchor -dJointGetUniversalAnchor2 -dJointGetUniversalAngle1 -dJointGetUniversalAngle1Rate -dJointGetUniversalAngle2 -dJointGetUniversalAngle2Rate -dJointGetUniversalAngles -dJointGetUniversalAxis1 -dJointGetUniversalAxis2 -dJointGetUniversalParam -dJointGroupCreate -dJointGroupDestroy -dJointGroupEmpty -dJointGroupGetCount -dJointIsEnabled -dJointSetAMotorAngle -dJointSetAMotorAxis -dJointSetAMotorMode -dJointSetAMotorNumAxes -dJointSetAMotorParam -dJointSetBallAnchor -dJointSetBallAnchor2 -dJointSetBallParam -dJointSetData -dJointSetFeedback -dJointSetFixed -dJointSetFixedParam -dJointSetHinge2Anchor -dJointSetHinge2Axis1 -dJointSetHinge2Axis2 -dJointSetHinge2Param -dJointSetHinge2SuspensionAxis -dJointSetHingeAnchor -dJointSetHingeAnchorDelta -dJointSetHingeAxis -dJointSetHingeAxisOffset -dJointSetHingeParam -dJointSetHingeSuspensionAxis -dJointSetLMotorAxis -dJointSetLMotorNumAxes -dJointSetLMotorParam -dJointSetLMotorPosition -dJointSetPRAnchor -dJointSetPRAxis1 -dJointSetPRAxis2 -dJointSetPRParam -dJointSetPUAnchor -dJointSetPUAnchorDelta -dJointSetPUAnchorOffset -dJointSetPUAxis1 -dJointSetPUAxis2 -dJointSetPUAxis3 -dJointSetPUAxisP -dJointSetPUParam -dJointSetPistonAnchor -dJointSetPistonAnchorOffset -dJointSetPistonAxis -dJointSetPistonAxisDelta -dJointSetPistonParam -dJointSetPlane2DAngleParam -dJointSetPlane2DXParam -dJointSetPlane2DYParam -dJointSetSliderAxis -dJointSetSliderAxisDelta -dJointSetSliderParam -dJointSetUniversalAnchor -dJointSetUniversalAxis1 -dJointSetUniversalAxis1Offset -dJointSetUniversalAxis2 -dJointSetUniversalAxis2Offset -dJointSetUniversalParam -dLDLTAddTL -dLDLTRemove -dMakeRandomMatrix -dMakeRandomVector -dMassAdd -dMassAdjust -dMassCheck -dMassRotate -dMassSetBox -dMassSetBoxTotal -dMassSetCappedCylinder -dMassSetCappedCylinderTotal -dMassSetCapsule -dMassSetCapsuleTotal -dMassSetCylinder -dMassSetCylinderTotal -dMassSetParameters -dMassSetSphere -dMassSetSphereTotal -dMassSetTrimesh -dMassSetTrimeshTotal -dMassSetZero -dMassTranslate -dMaxDifference -dMaxDifferenceLowerTriangle -dMessage -dMultiply0 -dMultiply1 -dMultiply2 -dNormalize3 -dNormalize4 -dOrthogonalizeR -dPlaneSpace -dPrintMatrix -dQFromAxisAndAngle -dQMultiply0 -dQMultiply1 -dQMultiply2 -dQMultiply3 -dQSetIdentity -dQfromR -dQuadTreeSpaceCreate -dRFrom2Axes -dRFromAxisAndAngle -dRFromEulerAngles -dRFromZAxis -dRSetIdentity -dRand -dRandGetSeed -dRandInt -dRandReal -dRandSetSeed -dRealloc -dRemoveRowCol -dRfromQ -dSafeNormalize3 -dSafeNormalize4 -dSetAllocHandler -dSetColliderOverride -dSetDebugHandler -dSetErrorHandler -dSetFreeHandler -dSetMessageHandler -dSetReallocHandler -dSetValue -dSetZero -dSimpleSpaceCreate -dSolveCholesky -dSolveL1 -dSolveL1T -dSolveLDLT -dSpaceAdd -dSpaceClean -dSpaceCollide -dSpaceCollide2 -dSpaceCollideAndWorldStep -dSpaceDestroy -dSpaceGetClass -dSpaceGetCleanup -dSpaceGetGeom -dSpaceGetManualCleanup -dSpaceGetNumGeoms -dSpaceGetSublevel -dSpaceQuery -dSpaceRemove -dSpaceSetCleanup -dSpaceSetManualCleanup -dSpaceSetSublevel -dStopwatchReset -dStopwatchStart -dStopwatchStop -dStopwatchTime -dSweepAndPruneSpaceCreate -dTestDataStructures -dTestRand -dTestSolveLCP -dTimerEnd -dTimerNow -dTimerReport -dTimerResolution -dTimerStart -dTimerTicksPerSecond -dToggleODE_MT -dVectorScale -dWorldCleanupWorkingMemory -dWorldCreate -dWorldDestroy -dWorldExportDIF -dWorldGetAngularDamping -dWorldGetAngularDampingThreshold -dWorldGetAutoDisableAngularThreshold -dWorldGetAutoDisableAverageSamplesCount -dWorldGetAutoDisableFlag -dWorldGetAutoDisableLinearThreshold -dWorldGetAutoDisableSteps -dWorldGetAutoDisableTime -dWorldGetCFM -dWorldGetContactMaxCorrectingVel -dWorldGetContactSurfaceLayer -dWorldGetERP -dWorldGetGravity -dWorldGetLinearDamping -dWorldGetLinearDampingThreshold -dWorldGetMaxAngularSpeed -dWorldGetQuickStepNumIterations -dWorldGetQuickStepW -dWorldImpulseToForce -dWorldQuickStep -dWorldRefreshParameters -dWorldSetAngularDamping -dWorldSetAngularDampingThreshold -dWorldSetAutoDisableAngularThreshold -dWorldSetAutoDisableAverageSamplesCount -dWorldSetAutoDisableFlag -dWorldSetAutoDisableLinearThreshold -dWorldSetAutoDisableSteps -dWorldSetAutoDisableTime -dWorldSetCFM -dWorldSetContactMaxCorrectingVel -dWorldSetContactSurfaceLayer -dWorldSetDamping -dWorldSetERP -dWorldSetGravity -dWorldSetLinearDamping -dWorldSetLinearDampingThreshold -dWorldSetMaxAngularSpeed -dWorldSetQuickStepNumIterations -dWorldSetQuickStepW -dWorldSetStepMemoryManager -dWorldSetStepMemoryReservationPolicy -dWorldStep -dWorldStepAndSpaceCollide -dWorldUseSharedWorkingMemory From 653dd4a4bd1b283769e6711dcd681014e9777b13 Mon Sep 17 00:00:00 2001 From: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> Date: Mon, 14 Jul 2025 01:46:21 -0700 Subject: [PATCH 10/16] Reset `WbFieldRef->last_update` After Simulation Reset (#6758) * send C_SUPERVISOR_SIMULATION_RESET when simulation is reset * reset field->last_update on reset * add test * fix WbFieldRef type * correctly set translation in world * fix string comparison * set different robot name * search for correct message type * fix assertion messages * fix initial assertion * fix test * move message id * add comment * update changelog * use WbFieldRef instead of WbFieldStruct* * formatting * use code block * remove old C_SUPERVISOR_SIMULATION_RESET definition Co-authored-by: Olivier Michel * update test world header --------- Co-authored-by: Olivier Michel --- docs/reference/changelog-r2025.md | 1 + src/controller/c/messages.h | 2 +- src/controller/c/supervisor.c | 9 +++ .../nodes/utils/WbSupervisorUtilities.cpp | 12 ++++ .../nodes/utils/WbSupervisorUtilities.hpp | 2 + .../.gitignore | 1 + .../Makefile | 25 +++++++++ .../supervisor_reset_simulation_fields.c | 56 +++++++++++++++++++ .../supervisor_reset_simulation_fields.wbt | 53 ++++++++++++++++++ 9 files changed, 160 insertions(+), 1 deletion(-) create mode 100644 tests/api/controllers/supervisor_reset_simulation_fields/.gitignore create mode 100644 tests/api/controllers/supervisor_reset_simulation_fields/Makefile create mode 100644 tests/api/controllers/supervisor_reset_simulation_fields/supervisor_reset_simulation_fields.c create mode 100644 tests/api/worlds/supervisor_reset_simulation_fields.wbt diff --git a/docs/reference/changelog-r2025.md b/docs/reference/changelog-r2025.md index 3c1bb676478..53bd90b58ae 100644 --- a/docs/reference/changelog-r2025.md +++ b/docs/reference/changelog-r2025.md @@ -10,6 +10,7 @@ - Fixed a bug preventing the `webots-controller` executable from running on arm-based mac devices ([#6806](https://github.com/cyberbotics/webots/pull/6806)). - Fixed a bug causing Webots to crash when multiple sounds were used with a [Speaker](speaker.md) node ([#6843](https://github.com/cyberbotics/webots/pull/6843)). - Fixed a bug causing the "Reload/Reset" buttons in the controller recompilation popup to not work on Windows ([#6844](https://github.com/cyberbotics/webots/pull/6844)). + - Fixed a bug causing supervisors to occasionally read stale field values after the simulation was reset ([#6758](https://github.com/cyberbotics/webots/pull/6758)). - Fixed a bug causing Webots to occasionally crash when unloading a world ([#6857](https://github.com/cyberbotics/webots/pull/6857)). ## Webots R2025a diff --git a/src/controller/c/messages.h b/src/controller/c/messages.h index 4eddad84b65..5c52ebc0625 100644 --- a/src/controller/c/messages.h +++ b/src/controller/c/messages.h @@ -75,7 +75,6 @@ #define C_SUPERVISOR_RELOAD_WORLD 52 #define C_SUPERVISOR_SET_LABEL 53 #define C_SUPERVISOR_SIMULATION_QUIT 54 -#define C_SUPERVISOR_SIMULATION_RESET 55 #define C_SUPERVISOR_SIMULATION_CHANGE_MODE 56 #define C_SUPERVISOR_SIMULATION_RESET_PHYSICS 57 #define C_SUPERVISOR_START_MOVIE 58 @@ -101,6 +100,7 @@ #define C_SUPERVISOR_NODE_GET_PROTO 78 // ctr <-> sim +#define C_SUPERVISOR_SIMULATION_RESET 55 #define C_ROBOT_WAIT_FOR_USER_INPUT_EVENT 80 #define C_ROBOT_WWI_MESSAGE 81 #define C_SUPERVISOR_SAVE_WORLD 82 diff --git a/src/controller/c/supervisor.c b/src/controller/c/supervisor.c index f18d19ece53..0985d171a84 100644 --- a/src/controller/c/supervisor.c +++ b/src/controller/c/supervisor.c @@ -1295,6 +1295,15 @@ static void supervisor_read_answer(WbDevice *d, WbRequest *r) { case C_SUPERVISOR_MOVIE_STATUS: movie_status = request_read_uchar(r); break; + case C_SUPERVISOR_SIMULATION_RESET: { + // Clear cached field values + WbFieldStruct *field = field_list; + while (field) { + field->last_update = -DBL_MAX; + field = field->next; + } + break; + } case C_SUPERVISOR_SAVE_WORLD: save_status = request_read_uchar(r); break; diff --git a/src/webots/nodes/utils/WbSupervisorUtilities.cpp b/src/webots/nodes/utils/WbSupervisorUtilities.cpp index 852f02a4cfc..16c96bd7aad 100644 --- a/src/webots/nodes/utils/WbSupervisorUtilities.cpp +++ b/src/webots/nodes/utils/WbSupervisorUtilities.cpp @@ -280,6 +280,7 @@ WbSupervisorUtilities::WbSupervisorUtilities(WbRobot *robot) : mRobot(robot) { // otherwise, conflicts can occur in case of multiple controllers connect(this, &WbSupervisorUtilities::changeSimulationModeRequested, this, &WbSupervisorUtilities::changeSimulationMode, Qt::QueuedConnection); + connect(WbWorld::instance(), &WbWorld::resetRequested, this, &WbSupervisorUtilities::simulationReset, Qt::QueuedConnection); } WbSupervisorUtilities::~WbSupervisorUtilities() { @@ -343,6 +344,7 @@ void WbSupervisorUtilities::initControllerRequests() { mNodesDeletedSinceLastStep.clear(); mUpdatedFields.clear(); mWatchedFields.clear(); + mSimulationReset = false; } QString WbSupervisorUtilities::readString(QDataStream &stream) { @@ -2347,6 +2349,11 @@ void WbSupervisorUtilities::writeAnswer(WbDataStream &stream) { } mVirtualRealityHeadsetOrientationRequested = false; } + if (mSimulationReset) { + stream << (short unsigned int)0; + stream << (unsigned char)C_SUPERVISOR_SIMULATION_RESET; + mSimulationReset = false; + } } void WbSupervisorUtilities::writeConfigure(WbDataStream &stream) { @@ -2419,3 +2426,8 @@ QString WbSupervisorUtilities::createLabelUpdateString(const WbWrenLabelOverlay .arg(y) .arg(text.replace("\n", "\\n")); } + +void WbSupervisorUtilities::simulationReset(bool restartControllers) { + if (!restartControllers) // If the controller is about to be restarted, there's no need to tell it to reset its own state + mSimulationReset = true; +} diff --git a/src/webots/nodes/utils/WbSupervisorUtilities.hpp b/src/webots/nodes/utils/WbSupervisorUtilities.hpp index 0614c364c2d..eb89bca4b5f 100644 --- a/src/webots/nodes/utils/WbSupervisorUtilities.hpp +++ b/src/webots/nodes/utils/WbSupervisorUtilities.hpp @@ -73,6 +73,7 @@ private slots: void removeTrackedContactPoints(QObject *obj); void removeTrackedPoseNode(QObject *obj); void removeTrackedField(QObject *obj); + void simulationReset(bool restartControllers); private: WbRobot *mRobot; @@ -111,6 +112,7 @@ private slots: bool mNodeExportStringRequest; bool mIsProtoRegenerated; bool mShouldRemoveNode; + bool mSimulationReset; // pointer to a single integer: if not NULL, the new status has to be sent to the libController int *mAnimationStartStatus; diff --git a/tests/api/controllers/supervisor_reset_simulation_fields/.gitignore b/tests/api/controllers/supervisor_reset_simulation_fields/.gitignore new file mode 100644 index 00000000000..18e0edccdb6 --- /dev/null +++ b/tests/api/controllers/supervisor_reset_simulation_fields/.gitignore @@ -0,0 +1 @@ +/supervisor_reset_simulation_fields diff --git a/tests/api/controllers/supervisor_reset_simulation_fields/Makefile b/tests/api/controllers/supervisor_reset_simulation_fields/Makefile new file mode 100644 index 00000000000..137d83b4e39 --- /dev/null +++ b/tests/api/controllers/supervisor_reset_simulation_fields/Makefile @@ -0,0 +1,25 @@ +# Copyright 1996-2023 Cyberbotics Ltd. +# +# 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 +# +# https://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. + +# Webots Makefile system +# +# You may add some variable definitions hereafter to customize the build process +# See documentation in $(WEBOTS_HOME_PATH)/resources/Makefile.include + + +# Do not modify the following: this includes Webots global Makefile.include +null := +space := $(null) $(null) +WEBOTS_HOME_PATH?=$(subst $(space),\ ,$(strip $(subst \,/,$(WEBOTS_HOME)))) +include $(WEBOTS_HOME_PATH)/resources/Makefile.include diff --git a/tests/api/controllers/supervisor_reset_simulation_fields/supervisor_reset_simulation_fields.c b/tests/api/controllers/supervisor_reset_simulation_fields/supervisor_reset_simulation_fields.c new file mode 100644 index 00000000000..0763ce855ea --- /dev/null +++ b/tests/api/controllers/supervisor_reset_simulation_fields/supervisor_reset_simulation_fields.c @@ -0,0 +1,56 @@ +/* + * Description: Test Supervisor device API + * This file contains tests of reset simulation method + */ + +#include +#include + +#include "../../../lib/ts_assertion.h" +#include "../../../lib/ts_utils.h" + +#define TIME_STEP 32 + +int main(int argc, char **argv) { + ts_setup(argv[1]); + + const double initial_translation[3] = {0, 0, 1}; + const double new_translation[3] = {1, 0, 0}; + WbFieldRef translation_field = wb_supervisor_node_get_field(wb_supervisor_node_get_from_def("SOLID"), "translation"); + if (strcmp(argv[1], "supervisor_reset_simulation_fields_resetter") == 0) { + wb_robot_step(TIME_STEP); + wb_robot_step(TIME_STEP); + + // + + wb_robot_step(TIME_STEP); + wb_supervisor_simulation_reset(); + wb_robot_step(TIME_STEP); // We have to wait another step or else the reset will overwrite the new value + wb_supervisor_field_set_sf_vec3f(translation_field, new_translation); + } else { + wb_robot_step(TIME_STEP); + wb_robot_step(TIME_STEP); + const double *first_translation = wb_supervisor_field_get_sf_vec3f(translation_field); + ts_assert_vec3_equal( + first_translation[0], first_translation[1], first_translation[2], initial_translation[0], initial_translation[1], + initial_translation[2], "SOLID's initial position should be [%f, %f, %f] not [%f, %f, %f]", initial_translation[0], + initial_translation[1], initial_translation[2], first_translation[0], first_translation[1], first_translation[2]); + wb_robot_step(TIME_STEP); + + // + + wb_robot_step(TIME_STEP); + + // + + wb_robot_step(TIME_STEP); + const double *second_translation = wb_supervisor_field_get_sf_vec3f(translation_field); + ts_assert_vec3_equal( + second_translation[0], second_translation[1], second_translation[2], new_translation[0], new_translation[1], + new_translation[2], "SOLID's position should be [%f, %f, %f] not [%f, %f, %f] after reset", new_translation[0], + new_translation[1], new_translation[2], second_translation[0], second_translation[1], second_translation[2]); + } + + ts_send_success(); + return EXIT_SUCCESS; +} diff --git a/tests/api/worlds/supervisor_reset_simulation_fields.wbt b/tests/api/worlds/supervisor_reset_simulation_fields.wbt new file mode 100644 index 00000000000..04338a4a7a5 --- /dev/null +++ b/tests/api/worlds/supervisor_reset_simulation_fields.wbt @@ -0,0 +1,53 @@ +#VRML_SIM R2025a utf8 + +EXTERNPROTO "webots://tests/default/protos/TestSuiteSupervisor.proto" +EXTERNPROTO "webots://tests/default/protos/TestSuiteEmitter.proto" + +WorldInfo { + info [ + "Test that fields do not return stale values after reset" + ] + basicTimeStep 8 + coordinateSystem "NUE" +} +Viewpoint { + orientation 0.3011392881427894 -0.8944857953945254 -0.3304698034227591 4.845225060401701 + position 8.056890161252701 5.15602094221405 0.024334960209242112 +} +Background { + skyColor [ + 0 0 1 + ] +} +DirectionalLight { + direction 0 -1 0 +} +DEF SOLID Solid { + translation 0 0 1 +} +TestSuiteSupervisor { +} +Robot { + controller "supervisor_reset_simulation_fields" + controllerArgs [ + "supervisor_reset_simulation_fields_checker" + ] + children [ + TestSuiteEmitter { + } + ] + name "checker robot" + supervisor TRUE +} +Robot { + controller "supervisor_reset_simulation_fields" + controllerArgs [ + "supervisor_reset_simulation_fields_resetter" + ] + children [ + TestSuiteEmitter { + } + ] + name "receiver robot" + supervisor TRUE +} From f531fb5c1b37c05b2f1543b8181547dab6b8a8c7 Mon Sep 17 00:00:00 2001 From: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> Date: Mon, 14 Jul 2025 01:58:38 -0700 Subject: [PATCH 11/16] Add Missing MATLAB Function Implementations (#6756) * add missing MATLAB functions * update changelog * remove test exclusions for the new functions --- docs/reference/changelog-r2025.md | 1 + lib/controller/matlab/.gitignore | 2 ++ src/controller/matlab/mgenerate.py | 2 ++ tests/sources/test_matlab_functions.py | 4 ---- 4 files changed, 5 insertions(+), 4 deletions(-) diff --git a/docs/reference/changelog-r2025.md b/docs/reference/changelog-r2025.md index 53bd90b58ae..91905c17870 100644 --- a/docs/reference/changelog-r2025.md +++ b/docs/reference/changelog-r2025.md @@ -2,6 +2,7 @@ ## Webots R2025b - Enhancements + - Added implementations of `wbu_system_tmpdir` and `wbu_system_webots_instance_path` to the MATLAB API ([#6756](https://github.com/cyberbotics/webots/pull/6756)). - Added missing import libraries on Windows ([#6753](https://github.com/cyberbotics/webots/pull/6753)). - Added some missing function definitions to the existing Windows libraries ([#6753](https://github.com/cyberbotics/webots/pull/6753)). - Cleanup diff --git a/lib/controller/matlab/.gitignore b/lib/controller/matlab/.gitignore index 36b5024c07a..a6dfc4109cd 100644 --- a/lib/controller/matlab/.gitignore +++ b/lib/controller/matlab/.gitignore @@ -371,6 +371,8 @@ wbu_motion_set_time.m wbu_motion_stop.m wbu_system_getenv.m wbu_system_short_path.m +wbu_system_tmpdir.m +wbu_system_webots_instance_path.m WB_STDOUT.m WB_STDERR.m WB_CHANNEL_BROADCAST.m diff --git a/src/controller/matlab/mgenerate.py b/src/controller/matlab/mgenerate.py index ffa3a213e6c..3a6e552a277 100755 --- a/src/controller/matlab/mgenerate.py +++ b/src/controller/matlab/mgenerate.py @@ -618,6 +618,8 @@ def main(args=None): # utils/system.h generator.gen(FUNC, "wbu_system_getenv(variable)") generator.gen(FUNC, "wbu_system_short_path(path)") + generator.gen(FUNC, "wbu_system_tmpdir()") + generator.gen(FUNC, "wbu_system_webots_instance_path(refresh)") # constants generator.gen_const("WB_STDOUT", "1") diff --git a/tests/sources/test_matlab_functions.py b/tests/sources/test_matlab_functions.py index 4b65b4d2544..cb3c7fa9ab3 100644 --- a/tests/sources/test_matlab_functions.py +++ b/tests/sources/test_matlab_functions.py @@ -64,10 +64,6 @@ def setUp(self): 'wb_device_get_type', # Deprecated since 8.0.0 'wb_node_get_name', # C API Only - - # Not Yet Implemented - 'wbu_system_tmpdir', - 'wbu_system_webots_instance_path', ] self.functions = [] From ec04f7e34e5e2b964e72b1fadd3d508d87ae70e8 Mon Sep 17 00:00:00 2001 From: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> Date: Mon, 14 Jul 2025 02:12:24 -0700 Subject: [PATCH 12/16] Rework Resource Handling in Node Exports (#6856) * unify existing export code * add simplified normal use case helper * cleanup existing export methods * prevent duplicate exports * add export support for resources that don't already have it * remove old url resolution code * revert extraneous WbURL changes * restore comment * use WbNode helpers in WbBackground * fix WbTrackWheel if-condition * run clang-format * update the changelog * use const reference in WbNode::exportResource * fix bad merge --- docs/reference/changelog-r2025.md | 4 ++ src/webots/nodes/WbBackground.cpp | 48 +++++++---------- src/webots/nodes/WbBackground.hpp | 1 + src/webots/nodes/WbCadShape.cpp | 39 ++++++-------- src/webots/nodes/WbCadShape.hpp | 1 + src/webots/nodes/WbCamera.cpp | 12 +++++ src/webots/nodes/WbCamera.hpp | 2 + src/webots/nodes/WbContactProperties.cpp | 14 +++++ src/webots/nodes/WbContactProperties.hpp | 4 ++ src/webots/nodes/WbImageTexture.cpp | 27 +++------- src/webots/nodes/WbImageTexture.hpp | 1 + src/webots/nodes/WbMesh.cpp | 30 +++-------- src/webots/nodes/WbMesh.hpp | 1 + src/webots/nodes/WbMotor.cpp | 12 +++++ src/webots/nodes/WbMotor.hpp | 3 ++ src/webots/nodes/WbSkin.cpp | 12 +++++ src/webots/nodes/WbSkin.hpp | 4 ++ src/webots/nodes/WbTrackWheel.cpp | 7 ++- src/webots/scene_tree/WbSceneTree.cpp | 14 ----- src/webots/vrml/WbNode.cpp | 67 +++++++++++++++++++++++- src/webots/vrml/WbNode.hpp | 12 +++++ src/webots/vrml/WbUrl.cpp | 33 +++--------- src/webots/vrml/WbUrl.hpp | 4 +- src/webots/vrml/WbWriter.hpp | 1 + 24 files changed, 210 insertions(+), 143 deletions(-) diff --git a/docs/reference/changelog-r2025.md b/docs/reference/changelog-r2025.md index 91905c17870..0c73537266a 100644 --- a/docs/reference/changelog-r2025.md +++ b/docs/reference/changelog-r2025.md @@ -2,6 +2,7 @@ ## Webots R2025b - Enhancements + - `WbCamera`, `WbContactProperties`, `WbMotor`, and `WbSkin` will now locally-download their resources if-necessary (like other nodes) when steaming or exporting to `w3d` ([#6856](https://github.com/cyberbotics/webots/pull/6856)). - Added implementations of `wbu_system_tmpdir` and `wbu_system_webots_instance_path` to the MATLAB API ([#6756](https://github.com/cyberbotics/webots/pull/6756)). - Added missing import libraries on Windows ([#6753](https://github.com/cyberbotics/webots/pull/6753)). - Added some missing function definitions to the existing Windows libraries ([#6753](https://github.com/cyberbotics/webots/pull/6753)). @@ -11,6 +12,9 @@ - Fixed a bug preventing the `webots-controller` executable from running on arm-based mac devices ([#6806](https://github.com/cyberbotics/webots/pull/6806)). - Fixed a bug causing Webots to crash when multiple sounds were used with a [Speaker](speaker.md) node ([#6843](https://github.com/cyberbotics/webots/pull/6843)). - Fixed a bug causing the "Reload/Reset" buttons in the controller recompilation popup to not work on Windows ([#6844](https://github.com/cyberbotics/webots/pull/6844)). + - Fixed resolution of relative paths when converting protos to their base nodes ([#6856](https://github.com/cyberbotics/webots/pull/6856)). + - **As a result of this change, relative paths that are not within a Webots-recognized resource field (ex. `url`) will no longer be updated when a proto is converted to its base nodes.** This should not affect most users. + - Fixed a bug causing `TrackWheel` nodes to lose their field values when used in a proto converted to a base node ([#6856](https://github.com/cyberbotics/webots/pull/6856)). - Fixed a bug causing supervisors to occasionally read stale field values after the simulation was reset ([#6758](https://github.com/cyberbotics/webots/pull/6758)). - Fixed a bug causing Webots to occasionally crash when unloading a world ([#6857](https://github.com/cyberbotics/webots/pull/6857)). diff --git a/src/webots/nodes/WbBackground.cpp b/src/webots/nodes/WbBackground.cpp index 6b445a25665..e623cb0f79b 100644 --- a/src/webots/nodes/WbBackground.cpp +++ b/src/webots/nodes/WbBackground.cpp @@ -679,10 +679,7 @@ WbRgb WbBackground::skyColor() const { } void WbBackground::exportNodeFields(WbWriter &writer) const { - if (writer.isWebots()) { - WbBaseNode::exportNodeFields(writer); - return; - } + WbBaseNode::exportNodeFields(writer); if (writer.isW3d()) { QString backgroundFileNames[6]; @@ -690,18 +687,8 @@ void WbBackground::exportNodeFields(WbWriter &writer) const { if (mUrlFields[i]->size() == 0) continue; - WbField urlFieldCopy(*findField(gUrlNames(i), true)); - const QString &imagePath = WbUrl::computePath(this, gUrlNames(i), mUrlFields[i]->item(0)); - if (WbUrl::isLocalUrl(imagePath)) - backgroundFileNames[i] = WbUrl::computeLocalAssetUrl(imagePath, writer.isW3d()); - else if (WbUrl::isWeb(imagePath)) - backgroundFileNames[i] = imagePath; - else { - if (writer.isWritingToFile()) - backgroundFileNames[i] = WbUrl::exportResource(this, imagePath, imagePath, writer.relativeTexturesPath(), writer); - else - backgroundFileNames[i] = WbUrl::expressRelativeToWorld(imagePath); - } + const QString &resolvedURL = WbUrl::computePath(this, gUrlNames(i), mUrlFields[i], 0); + backgroundFileNames[i] = exportResource(mUrlFields[i]->item(0), resolvedURL, writer.relativeTexturesPath(), writer); } QString irradianceFileNames[6]; @@ -709,18 +696,9 @@ void WbBackground::exportNodeFields(WbWriter &writer) const { if (mIrradianceUrlFields[i]->size() == 0) continue; - const QString &irradiancePath = WbUrl::computePath(this, gIrradianceUrlNames(i), mIrradianceUrlFields[i]->item(0)); - if (WbUrl::isLocalUrl(irradiancePath)) - irradianceFileNames[i] = WbUrl::computeLocalAssetUrl(irradiancePath, writer.isW3d()); - else if (WbUrl::isWeb(irradiancePath)) - irradianceFileNames[i] = irradiancePath; - else { - if (writer.isWritingToFile()) - irradianceFileNames[i] = - WbUrl::exportResource(this, irradiancePath, irradiancePath, writer.relativeTexturesPath(), writer); - else - irradianceFileNames[i] = WbUrl::expressRelativeToWorld(irradiancePath); - } + const QString &resolvedURL = WbUrl::computePath(this, gIrradianceUrlNames(i), mIrradianceUrlFields[i], 0); + irradianceFileNames[i] = + exportResource(mIrradianceUrlFields[i]->item(0), resolvedURL, writer.relativeTexturesPath(), writer); } writer << " "; @@ -730,7 +708,19 @@ void WbBackground::exportNodeFields(WbWriter &writer) const { if (!irradianceFileNames[i].isEmpty()) writer << gIrradianceUrlNames(i) << "='\"" << irradianceFileNames[i] << "\"' "; } + } else { + for (int i = 0; i < 6; ++i) { + exportMFResourceField(gUrlNames(i), mUrlFields[i], writer.relativeTexturesPath(), writer); + exportMFResourceField(gIrradianceUrlNames(i), mIrradianceUrlFields[i], writer.relativeTexturesPath(), writer); + } } +} - WbBaseNode::exportNodeFields(writer); +QStringList WbBackground::customExportedFields() const { + QStringList fields; + for (int i = 0; i < 6; ++i) { + fields << gUrlNames(i); + fields << gIrradianceUrlNames(i); + } + return fields; } diff --git a/src/webots/nodes/WbBackground.hpp b/src/webots/nodes/WbBackground.hpp index a90c9ad4b1b..c6340596215 100644 --- a/src/webots/nodes/WbBackground.hpp +++ b/src/webots/nodes/WbBackground.hpp @@ -59,6 +59,7 @@ class WbBackground : public WbBaseNode { protected: void exportNodeFields(WbWriter &writer) const override; + QStringList customExportedFields() const override; private: static QList cBackgroundList; diff --git a/src/webots/nodes/WbCadShape.cpp b/src/webots/nodes/WbCadShape.cpp index aad3201001d..9b5b4dbd2a3 100644 --- a/src/webots/nodes/WbCadShape.cpp +++ b/src/webots/nodes/WbCadShape.cpp @@ -568,46 +568,31 @@ const WbVector3 WbCadShape::absoluteScale() const { } void WbCadShape::exportNodeFields(WbWriter &writer) const { - if (!(writer.isW3d() || writer.isProto())) - return; + WbBaseNode::exportNodeFields(writer); if (mUrl->size() == 0) return; - WbBaseNode::exportNodeFields(writer); + if (!(writer.isW3d() || writer.isProto())) { + findField("url", true)->write(writer); + return; + } // export model WbField urlFieldCopy(*findField("url", true)); for (int i = 0; i < mUrl->size(); ++i) { - const QString &completeUrl = WbUrl::computePath(this, "url", mUrl, i); + const QString &resolvedURL = WbUrl::computePath(this, "url", mUrl, i); WbMFString *urlFieldValue = dynamic_cast(urlFieldCopy.value()); - if (WbUrl::isLocalUrl(completeUrl)) - urlFieldValue->setItem(i, WbUrl::computeLocalAssetUrl(completeUrl, writer.isW3d())); - else if (WbUrl::isWeb(completeUrl)) - urlFieldValue->setItem(i, completeUrl); - else { - urlFieldValue->setItem( - i, writer.isWritingToFile() ? WbUrl::exportMesh(this, mUrl, i, writer) : WbUrl::expressRelativeToWorld(completeUrl)); - } + urlFieldValue->setItem(i, exportResource(mUrl->item(i), resolvedURL, writer.relativeMeshesPath(), writer)); } // export materials if (writer.isW3d()) { // only needs to be included in the w3d, when converting to base node it shouldn't be included - const QString &parentUrl = WbUrl::computePath(this, "url", mUrl->item(0)); + const QString &parentUrl = WbUrl::computePath(this, "url", mUrl, 0); for (const QString &material : objMaterialList(parentUrl)) { QString materialUrl = WbUrl::combinePaths(material, parentUrl); WbMFString *urlFieldValue = dynamic_cast(urlFieldCopy.value()); - if (WbUrl::isLocalUrl(materialUrl)) - urlFieldValue->addItem(WbUrl::computeLocalAssetUrl(materialUrl, writer.isW3d())); - else if (WbUrl::isWeb(materialUrl)) - urlFieldValue->addItem(materialUrl); - else { - if (writer.isWritingToFile()) - urlFieldValue->addItem( - WbUrl::exportResource(this, materialUrl, materialUrl, writer.relativeMeshesPath(), writer, false)); - else - urlFieldValue->addItem(WbUrl::expressRelativeToWorld(materialUrl)); - } + urlFieldValue->addItem(exportResource(material, materialUrl, writer.relativeMeshesPath(), writer)); } } @@ -618,6 +603,12 @@ void WbCadShape::exportNodeFields(WbWriter &writer) const { urlFieldCopy.write(writer); } +QStringList WbCadShape::customExportedFields() const { + QStringList fields; + fields << "url"; + return fields; +} + QString WbCadShape::cadPath() const { return WbUrl::computePath(this, "url", mUrl, 0); } diff --git a/src/webots/nodes/WbCadShape.hpp b/src/webots/nodes/WbCadShape.hpp index fd02124b011..924f4556541 100644 --- a/src/webots/nodes/WbCadShape.hpp +++ b/src/webots/nodes/WbCadShape.hpp @@ -56,6 +56,7 @@ class WbCadShape : public WbBaseNode { protected: void exportNodeFields(WbWriter &writer) const override; + QStringList customExportedFields() const override; WbBoundingSphere *boundingSphere() const override { return mBoundingSphere; } void recomputeBoundingSphere() const; diff --git a/src/webots/nodes/WbCamera.cpp b/src/webots/nodes/WbCamera.cpp index 63133128695..eaeb1384fb0 100644 --- a/src/webots/nodes/WbCamera.cpp +++ b/src/webots/nodes/WbCamera.cpp @@ -1017,6 +1017,18 @@ WbVector3 WbCamera::urdfRotation(const WbMatrix3 &rotationMatrix) const { return eulerRotation; } +void WbCamera::exportNodeFields(WbWriter &writer) const { + WbAbstractCamera::exportNodeFields(writer); + + exportSFResourceField("noiseMaskUrl", mNoiseMaskUrl, writer.relativeMeshesPath(), writer); +} + +QStringList WbCamera::customExportedFields() const { + QStringList fields; + fields << "noiseMaskUrl"; + return fields; +} + ///////////////////// // Update methods // ///////////////////// diff --git a/src/webots/nodes/WbCamera.hpp b/src/webots/nodes/WbCamera.hpp index 456a6c09ca2..b3086d5f32e 100644 --- a/src/webots/nodes/WbCamera.hpp +++ b/src/webots/nodes/WbCamera.hpp @@ -67,6 +67,8 @@ class WbCamera : public WbAbstractCamera { void setup() override; void render() override; bool needToRender() const override; + void exportNodeFields(WbWriter &writer) const override; + QStringList customExportedFields() const override; private: WbSFNode *mFocus; diff --git a/src/webots/nodes/WbContactProperties.cpp b/src/webots/nodes/WbContactProperties.cpp index d179d00b829..b5a7fa07e9c 100644 --- a/src/webots/nodes/WbContactProperties.cpp +++ b/src/webots/nodes/WbContactProperties.cpp @@ -121,6 +121,20 @@ void WbContactProperties::postFinalize() { connect(mMaxContactJoints, &WbSFInt::changed, this, &WbContactProperties::updateMaxContactJoints); } +void WbContactProperties::exportNodeFields(WbWriter &writer) const { + WbBaseNode::exportNodeFields(writer); + + exportSFResourceField(gUrlNames[0], mBumpSound, writer.relativeSoundsPath(), writer); + exportSFResourceField(gUrlNames[1], mRollSound, writer.relativeSoundsPath(), writer); + exportSFResourceField(gUrlNames[2], mSlideSound, writer.relativeSoundsPath(), writer); +} + +QStringList WbContactProperties::customExportedFields() const { + QStringList fields; + fields << "url"; + return fields; +} + void WbContactProperties::updateCoulombFriction() { const int nbElements = mCoulombFriction->size(); if (nbElements < 1 || nbElements > 4) { diff --git a/src/webots/nodes/WbContactProperties.hpp b/src/webots/nodes/WbContactProperties.hpp index 10b9386e41c..a3dce99978f 100644 --- a/src/webots/nodes/WbContactProperties.hpp +++ b/src/webots/nodes/WbContactProperties.hpp @@ -64,6 +64,10 @@ class WbContactProperties : public WbBaseNode { void valuesChanged(); void needToEnableBodies(); +protected: + void exportNodeFields(WbWriter &writer) const override; + QStringList customExportedFields() const override; + private: // user accessible fields WbSFString *mMaterial1; diff --git a/src/webots/nodes/WbImageTexture.cpp b/src/webots/nodes/WbImageTexture.cpp index be09007f51c..026f5da5e3a 100644 --- a/src/webots/nodes/WbImageTexture.cpp +++ b/src/webots/nodes/WbImageTexture.cpp @@ -528,24 +528,7 @@ bool WbImageTexture::exportNodeHeader(WbWriter &writer) const { void WbImageTexture::exportNodeFields(WbWriter &writer) const { WbBaseNode::exportNodeFields(writer); - // export to ./textures folder relative to writer path - WbField urlFieldCopy(*findField("url", true)); - for (int i = 0; i < mUrl->size(); ++i) { - QString completeUrl = WbUrl::computePath(this, "url", mUrl, i); - WbMFString *urlFieldValue = dynamic_cast(urlFieldCopy.value()); - if (WbUrl::isLocalUrl(completeUrl)) - urlFieldValue->setItem(i, WbUrl::computeLocalAssetUrl(completeUrl, writer.isW3d())); - else if (WbUrl::isWeb(completeUrl)) - urlFieldValue->setItem(i, completeUrl); - else { - if (writer.isWritingToFile()) - urlFieldValue->setItem(i, WbUrl::exportTexture(this, mUrl, i, writer)); - else - urlFieldValue->setItem(i, WbUrl::expressRelativeToWorld(completeUrl)); - } - } - - urlFieldCopy.write(writer); + exportMFResourceField("url", mUrl, writer.relativeTexturesPath(), writer); if (writer.isW3d()) { if (!mRole.isEmpty()) @@ -553,6 +536,12 @@ void WbImageTexture::exportNodeFields(WbWriter &writer) const { } } +QStringList WbImageTexture::customExportedFields() const { + QStringList fields; + fields << "url"; + return fields; +} + void WbImageTexture::exportShallowNode(const WbWriter &writer) const { if (!writer.isW3d() || mUrl->size() == 0) return; @@ -560,7 +549,7 @@ void WbImageTexture::exportShallowNode(const WbWriter &writer) const { // note: the texture of the shallow nodes needs to be exported only if the URL is locally defined but not of type // 'webots://' since this case would be converted to a remote one that targets the current branch if (!WbUrl::isWeb(mUrl->item(0)) && !WbUrl::isLocalUrl(mUrl->item(0)) && !WbWorld::isW3dStreaming()) - WbUrl::exportTexture(this, mUrl, 0, writer); + WbUrl::exportResource(this, mUrl->item(0), WbUrl::computePath(this, "url", mUrl, 0), writer.relativeTexturesPath(), writer); } QStringList WbImageTexture::fieldsToSynchronizeWithW3d() const { diff --git a/src/webots/nodes/WbImageTexture.hpp b/src/webots/nodes/WbImageTexture.hpp index 04bbde70135..b68e81e0073 100644 --- a/src/webots/nodes/WbImageTexture.hpp +++ b/src/webots/nodes/WbImageTexture.hpp @@ -80,6 +80,7 @@ class WbImageTexture : public WbBaseNode { protected: bool exportNodeHeader(WbWriter &writer) const override; void exportNodeFields(WbWriter &writer) const override; + QStringList customExportedFields() const override; private: // user accessible fields diff --git a/src/webots/nodes/WbMesh.cpp b/src/webots/nodes/WbMesh.cpp index f2cc552c65d..0d6623d5f10 100644 --- a/src/webots/nodes/WbMesh.cpp +++ b/src/webots/nodes/WbMesh.cpp @@ -401,31 +401,15 @@ void WbMesh::updateMaterialIndex() { } void WbMesh::exportNodeFields(WbWriter &writer) const { - if (!(writer.isW3d() || writer.isProto())) - return; - - if (mUrl->size() == 0) - return; - - WbField urlFieldCopy(*findField("url", true)); - for (int i = 0; i < mUrl->size(); ++i) { - const QString &completeUrl = WbUrl::computePath(this, "url", mUrl, i); - WbMFString *urlFieldValue = dynamic_cast(urlFieldCopy.value()); - if (WbUrl::isLocalUrl(completeUrl)) - urlFieldValue->setItem(i, WbUrl::computeLocalAssetUrl(completeUrl, writer.isW3d())); - else if (WbUrl::isWeb(completeUrl)) - urlFieldValue->setItem(i, completeUrl); - else { - if (writer.isWritingToFile()) - urlFieldValue->setItem(i, WbUrl::exportMesh(this, mUrl, i, writer)); - else - urlFieldValue->setItem(i, WbUrl::expressRelativeToWorld(completeUrl)); - } - } + WbGeometry::exportNodeFields(writer); - urlFieldCopy.write(writer); + exportMFResourceField("url", mUrl, writer.relativeMeshesPath(), writer); +} - WbGeometry::exportNodeFields(writer); +QStringList WbMesh::customExportedFields() const { + QStringList fields; + fields << "url"; + return fields; } QStringList WbMesh::fieldsToSynchronizeWithW3d() const { diff --git a/src/webots/nodes/WbMesh.hpp b/src/webots/nodes/WbMesh.hpp index 2de1cdf027b..67acd664b05 100644 --- a/src/webots/nodes/WbMesh.hpp +++ b/src/webots/nodes/WbMesh.hpp @@ -48,6 +48,7 @@ class WbMesh : public WbTriangleMeshGeometry { protected: void exportNodeFields(WbWriter &writer) const override; + QStringList customExportedFields() const override; private: // user accessible fields diff --git a/src/webots/nodes/WbMotor.cpp b/src/webots/nodes/WbMotor.cpp index d5b0dcfe4d0..19cfe3b2385 100644 --- a/src/webots/nodes/WbMotor.cpp +++ b/src/webots/nodes/WbMotor.cpp @@ -853,3 +853,15 @@ QList WbMotor::findClosestDescendantNodesWithDedicatedWrenNo list << static_cast(it.next()); return list; } + +void WbMotor::exportNodeFields(WbWriter &writer) const { + WbJointDevice::exportNodeFields(writer); + + exportSFResourceField("sound", mSound, writer.relativeSoundsPath(), writer); +} + +QStringList WbMotor::customExportedFields() const { + QStringList fields; + fields << "sound"; + return fields; +} diff --git a/src/webots/nodes/WbMotor.hpp b/src/webots/nodes/WbMotor.hpp index 9d7bc97a0c8..48f5452456a 100644 --- a/src/webots/nodes/WbMotor.hpp +++ b/src/webots/nodes/WbMotor.hpp @@ -100,6 +100,9 @@ class WbMotor : public WbJointDevice { void enableMotorFeedback(int rate); virtual double computeFeedback() const = 0; + void exportNodeFields(WbWriter &writer) const override; + QStringList customExportedFields() const override; + protected slots: void updateMaxForceOrTorque(); void updateMinAndMaxPosition(); diff --git a/src/webots/nodes/WbSkin.cpp b/src/webots/nodes/WbSkin.cpp index e8d9be9825b..25a782c8c20 100644 --- a/src/webots/nodes/WbSkin.cpp +++ b/src/webots/nodes/WbSkin.cpp @@ -527,6 +527,18 @@ void WbSkin::reset(const QString &id) { } } +void WbSkin::exportNodeFields(WbWriter &writer) const { + WbBaseNode::exportNodeFields(writer); + + exportSFResourceField("modelUrl", mModelUrl, writer.relativeMeshesPath(), writer); +} + +QStringList WbSkin::customExportedFields() const { + QStringList fields; + fields << "modelUrl"; + return fields; +} + void WbSkin::updateModel() { applyTranslationToWren(); applyRotationToWren(); diff --git a/src/webots/nodes/WbSkin.hpp b/src/webots/nodes/WbSkin.hpp index 340a3a6c506..b39edaef082 100644 --- a/src/webots/nodes/WbSkin.hpp +++ b/src/webots/nodes/WbSkin.hpp @@ -67,6 +67,10 @@ class WbSkin : public WbBaseNode, public WbAbstractPose, public WbDevice { signals: void wrenMaterialChanged(); +protected: + void exportNodeFields(WbWriter &writer) const override; + QStringList customExportedFields() const override; + private: WbSkin &operator=(const WbSkin &); // non copyable WbNode *clone() const override { return new WbSkin(*this); } diff --git a/src/webots/nodes/WbTrackWheel.cpp b/src/webots/nodes/WbTrackWheel.cpp index a6288a6e642..b10e3462766 100644 --- a/src/webots/nodes/WbTrackWheel.cpp +++ b/src/webots/nodes/WbTrackWheel.cpp @@ -106,9 +106,8 @@ QStringList WbTrackWheel::fieldsToSynchronizeWithW3d() const { } void WbTrackWheel::exportNodeFields(WbWriter &writer) const { - if (!writer.isW3d()) - return; - WbBaseNode::exportNodeFields(writer); - writer << " rotation=\'" << mRotation->value() << "\'"; + + if (writer.isW3d()) + writer << " rotation=\'" << mRotation->value() << "\'"; } diff --git a/src/webots/scene_tree/WbSceneTree.cpp b/src/webots/scene_tree/WbSceneTree.cpp index c04698b5306..71765c4def0 100644 --- a/src/webots/scene_tree/WbSceneTree.cpp +++ b/src/webots/scene_tree/WbSceneTree.cpp @@ -750,20 +750,6 @@ void WbSceneTree::convertProtoToBaseNode(bool rootOnly) { writer.setRootNode(NULL); currentNode->write(writer); - // relative urls that get exposed by the conversion need to be changed to remote ones - QRegularExpressionMatchIterator it = WbUrl::vrmlResourceRegex().globalMatch(nodeString); - while (it.hasNext()) { - const QRegularExpressionMatch match = it.next(); - if (match.hasMatch()) { - QString asset = match.captured(0); - asset.replace("\"", ""); - if (!WbUrl::isWeb(asset) && QDir::isRelativePath(asset)) { - QString newUrl = QString("\"%1\"").arg(WbUrl::combinePaths(asset, currentNode->proto()->url())); - nodeString.replace(QString("\"%1\"").arg(asset), newUrl.replace(WbStandardPaths::webotsHomePath(), "webots://")); - } - } - } - const bool skipTemplateRegeneration = WbVrmlNodeUtilities::findUpperTemplateNeedingRegenerationFromField(parentField, parentNode); if (skipTemplateRegeneration) diff --git a/src/webots/vrml/WbNode.cpp b/src/webots/vrml/WbNode.cpp index 5648120bdd9..685e59ee0e4 100644 --- a/src/webots/vrml/WbNode.cpp +++ b/src/webots/vrml/WbNode.cpp @@ -1112,7 +1112,8 @@ void WbNode::exportNodeFields(WbWriter &writer) const { return; foreach (const WbField *f, fields()) { - if (!f->isDeprecated() && ((f->isW3d() || writer.isProto()) && f->singleType() != WB_SF_NODE)) + if (!f->isDeprecated() && ((f->isW3d() || writer.isProto()) && f->singleType() != WB_SF_NODE) && + !customExportedFields().contains(f->name())) f->write(writer); } } @@ -1245,6 +1246,70 @@ void WbNode::writeExport(WbWriter &writer) const { } } +QString WbNode::exportResource(const QString &rawURL, const QString &resolvedURL, const QString &relativeResourcePath, + const WbWriter &writer) const { + if (WbUrl::isLocalUrl(resolvedURL)) + return WbUrl::computeLocalAssetUrl(resolvedURL, writer.isW3d()); + else if (WbUrl::isWeb(resolvedURL)) + return resolvedURL; + else { + if (writer.isWritingToFile()) + return WbUrl::exportResource(this, rawURL, resolvedURL, relativeResourcePath, writer); + else + return WbUrl::expressRelativeToWorld(resolvedURL); + } +} + +void WbNode::exportMFResourceField(const QString &fieldName, const WbMFString *value, const QString &relativeResourcePath, + WbWriter &writer) const { + const WbField *originalField = findField(fieldName, true); + assert(originalField && originalField->type() == WB_MF_STRING); + + // only w3c and proto exports need urls to be resolved + if (!(writer.isW3d() || writer.isProto())) { + originalField->write(writer); + return; + } + + if (value->size() == 0) + return; + + WbField copiedField(*originalField); + WbMFString *newValue = dynamic_cast(copiedField.value()); + + for (int i = 0; i < value->size(); ++i) { + const QString &rawURL = value->item(i); + const QString &resolvedURL = WbUrl::computePath(this, fieldName, rawURL); + newValue->setItem(i, exportResource(rawURL, resolvedURL, relativeResourcePath, writer)); + } + + copiedField.write(writer); +} + +void WbNode::exportSFResourceField(const QString &fieldName, const WbSFString *value, const QString &relativeResourcePath, + WbWriter &writer) const { + const WbField *originalField = findField(fieldName, true); + assert(originalField && originalField->type() == WB_SF_STRING); + + // only w3c and proto exports need urls to be resolved + if (!(writer.isW3d() || writer.isProto())) { + originalField->write(writer); + return; + } + + const QString &rawURL = value->value(); + if (rawURL.isEmpty()) + return; + + WbField copiedField(*originalField); + WbSFString *newValue = dynamic_cast(copiedField.value()); + + const QString &resolvedURL = WbUrl::computePath(this, fieldName, rawURL); + newValue->setValue(exportResource(rawURL, resolvedURL, relativeResourcePath, writer)); + + copiedField.write(writer); +} + bool WbNode::operator==(const WbNode &other) const { if (mModel != other.mModel || isProtoInstance() != other.isProtoInstance() || (mProto && mProto->url() != other.mProto->url()) || mDefName != other.mDefName) diff --git a/src/webots/vrml/WbNode.hpp b/src/webots/vrml/WbNode.hpp index db1bc282f3e..ed95147a369 100644 --- a/src/webots/vrml/WbNode.hpp +++ b/src/webots/vrml/WbNode.hpp @@ -319,6 +319,18 @@ class WbNode : public QObject { virtual void exportNodeFooter(WbWriter &writer) const; virtual void exportExternalSubProto(WbWriter &writer) const; + // fields which should not be handled by the default exportNodeFields function + virtual QStringList customExportedFields() const { return QStringList(); } + + // Helper to handle exporting fields with resources which reference external files + QString exportResource(const QString &rawURL, const QString &resolvedURL, const QString &relativeResourcePath, + const WbWriter &writer) const; + // Wrappers for the most common use case (simply exporting a field with no additional processing) + void exportMFResourceField(const QString &fieldName, const WbMFString *value, const QString &relativeResourcePath, + WbWriter &writer) const; + void exportSFResourceField(const QString &fieldName, const WbSFString *value, const QString &relativeResourcePath, + WbWriter &writer) const; + // Methods related to URDF export const WbNode *findUrdfLinkRoot() const; // Finds first upper Webots node that is considered as URDF link virtual bool isUrdfRootLink() const; // Determines whether the Webots node is considered as URDF link as well diff --git a/src/webots/vrml/WbUrl.cpp b/src/webots/vrml/WbUrl.cpp index d126f6696e4..e996024276f 100644 --- a/src/webots/vrml/WbUrl.cpp +++ b/src/webots/vrml/WbUrl.cpp @@ -85,6 +85,7 @@ QString WbUrl::computePath(const WbNode *node, const QString &field, const QStri if (QDir::isRelativePath(url)) { const WbField *f = node->findField(field, true); + assert(f); const WbNode *protoNode = node->containingProto(false); protoNode = WbVrmlNodeUtilities::findFieldProtoScope(f, protoNode); @@ -132,7 +133,10 @@ QString WbUrl::resolveUrl(const QString &rawUrl) { } QString WbUrl::exportResource(const WbNode *node, const QString &url, const QString &sourcePath, - const QString &relativeResourcePath, const WbWriter &writer, const bool isTexture) { + const QString &relativeResourcePath, const WbWriter &writer) { + // in addition to writing the node, we want to ensure that the resource file exists + // at the expected location. If not, we should copy it, possibly creating the expected + // directory structure. const QFileInfo urlFileInfo(url); const QString fileName = urlFileInfo.fileName(); const QString expectedRelativePath = relativeResourcePath + fileName; @@ -155,11 +159,7 @@ QString WbUrl::exportResource(const WbNode *node, const QString &url, const QStr const QString extension = urlFileInfo.suffix(); for (int i = 1; i < 100; ++i) { // number of trials before failure - QString newRelativePath; - if (isTexture) - newRelativePath = writer.relativeTexturesPath() + baseName + '.' + QString::number(i) + '.' + extension; - else - newRelativePath = writer.relativeMeshesPath() + baseName + '.' + QString::number(i) + '.' + extension; + QString newRelativePath = relativeResourcePath + baseName + '.' + QString::number(i) + '.' + extension; const QString newAbsolutePath = writer.path() + "/" + newRelativePath; if (QFileInfo(newAbsolutePath).exists()) { @@ -170,11 +170,8 @@ QString WbUrl::exportResource(const WbNode *node, const QString &url, const QStr return newRelativePath; } } - if (isTexture) - node->warn(QObject::tr("Failure exporting texture, too many textures share the same name: %1.").arg(url)); - else - node->warn(QObject::tr("Failure exporting mesh, too many meshes share the same name: %1.").arg(url)); + node->warn(QObject::tr("Failure exporting resource, too many resources share the same name: %1.").arg(url)); return ""; } } else { // simple case @@ -183,22 +180,6 @@ QString WbUrl::exportResource(const WbNode *node, const QString &url, const QStr } } -QString WbUrl::exportTexture(const WbNode *node, const WbMFString *urlField, int index, const WbWriter &writer) { - // in addition to writing the node, we want to ensure that the texture file exists - // at the expected location. If not, we should copy it, possibly creating the expected - // directory structure. - return exportResource(node, QDir::fromNativeSeparators(urlField->item(index)), computePath(node, "url", urlField, index), - writer.relativeTexturesPath(), writer); -} - -QString WbUrl::exportMesh(const WbNode *node, const WbMFString *urlField, int index, const WbWriter &writer) { - // in addition to writing the node, we want to ensure that the mesh file exists - // at the expected location. If not, we should copy it, possibly creating the expected - // directory structure. - return exportResource(node, QDir::fromNativeSeparators(urlField->item(index)), computePath(node, "url", urlField, index), - writer.relativeMeshesPath(), writer, false); -} - bool WbUrl::isWeb(const QString &url) { return url.startsWith("https://") || url.startsWith("http://"); } diff --git a/src/webots/vrml/WbUrl.hpp b/src/webots/vrml/WbUrl.hpp index a52cf10a501..48fa8753b82 100644 --- a/src/webots/vrml/WbUrl.hpp +++ b/src/webots/vrml/WbUrl.hpp @@ -30,9 +30,7 @@ namespace WbUrl { QString combinePaths(const QString &rawUrl, const QString &rawParentUrl); QString exportResource(const WbNode *node, const QString &url, const QString &sourcePath, const QString &relativeResourcePath, - const WbWriter &writer, const bool isTexture = true); - QString exportTexture(const WbNode *node, const WbMFString *urlField, int index, const WbWriter &writer); - QString exportMesh(const WbNode *node, const WbMFString *urlField, int index, const WbWriter &writer); + const WbWriter &writer); QString missing(const QString &url); const QString &missingTexture(); diff --git a/src/webots/vrml/WbWriter.hpp b/src/webots/vrml/WbWriter.hpp index 408e3d905d3..c766d9b383f 100644 --- a/src/webots/vrml/WbWriter.hpp +++ b/src/webots/vrml/WbWriter.hpp @@ -91,6 +91,7 @@ class WbWriter { static QString relativeTexturesPath() { return "textures/"; } static QString relativeMeshesPath() { return "meshes/"; } + static QString relativeSoundsPath() { return "sounds/"; } private: void setType(); From cf743661107268382087198169b17749bc511dd2 Mon Sep 17 00:00:00 2001 From: trbljump Date: Mon, 14 Jul 2025 11:31:29 +0200 Subject: [PATCH 13/16] Fix PositionSensor.getMotor() (#6825) * Fix PositionSensor.getMotor() Was calling the wrong function to get the associated motor. * Update changelog-r2025.md * Add PR link --------- Co-authored-by: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> Co-authored-by: Olivier Michel --- docs/reference/changelog-r2025.md | 1 + lib/controller/python/controller/position_sensor.py | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/reference/changelog-r2025.md b/docs/reference/changelog-r2025.md index 0c73537266a..d0898b5577c 100644 --- a/docs/reference/changelog-r2025.md +++ b/docs/reference/changelog-r2025.md @@ -10,6 +10,7 @@ - **Removed `libController.a` and `libCppController.a` libraries on Windows. Please use `Controller.lib` and `CppController.lib` instead ([#6753](https://github.com/cyberbotics/webots/pull/6753)).** - Bug Fixes - Fixed a bug preventing the `webots-controller` executable from running on arm-based mac devices ([#6806](https://github.com/cyberbotics/webots/pull/6806)). + - Fixed a typo in the `controller.PositionSensor` Python class: the `motor` property code was calling the wrong method ([#6825](https://github.com/cyberbotics/webots/pull/6825)). - Fixed a bug causing Webots to crash when multiple sounds were used with a [Speaker](speaker.md) node ([#6843](https://github.com/cyberbotics/webots/pull/6843)). - Fixed a bug causing the "Reload/Reset" buttons in the controller recompilation popup to not work on Windows ([#6844](https://github.com/cyberbotics/webots/pull/6844)). - Fixed resolution of relative paths when converting protos to their base nodes ([#6856](https://github.com/cyberbotics/webots/pull/6856)). diff --git a/lib/controller/python/controller/position_sensor.py b/lib/controller/python/controller/position_sensor.py index e76840f2f59..4b9dc9463ec 100644 --- a/lib/controller/python/controller/position_sensor.py +++ b/lib/controller/python/controller/position_sensor.py @@ -51,7 +51,7 @@ def brake(self): @property def motor(self): from .motor import Motor - tag = wb.wb_brake_get_motor(self._tag) + tag = wb.wb_position_sensor_get_motor(self._tag) return None if tag == 0 else Motor(tag) @property From 9886dd01b3b85c73da74ea9ffd849f11e51c21a2 Mon Sep 17 00:00:00 2001 From: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> Date: Sun, 3 Aug 2025 14:11:37 -0700 Subject: [PATCH 14/16] Fix Crash when Python is not Found on Windows (#6870) * check for process failure in python version check * unify windows and linux python checks * add mac python advice to translation strings * remove unnecessary QProcess includes * import sys in 64-bit python check * fix indentation * fix crash on invalid command * Revert "remove unnecessary QProcess includes" (moved to another pr) This reverts commit 31f04ea9394e29c244618d4d9428f0f38b9ffa5a. * try removing unusedPrivateFunction cppcheck suppression * undo if/ifdef reorder * add else comment * Revert "fix crash on invalid command" I forgot that this only becomes necessary when some other changes are added (which will come in another PR) This reverts commit 15982ce2b19d6477c63e2317fb3c681bd4a81233. * formatting * remove newline * update changelog * wording --- docs/reference/changelog-r2025.md | 1 + src/webots/control/WbLanguageTools.cpp | 66 +++++++++++++------------- src/webots/control/WbLanguageTools.hpp | 3 -- 3 files changed, 34 insertions(+), 36 deletions(-) diff --git a/docs/reference/changelog-r2025.md b/docs/reference/changelog-r2025.md index d0898b5577c..d1f40b2a795 100644 --- a/docs/reference/changelog-r2025.md +++ b/docs/reference/changelog-r2025.md @@ -18,6 +18,7 @@ - Fixed a bug causing `TrackWheel` nodes to lose their field values when used in a proto converted to a base node ([#6856](https://github.com/cyberbotics/webots/pull/6856)). - Fixed a bug causing supervisors to occasionally read stale field values after the simulation was reset ([#6758](https://github.com/cyberbotics/webots/pull/6758)). - Fixed a bug causing Webots to occasionally crash when unloading a world ([#6857](https://github.com/cyberbotics/webots/pull/6857)). + - Fixed a crash occurring when Python was not found on Windows ([#6870](https://github.com/cyberbotics/webots/pull/6870)). ## Webots R2025a Released on January 31st, 2025. diff --git a/src/webots/control/WbLanguageTools.cpp b/src/webots/control/WbLanguageTools.cpp index c02850fb002..7815fdcd0aa 100644 --- a/src/webots/control/WbLanguageTools.cpp +++ b/src/webots/control/WbLanguageTools.cpp @@ -67,13 +67,16 @@ QString WbLanguageTools::pythonCommand(QString &shortVersion, const QString &com if (pythonCommand.isEmpty()) #ifdef _WIN32 pythonCommand = "python"; + if (!command.endsWith(".exe", Qt::CaseInsensitive)) + pythonCommand += ".exe"; #else pythonCommand = "python3"; #endif + const QString advice = #ifdef __APPLE__ - "To fix the problem, you should set the full path of your python command in " - "Webots->preferences->python command.\n"; + QObject::tr("To fix the problem, you should set the full path of your python command in " + "Webots->preferences->python command.\n"); #else QObject::tr("Webots requires Python version 3.7 or newer in your current PATH.\n" "To fix the problem, you should:\n" @@ -81,30 +84,8 @@ QString WbLanguageTools::pythonCommand(QString &shortVersion, const QString &com "2. Check the COMMAND set in the [python] section of the runtime.ini file of your controller program if any.\n" "3. Install a recent Python 64 bit version and ensure your PATH environment variable points to it.\n"); #endif -#ifdef _WIN32 - if (!command.endsWith(".exe", Qt::CaseInsensitive)) - pythonCommand += ".exe"; - QProcess process; - process.setProcessEnvironment(env); - process.start(pythonCommand, QStringList() << "-u" - << "-c" - << "import sys;print(sys.version);print(sys.maxsize > 2**32)"); - process.waitForFinished(); - const QString output = process.readAll(); - // "3.6.3 (v3.6.3:2c5fed8, Oct 3 2017, 18:11:49) [MSC v.1900 64 bit (AMD64)]\nTrue\n" or the like - const QStringList version = output.split("\n"); - const int v = (QString(version[0][2]) + (version[0][3] != '.' ? QString(version[0][3]) : "")).toInt(); - if (!version[0].startsWith("3.") || v < 7) { - WbLog::warning(QObject::tr("\"%1\" was not found.\n").arg(pythonCommand) + advice); - pythonCommand = "!"; - } else if (version.size() > 1 && version[1].startsWith("False")) { - WbLog::warning(QObject::tr("\"%1\" 64 bit was not found, but the 32 bit version was found.\n").arg(pythonCommand) + advice); - pythonCommand = "!"; - } else - shortVersion = QString(version[0][0]) + version[0][2]; - if (version[0][3] != '.') - shortVersion += version[0][3]; // handle versions 310, 311, 321, etc. -#elif __APPLE__ + +#ifdef __APPLE__ if (std::getenv("PWD")) shortVersion = checkIfPythonCommandExist(pythonCommand, env, true); else if (pythonCommand == "python" || pythonCommand == "python3") { @@ -129,18 +110,36 @@ QString WbLanguageTools::pythonCommand(QString &shortVersion, const QString &com if (pythonCommand == "!") WbLog::warning(QObject::tr("Python was not found.\n") + advice); -#else // __linux__ - shortVersion = checkIfPythonCommandExist(pythonCommand, env, true); +#else // __linux__ and _WIN32 + shortVersion = checkIfPythonCommandExist(pythonCommand, env, true); if (shortVersion.isEmpty()) { pythonCommand = "!"; WbLog::warning(QObject::tr("Python was not found.\n") + advice); + } else { // Python exists + +#ifdef _WIN32 // 64-bit check + QProcess process; + process.setProcessEnvironment(env); + process.start(pythonCommand, QStringList() << "-u" + << "-c" + << "import sys;print(sys.maxsize > 2**32)"); + process.waitForFinished(); + bool processSucceeded = process.error() == QProcess::UnknownError; + const QString output = process.readAll(); + if (!processSucceeded || !output.startsWith("True")) { + WbLog::warning(QObject::tr("\"%1\" 64 bit was not found, but the 32 bit version was found.\n").arg(pythonCommand) + + advice); + pythonCommand = "!"; + shortVersion = QString(); + } +#endif // _WIN32 } -#endif +#endif // __APPLE__ + return pythonCommand; } -#if defined __APPLE__ || defined __linux__ const QString WbLanguageTools::checkIfPythonCommandExist(const QString &pythonCommand, QProcessEnvironment &env, bool log) { QString shortVersion; QProcess process; @@ -148,20 +147,21 @@ const QString WbLanguageTools::checkIfPythonCommandExist(const QString &pythonCo process.start(pythonCommand, QStringList() << "-c" << "import sys;print(sys.version);"); process.waitForFinished(); + bool processSucceeded = process.error() == QProcess::UnknownError; const QString output = process.readAll(); // "3.8.10 (tags/v3.8.10:3d8993a, May 3 2021, 11:48:03) [MSC v.1928 64 bit (AMD64)]" or the like const QStringList version = output.split(" "); - if (!version[0].startsWith("3.")) { + const QStringList version_numbers(version[0].split(".")); + const int minor_version = version_numbers.size() >= 2 ? version_numbers[1].toInt() : 0; + if (!processSucceeded || !version[0].startsWith("3.") || minor_version < 7) { if (log) WbLog::warning(QObject::tr("\"%1\" was not found.\n").arg(pythonCommand)); shortVersion = QString(); } else { - const QStringList version_numbers(version[0].split(".")); shortVersion = version_numbers[0] + version_numbers[1]; } return shortVersion; } -#endif #ifdef __APPLE__ QString WbLanguageTools::findWorkingPythonPath(const QString &pythonVersion, QProcessEnvironment &env, bool log) { diff --git a/src/webots/control/WbLanguageTools.hpp b/src/webots/control/WbLanguageTools.hpp index 1e670df550a..e0b80c7b3aa 100644 --- a/src/webots/control/WbLanguageTools.hpp +++ b/src/webots/control/WbLanguageTools.hpp @@ -35,10 +35,7 @@ class WbLanguageTools { private: WbLanguageTools() {} ~WbLanguageTools() {} -#if defined __APPLE__ || defined __linux__ - // cppcheck-suppress unusedPrivateFunction static const QString checkIfPythonCommandExist(const QString &pythonCommand, QProcessEnvironment &env, bool log); -#endif #ifdef __APPLE__ static QString findWorkingPythonPath(const QString &pythonVersion, QProcessEnvironment &env, bool log); #endif From 1de87ccb4edc975f95c8e9b50824b954850e4ae8 Mon Sep 17 00:00:00 2001 From: Carlos Alvarado Martinez <45523697+calvarado2004@users.noreply.github.com> Date: Sun, 17 Aug 2025 01:29:33 -0400 Subject: [PATCH 15/16] Adding compilation support for Fedora 42 (#6780) * Update linux_compilation_dependencies.sh * Update linux_runtime_dependencies.sh * Update scripts/install/linux_compilation_dependencies.sh Co-authored-by: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> * add fedora warning and port additional install scripts * remove dependence on lsb-release * fix os version check * fix libfreetype includes * fix Ubuntu 22.04 check * use non-free ffmpeg * fix Makefile UBUNTU_VERSION --------- Co-authored-by: Olivier Michel Co-authored-by: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> Co-authored-by: CoolSpy3 --- resources/Makefile.os.include | 9 ++- .../install/linux_compilation_dependencies.sh | 55 ++++++++++--- ...linux_optional_compilation_dependencies.sh | 64 ++++++++++++--- scripts/install/linux_runtime_dependencies.sh | 81 +++++++++++++++---- scripts/install/linux_test_dependencies.sh | 46 +++++++++-- .../install/linux_web_viewer_dependencies.sh | 40 ++++++++- src/wren/Makefile | 3 + tests/test_suite.py | 15 +++- 8 files changed, 255 insertions(+), 58 deletions(-) diff --git a/resources/Makefile.os.include b/resources/Makefile.os.include index 60907b91072..87466ba0a75 100644 --- a/resources/Makefile.os.include +++ b/resources/Makefile.os.include @@ -50,22 +50,25 @@ ifeq ($(OSTYPE),Darwin) OSTYPE = darwin endif -# determine the OSARCH and UBUNTU_VERSION (linux only) +# determine the OSARCH, OSDIST, and UBUNTU_VERSION (linux only) ifeq ($(OSTYPE),linux) ifeq ($(filter x86_64, $(shell uname -a)),) OSARCH = i386 else OSARCH = x86_64 endif + OSDIST=$(shell grep ^ID= /etc/os-release | cut -d= -f2) ifeq ($(OSTYPE),linux) ifeq ($(SNAP_NAME), webots) UBUNTU_VERSION=22.04 else - ifneq (, $(shell which lsb_release)) - UBUNTU_VERSION:=$(shell lsb_release -sr) + ifneq (, $(wildcard /etc/os-release)) + UBUNTU_VERSION:=$(shell grep VERSION_ID /etc/os-release | cut -d= -f2 | tr -d '"') endif endif endif +else + OSDIST=$(OSTYPE) endif # OS specific variables diff --git a/scripts/install/linux_compilation_dependencies.sh b/scripts/install/linux_compilation_dependencies.sh index 213b51ad584..2aaa6ad2e86 100755 --- a/scripts/install/linux_compilation_dependencies.sh +++ b/scripts/install/linux_compilation_dependencies.sh @@ -1,25 +1,56 @@ #!/bin/bash -# exit when any command fails on CI +# Exit when any command fails on CI if [[ ! -z "$CI" ]]; then - set -e + set -e fi if [[ $EUID -ne 0 ]]; then - echo "This script must be run as root" - exit 1 + echo "This script must be run as root" + exit 1 fi -alias apt='apt --option="APT::Acquire::Retries=3"' -apt update -apt install --yes git lsb-release cmake swig libglu1-mesa-dev libglib2.0-dev libfreeimage3 libfreetype6-dev libxml2-dev libboost-dev libssh-gcrypt-dev libzip-dev libreadline-dev pbzip2 wget zip unzip python3 python3-pip libopenal-dev - -UBUNTU_VERSION=$(lsb_release -rs) -if [[ $UBUNTU_VERSION == "22.04" || $UBUNTU_VERSION == "24.04" ]]; then - apt install --yes libzip4 openssl +# Detect the operating system +if [ -f /etc/os-release ]; then + . /etc/os-release + OS=$ID + VERSION_ID=$VERSION_ID else - echo "Unsupported Linux version: dependencies may not be completely installed. Only the two latest Ubuntu LTS are supported." + echo "Cannot determine the operating system." + exit 1 fi +# Function to install packages on Ubuntu +install_ubuntu_packages() { + alias apt='apt --option="APT::Acquire::Retries=3"' + apt update + apt install --yes git cmake swig libglu1-mesa-dev libglib2.0-dev libfreeimage3 libfreetype6-dev libxml2-dev libboost-dev libssh-gcrypt-dev libzip-dev libreadline-dev pbzip2 wget zip unzip python3 python3-pip libopenal-dev + + if [[ $VERSION_ID == "22.04" || $VERSION_ID == "24.04" ]]; then + apt install --yes libzip4 openssl + else + echo "Unsupported Ubuntu version: dependencies may not be completely installed. Only the two latest Ubuntu LTS are supported." + fi +} + +# Function to install packages on Fedora +install_fedora_packages() { + dnf install -y git cmake swig mesa-libGLU-devel glib2-devel freeimage freetype-devel.x86_64 freetype-devel.i686 glibc-devel.x86_64 glibc-devel.i686 libxml2-devel boost-devel libssh-devel libzip-devel readline-devel pbzip2 wget zip unzip python3 python3-pip openal-soft-devel glm-devel stb-devel +} + +# Determine the operating system and call the appropriate function +case "$OS" in + ubuntu) + install_ubuntu_packages + ;; + fedora) + install_fedora_packages + ;; + *) + echo "Unsupported operating system: $OS" + exit 1 + ;; +esac + script_full_path=$(dirname "$0") $script_full_path/linux_runtime_dependencies.sh diff --git a/scripts/install/linux_optional_compilation_dependencies.sh b/scripts/install/linux_optional_compilation_dependencies.sh index 60d0f28973a..9fd1dba9e17 100755 --- a/scripts/install/linux_optional_compilation_dependencies.sh +++ b/scripts/install/linux_optional_compilation_dependencies.sh @@ -10,22 +10,60 @@ if [[ $EUID -ne 0 ]]; then exit 1 fi -# Install add-apt-repository command -alias apt='apt --option="APT::Acquire::Retries=3"' -apt install --yes software-properties-common -add-apt-repository -y ppa:deadsnakes/ppa -apt update -apt install --yes lsb-release curl python3.7-dev python3.8-dev python3.9-dev python3.10-dev dirmngr execstack libxerces-c-dev libfox-1.6-dev libgdal-dev libproj-dev libgl2ps-dev libssh-dev - -UBUNTU_VERSION=$(lsb_release -rs) -if [[ $UBUNTU_VERSION == "22.04" ]]; then - apt install --yes openjdk-18-jdk -elif [[ $UBUNTU_VERSION == "24.04" ]]; then - apt install --yes openjdk-21-jdk +# Detect the operating system +if [ -f /etc/os-release ]; then + . /etc/os-release + OS=$ID + VERSION_ID=$VERSION_ID else - echo "Unsupported Linux version: dependencies may not be completely installed. Only the two latest Ubuntu LTS versions are supported." + echo "Cannot determine the operating system." + exit 1 fi +# Function to install optional dependencies on Ubuntu +install_ubuntu_optional_compilation_packages() { + # Install add-apt-repository command + alias apt='apt --option="APT::Acquire::Retries=3"' + apt install --yes software-properties-common + add-apt-repository -y ppa:deadsnakes/ppa + apt update + apt install --yes curl python3.7-dev python3.8-dev python3.9-dev python3.10-dev dirmngr execstack libxerces-c-dev libfox-1.6-dev libgdal-dev libproj-dev libgl2ps-dev libssh-dev + + if [[ $VERSION_ID == "22.04" ]]; then + apt install --yes openjdk-18-jdk + elif [[ $VERSION_ID == "24.04" ]]; then + apt install --yes openjdk-21-jdk + else + echo "Unsupported Linux version: dependencies may not be completely installed. Only the two latest Ubuntu LTS versions are supported." + fi +} + +# Function to install runtime dependencies on Fedora +install_fedora_optional_compilation_packages() { + dnf install -y curl python3-devel execstack xerces-c-devel fox-devel gdal-devel proj-devel gl2ps-devel libssh-devel + dnf install -y java-21-openjdk-devel + + if [[ $VERSION_ID -le 42 ]]; then + dnf install -y gnupg2 + else + dnf install -y gnupg2-dirmngr + fi +} + +# Determine the operating system and call the appropriate function +case "$OS" in + ubuntu) + install_ubuntu_optional_compilation_packages + ;; + fedora) + install_fedora_optional_compilation_packages + ;; + *) + echo "Unsupported operating system: $OS" + exit 1 + ;; +esac + script_full_path=$(dirname "$0") $script_full_path/linux_test_dependencies.sh --norecurse $script_full_path/linux_compilation_dependencies.sh diff --git a/scripts/install/linux_runtime_dependencies.sh b/scripts/install/linux_runtime_dependencies.sh index 4593476be2c..169b0d242d4 100755 --- a/scripts/install/linux_runtime_dependencies.sh +++ b/scripts/install/linux_runtime_dependencies.sh @@ -1,25 +1,76 @@ #!/bin/bash -# exit when any command fails on CI +# Exit when any command fails on CI if [[ ! -z "$CI" ]]; then - set -e + set -e fi if [[ $EUID -ne 0 ]]; then - echo "This script must be run as root" - exit 1 + echo "This script must be run as root" + exit 1 fi -alias apt='apt --option="APT::Acquire::Retries=3"' -apt update -apt install --yes lsb-release g++ make libavcodec-extra libglu1-mesa libegl1 libxkbcommon-x11-dev libxcb-keysyms1 libxcb-image0 libxcb-icccm4 libxcb-randr0 libxcb-render-util0 libxcb-xinerama0 libxcomposite-dev libxtst6 libnss3 libxcb-cursor0 -if [[ -z "$DISPLAY" ]]; then - apt install --yes xvfb -fi - -UBUNTU_VERSION=$(lsb_release -rs) -if [[ $UBUNTU_VERSION == "22.04" || $UBUNTU_VERSION == "24.04" ]]; then - apt install --yes ffmpeg +# Detect the operating system +if [ -f /etc/os-release ]; then + . /etc/os-release + OS=$ID + VERSION_ID=$VERSION_ID else - echo "Unsupported Linux version: dependencies may not be completely installed. Only the two latest Ubuntu LTS are supported." + echo "Cannot determine the operating system." + exit 1 fi + +# Function to install runtime dependencies on Ubuntu +install_ubuntu_runtime_packages() { + alias apt='apt --option="APT::Acquire::Retries=3"' + apt update + apt install --yes g++ make libavcodec-extra libglu1-mesa libegl1 \ + libxkbcommon-x11-dev libxcb-keysyms1 libxcb-image0 libxcb-icccm4 libxcb-randr0 \ + libxcb-render-util0 libxcb-xinerama0 libxcomposite-dev libxtst6 libnss3 libxcb-cursor0 + + if [[ -z "$DISPLAY" ]]; then + apt install --yes xvfb + fi + + if [[ $VERSION_ID == "22.04" || $VERSION_ID == "24.04" ]]; then + apt install --yes ffmpeg + else + echo "Unsupported Linux version: dependencies may not be completely installed. Only the two latest Ubuntu LTS are supported." + fi +} + +# Function to install runtime dependencies on Fedora +install_fedora_runtime_packages() { + dnf install -y gcc-c++ make mesa-libGLU libEGL \ + xkeyboard-config libxcb libXcomposite libXtst nss xcb-util xcb-util-image \ + xcb-util-keysyms xcb-util-renderutil xcb-util-wm xcb-util-cursor \ + + if [[ -z "$DISPLAY" ]]; then + dnf install -y xorg-x11-server-Xvfb + fi + + # Install ffmpeg (with non-free codecs) + # Enable RPMFusion + dnf -y install https://mirrors.rpmfusion.org/free/fedora/rpmfusion-free-release-$(rpm -E %fedora).noarch.rpm https://mirrors.rpmfusion.org/nonfree/fedora/rpmfusion-nonfree-release-$(rpm -E %fedora).noarch.rpm + if dnf list installed ffmpeg-free &> /dev/null; then + dnf swap -y ffmpeg-free ffmpeg --allowerasing + else + dnf install -y ffmpeg + fi + + echo "WARNING: Fedora is not an officially supported OS! Dependencies may not be completely installed. Only the two latest Ubuntu LTS are supported." +} + +# Determine the operating system and call the appropriate function +case "$OS" in + ubuntu) + install_ubuntu_runtime_packages + ;; + fedora) + install_fedora_runtime_packages + ;; + *) + echo "Unsupported operating system: $OS" + exit 1 + ;; +esac diff --git a/scripts/install/linux_test_dependencies.sh b/scripts/install/linux_test_dependencies.sh index 49842a6ed4b..c1cf107b710 100755 --- a/scripts/install/linux_test_dependencies.sh +++ b/scripts/install/linux_test_dependencies.sh @@ -2,19 +2,49 @@ # exit when any command fails on CI if [[ ! -z "$CI" ]]; then - set -e + set -e fi if [[ $EUID -ne 0 ]]; then - echo "This script must be run as root" - exit 1 + echo "This script must be run as root" + exit 1 fi -alias apt='apt --option="APT::Acquire::Retries=3"' -apt install liburdfdom-tools -y +# Detect the operating system +if [ -f /etc/os-release ]; then + . /etc/os-release + OS=$ID + VERSION_ID=$VERSION_ID +else + echo "Cannot determine the operating system." + exit 1 +fi + +install_ubuntu_test_packages() { + alias apt='apt --option="APT::Acquire::Retries=3"' + apt install liburdfdom-tools -y +} + +install_fedora_test_packages() { + dnf install -y urdfdom-devel +} + +# Determine the operating system and call the appropriate function +case "$OS" in + ubuntu) + install_ubuntu_test_packages + ;; + fedora) + install_fedora_test_packages + ;; + *) + echo "Unsupported operating system: $OS" + exit 1 + ;; +esac if [[ $@ != *"--norecurse"* ]]; then - echo "Installing runtime dependencies" - script_full_path=$(dirname "$0") - $script_full_path/linux_runtime_dependencies.sh + echo "Installing runtime dependencies" + script_full_path=$(dirname "$0") + $script_full_path/linux_runtime_dependencies.sh fi diff --git a/scripts/install/linux_web_viewer_dependencies.sh b/scripts/install/linux_web_viewer_dependencies.sh index 6fbf28cecae..314fae9255b 100755 --- a/scripts/install/linux_web_viewer_dependencies.sh +++ b/scripts/install/linux_web_viewer_dependencies.sh @@ -10,12 +10,42 @@ if [[ $EUID -ne 0 ]]; then exit 1 fi -alias apt='apt --option="APT::Acquire::Retries=3"' -apt install python3-pip python3-setuptools -y +# Detect the operating system +if [ -f /etc/os-release ]; then + . /etc/os-release + OS=$ID + VERSION_ID=$VERSION_ID +else + echo "Cannot determine the operating system." + exit 1 +fi + +install_ubuntu_web_viewer_packages() { + alias apt='apt --option="APT::Acquire::Retries=3"' + apt install python3-pip python3-setuptools -y +} + +install_fedora_web_viewer_packages() { + dnf install -y python3-pip python3-setuptools +} + +# Determine the operating system and call the appropriate function +case "$OS" in + ubuntu) + install_ubuntu_web_viewer_packages + ;; + fedora) + install_fedora_web_viewer_packages + ;; + *) + echo "Unsupported operating system: $OS" + exit 1 + ;; +esac + pip3 install --upgrade pip pip3 install pyclibrary - git clone https://github.com/emscripten-core/emsdk.git dependencies/emsdk USER=$(env | grep SUDO_USER | cut -d '=' -f 2-) @@ -26,3 +56,7 @@ chown -R $USER dependencies/emsdk WEBOTS_HOME=$(pwd) echo 'source "'$WEBOTS_HOME'/dependencies/emsdk/emsdk_env.sh" >/dev/null 2>&1' >> /home/$USER/.bashrc + +if [[ "$OS" == "fedora" ]]; then + echo "WARNING: Fedora is not an officially supported OS! Dependencies may not be completely installed. Only the two latest Ubuntu LTS are supported." +fi diff --git a/src/wren/Makefile b/src/wren/Makefile index 4daa8b827f3..7f789425448 100644 --- a/src/wren/Makefile +++ b/src/wren/Makefile @@ -30,6 +30,9 @@ ifeq ($(OSTYPE),darwin) INCLUDE += -I$(WEBOTS_DEPENDENCY_PATH)/freetype2 -I$(WEBOTS_DEPENDENCY_PATH)/assimp/include else ifeq ($(OSTYPE),linux) INCLUDE += -I/usr/include/freetype2 -I$(WEBOTS_HOME_PATH)/include/libassimp/include +ifeq ($(OSDIST), fedora) +INCLUDE += -idirafter/usr/include +endif else ifeq ($(OSTYPE),windows) INCLUDE += -I/mingw64/include/freetype2 -I/mingw64/include -I$(WEBOTS_DEPENDENCY_PATH) endif diff --git a/tests/test_suite.py b/tests/test_suite.py index 68b7ba0a7c2..ea03c7ccc56 100755 --- a/tests/test_suite.py +++ b/tests/test_suite.py @@ -35,11 +35,18 @@ from command import Command from cache.cache_environment import update_cache_urls +is_ubuntu_22_04 = False if sys.platform == 'linux': - result = subprocess.run(['lsb_release', '-sr'], stdout=subprocess.PIPE) - is_ubuntu_22_04 = result.stdout.decode().strip() == '22.04' -else: - is_ubuntu_22_04 = False + try: + with open('/etc/os-release') as releaseInfo: + for var in releaseInfo.readlines(): + var = var.strip() + if var.startswith('VERSION_ID'): + is_ubuntu_22_04 = var == 'VERSION_ID="22.04"' + break + except OSError: + print('WARNING: /etc/os-release not found! Assuming not Ubuntu 22.04.') + # monitor failures failures = 0 From f355c4d330cab9a6894eac63bb3c05c47e3943b0 Mon Sep 17 00:00:00 2001 From: CoolSpy3 <55305038+CoolSpy3@users.noreply.github.com> Date: Sun, 17 Aug 2025 11:16:20 -0700 Subject: [PATCH 16/16] remove movie test exclusion from Ubuntu 22.04 (#6874) --- tests/test_suite.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/tests/test_suite.py b/tests/test_suite.py index ea03c7ccc56..3305d29ceee 100755 --- a/tests/test_suite.py +++ b/tests/test_suite.py @@ -208,14 +208,12 @@ def generateWorldsList(groupName): # speaker test not working on github action because of missing sound drivers # robot window test cannot open a browser for the robot window in a headless environment # on non-mac operating systems - # movie recording test not working on BETA Ubuntu 22.04 GitHub Action environment # billboard test not working in macos GitHub Action environment # billboard and robot window not working on windows GitHub Action environment. if (not filename.endswith('_temp.wbt') and not ('GITHUB_ACTIONS' in os.environ and ( filename.endswith('speaker.wbt') or filename.endswith('local_proto_with_texture.wbt') or - (filename.endswith('supervisor_start_stop_movie.wbt') and is_ubuntu_22_04) or (filename.endswith('billboard.wbt') and sys.platform == 'darwin') or (filename.endswith('billboard.wbt') and sys.platform == 'win32') or (filename.endswith('robot_window_html.wbt') and sys.platform == 'linux') or