diff --git a/.github/workflows/test_suite_mac.yml b/.github/workflows/test_suite_mac.yml index 66447fc5510..fa1946a9300 100644 --- a/.github/workflows/test_suite_mac.yml +++ b/.github/workflows/test_suite_mac.yml @@ -19,7 +19,7 @@ jobs: if: ${{ contains(github.event.pull_request.labels.*.name, 'test webots build') }} strategy: matrix: - os: [macos-11] + os: [macos-14] runs-on: ${{ matrix.os }} steps: - uses: actions/checkout@v3 @@ -33,7 +33,7 @@ jobs: if: ${{ github.event_name == 'push' || github.event_name == 'schedule' || contains(github.event.pull_request.labels.*.name, 'test distribution') || contains(github.event.pull_request.labels.*.name, 'test suite') }} strategy: matrix: - os: [macos-11] + os: [macos-14] runs-on: ${{ matrix.os }} steps: - uses: actions/checkout@v3 @@ -69,7 +69,7 @@ jobs: if: ${{ contains(github.event.pull_request.labels.*.name, 'test suite') }} strategy: matrix: - os: [macos-11] + os: [macos-14] runs-on: ${{ matrix.os }} steps: - uses: actions/checkout@v3 @@ -98,7 +98,7 @@ jobs: if: ${{ always() && !contains(github.event.pull_request.labels.*.name, 'test distribution') && !contains(github.event.pull_request.labels.*.name, 'test webots build') }} strategy: matrix: - os: [macos-11] + os: [macos-14] runs-on: ubuntu-latest steps: - name: Delete artifacts diff --git a/.github/workflows/test_suite_mac_develop.yml b/.github/workflows/test_suite_mac_develop.yml index a84a8add932..0e108da53f5 100644 --- a/.github/workflows/test_suite_mac_develop.yml +++ b/.github/workflows/test_suite_mac_develop.yml @@ -13,7 +13,7 @@ jobs: if: ${{ contains(github.event.pull_request.labels.*.name, 'test webots build') }} strategy: matrix: - os: [macos-11] + os: [macos-14] runs-on: ${{ matrix.os }} steps: - uses: actions/checkout@v3 @@ -28,7 +28,7 @@ jobs: if: ${{ github.event_name == 'push' || github.event_name == 'schedule' || contains(github.event.pull_request.labels.*.name, 'test distribution') || contains(github.event.pull_request.labels.*.name, 'test suite') }} strategy: matrix: - os: [macos-11] + os: [macos-14] runs-on: ${{ matrix.os }} steps: - uses: actions/checkout@v3 @@ -65,7 +65,7 @@ jobs: if: ${{ contains(github.event.pull_request.labels.*.name, 'test suite') }} strategy: matrix: - os: [macos-11] + os: [macos-14] runs-on: ${{ matrix.os }} steps: - uses: actions/checkout@v3 @@ -96,7 +96,7 @@ jobs: if: ${{ always() && !contains(github.event.pull_request.labels.*.name, 'test distribution') && !contains(github.event.pull_request.labels.*.name, 'test webots build') }} strategy: matrix: - os: [macos-11] + os: [macos-14] runs-on: ubuntu-latest steps: - name: Delete artifacts diff --git a/.github/workflows/tests_sources.yml b/.github/workflows/tests_sources.yml index c4193f0dae3..36153365fd6 100644 --- a/.github/workflows/tests_sources.yml +++ b/.github/workflows/tests_sources.yml @@ -34,15 +34,15 @@ jobs: strategy: fail-fast: false matrix: - os: [ubuntu-22.04, macos-11, windows-2019] + os: [ubuntu-22.04, macos-14, windows-2019] python: [3.9] include: - os: ubuntu-22.04 - DEPENDENCIES_INSTALLATION: "wget https://github.com/danmar/cppcheck/archive/refs/tags/2.10.tar.gz; tar -xf 2.10.tar.gz -C ~/; mkdir -p ~/cppcheck-2.10/build; cd ~/cppcheck-2.10/build; cmake ..; cmake --build .; export PATH=~/cppcheck-2.10/build/bin:$PATH" - - os: macos-11 - DEPENDENCIES_INSTALLATION: "brew tap-new --no-git $USER/local-cppcheck; brew extract --version=2.10 cppcheck $USER/local-cppcheck; brew install cppcheck@2.10; 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" + 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 ..; cmake --build .; 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 - DEPENDENCIES_INSTALLATION: "choco install -y cppcheck --version=2.10 || 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\"" + 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' steps: diff --git a/.github/workflows/tests_sources_with_latest_cppcheck.yml b/.github/workflows/tests_sources_with_latest_cppcheck.yml index 107ea225084..fbef60e4d70 100644 --- a/.github/workflows/tests_sources_with_latest_cppcheck.yml +++ b/.github/workflows/tests_sources_with_latest_cppcheck.yml @@ -30,12 +30,12 @@ jobs: strategy: fail-fast: false matrix: - os: [ubuntu-22.04, macos-11, windows-2019] + os: [ubuntu-22.04, macos-14, windows-2019] python: [3.9] include: - os: ubuntu-22.04 DEPENDENCIES_INSTALLATION: "sudo apt -y install cppcheck" - - os: macos-11 + - 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 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\"" diff --git a/docs/guide/system-requirements.md b/docs/guide/system-requirements.md index 300b783c353..02b40c10604 100644 --- a/docs/guide/system-requirements.md +++ b/docs/guide/system-requirements.md @@ -19,7 +19,7 @@ We recommend using a recent version of Linux. Webots is provided for Linux 64 (x86-64) systems only. Webots doesn't run on Ubuntu versions earlier than 20.04. - Windows: Webots runs on Windows 11 and Windows 10 (64-bit versions only). -- Mac: Webots runs on macOS 11 "Big Sur", macOS 12 "Monterey" and macOS 13 "Ventura". +- Mac: Webots runs on macOS macOS 12 "Monterey", macOS 13 "Ventura", and macOS 14 "Sonoma". Webots may work but is not officially supported on earlier versions of the above mentioned operating systems. diff --git a/docs/reference/changelog-r2024.md b/docs/reference/changelog-r2024.md index 852cc8b9e32..e8bd19ef69b 100644 --- a/docs/reference/changelog-r2024.md +++ b/docs/reference/changelog-r2024.md @@ -4,6 +4,7 @@ Released on December **th, 2023. - New Features - **Change the name of the web scene format from `X3D` to `W3D` ([#6280](https://github.com/cyberbotics/webots/pull/6280)).** + - Removed support for macOS 11 "Big Sur" and added support for macOS 14 "Sonoma" ([#6580](https://github.com/cyberbotics/webots/pull/6580)). - Enhancements - Improved the image range of the rotating [Lidar](lidar.md) ([#6324](https://github.com/cyberbotics/webots/pull/6324)). - Cleanup @@ -11,5 +12,5 @@ Released on December **th, 2023. - Bug Fixes - Fixed error message on Windows when `libssl-3-x64.dll` was added to `PATH` ([#6553](https://github.com/cyberbotics/webots/pull/6553)). - Fixed length of arrays returned by `getPose()` in Java ([#6556](https://github.com/cyberbotics/webots/pull/6556)). - - Fixed length of arrays returned by `CameraRecognitionObject.getColors()` in Java ([#6564](https://github.com/cyberbotics/webots/pull/6564)) - - Fixed handling of device objects with the same name in the controller API ([#6579](https://github.com/cyberbotics/webots/pull/6579)) + - Fixed length of arrays returned by `CameraRecognitionObject.getColors()` in Java ([#6564](https://github.com/cyberbotics/webots/pull/6564)). + - Fixed handling of device objects with the same name in the controller API ([#6579](https://github.com/cyberbotics/webots/pull/6579)). diff --git a/include/controller/c/webots/plugins/robot_window/generic_robot_window/generic.h b/include/controller/c/webots/plugins/robot_window/generic_robot_window/generic.h index 26b21ab7b18..62f3eb09d8b 100644 --- a/include/controller/c/webots/plugins/robot_window/generic_robot_window/generic.h +++ b/include/controller/c/webots/plugins/robot_window/generic_robot_window/generic.h @@ -29,7 +29,7 @@ extern "C" { #endif void wbu_generic_robot_window_parse_device_command(char *token, char *tokens); -bool wbu_generic_robot_window_parse_device_control_command(char *first_token, char *tokens); +bool wbu_generic_robot_window_parse_device_control_command(const char *first_token, char *tokens); bool wbu_generic_robot_window_handle_messages(const char *message); void wbu_generic_robot_window_init(); void wbu_generic_robot_window_update(); diff --git a/include/controller/c/webots/utils/string.h b/include/controller/c/webots/utils/string.h index 9e972e5a0c9..692af987c56 100644 --- a/include/controller/c/webots/utils/string.h +++ b/include/controller/c/webots/utils/string.h @@ -26,7 +26,7 @@ extern "C" { #endif char *wbu_string_strsep(char **stringp, const char *delim); -char *wbu_string_replace(char *value, char *before, char *after); +char *wbu_string_replace(char *value, const char *before, const char *after); #ifdef __cplusplus } diff --git a/include/wren/drawable_texture.h b/include/wren/drawable_texture.h index 457a96d8a7d..e28c71e42d4 100644 --- a/include/wren/drawable_texture.h +++ b/include/wren/drawable_texture.h @@ -15,7 +15,7 @@ typedef struct WrFont WrFont; WrDrawableTexture *wr_drawable_texture_new(); void wr_drawable_texture_set_font(WrDrawableTexture *texture, WrFont *font); -void wr_drawable_texture_set_color(WrDrawableTexture *texture, float *color); +void wr_drawable_texture_set_color(WrDrawableTexture *texture, const float *color); void wr_drawable_texture_set_antialasing(WrDrawableTexture *texture, bool enabled); void wr_drawable_texture_set_use_premultiplied_alpha(WrDrawableTexture *texture, bool premultipliedAlpha); diff --git a/projects/default/controllers/ros/RosSensor.cpp b/projects/default/controllers/ros/RosSensor.cpp index a2175a56fe9..8a7b1aea156 100644 --- a/projects/default/controllers/ros/RosSensor.cpp +++ b/projects/default/controllers/ros/RosSensor.cpp @@ -14,7 +14,7 @@ #include "RosSensor.hpp" -RosSensor::RosSensor(std::string deviceName, Device *device, Ros *ros, bool enableDefaultServices) : +RosSensor::RosSensor(const std::string &deviceName, Device *device, Ros *ros, bool enableDefaultServices) : RosDevice(device, ros, enableDefaultServices), mFrameIdPrefix("") { std::string fixedDeviceName = Ros::fixedNameString(deviceName); diff --git a/projects/default/controllers/ros/RosSensor.hpp b/projects/default/controllers/ros/RosSensor.hpp index 86ecc1ea01a..be41ddd1637 100644 --- a/projects/default/controllers/ros/RosSensor.hpp +++ b/projects/default/controllers/ros/RosSensor.hpp @@ -34,7 +34,7 @@ class RosSensor : public RosDevice { bool enableSensor(int timestep); protected: - RosSensor(std::string deviceName, Device *device, Ros *ros, bool enableDefaultServices = true); + RosSensor(const std::string &deviceName, Device *device, Ros *ros, bool enableDefaultServices = true); virtual ros::Publisher createPublisher() = 0; virtual void publishValue(ros::Publisher publisher) = 0; diff --git a/projects/default/libraries/vehicle/c/car/src/car.c b/projects/default/libraries/vehicle/c/car/src/car.c index 8b81fecc0d8..f1ce8a805eb 100644 --- a/projects/default/libraries/vehicle/c/car/src/car.c +++ b/projects/default/libraries/vehicle/c/car/src/car.c @@ -138,7 +138,7 @@ void wbu_car_init() { // Parse vehicle caracteristics from the beginning of the data string char engine_type; int engine_sound_length; - char *sub_data_string = (char *)wb_robot_get_custom_data(); + const char *sub_data_string = wb_robot_get_custom_data(); i = sscanf(sub_data_string, "%lf %lf %lf %lf %lf %lf %lf %c %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %d %d", &instance->wheelbase, &instance->track_front, &instance->track_rear, &instance->front_wheel_radius, &instance->rear_wheel_radius, &instance->brake_coefficient, &instance->defaultDampingConstant, &engine_type, diff --git a/projects/default/libraries/vehicle/c/driver/src/driver.c b/projects/default/libraries/vehicle/c/driver/src/driver.c index d02c93b2590..9d2bc3904d0 100644 --- a/projects/default/libraries/vehicle/c/driver/src/driver.c +++ b/projects/default/libraries/vehicle/c/driver/src/driver.c @@ -448,6 +448,7 @@ static void update_engine_sound() { } if (rpm < instance->car->engine_min_rpm) rpm = instance->car->engine_min_rpm; + // cppcheck-suppress variableScope double pitch = rpm / instance->car->engine_sound_rpm_reference; if (stop_sound) wb_speaker_stop(instance->engine_speaker, instance->car->engine_sound); diff --git a/projects/default/libraries/vehicle/java/Makefile b/projects/default/libraries/vehicle/java/Makefile index 98391dc9381..63670bb34e2 100644 --- a/projects/default/libraries/vehicle/java/Makefile +++ b/projects/default/libraries/vehicle/java/Makefile @@ -88,10 +88,10 @@ $(WRAPPER_OBJECT): $(WRAPPER) @$(CXX) $(CFLAGS2) $(INCLUDES) $(JAVA_INCLUDES) $< -o "$@" $(WRAPPER_OBJECT_ARM64): $(WRAPPER) - @$(CXX) -target arm64-apple-macos11 $(CFLAGS2) $(INCLUDES) $(JAVA_INCLUDES) $< -o "$@" + @$(CXX) -target arm64-apple-macos12 $(CFLAGS2) $(INCLUDES) $(JAVA_INCLUDES) $< -o "$@" $(WRAPPER_OBJECT_X86_64): $(WRAPPER) - @$(CXX) -target x86_64-apple-macos11 $(CFLAGS2) $(INCLUDES) $(JAVA_INCLUDES) $< -o "$@" + @$(CXX) -target x86_64-apple-macos12 $(CFLAGS2) $(INCLUDES) $(JAVA_INCLUDES) $< -o "$@" %.so: $(WRAPPER_OBJECT) @mkdir -p $(WEBOTS_CONTROLLER_LIB_PATH)/java @@ -102,8 +102,8 @@ $(WRAPPER_OBJECT_X86_64): $(WRAPPER) @$(CXX) -shared -mwindows -Wl,--add-stdcall-alias -Wl,--enable-auto-import -O -lm $< $(LIB) -o "$@" %.jnilib: $(WRAPPER_OBJECT_ARM64) $(WRAPPER_OBJECT_X86_64) - @$(CXX) -target arm64-apple-macos11 $(CFLAGS1) -bundle $(WRAPPER_OBJECT_ARM64) $(LIB) -o lib$(MODULE_NAME)-arm64.jnilib - @$(CXX) -target x86_64-apple-macos11 $(CFLAGS1) -bundle $(WRAPPER_OBJECT_X86_64) $(LIB) -o lib$(MODULE_NAME)-x86_64.jnilib + @$(CXX) -target arm64-apple-macos12 $(CFLAGS1) -bundle $(WRAPPER_OBJECT_ARM64) $(LIB) -o lib$(MODULE_NAME)-arm64.jnilib + @$(CXX) -target x86_64-apple-macos12 $(CFLAGS1) -bundle $(WRAPPER_OBJECT_X86_64) $(LIB) -o lib$(MODULE_NAME)-x86_64.jnilib @mkdir -p $(WEBOTS_CONTROLLER_LIB_PATH)/java @lipo -create -output "$@" lib$(MODULE_NAME)-arm64.jnilib lib$(MODULE_NAME)-x86_64.jnilib @codesign -s - "$@" diff --git a/projects/humans/skin_animated_humans/libraries/bvh_util/src/bvh_util.c b/projects/humans/skin_animated_humans/libraries/bvh_util/src/bvh_util.c index cf08f213f40..2b7707e4a93 100644 --- a/projects/humans/skin_animated_humans/libraries/bvh_util/src/bvh_util.c +++ b/projects/humans/skin_animated_humans/libraries/bvh_util/src/bvh_util.c @@ -73,8 +73,8 @@ typedef struct WbuBvhMotionPrivate { // Utility functions // //***********************************// -static BvhMotionJointPrivate_t *add_new_joint(FILE *file, WbuBvhMotion motion, char *this_name, BvhMotionJointPrivate_t *parent, - int *channels_count) { +static BvhMotionJointPrivate_t *add_new_joint(FILE *file, WbuBvhMotion motion, const char *this_name, + BvhMotionJointPrivate_t *parent, int *channels_count) { // create and init new joint BvhMotionJointPrivate_t *new_joint = malloc(sizeof(BvhMotionJointPrivate_t)); new_joint->name = (char *)malloc(strlen(this_name) + 1); @@ -100,7 +100,7 @@ static BvhMotionJointPrivate_t *add_new_joint(FILE *file, WbuBvhMotion motion, c char line[MAX_LINE]; while (fgets(line, MAX_LINE, file)) { - char *token = strtok(line, DELIM); + const char *token = strtok(line, DELIM); // opening bracket of joint if (strcmp(token, "{") == 0) @@ -193,7 +193,7 @@ static BvhMotionJointPrivate_t *add_new_joint(FILE *file, WbuBvhMotion motion, c static void read_motion(FILE *file, WbuBvhMotion motion, int frame_channels_count) { int n_frames = motion->n_frames; - char *token; + const char *token; int joint_index; // init joints @@ -316,7 +316,7 @@ WbuBvhMotion wbu_bvh_read_file(const char *filename) { int channels_count = 0; char line[MAX_LINE]; while (fgets(line, MAX_LINE, file)) { - char *token; + const char *token; token = strtok(line, DELIM); // skeleton section if (strcmp(token, "HIERARCHY") == 0) @@ -476,7 +476,7 @@ void wbu_bvh_set_scale(WbuBvhMotion motion, double scale) { const double *wbu_bvh_get_root_translation(const WbuBvhMotion motion) { static double result[3]; int frame_index = motion->current_frame; - double *frame_position = motion->joint_list[0]->frame_position[frame_index]; + const double *frame_position = motion->joint_list[0]->frame_position[frame_index]; int i = 0; for (; i < 3; ++i) result[i] = frame_position[i] * motion->scale_factor; diff --git a/projects/objects/factory/conveyors/controllers/conveyor_belt/conveyor_belt.c b/projects/objects/factory/conveyors/controllers/conveyor_belt/conveyor_belt.c index eafb4aa693d..7dc9dda7da7 100644 --- a/projects/objects/factory/conveyors/controllers/conveyor_belt/conveyor_belt.c +++ b/projects/objects/factory/conveyors/controllers/conveyor_belt/conveyor_belt.c @@ -21,6 +21,7 @@ #include #include +// cppcheck-suppress constParameter int main(int argc, char *argv[]) { wb_robot_init(); assert(argc == 3); // speed and timer excepted as argument. diff --git a/projects/robots/bitcraze/crazyflie/controllers/crazyflie/pid_controller.c b/projects/robots/bitcraze/crazyflie/controllers/crazyflie/pid_controller.c index b6a47640cbf..a8023597a21 100644 --- a/projects/robots/bitcraze/crazyflie/controllers/crazyflie/pid_controller.c +++ b/projects/robots/bitcraze/crazyflie/controllers/crazyflie/pid_controller.c @@ -53,8 +53,8 @@ void init_pid_attitude_fixed_height_controller() { altitudeIntegrator = 0; } -void pid_attitude_fixed_height_controller(actual_state_t actual_state, desired_state_t *desired_state, gains_pid_t gains_pid, - double dt, motor_power_t *motorCommands) { +void pid_attitude_fixed_height_controller(actual_state_t actual_state, const desired_state_t *desired_state, + gains_pid_t gains_pid, double dt, motor_power_t *motorCommands) { control_commands_t control_commands = {0}; pid_fixed_height_controller(actual_state, desired_state, gains_pid, dt, &control_commands); pid_attitude_controller(actual_state, desired_state, gains_pid, dt, &control_commands); @@ -70,8 +70,8 @@ void pid_velocity_fixed_height_controller(actual_state_t actual_state, desired_s motor_mixing(control_commands, motorCommands); } -void pid_fixed_height_controller(actual_state_t actual_state, desired_state_t *desired_state, gains_pid_t gains_pid, double dt, - control_commands_t *control_commands) { +void pid_fixed_height_controller(actual_state_t actual_state, const desired_state_t *desired_state, gains_pid_t gains_pid, + double dt, control_commands_t *control_commands) { double altitudeError = desired_state->altitude - actual_state.altitude; double altitudeDerivativeError = (altitudeError - pastAltitudeError) / dt; control_commands->altitude = @@ -91,8 +91,8 @@ void motor_mixing(control_commands_t control_commands, motor_power_t *motorComma motorCommands->m4 = control_commands.altitude + control_commands.roll + control_commands.pitch - control_commands.yaw; } -void pid_attitude_controller(actual_state_t actual_state, desired_state_t *desired_state, gains_pid_t gains_pid, double dt, - control_commands_t *control_commands) { +void pid_attitude_controller(actual_state_t actual_state, const desired_state_t *desired_state, gains_pid_t gains_pid, + double dt, control_commands_t *control_commands) { // Calculate errors double pitchError = desired_state->pitch - actual_state.pitch; double pitchDerivativeError = (pitchError - pastPitchError) / dt; diff --git a/projects/robots/bitcraze/crazyflie/controllers/crazyflie/pid_controller.h b/projects/robots/bitcraze/crazyflie/controllers/crazyflie/pid_controller.h index 24909dbe103..2bd2e78e978 100644 --- a/projects/robots/bitcraze/crazyflie/controllers/crazyflie/pid_controller.h +++ b/projects/robots/bitcraze/crazyflie/controllers/crazyflie/pid_controller.h @@ -76,19 +76,19 @@ typedef struct gains_pid_s { float constrain(float value, const float minVal, const float maxVal); void init_pid_attitude_fixed_height_controller(); -void pid_attitude_fixed_height_controller(actual_state_t actual_state, desired_state_t *desired_state, gains_pid_t gains_pid, - double dt, motor_power_t *motorCommands); +void pid_attitude_fixed_height_controller(actual_state_t actual_state, const desired_state_t *desired_state, + gains_pid_t gains_pid, double dt, motor_power_t *motorCommands); void pid_velocity_fixed_height_controller(actual_state_t actual_state, desired_state_t *desired_state, gains_pid_t gains_pid, double dt, motor_power_t *motorCommands); -void pid_fixed_height_controller(actual_state_t actual_state, desired_state_t *desired_state, gains_pid_t gains_pid, double dt, - control_commands_t *control_commands); +void pid_fixed_height_controller(actual_state_t actual_state, const desired_state_t *desired_state, gains_pid_t gains_pid, + double dt, control_commands_t *control_commands); void motor_mixing(control_commands_t control_commands, motor_power_t *motorCommands); -void pid_attitude_controller(actual_state_t actual_state, desired_state_t *desired_state, gains_pid_t gains_pid, double dt, - control_commands_t *control_commands); +void pid_attitude_controller(actual_state_t actual_state, const desired_state_t *desired_state, gains_pid_t gains_pid, + double dt, control_commands_t *control_commands); void pid_horizontal_velocity_controller(actual_state_t actual_state, desired_state_t *desired_state, gains_pid_t gains_pid, double dt); diff --git a/projects/robots/bluebotics/shrimp/controllers/shrimp/shrimp.c b/projects/robots/bluebotics/shrimp/controllers/shrimp/shrimp.c index 1c8e803f2c0..fd081ed4050 100644 --- a/projects/robots/bluebotics/shrimp/controllers/shrimp/shrimp.c +++ b/projects/robots/bluebotics/shrimp/controllers/shrimp/shrimp.c @@ -53,7 +53,7 @@ static void print_keyboard_help() { * This function is simply used to display clearly the answers of the Shrimp * to our commands. */ -static void print_answer(unsigned char *answer) { +static void print_answer(const unsigned char *answer) { int i; char answer_string[MAX_STRING_SIZE]; @@ -181,7 +181,7 @@ static void run_step() { int main() { unsigned char buffer[MAX_BUFFER_SIZE]; - unsigned char *answer; + const unsigned char *answer; int position, in_position; wb_robot_init(); diff --git a/projects/robots/bluebotics/shrimp/controllers/shrimp/shrimp_protocol.c b/projects/robots/bluebotics/shrimp/controllers/shrimp/shrimp_protocol.c index 6ad3ae1e007..937bd5d6028 100644 --- a/projects/robots/bluebotics/shrimp/controllers/shrimp/shrimp_protocol.c +++ b/projects/robots/bluebotics/shrimp/controllers/shrimp/shrimp_protocol.c @@ -264,6 +264,7 @@ static void command_01(byte *answer) { answer[3] = SHRIMP_PATCH_NUMBER; } +// cppcheck-suppress constParameterPointer /* * This function allows to to set the speed and the steering angle of the * robot. diff --git a/projects/robots/epfl/lis/controllers/blimp/js.h b/projects/robots/epfl/lis/controllers/blimp/js.h index 14c6bf86d8f..c41828b814c 100644 --- a/projects/robots/epfl/lis/controllers/blimp/js.h +++ b/projects/robots/epfl/lis/controllers/blimp/js.h @@ -495,13 +495,13 @@ class jsJoystick { saturate[axis] = st; } - void setMinRange(float *axes) { + void setMinRange(const float *axes) { memcpy(min, axes, num_axes * sizeof(float)); } - void setMaxRange(float *axes) { + void setMaxRange(const float *axes) { memcpy(max, axes, num_axes * sizeof(float)); } - void setCenter(float *axes) { + void setCenter(const float *axes) { memcpy(center, axes, num_axes * sizeof(float)); } diff --git a/projects/robots/fujitsu/hoap2/controllers/hoap2/hoap2.c b/projects/robots/fujitsu/hoap2/controllers/hoap2/hoap2.c index 007383fd803..a388dac7139 100644 --- a/projects/robots/fujitsu/hoap2/controllers/hoap2/hoap2.c +++ b/projects/robots/fujitsu/hoap2/controllers/hoap2/hoap2.c @@ -133,6 +133,7 @@ static const char *joint_number_to_name(int num) { } } +// cppcheck-suppress constParameter int main(int argc, char *argv[]) { int i, sampling; int com_interval; @@ -189,7 +190,7 @@ int main(int argc, char *argv[]) { next_position[larm_joint_5] = 0.0; next_position[rarm_joint_5] = 0.0; - char *ptr = fgets(l, 500, file); + const char *ptr = fgets(l, 500, file); if (ptr == NULL) { fprintf(stderr, "Error while reading the %s file\n", filename); fclose(file); diff --git a/projects/robots/gctronic/e-puck/controllers/e-puck2_server/e-puck2_server.c b/projects/robots/gctronic/e-puck/controllers/e-puck2_server/e-puck2_server.c index 8fafeac0d68..03e108f8532 100644 --- a/projects/robots/gctronic/e-puck/controllers/e-puck2_server/e-puck2_server.c +++ b/projects/robots/gctronic/e-puck/controllers/e-puck2_server/e-puck2_server.c @@ -77,7 +77,7 @@ static bool socket_set_non_blocking(int fd) { static int socket_accept(int server_fd) { int cfd; struct sockaddr_in client; - struct hostent *client_info; + const struct hostent *client_info; #ifndef _WIN32 socklen_t asize; #else diff --git a/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/Communication.cpp b/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/Communication.cpp index f9ec32ea6db..e8b95909fa9 100644 --- a/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/Communication.cpp +++ b/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/Communication.cpp @@ -116,7 +116,7 @@ bool Communication::sendPacket(const Packet *packet) { return false; } -bool Communication::receivePacket(Packet *packet) { +bool Communication::receivePacket(const Packet *packet) { try { if (mSerial) { int packetSize = packet->size(); diff --git a/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/Communication.hpp b/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/Communication.hpp index e95ba010e3f..e8d7d76a5c7 100644 --- a/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/Communication.hpp +++ b/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/Communication.hpp @@ -32,7 +32,7 @@ class Communication { bool isInitialized() const { return mInitialized; } bool sendPacket(const Packet *packet); - bool receivePacket(Packet *packet); + bool receivePacket(const Packet *packet); char *talk(const char *source); char *readLine(); diff --git a/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/EPuckInputPacket.cpp b/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/EPuckInputPacket.cpp index 2a0f906e15b..762d339faea 100644 --- a/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/EPuckInputPacket.cpp +++ b/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/EPuckInputPacket.cpp @@ -116,7 +116,7 @@ void EPuckInputPacket::decode(int simulationTime, const EPuckOutputPacket &outpu int mode = (int)readUCharAt(currentPos++); int wh1 = (int)readUCharAt(currentPos++); // can be width or height depending on the mode int wh2 = (int)readUCharAt(currentPos++); // can be width or height depending on the mode - const unsigned char *rawImage = (const unsigned char *)&(data()[currentPos]); + const unsigned char *rawImage = reinterpret_cast(&(data()[currentPos])); Camera *camera = DeviceManager::instance()->camera(); camera->resetSensorRequested(); diff --git a/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/EPuckOutputPacket.cpp b/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/EPuckOutputPacket.cpp index 98bda764ace..06263747f52 100644 --- a/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/EPuckOutputPacket.cpp +++ b/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/EPuckOutputPacket.cpp @@ -89,7 +89,7 @@ void EPuckOutputPacket::apply(int simulationTime) { // the order of the sensors should match with EPuckInputPacket::decode() // accelerometer management - TripleValuesSensor *accelerometer = DeviceManager::instance()->accelerometer(); + const TripleValuesSensor *accelerometer = DeviceManager::instance()->accelerometer(); if (accelerometer->isSensorRequested()) { mAccelerometerRequested = true; append(static_cast(-'a')); @@ -99,7 +99,7 @@ void EPuckOutputPacket::apply(int simulationTime) { // manage the optional ground sensors // (send the command if at least one ground sensor is required) for (int i = 0; i < 3; i++) { - SingleValueSensor *gs = DeviceManager::instance()->groundSensor(i); + const SingleValueSensor *gs = DeviceManager::instance()->groundSensor(i); if (gs && gs->isSensorRequested()) { mGroundSensorRequested = true; append(static_cast(-'M')); @@ -111,7 +111,7 @@ void EPuckOutputPacket::apply(int simulationTime) { // manage the distance sensors // (send the command if at least one distance sensor is required) for (int i = 0; i < 8; i++) { - SingleValueSensor *ds = DeviceManager::instance()->distanceSensor(i); + const SingleValueSensor *ds = DeviceManager::instance()->distanceSensor(i); if (ds->isSensorRequested()) { mDistanceSensorRequested = true; append(static_cast(-'N')); @@ -123,7 +123,7 @@ void EPuckOutputPacket::apply(int simulationTime) { // manage the light sensors // (send the command if at least one light sensor is required) for (int i = 0; i < 8; i++) { - SingleValueSensor *ls = DeviceManager::instance()->lightSensor(i); + const SingleValueSensor *ls = DeviceManager::instance()->lightSensor(i); if (ls->isSensorRequested()) { mLightSensorRequested = true; append(static_cast(-'O')); @@ -143,7 +143,7 @@ void EPuckOutputPacket::apply(int simulationTime) { // camera management // it's better to put the camera at the end in case of // retrieval after transmission troubles - Camera *camera = DeviceManager::instance()->camera(); + const Camera *camera = DeviceManager::instance()->camera(); if (camera->isSensorRequested()) { mCameraRequested = true; append(static_cast(-'I')); diff --git a/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/Serial.cpp b/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/Serial.cpp index 36a526b3e81..d5f79e32eee 100644 --- a/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/Serial.cpp +++ b/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_bluetooth/Serial.cpp @@ -384,7 +384,7 @@ void Serial::updatePorts() { printf("IOServiceMatching failed.\n"); CFDictionarySetValue(classesToMatch, CFSTR(kIOSerialBSDTypeKey), CFSTR(kIOSerialBSDRS232Type)); - kernResult = IOServiceGetMatchingServices(kIOMasterPortDefault, classesToMatch, &serialPortIterator); + kernResult = IOServiceGetMatchingServices(kIOMainPortDefault, classesToMatch, &serialPortIterator); if (kernResult != KERN_SUCCESS) printf("IOServiceGetMatchingServices failed: %d\n", kernResult); io_object_t service; diff --git a/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_wifi/Communication.cpp b/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_wifi/Communication.cpp index 129a122c9f0..825d72ac6c4 100644 --- a/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_wifi/Communication.cpp +++ b/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_wifi/Communication.cpp @@ -60,7 +60,7 @@ Communication::~Communication() { bool Communication::initialize(const string &ip) { struct sockaddr_in address; - struct hostent *server; + const struct hostent *server; int rc; mFd = socket(AF_INET, SOCK_STREAM, 0); if (mFd == -1) { @@ -78,7 +78,7 @@ bool Communication::initialize(const string &ip) { cleanup(); return false; } - rc = connect(mFd, (struct sockaddr *)&address, sizeof(struct sockaddr)); + rc = connect(mFd, reinterpret_cast(&address), sizeof(struct sockaddr)); if (rc == -1) { fprintf(stderr, "Cannot connect to the server\n"); cleanup(); diff --git a/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_wifi/EPuckCommandPacket.cpp b/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_wifi/EPuckCommandPacket.cpp index 3bf4ce47862..e4cda3059d8 100644 --- a/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_wifi/EPuckCommandPacket.cpp +++ b/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_wifi/EPuckCommandPacket.cpp @@ -73,7 +73,7 @@ int EPuckCommandPacket::apply(int simulationTime) { // send the led commands mData[7] = 0; for (int i = 0; i < 10; i++) { - Led *led = DeviceManager::instance()->led(i); + const Led *led = DeviceManager::instance()->led(i); const char d = mData[7]; const int state = led->state(); switch (led->index()) { diff --git a/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_wifi/Wrapper.cpp b/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_wifi/Wrapper.cpp index f73eae5ecb6..f13d761966e 100644 --- a/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_wifi/Wrapper.cpp +++ b/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_wifi/Wrapper.cpp @@ -177,7 +177,7 @@ int Wrapper::robotStep(int step) { break; if (command == 1 && got_camera_image) break; - if (command == 0 && header == 3) + if (command == 0) break; #ifdef LOG_COMMUNICATION_TIME @@ -256,7 +256,7 @@ int Wrapper::robotStep(int step) { } } } while (true); - Camera *camera = DeviceManager::instance()->camera(); + const Camera *camera = DeviceManager::instance()->camera(); if (camera->isEnabled()) { unsigned char *bgraImage = static_cast(malloc(160 * 120 * 4)); if (camera->rawToBgraImage(bgraImage, static_cast(image))) { @@ -266,7 +266,7 @@ int Wrapper::robotStep(int step) { log("Cannot rawToBgraImage\n"); free(bgraImage); } - TripleValuesSensor *accelerometer = DeviceManager::instance()->accelerometer(); + const TripleValuesSensor *accelerometer = DeviceManager::instance()->accelerometer(); if (accelerometer->isEnabled()) { const double calibration_k[3] = {-9.81 / 800.0, 9.81 / 800.0, 9.81 / 800.0}; const double calibration_offset = -2000.0; @@ -383,6 +383,7 @@ void Wrapper::ledSet(WbDeviceTag tag, int state) { led->setState(state); } +// cppcheck-suppress constParameterPointer void *Wrapper::callCustomFunction(void *args) { return NULL; } diff --git a/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_wifi/test.c b/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_wifi/test.c index bf876023e80..cf0aaac4660 100644 --- a/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_wifi/test.c +++ b/projects/robots/gctronic/e-puck/plugins/remote_controls/e-puck_wifi/test.c @@ -32,7 +32,7 @@ static void save_bmp_image(const char *filename, const unsigned char *image, int int filesize = 54 + 3 * width * height; unsigned char bmpfileheader[14] = {'B', 'M', 0, 0, 0, 0, 0, 0, 0, 0, 54, 0, 0, 0}; unsigned char bmpinfoheader[40] = {40, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 24, 0}; - unsigned char bmppad[3] = {0, 0, 0}; + const unsigned char bmppad[3] = {0, 0, 0}; bmpfileheader[2] = (unsigned char)(filesize); bmpfileheader[3] = (unsigned char)(filesize >> 8); bmpfileheader[4] = (unsigned char)(filesize >> 16); @@ -77,7 +77,7 @@ static void cleanup() { int main(int argc, const char *argv[]) { struct sockaddr_in address; - struct hostent *server; + const struct hostent *server; int rc; const char *ip = argv[1]; diff --git a/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/Makefile b/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/Makefile index bf117298c74..2809e56e36e 100644 --- a/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/Makefile +++ b/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/Makefile @@ -81,7 +81,8 @@ WEBOTS_HOME_PATH?=$(subst $(space),\ ,$(strip $(subst \,/,$(WEBOTS_HOME)))) include $(WEBOTS_HOME_PATH)/resources/Makefile.include # wb_robot_get_controller_name() is deprecated -WBCFLAGS += -std=c++17 -Wno-deprecated-declarations +WBCFLAGS += -Wno-deprecated-declarations +WBCXXFLAGS += -std=c++17 MOC_SOURCES = $(addprefix $(BUILD_DIR)/,$(notdir $(HPP_FILES_TO_MOC:.hpp=.moc.cpp))) MOC_DIRECTORIES = $(sort $(dir $(HPP_FILES_TO_MOC))) diff --git a/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/Automaton.cpp b/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/Automaton.cpp index 425bbfba57e..0806f040f71 100644 --- a/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/Automaton.cpp +++ b/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/Automaton.cpp @@ -61,6 +61,7 @@ void Automaton::addTransition(Transition *t) { void Automaton::deleteAllObjects() { QList states; foreach (AutomatonObject *object, mObjects) { + // cppcheck-suppress constVariablePointer State *state = dynamic_cast(object); if (state) { states.append(state); @@ -121,6 +122,7 @@ void Automaton::deleteSelectedObjects() { QList transitions; foreach (AutomatonObject *object, mObjects) { if (object->isSelected()) { + // cppcheck-suppress constVariablePointer Transition *transition = dynamic_cast(object); if (transition) transitions.append(transition); @@ -133,6 +135,7 @@ void Automaton::deleteSelectedObjects() { QList states; foreach (AutomatonObject *object, mObjects) { if (object->isSelected()) { + // cppcheck-suppress constVariablePointer State *state = dynamic_cast(object); if (state) states.append(state); @@ -144,9 +147,9 @@ void Automaton::deleteSelectedObjects() { int Automaton::computeNumberOfSelectedStates() const { int counter = 0; - foreach (AutomatonObject *object, mObjects) + foreach (const AutomatonObject *object, mObjects) if (object->isSelected()) { - State *state = dynamic_cast(object); + const State *state = dynamic_cast(object); if (state) counter++; } @@ -155,7 +158,7 @@ int Automaton::computeNumberOfSelectedStates() const { int Automaton::computeNumberOfSelectedItems() const { int counter = 0; - foreach (AutomatonObject *object, mObjects) + foreach (const AutomatonObject *object, mObjects) if (object->isSelected()) counter++; return counter; @@ -264,13 +267,13 @@ void Automaton::fromString(const QString &string) { QString Automaton::toString() const { QString out; - foreach (AutomatonObject *object, mObjects) { - State *state = dynamic_cast(object); + foreach (const AutomatonObject *object, mObjects) { + const State *state = dynamic_cast(object); if (state) out += state->toString() + "\n"; } - foreach (AutomatonObject *object, mObjects) { - Transition *transition = dynamic_cast(object); + foreach (const AutomatonObject *object, mObjects) { + const Transition *transition = dynamic_cast(object); if (transition) out += transition->toString() + "\n"; } diff --git a/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/AutomatonScene.cpp b/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/AutomatonScene.cpp index 280367318f6..60aeb8d29c2 100644 --- a/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/AutomatonScene.cpp +++ b/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/AutomatonScene.cpp @@ -107,8 +107,8 @@ void AutomatonScene::mouseReleaseEvent(QGraphicsSceneMouseEvent *event) { endItems.removeFirst(); if (startItems.count() > 0 && endItems.count() > 0 && startItems.first() != endItems.first()) { - StateRepresentation *start = dynamic_cast(startItems.first()); - StateRepresentation *end = dynamic_cast(endItems.first()); + const StateRepresentation *start = dynamic_cast(startItems.first()); + const StateRepresentation *end = dynamic_cast(endItems.first()); if (start && end) { QPointF midPoint(mTransitionCreationLine->line().pointAt(0.5)); mModel->automaton()->createTransition(midPoint, start->state(), end->state()); @@ -127,8 +127,8 @@ void AutomatonScene::mouseReleaseEvent(QGraphicsSceneMouseEvent *event) { QGraphicsItem *AutomatonScene::findRepresentationFromAutomatonObject(AutomatonObject *o) const { foreach (QGraphicsItem *item, items()) { - StateRepresentation *sr = dynamic_cast(item); - TransitionRepresentation *tr = dynamic_cast(item); + const StateRepresentation *sr = dynamic_cast(item); + const TransitionRepresentation *tr = dynamic_cast(item); if (sr && sr->state() == o) return item; else if (tr && tr->transition() == o) @@ -147,8 +147,8 @@ TransitionRepresentation *AutomatonScene::findTransitionRepresentationFromTransi void AutomatonScene::updateEnabled(bool enabled) { foreach (QGraphicsItem *item, items()) { - StateRepresentation *sr = dynamic_cast(item); - TransitionRepresentation *tr = dynamic_cast(item); + const StateRepresentation *sr = dynamic_cast(item); + const TransitionRepresentation *tr = dynamic_cast(item); if (sr || tr) item->setEnabled(enabled); } diff --git a/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/BotStudioWindow.cpp b/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/BotStudioWindow.cpp index 37c01eb0b6b..a32d89299b8 100644 --- a/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/BotStudioWindow.cpp +++ b/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/BotStudioWindow.cpp @@ -230,7 +230,7 @@ void BotStudioWindow::openStateMachine() { if (dialog.exec()) fileNames = dialog.selectedFiles(); - if (fileNames.size() > 0 && !fileNames.isEmpty()) { + if (!fileNames.isEmpty()) { mFile->setFileName(fileNames[0]); loadStateMachine(); updateToolBars(); @@ -295,7 +295,7 @@ void BotStudioWindow::saveAsStateMachine() { if (dialog.exec()) fileNames = dialog.selectedFiles(); - if (fileNames.size() > 0 && !fileNames.isEmpty()) + if (!fileNames.isEmpty()) mFile->setFileName(fileNames[0]); saveStateMachine(); diff --git a/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/State.hpp b/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/State.hpp index 0493e4014ba..91646c01fbe 100644 --- a/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/State.hpp +++ b/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/State.hpp @@ -49,7 +49,7 @@ class State : public AutomatonObject { void removeTransition(Transition *t); void removeTransitionAt(int i); void removeAllTransitions(); - QList transitions() const { return mTransition; } + const QList &transitions() const { return mTransition; } void fromString(const QString &string); void fromStringVersion3(const QString &string); // backward compatibility code diff --git a/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/SwitchWidget.cpp b/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/SwitchWidget.cpp index 661ed097241..3afaa286fda 100644 --- a/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/SwitchWidget.cpp +++ b/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/core/SwitchWidget.cpp @@ -57,9 +57,9 @@ SwitchWidget::~SwitchWidget() { } void SwitchWidget::selectWidget() { - AutomatonObject *object = mModel->automaton()->findSelectedObject(); - State *state = dynamic_cast(object); - Transition *transition = dynamic_cast(object); + const AutomatonObject *object = mModel->automaton()->findSelectedObject(); + const State *state = dynamic_cast(object); + const Transition *transition = dynamic_cast(object); if (state) { RobotActuatorCommand *actuatorCommand = state->actuatorCommand(); diff --git a/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/e-puck/EPuckConditionWidget.cpp b/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/e-puck/EPuckConditionWidget.cpp index 97d4195e2f3..abad4dd552c 100644 --- a/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/e-puck/EPuckConditionWidget.cpp +++ b/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/e-puck/EPuckConditionWidget.cpp @@ -112,7 +112,7 @@ void EPuckConditionWidget::blockSlidersSignals(bool block) { void EPuckConditionWidget::setSensorCondition(RobotSensorCondition *condition) { blockSlidersSignals(true); RobotConditionWidget::setSensorCondition(condition); - EPuckSensorCondition *esc = static_cast(sensorCondition()); + const EPuckSensorCondition *esc = static_cast(sensorCondition()); for (int i = 0; i < EPuckFacade::NUMBER_OF_DISTANCE_SENSORS; i++) { mDistanceSensorSliders[i]->setInverted(esc->distanceSensorInverted(i)); @@ -131,7 +131,7 @@ void EPuckConditionWidget::setSensorCondition(RobotSensorCondition *condition) { } void EPuckConditionWidget::updateSensorCondition() { - EPuckSlider *slider = dynamic_cast(sender()); + const EPuckSlider *slider = dynamic_cast(sender()); if (slider) { blockSlidersSignals(true); diff --git a/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/e-puck/EPuckStateWidget.cpp b/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/e-puck/EPuckStateWidget.cpp index 851e107a6a5..b8ca24d46cc 100644 --- a/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/e-puck/EPuckStateWidget.cpp +++ b/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/e-puck/EPuckStateWidget.cpp @@ -73,7 +73,7 @@ EPuckStateWidget::~EPuckStateWidget() { void EPuckStateWidget::setActuatorCommand(RobotActuatorCommand *command) { RobotStateWidget::setActuatorCommand(command); - EPuckActuatorCommand *eac = static_cast(actuatorCommand()); + const EPuckActuatorCommand *eac = static_cast(actuatorCommand()); mSpeedSliders[EPuckFacade::LEFT]->setValue(eac->leftSpeed()); mSpeedSliders[EPuckFacade::RIGHT]->setValue(eac->rightSpeed()); @@ -82,7 +82,7 @@ void EPuckStateWidget::setActuatorCommand(RobotActuatorCommand *command) { } void EPuckStateWidget::updateSpeedCommand() { - EPuckSlider *slider = dynamic_cast(sender()); + const EPuckSlider *slider = dynamic_cast(sender()); if (slider) { EPuckActuatorCommand *eac = static_cast(actuatorCommand()); int value = slider->value(); @@ -95,7 +95,7 @@ void EPuckStateWidget::updateSpeedCommand() { } void EPuckStateWidget::updateLedCommand() { - EPuckLedButton *button = dynamic_cast(sender()); + const EPuckLedButton *button = dynamic_cast(sender()); if (button) { EPuckActuatorCommand *eac = static_cast(actuatorCommand()); int value = button->value(); diff --git a/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/e-puck/EPuckViewWidget.cpp b/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/e-puck/EPuckViewWidget.cpp index dd8a9f2fdcb..c7312c5db1c 100644 --- a/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/e-puck/EPuckViewWidget.cpp +++ b/projects/robots/gctronic/e-puck/plugins/robot_windows/botstudio/e-puck/EPuckViewWidget.cpp @@ -97,7 +97,7 @@ EPuckViewWidget::~EPuckViewWidget() { void EPuckViewWidget::updateValues() { setUpdatesEnabled(false); - EPuckFacade *epuck = static_cast(mModel->robotFacade()); + const EPuckFacade *epuck = static_cast(mModel->robotFacade()); for (int i = 0; i < EPuckFacade::NUMBER_OF_DISTANCE_SENSORS; i++) mDistanceSensorSliders[i]->setValue(epuck->distanceSensorValue(i)); diff --git a/projects/robots/gctronic/elisa/controllers/elisa3/elisa3.c b/projects/robots/gctronic/elisa/controllers/elisa3/elisa3.c index cb377f9ccf2..33891c528b4 100644 --- a/projects/robots/gctronic/elisa/controllers/elisa3/elisa3.c +++ b/projects/robots/gctronic/elisa/controllers/elisa3/elisa3.c @@ -52,6 +52,7 @@ static void init_devices() { step(); } +// cppcheck-suppress constParameter int main(int argc, char *argv[]) { /* define variables */ long int currentColor = 0; diff --git a/projects/robots/k-team/khepera1/controllers/tcpip/client.c b/projects/robots/k-team/khepera1/controllers/tcpip/client.c index 8199d6e4af7..b5a4f0bb0e9 100644 --- a/projects/robots/k-team/khepera1/controllers/tcpip/client.c +++ b/projects/robots/k-team/khepera1/controllers/tcpip/client.c @@ -42,7 +42,7 @@ int main(int argc, char *argv[]) { struct sockaddr_in address; - struct hostent *server; + const struct hostent *server; int fd, rc; char buffer[256]; diff --git a/projects/robots/k-team/khepera1/controllers/tcpip/tcpip.c b/projects/robots/k-team/khepera1/controllers/tcpip/tcpip.c index e772d7050f4..4e7752d87e0 100644 --- a/projects/robots/k-team/khepera1/controllers/tcpip/tcpip.c +++ b/projects/robots/k-team/khepera1/controllers/tcpip/tcpip.c @@ -85,7 +85,7 @@ static int accept_client(int server_fd) { #else int asize; #endif - struct hostent *client_info; + const struct hostent *client_info; asize = sizeof(struct sockaddr_in); diff --git a/projects/robots/kondo/khr-2hv/controllers/khr-2hv_demo/khr2.cpp b/projects/robots/kondo/khr-2hv/controllers/khr-2hv_demo/khr2.cpp index a9b0c5d31e7..13e3c95847f 100644 --- a/projects/robots/kondo/khr-2hv/controllers/khr-2hv_demo/khr2.cpp +++ b/projects/robots/kondo/khr-2hv/controllers/khr-2hv_demo/khr2.cpp @@ -52,6 +52,7 @@ const char *motion_files[NUMBER_OF_MOTION_FILES + 1] = {"2HV001RC_Walk_Forward.R "2HV024RC_Startup2.RCB", // 23 NULL}; +// cppcheck-suppress constParameter int main(int argc, char *argv[]) { // init wb_robot_init(); diff --git a/projects/robots/kondo/khr-2hv/controllers/khr-2hv_demo/rcb3_simulator.cpp b/projects/robots/kondo/khr-2hv/controllers/khr-2hv_demo/rcb3_simulator.cpp index 77421ab11b1..63d84865d6f 100644 --- a/projects/robots/kondo/khr-2hv/controllers/khr-2hv_demo/rcb3_simulator.cpp +++ b/projects/robots/kondo/khr-2hv/controllers/khr-2hv_demo/rcb3_simulator.cpp @@ -694,7 +694,7 @@ bool rcb3_simulator::read_rcb_file(const char *filename, RCBMotion &motion) { item.m_name = NULL; while (!feof(f)) { memset(buffer, 0, 512); - char *ptr = fgets(buffer, 512, f); + const char *ptr = fgets(buffer, 512, f); if (ptr == NULL) break; if (buffer[0] == '[') { @@ -754,7 +754,7 @@ bool rcb3_simulator::read_rcb_file(const char *filename, RCBMotion &motion) { else if (strncmp(buffer, "Name", 4) == 0) item.m_name = strdup(buffer + 5); else if (strncmp(buffer, "Prm", 3) == 0) { - char *token = strtok(buffer + 4, ","); + const char *token = strtok(buffer + 4, ","); while (token) { int v = atoi(token); token = strtok(NULL, ","); @@ -767,7 +767,7 @@ bool rcb3_simulator::read_rcb_file(const char *filename, RCBMotion &motion) { if (strstr(buffer, "Origin") != NULL) { link.m_origin = atoi(buffer + 7); } else if (strstr(buffer, "Point") != NULL) { - char *token = strtok(buffer + 6, ", "); + const char *token = strtok(buffer + 6, ", "); while (token) { if (isdigit(*token)) { int v = atoi(token); diff --git a/projects/robots/kuka/youbot/libraries/youbot_control/include/base.h b/projects/robots/kuka/youbot/libraries/youbot_control/include/base.h index a71767cce53..e6483bc46f4 100644 --- a/projects/robots/kuka/youbot/libraries/youbot_control/include/base.h +++ b/projects/robots/kuka/youbot/libraries/youbot_control/include/base.h @@ -37,7 +37,7 @@ void base_turn_right(); void base_strafe_left(); void base_strafe_right(); -void base_move(); +void base_move(double vx, double vy, double omega); void base_forwards_increment(); void base_backwards_increment(); void base_turn_left_increment(); diff --git a/projects/robots/kuka/youbot/libraries/youbot_control/src/base.c b/projects/robots/kuka/youbot/libraries/youbot_control/src/base.c index 0aca8cf751a..f06ca2478a6 100644 --- a/projects/robots/kuka/youbot/libraries/youbot_control/src/base.c +++ b/projects/robots/kuka/youbot/libraries/youbot_control/src/base.c @@ -66,7 +66,7 @@ static void base_set_wheel_velocity(WbDeviceTag t, double velocity) { wb_motor_set_velocity(t, velocity); } -static void base_set_wheel_speeds_helper(double speeds[4]) { +static void base_set_wheel_speeds_helper(const double speeds[4]) { int i; for (i = 0; i < 4; i++) base_set_wheel_velocity(wheels[i], speeds[i]); diff --git a/projects/robots/robotis/darwin-op/controllers/soccer/Soccer.cpp b/projects/robots/robotis/darwin-op/controllers/soccer/Soccer.cpp index 2609be04085..070b0153ba9 100644 --- a/projects/robots/robotis/darwin-op/controllers/soccer/Soccer.cpp +++ b/projects/robots/robotis/darwin-op/controllers/soccer/Soccer.cpp @@ -158,6 +158,7 @@ void Soccer::run() { const double acc_step = 20; while (true) { + // cppcheck-suppress variableScope double x, y, neckPosition, headPosition; bool ballInFieldOfView = getBallCenter(x, y); const double *acc = mAccelerometer->getValues(); diff --git a/projects/robots/robotis/darwin-op/libraries/managers/src/RobotisOp2MotionManager.cpp b/projects/robots/robotis/darwin-op/libraries/managers/src/RobotisOp2MotionManager.cpp index 76348ab3e00..24441aa60ec 100644 --- a/projects/robots/robotis/darwin-op/libraries/managers/src/RobotisOp2MotionManager.cpp +++ b/projects/robots/robotis/darwin-op/libraries/managers/src/RobotisOp2MotionManager.cpp @@ -187,7 +187,7 @@ void RobotisOp2MotionManager::playPage(int id, bool sync) { } else { InitMotionAsync(); mPage = new Action::PAGE; - if (!(mAction->LoadPage(id, (Action::PAGE *)mPage))) + if (!(mAction->LoadPage(id, static_cast(mPage)))) cerr << "Cannot load the page" << endl; } #endif @@ -278,21 +278,21 @@ void RobotisOp2MotionManager::step(int duration) { } else if (mWait > 0) mWait--; else { - if (mStepnum < ((Action::PAGE *)mPage)->header.stepnum) { + if (mStepnum < static_cast(mPage)->header.stepnum) { for (int k = 0; k < DMM_NMOTORS; k++) - mTargetPositions[k] = valueToPosition(((Action::PAGE *)mPage)->step[mStepnum].position[k + 1]); - mStepNumberToAchieveTarget = (8 * ((Action::PAGE *)mPage)->step[mStepnum].time) / mBasicTimeStep; + mTargetPositions[k] = valueToPosition(static_cast(mPage)->step[mStepnum].position[k + 1]); + mStepNumberToAchieveTarget = (8 * static_cast(mPage)->step[mStepnum].time) / mBasicTimeStep; if (mStepNumberToAchieveTarget == 0) mStepNumberToAchieveTarget = 1; - mWait = (8 * ((Action::PAGE *)mPage)->step[mStepnum].pause) / mBasicTimeStep + 0.5; + mWait = (8 * static_cast(mPage)->step[mStepnum].pause) / mBasicTimeStep + 0.5; mStepnum++; step(duration); - } else if (mRepeat < (((Action::PAGE *)mPage)->header.repeat)) { + } else if (mRepeat < (static_cast(mPage)->header.repeat)) { mRepeat++; mStepnum = 0; step(duration); - } else if (((Action::PAGE *)mPage)->header.next != 0) - playPage(((Action::PAGE *)mPage)->header.next, true); + } else if (static_cast(mPage)->header.next != 0) + playPage(static_cast(mPage)->header.next, true); else mMotionPlaying = false; } diff --git a/projects/robots/robotis/darwin-op/transfer/src/Motion.cpp b/projects/robots/robotis/darwin-op/transfer/src/Motion.cpp index 2597dee0cd2..e7819bf28ca 100644 --- a/projects/robots/robotis/darwin-op/transfer/src/Motion.cpp +++ b/projects/robots/robotis/darwin-op/transfer/src/Motion.cpp @@ -199,7 +199,7 @@ void Motion::playStep() { for (poseIt = mPoses.begin(); poseIt != mPoses.end(); ++poseIt) { Pose *pose = *poseIt; if (pose->time <= mElapsed) { - MotorCommand *command = pose->commands[i]; + const MotorCommand *command = pose->commands[i]; if (command->defined) { beforeTime = pose->time; beforeValue = command->value; @@ -213,7 +213,7 @@ void Motion::playStep() { for (poseRIt = mPoses.rbegin(); poseRIt != mPoses.rend(); ++poseRIt) { Pose *pose = *poseRIt; if (pose->time >= mElapsed) { - MotorCommand *command = pose->commands[i]; + const MotorCommand *command = pose->commands[i]; if (command->defined) { afterTime = pose->time; afterValue = command->value; diff --git a/projects/robots/softbank/nao/controllers/nao_soccer_player/nao_soccer_player.c b/projects/robots/softbank/nao/controllers/nao_soccer_player/nao_soccer_player.c index 096d15860b2..0ea689c41df 100644 --- a/projects/robots/softbank/nao/controllers/nao_soccer_player/nao_soccer_player.c +++ b/projects/robots/softbank/nao/controllers/nao_soccer_player/nao_soccer_player.c @@ -89,7 +89,7 @@ static void load_motion_list() { const char *motion_dir = "../../motions"; DIR *d = opendir(motion_dir); if (d) { - struct dirent *dir; + const struct dirent *dir; struct Motion *current_motion = NULL; while ((dir = readdir(d)) != NULL) { const char *name = dir->d_name; diff --git a/projects/robots/sony/aibo/libraries/mtn/mtn.c b/projects/robots/sony/aibo/libraries/mtn/mtn.c index fa24de08df3..03ffd4de55a 100644 --- a/projects/robots/sony/aibo/libraries/mtn/mtn.c +++ b/projects/robots/sony/aibo/libraries/mtn/mtn.c @@ -341,11 +341,11 @@ void mtn_delete(MTN *mtn) { free(mtn); } -int mtn_get_length(MTN *mtn) { +int mtn_get_length(const MTN *mtn) { return mtn->length; } -int mtn_get_time(MTN *mtn) { +int mtn_get_time(const MTN *mtn) { return mtn->current_time; } @@ -354,7 +354,7 @@ void mtn_play(MTN *mtn) { // TODO: check for possible joint control clashes before appending to the running list } -int mtn_is_over(MTN *mtn) { +int mtn_is_over(const MTN *mtn) { return !list_contains(mtn); // rationale: an MTN is over when it reaches its final position; // when that happens, it is removed from the simultaneous play queue @@ -364,7 +364,7 @@ const char *mtn_get_error() { return mtn_last_error; } -void mtn_fprint(FILE *fd, MTN *mtn) { +void mtn_fprint(FILE *fd, const MTN *mtn) { int i, j; fprintf(fd, "MTN version:\t%d.%d\n", mtn->major_version, mtn->minor_version); fprintf(fd, "# keyframes:\t%d\n", mtn->number_of_keyframes); diff --git a/projects/robots/sony/aibo/libraries/mtn/mtn.h b/projects/robots/sony/aibo/libraries/mtn/mtn.h index 18e44160dda..94687aa2280 100644 --- a/projects/robots/sony/aibo/libraries/mtn/mtn.h +++ b/projects/robots/sony/aibo/libraries/mtn/mtn.h @@ -45,16 +45,16 @@ void mtn_play(MTN *mtn); void mtn_step(int ms); // total length of the movement in milliseconds -int mtn_get_length(MTN *mtn); +int mtn_get_length(const MTN *mtn); // current time (ms) of the execution of the MTN file -int mtn_get_time(MTN *mtn); +int mtn_get_time(const MTN *mtn); // return 1 if the MTN movement has completed, 0 otherwise -int mtn_is_over(MTN *mtn); +int mtn_is_over(const MTN *mtn); // used for debugging -void mtn_fprint(FILE *fd, MTN *mtn); +void mtn_fprint(FILE *fd, const MTN *mtn); // delete the resources used by a MTN object void mtn_delete(MTN *mtn); diff --git a/projects/samples/contests/ratslife/controllers/contest_manager/maze_builder.c b/projects/samples/contests/ratslife/controllers/contest_manager/maze_builder.c index f0449c7491b..214382793c8 100644 --- a/projects/samples/contests/ratslife/controllers/contest_manager/maze_builder.c +++ b/projects/samples/contests/ratslife/controllers/contest_manager/maze_builder.c @@ -117,17 +117,17 @@ static void place_interval(double x, double y) { } // return the x position in meter of a given cell -static double cell_get_x_pos(Cell *c) { +static double cell_get_x_pos(const Cell *c) { return RATIO * c->pos_x; } // return the y position in meter of a given cell -static double cell_get_y_pos(Cell *c) { +static double cell_get_y_pos(const Cell *c) { return RATIO * c->pos_y; } // return the angle in radian that a special cell should have -static double cell_get_angle(Cell *c) { +static double cell_get_angle(const Cell *c) { if (c->feeder != None) { switch (c->feeder) { case North: @@ -159,19 +159,19 @@ static double cell_get_angle(Cell *c) { } // return the x position in meter of a given link -static double link_get_x_pos(Link *l) { +static double link_get_x_pos(const Link *l) { return 0.5 * (cell_get_x_pos(l->cell_A) + cell_get_x_pos(l->cell_B)); } // return the y position in meter of a given link -static double link_get_y_pos(Link *l) { +static double link_get_y_pos(const Link *l) { return 0.5 * (cell_get_y_pos(l->cell_A) + cell_get_y_pos(l->cell_B)); } // return the angle in radian that a link should have -static double link_get_angle(Link *l) { - Cell *a = l->cell_A; - Cell *b = l->cell_B; +static double link_get_angle(const Link *l) { + const Cell *a = l->cell_A; + const Cell *b = l->cell_B; if (a->pos_x != b->pos_x) return 0.0; else if (a->pos_y != b->pos_y) @@ -198,7 +198,7 @@ void build_maze(Maze *maze) { // place the internal walls LLIST *links = maze->links; while (links) { - Link *link = links->data; + const Link *link = links->data; if (link->wall) place_wall(link_get_x_pos(link), link_get_y_pos(link), link_get_angle(link)); links = links->next; @@ -224,7 +224,7 @@ void build_maze(Maze *maze) { for (k = 0; k < dim; k++) { Cell *cell = maze->cells[k]; for (l = 0; l < cell->link_number; l++) { - Link *link = cell->links[l]; + const Link *link = cell->links[l]; if (link->wall) { double dx = px - link_get_x_pos(link); double dy = py - link_get_y_pos(link); @@ -244,7 +244,7 @@ void build_maze(Maze *maze) { // place the feeders and the e-pucks for (i = 0; i < dim; i++) { - Cell *c = maze->cells[i]; + const Cell *c = maze->cells[i]; if (c->feeder != None) place_feeder(cell_get_x_pos(c), cell_get_y_pos(c), cell_get_angle(c)); else if (c->init_pos != None) diff --git a/projects/samples/contests/ratslife/controllers/contest_manager/maze_generator.c b/projects/samples/contests/ratslife/controllers/contest_manager/maze_generator.c index 2247d21fcef..14f91d5cd42 100644 --- a/projects/samples/contests/ratslife/controllers/contest_manager/maze_generator.c +++ b/projects/samples/contests/ratslife/controllers/contest_manager/maze_generator.c @@ -62,7 +62,7 @@ static Cell *get_linked_cell(const Cell *c, const Link *l) { } // get the orientation of cell b regard to cell a -static Orientation get_orientation(Cell *a, Cell *b) { +static Orientation get_orientation(const Cell *a, const Cell *b) { if (a->pos_x > b->pos_x) return West; else if (a->pos_x < b->pos_x) @@ -282,7 +282,7 @@ void display_maze(Maze *maze, WbDeviceTag display) { wb_display_set_color(display, black); for (j = 0; j < maze->height; j++) { for (i = 0; i < maze->width; i++) { - Cell *c = maze->cells[maze->width * j + i]; + const Cell *c = maze->cells[maze->width * j + i]; int indexX = (2 * i + 1); int indexY = (2 * j + 1); if (c->feeder != None) { @@ -297,7 +297,7 @@ void display_maze(Maze *maze, WbDeviceTag display) { } for (w = 0; w < c->link_number; w++) { if (c->links[w]->wall) { - Cell *n = get_linked_cell(c, c->links[w]); + const Cell *n = get_linked_cell(c, c->links[w]); Orientation o = get_orientation(c, n); switch (o) { case North: 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 8be1d7b6734..9be182ac975 100644 --- a/projects/samples/contests/ratslife/controllers/contest_manager/round_manager.c +++ b/projects/samples/contests/ratslife/controllers/contest_manager/round_manager.c @@ -128,7 +128,7 @@ static void move_viewpoint() { static void init_mode() { mode = COMMON; - char *ratslife_env_var = getenv("WEBOTS_RATSLIFE"); + const char *ratslife_env_var = getenv("WEBOTS_RATSLIFE"); if (ratslife_env_var) { if (0 == strcmp(ratslife_env_var, "CONTEST")) { mode = CONTEST; diff --git a/projects/samples/contests/tower_of_hanoi/controllers/hanoi/hanoi.c b/projects/samples/contests/tower_of_hanoi/controllers/hanoi/hanoi.c index 0c46d912486..457275fec3c 100644 --- a/projects/samples/contests/tower_of_hanoi/controllers/hanoi/hanoi.c +++ b/projects/samples/contests/tower_of_hanoi/controllers/hanoi/hanoi.c @@ -119,13 +119,13 @@ static void automatic_behavior() { double distance_arm0_platform = 0.2; double distance_arm0_robot_center = 0.189; double distance_origin_platform = 1.0; - double angles[3] = {0.0, 2.0 * M_PI / 3.0, -2.0 * M_PI / 3.0}; + const double angles[3] = {0.0, 2.0 * M_PI / 3.0, -2.0 * M_PI / 3.0}; int GOTO_SRC = 0, GOTO_TMP = 1, GOTO_DST = 2; double delta = distance_origin_platform - distance_arm0_platform - distance_arm0_robot_center; - double goto_info[3][3] = {{delta * sin(angles[0]), delta * cos(angles[0]), -angles[0]}, - {delta * sin(angles[1]), delta * cos(angles[1]), -angles[1]}, - {delta * sin(angles[2]), delta * cos(angles[2]), -angles[2]}}; + const double goto_info[3][3] = {{delta * sin(angles[0]), delta * cos(angles[0]), -angles[0]}, + {delta * sin(angles[1]), delta * cos(angles[1]), -angles[1]}, + {delta * sin(angles[2]), delta * cos(angles[2]), -angles[2]}}; arm_set_height(ARM_HANOI_PREPARE); // SRC A1 => DST diff --git a/projects/samples/curriculum/controllers/advanced_particle_swarm_optimization/advanced_particle_swarm_optimization.c b/projects/samples/curriculum/controllers/advanced_particle_swarm_optimization/advanced_particle_swarm_optimization.c index 965350ef09e..9a7c8a8b5e9 100644 --- a/projects/samples/curriculum/controllers/advanced_particle_swarm_optimization/advanced_particle_swarm_optimization.c +++ b/projects/samples/curriculum/controllers/advanced_particle_swarm_optimization/advanced_particle_swarm_optimization.c @@ -116,8 +116,7 @@ static void reset(void) { s[2]++; // increases the device number wb_distance_sensor_enable(ds[i], TIME_STEP); } - char *robot_name; - robot_name = (char *)wb_robot_get_name(); + const char *robot_name = wb_robot_get_name(); sscanf(robot_name, "epuck%d", &robot_id); // read robot id from the robot's name diff --git a/projects/samples/curriculum/controllers/advanced_particle_swarm_optimization/pso.c b/projects/samples/curriculum/controllers/advanced_particle_swarm_optimization/pso.c index f1f468d256f..be3b8fc7860 100644 --- a/projects/samples/curriculum/controllers/advanced_particle_swarm_optimization/pso.c +++ b/projects/samples/curriculum/controllers/advanced_particle_swarm_optimization/pso.c @@ -104,12 +104,12 @@ void ActivateLayer(layer_t *l) { } }*/ -void EvolveLayer(layer_t *l, layer_t *pbest, layer_t *gbest) { +void EvolveLayer(layer_t *l, const layer_t *pbest, const layer_t *gbest) { int i, j; float *lW = l->W; float *lvW = l->vW; - float *gbW = gbest->W; - float *pbW = pbest->W; + const float *gbW = gbest->W; + const float *pbW = pbest->W; for (i = 0; i < l->width; i++) { for (j = 0; j < l->depth; j++) { @@ -123,7 +123,7 @@ void EvolveLayer(layer_t *l, layer_t *pbest, layer_t *gbest) { } } -void PrintLayerOutput(layer_t *l) { +void PrintLayerOutput(const layer_t *l) { int i; char *main_buffer = (char *)malloc(sizeof(char) * (10 * l->depth + 1)); strcpy(main_buffer, ""); @@ -138,7 +138,7 @@ void PrintLayerOutput(layer_t *l) { free(main_buffer); } -void SaveLayerWeights(layer_t *l, FILE *fp) { +void SaveLayerWeights(const layer_t *l, FILE *fp) { if (fwrite(l->W, (sizeof(float) * (l->depth) * (l->width)), 1, fp) != 1) printf("error writing to file\n"); } diff --git a/projects/samples/curriculum/controllers/advanced_particle_swarm_optimization_supervisor/advanced_particle_swarm_optimization_supervisor.c b/projects/samples/curriculum/controllers/advanced_particle_swarm_optimization_supervisor/advanced_particle_swarm_optimization_supervisor.c index 427df3c2780..904824339f7 100644 --- a/projects/samples/curriculum/controllers/advanced_particle_swarm_optimization_supervisor/advanced_particle_swarm_optimization_supervisor.c +++ b/projects/samples/curriculum/controllers/advanced_particle_swarm_optimization_supervisor/advanced_particle_swarm_optimization_supervisor.c @@ -157,7 +157,7 @@ int main() { while (nb_received != NB_ROBOTS) { // robot_console_printf("In the while, receiver queue length: %d\n", receiver_get_queue_length(receiver)); - float *inbuffer; + const float *inbuffer; // get all the new messages from the robots while (wb_receiver_get_queue_length(receiver) > 0) { // robot_console_printf("Something received\n"); diff --git a/projects/samples/curriculum/controllers/advanced_path_planning_NF1/advanced_path_planning_NF1.c b/projects/samples/curriculum/controllers/advanced_path_planning_NF1/advanced_path_planning_NF1.c index 4b9a1c99cc2..f38beb39531 100644 --- a/projects/samples/curriculum/controllers/advanced_path_planning_NF1/advanced_path_planning_NF1.c +++ b/projects/samples/curriculum/controllers/advanced_path_planning_NF1/advanced_path_planning_NF1.c @@ -202,6 +202,7 @@ static float distance_to_segment(float x, float y, float ax, float ay, float bx, float v1p_x = x - ax; // vector from 1st segment point to test point float v1p_y = y - ay; float norm_v12 = sqrt(v12_x * v12_x + v12_y * v12_y); + // cppcheck-suppress variableScope float norm_v1p = sqrt(v1p_x * v1p_x + v1p_y * v1p_y); float dot_v12_v1p = v12_x * v1p_x + v12_y * v1p_y; diff --git a/projects/samples/curriculum/controllers/advanced_path_planning_potential_field/advanced_path_planning_potential_field.c b/projects/samples/curriculum/controllers/advanced_path_planning_potential_field/advanced_path_planning_potential_field.c index 733a7f9d54e..71c3d233f0d 100644 --- a/projects/samples/curriculum/controllers/advanced_path_planning_potential_field/advanced_path_planning_potential_field.c +++ b/projects/samples/curriculum/controllers/advanced_path_planning_potential_field/advanced_path_planning_potential_field.c @@ -176,6 +176,7 @@ static float distance_to_segment(float x, float y, float ax, float ay, float bx, float v1p_x = x - ax; // vector from 1st segment point to test point float v1p_y = y - ay; float norm_v12 = sqrt(v12_x * v12_x + v12_y * v12_y); + // cppcheck-suppress variableScope float norm_v1p = sqrt(v1p_x * v1p_x + v1p_y * v1p_y); float dot_v12_v1p = v12_x * v1p_x + v12_y * v1p_y; diff --git a/projects/samples/curriculum/lib/backprop.c b/projects/samples/curriculum/lib/backprop.c index 7c2ff90098d..5cedcf71ea6 100644 --- a/projects/samples/curriculum/lib/backprop.c +++ b/projects/samples/curriculum/lib/backprop.c @@ -99,7 +99,7 @@ void WeightedGradient(layer_t *l, float *Wg) { } } -void PrintLayerOutput(layer_t *l) { +void PrintLayerOutput(const layer_t *l) { int i; char *main_buffer = (char *)malloc(sizeof(char) * (10 * l->depth + 1)); main_buffer[0] = '\0'; @@ -114,12 +114,12 @@ void PrintLayerOutput(layer_t *l) { free(main_buffer); } -void SaveLayerWeights(layer_t *l, FILE *fp) { +void SaveLayerWeights(const layer_t *l, FILE *fp) { if (fwrite(l->W, (sizeof(float) * (l->depth) * (l->width)), 1, fp) != 1) printf("error writing to file\n"); } -void SaveLayerWeightsHDT(layer_t *l, FILE *fp) { +void SaveLayerWeightsHDT(const layer_t *l, FILE *fp) { int i, j; float *W; diff --git a/projects/samples/robotbenchmark/wall_following/controllers/wall_following_supervisor/wall_following_metric.c b/projects/samples/robotbenchmark/wall_following/controllers/wall_following_supervisor/wall_following_metric.c index 97c3c98cc8b..20b97cb611f 100644 --- a/projects/samples/robotbenchmark/wall_following/controllers/wall_following_supervisor/wall_following_metric.c +++ b/projects/samples/robotbenchmark/wall_following/controllers/wall_following_supervisor/wall_following_metric.c @@ -85,8 +85,8 @@ WallFollowingMetric *create_new_wall_following_metric(const double *robot_starti } // This vector corresponds to the first segment of the wall. - double robot_first_wall_segment_vector[2] = {segment_length * cos(first_segment_orientation), - segment_length * sin(first_segment_orientation)}; + const double robot_first_wall_segment_vector[2] = {segment_length * cos(first_segment_orientation), + segment_length * sin(first_segment_orientation)}; // This vector represents the distance between the starting position of the robot and the first segment // of the wall. diff --git a/projects/vehicles/plugins/robot_windows/automobile/automobile.c b/projects/vehicles/plugins/robot_windows/automobile/automobile.c index 5bdd270e4c3..e9fe67dfc65 100644 --- a/projects/vehicles/plugins/robot_windows/automobile/automobile.c +++ b/projects/vehicles/plugins/robot_windows/automobile/automobile.c @@ -324,7 +324,7 @@ void wb_robot_window_step(int time_step) { while ((message = wb_robot_wwi_receive_text())) { if (!wbu_generic_robot_window_handle_messages(message)) { char *tokens = strdup(message); - char *token = NULL; + const char *token = NULL; while ((token = wbu_string_strsep(&tokens, ","))) { char *command = strdup(token); char *first_word = wbu_string_strsep(&command, ":"); diff --git a/projects/vehicles/plugins/robot_windows/automobile_window/Makefile b/projects/vehicles/plugins/robot_windows/automobile_window/Makefile index 8c1e6ba2dbd..38bfbd0ec5f 100644 --- a/projects/vehicles/plugins/robot_windows/automobile_window/Makefile +++ b/projects/vehicles/plugins/robot_windows/automobile_window/Makefile @@ -60,11 +60,11 @@ ifeq ($(OSTYPE),linux) endif ifeq ($(OSTYPE),darwin) - WBCFLAGS += -Wno-unknown-pragmas -target $(PROCESSOR)-apple-macos11 + WBCFLAGS += -Wno-unknown-pragmas -target $(PROCESSOR)-apple-macos12 FRAMEWORKS_DIR = $(WEBOTS_HOME)/Contents/Frameworks INCLUDE += -F"$(FRAMEWORKS_DIR)" FRAMEWORKS += -F"$(FRAMEWORKS_DIR)" - LD_FLAGS = -target $(PROCESSOR)-apple-macos11 + LD_FLAGS = -target $(PROCESSOR)-apple-macos12 DYNAMIC_LIBRARIES += -bind_at_load $(FRAMEWORKS) MOC = "$(WEBOTS_HOME)/bin/qt/moc" MOC_PLATFORM_FLAGS = -D__APPLE__ diff --git a/resources/Makefile.include b/resources/Makefile.include index e616ed624f9..b55fecfb20c 100644 --- a/resources/Makefile.include +++ b/resources/Makefile.include @@ -210,15 +210,15 @@ endif ifneq ($(C_SOURCES)$(CXX_SOURCES),) ifdef BUILD_EXECUTABLE MAIN_TARGET = $(NAME)$(EXE_EXTENSION) - X86_64_LINKER = -target x86_64-apple-macos11 - ARM64_LINKER = -target arm64-apple-macos11 + X86_64_LINKER = -target x86_64-apple-macos12 + ARM64_LINKER = -target arm64-apple-macos12 else ifdef BUILD_STATIC_LIBRARY MAIN_TARGET ?= $(LIB_PREFIX)$(NAME)$(STATIC_LIB_EXTENSION) else MAIN_TARGET ?= $(LIB_PREFIX)$(NAME)$(SHARED_LIB_EXTENSION) - X86_64_LINKER = -target x86_64-apple-macos11 - ARM64_LINKER = -target arm64-apple-macos11 + X86_64_LINKER = -target x86_64-apple-macos12 + ARM64_LINKER = -target arm64-apple-macos12 endif endif endif @@ -321,8 +321,8 @@ endif ifeq ($(OSTYPE),darwin) ifdef NO_FAT_BINARY - WBCFLAGS += -target $(PROCESSOR)-apple-macos11 - DYNAMIC_LINK_FLAGS += -target $(PROCESSOR)-apple-macos11 + WBCFLAGS += -target $(PROCESSOR)-apple-macos12 + DYNAMIC_LINK_FLAGS += -target $(PROCESSOR)-apple-macos12 endif WBCFLAGS += -mmacosx-version-min=$(MACOSX_MIN_SDK_VERSION) DYNAMIC_LINK_FLAGS += -mmacosx-version-min=$(MACOSX_MIN_SDK_VERSION) @@ -355,7 +355,7 @@ ifdef USE_CXX endif endif ifeq ($(OSTYPE),darwin) - WBCFLAGS += -stdlib=libc++ + WBCXXFLAGS += -stdlib=libc++ DYNAMIC_LINK_FLAGS += -stdlib=libc++ endif else @@ -600,15 +600,15 @@ $(BUILD_GOAL_DIR)/%.d:%.c $(BUILD_GOAL_DIR)/%.d:%.cc @echo "# updating" $(notdir $@) - $(SILENT)$(CXX) $(INCLUDE) $(WBCFLAGS) $(CFLAGS -MM $< -MT $(addprefix $(BUILD_GOAL_DIR)/,$(notdir $(<:.cc=.o))) > $@ + $(SILENT)$(CXX) $(INCLUDE) $(WBCFLAGS) $(WBCXXFLAGS) $(CFLAGS) -MM $< -MT $(addprefix $(BUILD_GOAL_DIR)/,$(notdir $(<:.cc=.o))) > $@ $(BUILD_GOAL_DIR)/%.d:%.c++ @echo "# updating" $(notdir $@) - $(SILENT)$(CXX) $(INCLUDE) $(WBCFLAGS) $(CFLAGS) -MM $< -MT $(addprefix $(BUILD_GOAL_DIR)/,$(notdir $(<:.c++=.o))) > $@ + $(SILENT)$(CXX) $(INCLUDE) $(WBCFLAGS) $(WBCXXFLAGS) $(CFLAGS) -MM $< -MT $(addprefix $(BUILD_GOAL_DIR)/,$(notdir $(<:.c++=.o))) > $@ $(BUILD_GOAL_DIR)/%.d:%.cpp @echo "# updating" $(notdir $@) - $(SILENT)$(CXX) $(INCLUDE) $(WBCFLAGS) $(CFLAGS) -MM $< -MT $(addprefix $(BUILD_GOAL_DIR)/,$(notdir $(<:.cpp=.o))) > $@ + $(SILENT)$(CXX) $(INCLUDE) $(WBCFLAGS) $(WBCXXFLAGS) $(CFLAGS) -MM $< -MT $(addprefix $(BUILD_GOAL_DIR)/,$(notdir $(<:.cpp=.o))) > $@ # dependencies ifdef GOAL @@ -627,35 +627,35 @@ $(BUILD_GOAL_DIR)/%.o:%.c $(BUILD_GOAL_DIR)/x86_64/%.o:%.c @echo "# compiling" $(notdir $<) "(x86_64)" - $(SILENT)$(CC) -c -target x86_64-apple-macos11 $(WBCFLAGS) $(CFLAGS) $(INCLUDE) $< -o $@ + $(SILENT)$(CC) -c -target x86_64-apple-macos12 $(WBCFLAGS) $(CFLAGS) $(INCLUDE) $< -o $@ $(BUILD_GOAL_DIR)/arm64/%.o:%.c @echo "# compiling" $(notdir $<) "(arm64)" - $(SILENT)$(CC) -c -target arm64-apple-macos11 $(WBCFLAGS) $(CFLAGS) $(INCLUDE) $< -o $@ + $(SILENT)$(CC) -c -target arm64-apple-macos12 $(WBCFLAGS) $(CFLAGS) $(INCLUDE) $< -o $@ $(BUILD_GOAL_DIR)/%.o:%.cc @echo "# compiling" $(notdir $<) - $(SILENT)$(CXX) -c $(WBCFLAGS) $(CFLAGS) $(CXXFLAGS) $(INCLUDE) $< -o $@ + $(SILENT)$(CXX) -c $(WBCFLAGS) $(WBCXXFLAGS) $(CFLAGS) $(CXXFLAGS) $(INCLUDE) $< -o $@ $(BUILD_GOAL_DIR)/%.o:%.c++ @echo "# compiling" $(notdir $<) - $(SILENT)$(CXX) -c $(WBCFLAGS) $(CFLAGS) $(CXXFLAGS) $(INCLUDE) $< -o $@ + $(SILENT)$(CXX) -c $(WBCFLAGS) $(WBCXXFLAGS) $(CFLAGS) $(CXXFLAGS) $(INCLUDE) $< -o $@ $(BUILD_GOAL_DIR)/%.o:%.cpp @echo "# compiling" $(notdir $<) - $(SILENT)$(CXX) -c $(WBCFLAGS) $(CFLAGS) $(CXXFLAGS) $(INCLUDE) $< -o $@ + $(SILENT)$(CXX) -c $(WBCFLAGS) $(WBCXXFLAGS) $(CFLAGS) $(CXXFLAGS) $(INCLUDE) $< -o $@ $(BUILD_GOAL_DIR)/x86_64/%.o:%.cpp @echo "# compiling" $(notdir $<) "(x86_64)" - $(SILENT)$(CXX) -c -target x86_64-apple-macos11 $(WBCFLAGS) $(CFLAGS) $(CXXFLAGS) $(INCLUDE) $< -o $@ + $(SILENT)$(CXX) -c -target x86_64-apple-macos12 $(WBCFLAGS) $(WBCXXFLAGS) $(CFLAGS) $(CXXFLAGS) $(INCLUDE) $< -o $@ $(BUILD_GOAL_DIR)/arm64/%.o:%.cpp @echo "# compiling" $(notdir $<) "(arm64)" - $(SILENT)$(CXX) -c -target arm64-apple-macos11 $(WBCFLAGS) $(CFLAGS) $(CXXFLAGS) $(INCLUDE) $< -o $@ + $(SILENT)$(CXX) -c -target arm64-apple-macos12 $(WBCFLAGS) $(WBCXXFLAGS) $(CFLAGS) $(CXXFLAGS) $(INCLUDE) $< -o $@ $(BUILD_GOAL_DIR_EMCC)/%.o:%.cpp @echo "# compiling with emcc " $(notdir $<) - $(SILENT)emcc -O3 -c $(WBCFLAGS) $(CFLAGS) $(CXXFLAGS) $(INCLUDE) $< -o $(@) + $(SILENT)emcc -O3 -c $(WBCFLAGS) $(WBCXXFLAGS) $(CFLAGS) $(CXXFLAGS) $(INCLUDE) $< -o $(@) ###----------------------------------------------------------------------------- ### How to clean up the directory diff --git a/resources/Makefile.os.include b/resources/Makefile.os.include index 59e04a0d6c2..7a56e5cd037 100644 --- a/resources/Makefile.os.include +++ b/resources/Makefile.os.include @@ -72,8 +72,8 @@ endif ifeq ($(OSTYPE),darwin) - SUPPORTED_SDK = 11 12 - MACOSX_MIN_SDK_VERSION = 11 + SUPPORTED_SDK = 12 13 14 + MACOSX_MIN_SDK_VERSION = 12 ECHO = echo # cf. https://stackoverflow.com/a/30225756/2210777 MACOSX_SDK_PATH = $(shell xcrun --sdk macosx --show-sdk-path) diff --git a/resources/projects/libraries/generic_robot_window/generic.c b/resources/projects/libraries/generic_robot_window/generic.c index 0cddc58868b..8b61fd2a756 100644 --- a/resources/projects/libraries/generic_robot_window/generic.c +++ b/resources/projects/libraries/generic_robot_window/generic.c @@ -207,12 +207,12 @@ void wbu_generic_robot_window_parse_device_command(char *token, char *tokens) { }; } -bool wbu_generic_robot_window_parse_device_control_command(char *first_token, char *tokens) { +bool wbu_generic_robot_window_parse_device_control_command(const char *first_token, char *tokens) { if (strcmp(first_token, "device-control-mode") != 0) return false; WbNodeType type = WB_NODE_NO_NODE; - char *token = NULL; + const char *token = NULL; while ((token = wbu_string_strsep(&tokens, ":"))) { if (type == WB_NODE_NO_NODE) { type = stringToDeviceType(token); diff --git a/resources/projects/libraries/qt_utils/devices/Motor.cpp b/resources/projects/libraries/qt_utils/devices/Motor.cpp index f79b0e2da54..19f56e76c0f 100644 --- a/resources/projects/libraries/qt_utils/devices/Motor.cpp +++ b/resources/projects/libraries/qt_utils/devices/Motor.cpp @@ -7,7 +7,7 @@ using namespace webotsQtUtils; Motor::Motor(WbDeviceTag tag) : Device(tag) { } -void Motor::enable(bool enable) { +void Motor::enable(bool enable) const { if (wb_motor_get_type(mTag) == WB_ROTATIONAL) { if (enable) wb_motor_enable_torque_feedback(mTag, static_cast(wb_robot_get_basic_time_step())); @@ -47,6 +47,6 @@ double Motor::targetPosition() const { return wb_motor_get_target_position(mTag); } -void Motor::setPosition(double position) { +void Motor::setPosition(double position) const { wb_motor_set_position(mTag, position); } diff --git a/resources/projects/libraries/qt_utils/devices/Motor.hpp b/resources/projects/libraries/qt_utils/devices/Motor.hpp index 8cdcdc30554..4173c3a5ad0 100644 --- a/resources/projects/libraries/qt_utils/devices/Motor.hpp +++ b/resources/projects/libraries/qt_utils/devices/Motor.hpp @@ -11,15 +11,15 @@ namespace webotsQtUtils { class Motor : public Device { public: explicit Motor(WbDeviceTag tag); - virtual ~Motor() {} + virtual ~Motor() override {} - void enable(bool enable); + void enable(bool enable) const; bool isEnabled() const; double minPosition() const; double maxPosition() const; double position() const; double targetPosition() const; - void setPosition(double position); + void setPosition(double position) const; }; } // namespace webotsQtUtils diff --git a/resources/projects/libraries/qt_utils/graph2d/Graph2D.cpp b/resources/projects/libraries/qt_utils/graph2d/Graph2D.cpp index 86a06a0b5b3..1f6868ff119 100644 --- a/resources/projects/libraries/qt_utils/graph2d/Graph2D.cpp +++ b/resources/projects/libraries/qt_utils/graph2d/Graph2D.cpp @@ -191,7 +191,7 @@ void Graph2D::extendRange() { } void Graph2D::extendXRange() { - foreach (Point2D *point, mPoints) { + foreach (const Point2D *point, mPoints) { if (point->x() < mRanges[CX][MIN]) mRanges[CX][MIN] = point->x(); if (point->x() > mRanges[CX][MAX]) @@ -200,7 +200,7 @@ void Graph2D::extendXRange() { } void Graph2D::extendYRange() { - foreach (Point2D *point, mPoints) { + foreach (const Point2D *point, mPoints) { if (point->y() < mRanges[CY][MIN]) mRanges[CY][MIN] = point->y(); if (point->y() > mRanges[CY][MAX]) @@ -237,9 +237,9 @@ int Graph2D::yToV(double y) { } void Graph2D::drawPoints(QPainter &painter) { - foreach (QColor *color, mColors) { + foreach (const QColor *color, mColors) { painter.setPen(*color); - foreach (Point2D *point, mPoints) { + foreach (const Point2D *point, mPoints) { if (point->color() == *color && point->x() <= mRanges[CX][MAX] && point->x() >= mRanges[CX][MIN] && point->y() <= mRanges[CY][MAX] && point->y() >= mRanges[CY][MIN]) drawUVPoint(painter, xToU(point->x()), yToV(point->y())); @@ -248,9 +248,9 @@ void Graph2D::drawPoints(QPainter &painter) { } void Graph2D::drawLines(QPainter &painter) { - foreach (QColor *color, mColors) { + foreach (const QColor *color, mColors) { painter.setPen(*color); - foreach (Line2D *line, mLines) { + foreach (const Line2D *line, mLines) { if (line->color() == *color) painter.drawLine(xToU(line->x1()), yToV(line->y1()), xToU(line->x2()), yToV(line->y2())); } diff --git a/resources/projects/libraries/qt_utils/gui/GenericWindow.cpp b/resources/projects/libraries/qt_utils/gui/GenericWindow.cpp index fc14fcd9b7c..9ad14793662 100644 --- a/resources/projects/libraries/qt_utils/gui/GenericWindow.cpp +++ b/resources/projects/libraries/qt_utils/gui/GenericWindow.cpp @@ -67,10 +67,12 @@ GenericWindow::GenericWindow(const QStringList &hiddenDevices) : MainWindow(), m continue; WbNodeType type = wb_device_get_node_type(tag); if (type == WB_NODE_LINEAR_MOTOR || type == WB_NODE_ROTATIONAL_MOTOR) { + // cppcheck-suppress constVariablePointer Motor *motor = new Motor(tag); mDeviceList << motor; motorList << motor; } else { + // cppcheck-suppress constVariablePointer Device *device = new Device(tag); mDeviceList << device; } diff --git a/resources/projects/libraries/qt_utils/motion_editor/AddStateDialog.cpp b/resources/projects/libraries/qt_utils/motion_editor/AddStateDialog.cpp index 60d822ba731..2704342e381 100644 --- a/resources/projects/libraries/qt_utils/motion_editor/AddStateDialog.cpp +++ b/resources/projects/libraries/qt_utils/motion_editor/AddStateDialog.cpp @@ -65,8 +65,8 @@ void AddStateDialog::populateListWidget() { QSet motorAlreadyDefined; if (mMotion->poses().count() > 0) { - Pose *pose = mMotion->poses()[0]; - foreach (MotorTargetState *state, pose->states()) + const Pose *pose = mMotion->poses()[0]; + foreach (const MotorTargetState *state, pose->states()) motorAlreadyDefined.insert(state->motor()->name()); } diff --git a/resources/projects/libraries/qt_utils/motion_editor/Motion.cpp b/resources/projects/libraries/qt_utils/motion_editor/Motion.cpp index 292911561df..376249e330e 100644 --- a/resources/projects/libraries/qt_utils/motion_editor/Motion.cpp +++ b/resources/projects/libraries/qt_utils/motion_editor/Motion.cpp @@ -83,10 +83,10 @@ void Motion::save() const { } out << "\n"; - foreach (Pose *pose, mPoses) { + foreach (const Pose *pose, mPoses) { out << pose->toTimeString() << "," << pose->name(); - foreach (Device *motor, motors) { + foreach (const Device *motor, motors) { MotorTargetState *state = pose->findStateByMotorName(motor->name()); out << ","; if (state->isDefined()) @@ -102,7 +102,7 @@ void Motion::save() const { void Motion::applyPoseToRobot(Pose *pose) { if (pose && !mPlayer->isPlaying()) { - foreach (MotorTargetState *state, pose->states()) { + foreach (const MotorTargetState *state, pose->states()) { if (state->isDefined()) state->motor()->setPosition(state->value()); } @@ -148,10 +148,10 @@ bool Motion::validate() const { return true; QList motors; - foreach (MotorTargetState *state, mPoses[0]->states()) + foreach (const MotorTargetState *state, mPoses[0]->states()) motors << state->motor(); - foreach (Pose *pose, mPoses) { + foreach (const Pose *pose, mPoses) { if (pose->states().count() != motors.count()) return false; @@ -301,8 +301,8 @@ void Motion::newPoseAt(int index) { pose->setName(tr("Unnamed %1").arg(mNewPoseCounter++)); if (mPoses.count() > 0) { - Pose *referencePose = mPoses[0]; - foreach (MotorTargetState *referenceState, referencePose->states()) { + const Pose *referencePose = mPoses[0]; + foreach (const MotorTargetState *referenceState, referencePose->states()) { pose->createAndAppendState(referenceState->motor()); } } @@ -389,8 +389,8 @@ void Motion::deleteStatesByMotorName(const QString &motorName) { } bool Motion::isSomeStateDefinedByMotorName(const QString &motorName) const { - foreach (Pose *pose, mPoses) { - MotorTargetState *state = pose->findStateByMotorName(motorName); + foreach (const Pose *pose, mPoses) { + const MotorTargetState *state = pose->findStateByMotorName(motorName); if (state->isDefined()) return true; } diff --git a/resources/projects/libraries/qt_utils/motion_editor/MotionPlayer.cpp b/resources/projects/libraries/qt_utils/motion_editor/MotionPlayer.cpp index fe9ffacebf9..124c6a18b67 100644 --- a/resources/projects/libraries/qt_utils/motion_editor/MotionPlayer.cpp +++ b/resources/projects/libraries/qt_utils/motion_editor/MotionPlayer.cpp @@ -98,8 +98,8 @@ void MotionPlayer::writeActuators() { afterPose->select(); for (int i = 0; i < count; i++) { - MotorTargetState *beforeState = beforePose->states()[i]; - MotorTargetState *afterState = afterPose->states()[i]; + const MotorTargetState *beforeState = beforePose->states()[i]; + const MotorTargetState *afterState = afterPose->states()[i]; assert(beforeState->motor()->tag() == afterState->motor()->tag()); @@ -153,7 +153,7 @@ void MotionPlayer::updateMotionDuration() { if (!mMotion) return; - foreach (Pose *pose, mMotion->poses()) { + foreach (const Pose *pose, mMotion->poses()) { if (pose->time() > mMotionDuration) mMotionDuration = pose->time(); } diff --git a/resources/projects/libraries/qt_utils/motion_editor/MotionWidget.cpp b/resources/projects/libraries/qt_utils/motion_editor/MotionWidget.cpp index 2d3af7f0070..b09ce480bf2 100644 --- a/resources/projects/libraries/qt_utils/motion_editor/MotionWidget.cpp +++ b/resources/projects/libraries/qt_utils/motion_editor/MotionWidget.cpp @@ -110,14 +110,14 @@ void MotionWidget::selectPoseFromModel(int index) { } void MotionWidget::updatePoseFromModel(int index) { - Pose *pose = mMotion->poses().at(index); + const Pose *pose = mMotion->poses().at(index); QListWidgetItem *i = mListWidget->item(index); i->setText(pose->toString()); setItemAppearance(i, pose->status()); } void MotionWidget::insertPoseFromModel(int index) { - Pose *pose = mMotion->poses().at(index); + const Pose *pose = mMotion->poses().at(index); QListWidgetItem *i = new QListWidgetItem(pose->toString()); setItemAppearance(i, pose->status()); mListWidget->insertItem(index, i); diff --git a/resources/projects/libraries/qt_utils/motion_editor/MotionWidget.hpp b/resources/projects/libraries/qt_utils/motion_editor/MotionWidget.hpp index c73d8758935..98008c055c3 100644 --- a/resources/projects/libraries/qt_utils/motion_editor/MotionWidget.hpp +++ b/resources/projects/libraries/qt_utils/motion_editor/MotionWidget.hpp @@ -21,7 +21,7 @@ namespace webotsQtUtils { public: explicit MotionWidget(QWidget *parent = NULL); - virtual ~MotionWidget(); + virtual ~MotionWidget() override; void setMotion(Motion *motion); diff --git a/resources/projects/libraries/qt_utils/motion_editor/Pose.cpp b/resources/projects/libraries/qt_utils/motion_editor/Pose.cpp index f317cdb609d..9b01fecdf8f 100644 --- a/resources/projects/libraries/qt_utils/motion_editor/Pose.cpp +++ b/resources/projects/libraries/qt_utils/motion_editor/Pose.cpp @@ -115,7 +115,7 @@ MotorTargetState *Pose::findStateByMotorName(const QString &motorName) const { int Pose::computeIndexOfStateByMotorName(const QString &motorName) const { int index = 0; - foreach (MotorTargetState *state, mStates) { + foreach (const MotorTargetState *state, mStates) { if (state->motor()->name() == motorName) return index; index++; @@ -198,7 +198,7 @@ int Pose::computeStateToIndex(MotorTargetState *s) const { void Pose::updateIsValid() { // recompute flag bool isValid = true; - foreach (MotorTargetState *state, mStates) { + foreach (const MotorTargetState *state, mStates) { if (!state->isValid()) { isValid = false; break; @@ -219,7 +219,7 @@ void Pose::updateIsModified(bool modified) { } else if (mIsModified != modified) { // recompute flag modified = false; - foreach (MotorTargetState *state, mStates) { + foreach (const MotorTargetState *state, mStates) { if (state->isModified()) { modified = true; break; diff --git a/resources/projects/libraries/qt_utils/motion_editor/PoseWidget.cpp b/resources/projects/libraries/qt_utils/motion_editor/PoseWidget.cpp index 0df421942e7..d99f58073c1 100644 --- a/resources/projects/libraries/qt_utils/motion_editor/PoseWidget.cpp +++ b/resources/projects/libraries/qt_utils/motion_editor/PoseWidget.cpp @@ -85,7 +85,7 @@ void PoseWidget::newItemAt(int index) { void PoseWidget::deleteItemAt(int index) { Motion *motion = Motion::instance(); if (motion && mPose) { - MotorTargetState *stateToDelete = mPose->states().at(index); + const MotorTargetState *stateToDelete = mPose->states().at(index); bool deleteAllowed = true; bool atLeastOneDefinedRelatedState = motion->isSomeStateDefinedByMotorName(stateToDelete->motor()->name()); @@ -139,7 +139,7 @@ void PoseWidget::updatePoseFromModel(bool isStatusUpdate) { void PoseWidget::updateStateFromModel(int index) { if (mPose) { - MotorTargetState *state = mPose->states().at(index); + const MotorTargetState *state = mPose->states().at(index); QListWidgetItem *i = mListWidget->item(index); i->setText(state->toString()); setItemAppearance(i, state->status()); @@ -151,7 +151,7 @@ void PoseWidget::updateStateFromModel(int index) { void PoseWidget::insertStateFromModel(int index) { if (mPose) { - MotorTargetState *state = mPose->states().at(index); + const MotorTargetState *state = mPose->states().at(index); QListWidgetItem *i = new QListWidgetItem(state->toString()); setItemAppearance(i, state->status()); mListWidget->insertItem(index, i); diff --git a/resources/projects/libraries/qt_utils/motion_editor/PoseWidget.hpp b/resources/projects/libraries/qt_utils/motion_editor/PoseWidget.hpp index 9c9179bfa0f..de0b8bad01c 100644 --- a/resources/projects/libraries/qt_utils/motion_editor/PoseWidget.hpp +++ b/resources/projects/libraries/qt_utils/motion_editor/PoseWidget.hpp @@ -21,7 +21,7 @@ namespace webotsQtUtils { public: explicit PoseWidget(QWidget *parent = NULL); - virtual ~PoseWidget(); + virtual ~PoseWidget() override; void changePose(Pose *pose); diff --git a/resources/projects/libraries/qt_utils/widgets/AccelerometerWidget.hpp b/resources/projects/libraries/qt_utils/widgets/AccelerometerWidget.hpp index c995291e967..68e0733ef58 100644 --- a/resources/projects/libraries/qt_utils/widgets/AccelerometerWidget.hpp +++ b/resources/projects/libraries/qt_utils/widgets/AccelerometerWidget.hpp @@ -13,7 +13,7 @@ namespace webotsQtUtils { public: explicit AccelerometerWidget(Device *device, QWidget *parent = NULL); - virtual ~AccelerometerWidget() {} + virtual ~AccelerometerWidget() override {} protected slots: void enable(bool enable) override; diff --git a/resources/projects/libraries/qt_utils/widgets/CameraWidget.hpp b/resources/projects/libraries/qt_utils/widgets/CameraWidget.hpp index 6730ea1fd07..1b71ca020fd 100644 --- a/resources/projects/libraries/qt_utils/widgets/CameraWidget.hpp +++ b/resources/projects/libraries/qt_utils/widgets/CameraWidget.hpp @@ -16,7 +16,7 @@ namespace webotsQtUtils { public: explicit CameraWidget(Device *device, QWidget *parent = NULL); - virtual ~CameraWidget() {} + virtual ~CameraWidget() override {} void readSensors() override; diff --git a/resources/projects/libraries/qt_utils/widgets/CompassWidget.hpp b/resources/projects/libraries/qt_utils/widgets/CompassWidget.hpp index 86cb482f9dd..67960c3b186 100644 --- a/resources/projects/libraries/qt_utils/widgets/CompassWidget.hpp +++ b/resources/projects/libraries/qt_utils/widgets/CompassWidget.hpp @@ -13,7 +13,7 @@ namespace webotsQtUtils { public: explicit CompassWidget(Device *device, QWidget *parent = NULL); - virtual ~CompassWidget() {} + virtual ~CompassWidget() override {} protected slots: void enable(bool enable) override; diff --git a/resources/projects/libraries/qt_utils/widgets/DistanceSensorWidget.hpp b/resources/projects/libraries/qt_utils/widgets/DistanceSensorWidget.hpp index 1a1298bd5bc..a5dd51ebadf 100644 --- a/resources/projects/libraries/qt_utils/widgets/DistanceSensorWidget.hpp +++ b/resources/projects/libraries/qt_utils/widgets/DistanceSensorWidget.hpp @@ -13,7 +13,7 @@ namespace webotsQtUtils { public: explicit DistanceSensorWidget(Device *device, QWidget *parent = NULL); - virtual ~DistanceSensorWidget() {} + virtual ~DistanceSensorWidget() override {} protected slots: void enable(bool enable) override; diff --git a/resources/projects/libraries/qt_utils/widgets/GPSWidget.hpp b/resources/projects/libraries/qt_utils/widgets/GPSWidget.hpp index c5dfa3f0882..cf2096fb452 100644 --- a/resources/projects/libraries/qt_utils/widgets/GPSWidget.hpp +++ b/resources/projects/libraries/qt_utils/widgets/GPSWidget.hpp @@ -13,7 +13,7 @@ namespace webotsQtUtils { public: explicit GPSWidget(Device *device, QWidget *parent = NULL); - virtual ~GPSWidget() {} + virtual ~GPSWidget() override {} protected slots: void enable(bool enable) override; diff --git a/resources/projects/libraries/qt_utils/widgets/GyroWidget.hpp b/resources/projects/libraries/qt_utils/widgets/GyroWidget.hpp index 1fde02d9431..f5b884a15af 100644 --- a/resources/projects/libraries/qt_utils/widgets/GyroWidget.hpp +++ b/resources/projects/libraries/qt_utils/widgets/GyroWidget.hpp @@ -13,7 +13,7 @@ namespace webotsQtUtils { public: explicit GyroWidget(Device *device, QWidget *parent = NULL); - virtual ~GyroWidget() {} + virtual ~GyroWidget() override {} protected slots: void enable(bool enable) override; diff --git a/resources/projects/libraries/qt_utils/widgets/InertialUnitWidget.hpp b/resources/projects/libraries/qt_utils/widgets/InertialUnitWidget.hpp index 84473020f22..8302e7552e6 100644 --- a/resources/projects/libraries/qt_utils/widgets/InertialUnitWidget.hpp +++ b/resources/projects/libraries/qt_utils/widgets/InertialUnitWidget.hpp @@ -13,7 +13,7 @@ namespace webotsQtUtils { public: explicit InertialUnitWidget(Device *device, QWidget *parent = NULL); - virtual ~InertialUnitWidget() {} + virtual ~InertialUnitWidget() override {} protected slots: void enable(bool enable) override; diff --git a/resources/projects/libraries/qt_utils/widgets/LidarWidget.hpp b/resources/projects/libraries/qt_utils/widgets/LidarWidget.hpp index f110bf0d418..f3661f19fda 100644 --- a/resources/projects/libraries/qt_utils/widgets/LidarWidget.hpp +++ b/resources/projects/libraries/qt_utils/widgets/LidarWidget.hpp @@ -16,7 +16,7 @@ namespace webotsQtUtils { public: explicit LidarWidget(Device *device, QWidget *parent = NULL); - virtual ~LidarWidget() {} + virtual ~LidarWidget() override {} void readSensors() override; diff --git a/resources/projects/libraries/qt_utils/widgets/LightSensorWidget.hpp b/resources/projects/libraries/qt_utils/widgets/LightSensorWidget.hpp index a831ac32659..8d1f51935b2 100644 --- a/resources/projects/libraries/qt_utils/widgets/LightSensorWidget.hpp +++ b/resources/projects/libraries/qt_utils/widgets/LightSensorWidget.hpp @@ -13,7 +13,7 @@ namespace webotsQtUtils { public: explicit LightSensorWidget(Device *device, QWidget *parent = NULL); - virtual ~LightSensorWidget() {} + virtual ~LightSensorWidget() override {} protected slots: void enable(bool enable) override; diff --git a/resources/projects/libraries/qt_utils/widgets/MotorWidget.hpp b/resources/projects/libraries/qt_utils/widgets/MotorWidget.hpp index aff21711831..fe994bcb64a 100644 --- a/resources/projects/libraries/qt_utils/widgets/MotorWidget.hpp +++ b/resources/projects/libraries/qt_utils/widgets/MotorWidget.hpp @@ -16,7 +16,7 @@ namespace webotsQtUtils { public: explicit MotorWidget(Device *device, QWidget *parent = NULL); - virtual ~MotorWidget() {} + virtual ~MotorWidget() override {} void setupBounds(); diff --git a/resources/projects/libraries/qt_utils/widgets/PositionSensorWidget.hpp b/resources/projects/libraries/qt_utils/widgets/PositionSensorWidget.hpp index 1b4e1b6d26e..030e7d03cf2 100644 --- a/resources/projects/libraries/qt_utils/widgets/PositionSensorWidget.hpp +++ b/resources/projects/libraries/qt_utils/widgets/PositionSensorWidget.hpp @@ -13,7 +13,7 @@ namespace webotsQtUtils { public: explicit PositionSensorWidget(Device *device, QWidget *parent = NULL); - virtual ~PositionSensorWidget() {} + virtual ~PositionSensorWidget() override {} protected slots: void enable(bool enable) override; diff --git a/resources/projects/libraries/qt_utils/widgets/RadarWidget.hpp b/resources/projects/libraries/qt_utils/widgets/RadarWidget.hpp index e93b296669d..7de884933ff 100644 --- a/resources/projects/libraries/qt_utils/widgets/RadarWidget.hpp +++ b/resources/projects/libraries/qt_utils/widgets/RadarWidget.hpp @@ -18,7 +18,7 @@ namespace webotsQtUtils { public: explicit RadarWidget(Device *device, QWidget *parent = NULL); - virtual ~RadarWidget() {} + virtual ~RadarWidget() override {} void readSensors() override; diff --git a/resources/projects/libraries/qt_utils/widgets/RangeFinderWidget.hpp b/resources/projects/libraries/qt_utils/widgets/RangeFinderWidget.hpp index ee8d3629fdf..bcb70a3fa0a 100644 --- a/resources/projects/libraries/qt_utils/widgets/RangeFinderWidget.hpp +++ b/resources/projects/libraries/qt_utils/widgets/RangeFinderWidget.hpp @@ -16,7 +16,7 @@ namespace webotsQtUtils { public: explicit RangeFinderWidget(Device *device, QWidget *parent = NULL); - virtual ~RangeFinderWidget() {} + virtual ~RangeFinderWidget() override {} void readSensors() override; diff --git a/resources/projects/libraries/qt_utils/widgets/ScalarSensorWidget.hpp b/resources/projects/libraries/qt_utils/widgets/ScalarSensorWidget.hpp index 99fe96af4d4..2630731e036 100644 --- a/resources/projects/libraries/qt_utils/widgets/ScalarSensorWidget.hpp +++ b/resources/projects/libraries/qt_utils/widgets/ScalarSensorWidget.hpp @@ -15,7 +15,7 @@ namespace webotsQtUtils { class ScalarSensorWidget : public SensorWidget { public: explicit ScalarSensorWidget(Device *device, QWidget *parent = NULL); - virtual ~ScalarSensorWidget() {} + virtual ~ScalarSensorWidget() override {} void readSensors() override; diff --git a/resources/projects/libraries/qt_utils/widgets/SensorWidget.hpp b/resources/projects/libraries/qt_utils/widgets/SensorWidget.hpp index 4f9d655fb5a..198ef7d3e3d 100644 --- a/resources/projects/libraries/qt_utils/widgets/SensorWidget.hpp +++ b/resources/projects/libraries/qt_utils/widgets/SensorWidget.hpp @@ -15,7 +15,7 @@ namespace webotsQtUtils { public: explicit SensorWidget(Device *device, QWidget *parent = NULL); - virtual ~SensorWidget() {} + virtual ~SensorWidget() override {} void readSensors() override; diff --git a/resources/projects/libraries/qt_utils/widgets/TouchSensorScalarWidget.hpp b/resources/projects/libraries/qt_utils/widgets/TouchSensorScalarWidget.hpp index 923bd6173e0..fd6bf628bad 100644 --- a/resources/projects/libraries/qt_utils/widgets/TouchSensorScalarWidget.hpp +++ b/resources/projects/libraries/qt_utils/widgets/TouchSensorScalarWidget.hpp @@ -13,7 +13,7 @@ namespace webotsQtUtils { public: explicit TouchSensorScalarWidget(Device *device, QWidget *parent = NULL); - virtual ~TouchSensorScalarWidget() {} + virtual ~TouchSensorScalarWidget() override {} protected slots: void enable(bool enable) override; diff --git a/resources/projects/libraries/qt_utils/widgets/TouchSensorVectorialWidget.hpp b/resources/projects/libraries/qt_utils/widgets/TouchSensorVectorialWidget.hpp index 8776fc25e81..b9d232e5c80 100644 --- a/resources/projects/libraries/qt_utils/widgets/TouchSensorVectorialWidget.hpp +++ b/resources/projects/libraries/qt_utils/widgets/TouchSensorVectorialWidget.hpp @@ -13,7 +13,7 @@ namespace webotsQtUtils { public: explicit TouchSensorVectorialWidget(Device *device, QWidget *parent = NULL); - virtual ~TouchSensorVectorialWidget() {} + virtual ~TouchSensorVectorialWidget() override {} protected slots: void enable(bool enable) override; diff --git a/resources/projects/libraries/qt_utils/widgets/VectorialSensorWidget.hpp b/resources/projects/libraries/qt_utils/widgets/VectorialSensorWidget.hpp index 42f5457e2c3..2e54c865337 100644 --- a/resources/projects/libraries/qt_utils/widgets/VectorialSensorWidget.hpp +++ b/resources/projects/libraries/qt_utils/widgets/VectorialSensorWidget.hpp @@ -21,7 +21,7 @@ namespace webotsQtUtils { public: explicit VectorialSensorWidget(Device *device, QWidget *parent = NULL); - virtual ~VectorialSensorWidget(); + virtual ~VectorialSensorWidget() override; void readSensors() override; diff --git a/resources/projects/plugins/physics/Makefile b/resources/projects/plugins/physics/Makefile index 2dcfa084557..e5b1312ffa1 100644 --- a/resources/projects/plugins/physics/Makefile +++ b/resources/projects/plugins/physics/Makefile @@ -39,10 +39,10 @@ ifeq ($(OSTYPE), darwin) release debug profile: physics.a physics-x86_64.o: physics.c $(WEBOTS_HOME_PATH)/include/plugins/physics.h - @gcc -target x86_64-apple-macos11 $(CFLAGS) $(PLATFORM_FLAGS) physics.c -I$(WEBOTS_HOME_PATH)/include -I$(WEBOTS_HOME_PATH)/include/ode -o $@ + @gcc -target x86_64-apple-macos12 $(CFLAGS) $(PLATFORM_FLAGS) physics.c -I$(WEBOTS_HOME_PATH)/include -I$(WEBOTS_HOME_PATH)/include/ode -o $@ physics-arm64.o: physics.c $(WEBOTS_HOME_PATH)/include/plugins/physics.h - @gcc -target arm64-apple-macos11 $(CFLAGS) $(PLATFORM_FLAGS) physics.c -I$(WEBOTS_HOME_PATH)/include -I$(WEBOTS_HOME_PATH)/include/ode -o $@ + @gcc -target arm64-apple-macos12 $(CFLAGS) $(PLATFORM_FLAGS) physics.c -I$(WEBOTS_HOME_PATH)/include -I$(WEBOTS_HOME_PATH)/include/ode -o $@ physics.a: physics-x86_64.o physics-arm64.o @ar rcs physics-x86_64.a physics-x86_64.o diff --git a/resources/projects/plugins/robot_windows/generic/generic.c b/resources/projects/plugins/robot_windows/generic/generic.c index c9cd3c5a805..a3480ad6878 100644 --- a/resources/projects/plugins/robot_windows/generic/generic.c +++ b/resources/projects/plugins/robot_windows/generic/generic.c @@ -19,7 +19,7 @@ void wb_robot_window_step(int time_step) { // example: // "e-puck:forward,ds0:enable,myMotor0:value=1.2" char *tokens = strdup(message); - char *token = NULL; + const char *token = NULL; while ((token = wbu_string_strsep(&tokens, ","))) { char *command = strdup(token); char *first_word = wbu_string_strsep(&command, ":"); diff --git a/src/controller/c/Makefile b/src/controller/c/Makefile index 4b4413aa254..00ea8b16b26 100644 --- a/src/controller/c/Makefile +++ b/src/controller/c/Makefile @@ -42,7 +42,7 @@ LIBCONTROLLER_VERSION := "$(shell cat $(WEBOTS_HOME_PATH)/resources/version.txt) endif ifeq ($(OSTYPE),darwin) -CFLAGS = -mmacosx-version-min=$(MACOSX_MIN_SDK_VERSION) -fpascal-strings -Wno-deprecated-declarations -I/Developer/Headers/FlatCarbon -Wall -fno-common -D LIBCONTROLLER_VERSION='$(LIBCONTROLLER_VERSION)' +CFLAGS = -mmacosx-version-min=$(MACOSX_MIN_SDK_VERSION) -fpascal-strings -Wno-deprecated-declarations -Wno-single-bit-bitfield-constant-conversion -I/Developer/Headers/FlatCarbon -Wall -fno-common -D LIBCONTROLLER_VERSION='$(LIBCONTROLLER_VERSION)' INCLUDE = -I$(WEBOTS_HOME_PATH)/include/controller/c -I$(WEBOTS_HOME_PATH)/include LD_FLAGS = -mmacosx-version-min=$(MACOSX_MIN_SDK_VERSION) -dynamiclib -install_name @rpath/Contents/lib/controller/libController.dylib -compatibility_version 1.0 -current_version 1.0.0 SHARED_LIBS = -lz @@ -155,12 +155,12 @@ $(TARGET): $(OBJDIR)/x86_64/libController.dylib $(OBJDIR)/arm64/libController.dy $(OBJDIR)/x86_64/libController.dylib: $(X86_64_OBJECTS) @echo "# linking "$@" (x86_64)" - @$(CC) $(LD_FLAGS) -target x86_64-apple-macos11 -o $@ $(X86_64_OBJECTS) $(SHARED_LIBS) + @$(CC) $(LD_FLAGS) -target x86_64-apple-macos12 -o $@ $(X86_64_OBJECTS) $(SHARED_LIBS) @chmod a-x $@ $(OBJDIR)/arm64/libController.dylib: $(ARM64_OBJECTS) @echo "# linking "$@" (arm64)" - @$(CC) $(LD_FLAGS) -target arm64-apple-macos11 -o $@ $(ARM64_OBJECTS) $(SHARED_LIBS) + @$(CC) $(LD_FLAGS) -target arm64-apple-macos12 -o $@ $(ARM64_OBJECTS) $(SHARED_LIBS) @chmod a-x $@ endif @@ -180,11 +180,11 @@ $(OBJDIR)/%.o:%.c $(OBJDIR)/arm64/%o:%c @echo "# compiling "$<" (arm64)" - @$(CC) -c -target arm64-apple-macos11 $(CFLAGS) $(EXTRA_CFLAGS) $(INCLUDE) $< -o $(OBJDIR)/arm64/$(notdir $@) + @$(CC) -c -target arm64-apple-macos12 $(CFLAGS) $(EXTRA_CFLAGS) $(INCLUDE) $< -o $(OBJDIR)/arm64/$(notdir $@) $(OBJDIR)/x86_64/%o:%c @echo "# compiling "$<" (x86_64)" - @$(CC) -c -target x86_64-apple-macos11 $(CFLAGS) $(EXTRA_CFLAGS) $(INCLUDE) $< -o $(OBJDIR)/x86_64/$(notdir $@) + @$(CC) -c -target x86_64-apple-macos12 $(CFLAGS) $(EXTRA_CFLAGS) $(INCLUDE) $< -o $(OBJDIR)/x86_64/$(notdir $@) $(OBJDIR)/%.d:%.c @echo "# updating "$(notdir $@) diff --git a/src/controller/c/abstract_camera.c b/src/controller/c/abstract_camera.c index 7045fbb55a3..6649b000b8b 100644 --- a/src/controller/c/abstract_camera.c +++ b/src/controller/c/abstract_camera.c @@ -120,50 +120,50 @@ void wb_abstract_camera_enable(WbDevice *d, int sampling_period) { robot_mutex_unlock(); } -int wb_abstract_camera_get_sampling_period(WbDevice *d) { +int wb_abstract_camera_get_sampling_period(const WbDevice *d) { int sampling_period = 0; robot_mutex_lock(); - AbstractCamera *ac = d->pdata; + const AbstractCamera *ac = d->pdata; if (ac) sampling_period = ac->sampling_period; robot_mutex_unlock(); return sampling_period; } -int wb_abstract_camera_get_height(WbDevice *d) { +int wb_abstract_camera_get_height(const WbDevice *d) { int result = -1; robot_mutex_lock(); - AbstractCamera *ac = d->pdata; + const AbstractCamera *ac = d->pdata; if (ac) result = ac->height; robot_mutex_unlock(); return result; } -int wb_abstract_camera_get_width(WbDevice *d) { +int wb_abstract_camera_get_width(const WbDevice *d) { int result = -1; robot_mutex_lock(); - AbstractCamera *ac = d->pdata; + const AbstractCamera *ac = d->pdata; if (ac) result = ac->width; robot_mutex_unlock(); return result; } -double wb_abstract_camera_get_fov(WbDevice *d) { +double wb_abstract_camera_get_fov(const WbDevice *d) { double result = NAN; robot_mutex_lock(); - AbstractCamera *ac = d->pdata; + const AbstractCamera *ac = d->pdata; if (ac) result = ac->fov; robot_mutex_unlock(); return result; } -double wb_abstract_camera_get_near(WbDevice *d) { +double wb_abstract_camera_get_near(const WbDevice *d) { double result = NAN; robot_mutex_lock(); - AbstractCamera *ac = d->pdata; + const AbstractCamera *ac = d->pdata; if (ac) result = ac->camnear; robot_mutex_unlock(); diff --git a/src/controller/c/abstract_camera.h b/src/controller/c/abstract_camera.h index a7e464558fc..1187863dde4 100644 --- a/src/controller/c/abstract_camera.h +++ b/src/controller/c/abstract_camera.h @@ -55,10 +55,10 @@ unsigned char *wbr_abstract_camera_get_image_buffer(WbDevice *d); void abstract_camera_allocate_image(WbDevice *d, int size); void wb_abstract_camera_enable(WbDevice *d, int sampling_period); -int wb_abstract_camera_get_sampling_period(WbDevice *d); -int wb_abstract_camera_get_height(WbDevice *d); -int wb_abstract_camera_get_width(WbDevice *d); -double wb_abstract_camera_get_fov(WbDevice *d); -double wb_abstract_camera_get_near(WbDevice *d); +int wb_abstract_camera_get_sampling_period(const WbDevice *d); +int wb_abstract_camera_get_height(const WbDevice *d); +int wb_abstract_camera_get_width(const WbDevice *d); +double wb_abstract_camera_get_fov(const WbDevice *d); +double wb_abstract_camera_get_near(const WbDevice *d); #endif // ABSTRACT_CAMERA_PRIVATE_H diff --git a/src/controller/c/accelerometer.c b/src/controller/c/accelerometer.c index fbe810c6747..56964851664 100644 --- a/src/controller/c/accelerometer.c +++ b/src/controller/c/accelerometer.c @@ -77,7 +77,7 @@ static void accelerometer_read_answer(WbDevice *d, WbRequest *r) { int wb_accelerometer_get_lookup_table_size(WbDeviceTag tag) { int result = 0; robot_mutex_lock(); - Accelerometer *dev = accelerometer_get_struct(tag); + const Accelerometer *dev = accelerometer_get_struct(tag); if (dev) result = dev->lookup_table_size; else @@ -87,9 +87,9 @@ int wb_accelerometer_get_lookup_table_size(WbDeviceTag tag) { } const double *wb_accelerometer_get_lookup_table(WbDeviceTag tag) { - double *result = NULL; + const double *result = NULL; robot_mutex_lock(); - Accelerometer *dev = accelerometer_get_struct(tag); + const Accelerometer *dev = accelerometer_get_struct(tag); if (dev) result = dev->lookup_table; else @@ -158,7 +158,7 @@ void wb_accelerometer_enable(WbDeviceTag tag, int sampling_period) { } void wb_accelerometer_disable(WbDeviceTag tag) { - Accelerometer *acc = accelerometer_get_struct(tag); + const Accelerometer *acc = accelerometer_get_struct(tag); if (acc) wb_accelerometer_enable(tag, 0); else @@ -168,7 +168,7 @@ void wb_accelerometer_disable(WbDeviceTag tag) { int wb_accelerometer_get_sampling_period(WbDeviceTag tag) { int sampling_period = 0; robot_mutex_lock(); - Accelerometer *acc = accelerometer_get_struct(tag); + const Accelerometer *acc = accelerometer_get_struct(tag); if (acc) sampling_period = acc->sampling_period; else @@ -180,7 +180,7 @@ int wb_accelerometer_get_sampling_period(WbDeviceTag tag) { const double *wb_accelerometer_get_values(WbDeviceTag tag) { const double *result = NULL; robot_mutex_lock(); - Accelerometer *acc = accelerometer_get_struct(tag); + const Accelerometer *acc = accelerometer_get_struct(tag); if (acc) { if (acc->sampling_period == 0) fprintf(stderr, "Error: %s() called for a disabled device! Please use: wb_accelerometer_enable().\n", __FUNCTION__); diff --git a/src/controller/c/altimeter.c b/src/controller/c/altimeter.c index 0403492199b..fcf6934ad7f 100644 --- a/src/controller/c/altimeter.c +++ b/src/controller/c/altimeter.c @@ -110,7 +110,7 @@ void wb_altimeter_enable(WbDeviceTag tag, int sampling_period) { } void wb_altimeter_disable(WbDeviceTag tag) { - Altimeter *altimeter = altimeter_get_struct(tag); + const Altimeter *altimeter = altimeter_get_struct(tag); if (altimeter) wb_altimeter_enable(tag, 0); else @@ -120,7 +120,7 @@ void wb_altimeter_disable(WbDeviceTag tag) { int wb_altimeter_get_sampling_period(WbDeviceTag tag) { int sampling_period = 0; robot_mutex_lock(); - Altimeter *altimeter = altimeter_get_struct(tag); + const Altimeter *altimeter = altimeter_get_struct(tag); if (altimeter) sampling_period = altimeter->sampling_period; else @@ -132,7 +132,7 @@ int wb_altimeter_get_sampling_period(WbDeviceTag tag) { double wb_altimeter_get_value(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - Altimeter *altimeter = altimeter_get_struct(tag); + const Altimeter *altimeter = altimeter_get_struct(tag); if (altimeter) { if (altimeter->sampling_period <= 0) fprintf(stderr, "Error: %s() called for a disabled device! Please use: wb_altimeter_enable().\n", __FUNCTION__); diff --git a/src/controller/c/brake.c b/src/controller/c/brake.c index ba30ff8d687..30baa48d4c7 100644 --- a/src/controller/c/brake.c +++ b/src/controller/c/brake.c @@ -115,7 +115,7 @@ void wb_brake_set_damping_constant(WbDeviceTag tag, double damping_constant) { return; } - Brake *b = brake_get_struct(tag); + const Brake *b = brake_get_struct(tag); if (!b) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return; @@ -129,7 +129,7 @@ void wb_brake_set_damping_constant(WbDeviceTag tag, double damping_constant) { WbJointType wb_brake_get_type(WbDeviceTag tag) { WbJointType type = WB_ROTATIONAL; robot_mutex_lock(); - Brake *b = brake_get_struct(tag); + const Brake *b = brake_get_struct(tag); if (b) type = b->type; else diff --git a/src/controller/c/camera.c b/src/controller/c/camera.c index 2d2e26aa740..c8209fee285 100644 --- a/src/controller/c/camera.c +++ b/src/controller/c/camera.c @@ -360,7 +360,7 @@ void wb_camera_enable(WbDeviceTag tag, int sampling_period) { } void wb_camera_disable(WbDeviceTag tag) { - Camera *c = camera_get_struct(tag); + const Camera *c = camera_get_struct(tag); if (c) wb_camera_enable(tag, 0); else @@ -368,28 +368,28 @@ void wb_camera_disable(WbDeviceTag tag) { } int wb_camera_get_sampling_period(WbDeviceTag tag) { - WbDevice *d = camera_get_device(tag); + const WbDevice *d = camera_get_device(tag); if (!d) fprintf(stderr, "Error: %s: invalid device tag.\n", __FUNCTION__); return wb_abstract_camera_get_sampling_period(d); } int wb_camera_get_height(WbDeviceTag tag) { - WbDevice *d = camera_get_device(tag); + const WbDevice *d = camera_get_device(tag); if (!d) fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return wb_abstract_camera_get_height(d); } int wb_camera_get_width(WbDeviceTag tag) { - WbDevice *d = camera_get_device(tag); + const WbDevice *d = camera_get_device(tag); if (!d) fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return wb_abstract_camera_get_width(d); } double wb_camera_get_fov(WbDeviceTag tag) { - WbDevice *d = camera_get_device(tag); + const WbDevice *d = camera_get_device(tag); if (!d) fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return wb_abstract_camera_get_fov(d); @@ -398,7 +398,7 @@ double wb_camera_get_fov(WbDeviceTag tag) { double wb_camera_get_min_fov(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - Camera *c = camera_get_struct(tag); + const Camera *c = camera_get_struct(tag); if (c) result = c->min_fov; else @@ -410,7 +410,7 @@ double wb_camera_get_min_fov(WbDeviceTag tag) { double wb_camera_get_max_fov(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - Camera *c = camera_get_struct(tag); + const Camera *c = camera_get_struct(tag); if (c) result = c->max_fov; else @@ -449,7 +449,7 @@ void wb_camera_set_fov(WbDeviceTag tag, double fov) { double wb_camera_get_focal_length(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - Camera *c = camera_get_struct(tag); + const Camera *c = camera_get_struct(tag); if (c) result = c->focal_length; else @@ -461,7 +461,7 @@ double wb_camera_get_focal_length(WbDeviceTag tag) { double wb_camera_get_exposure(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - Camera *c = camera_get_struct(tag); + const Camera *c = camera_get_struct(tag); if (c) result = c->exposure; else @@ -487,7 +487,7 @@ void wb_camera_set_exposure(WbDeviceTag tag, double exposure) { double wb_camera_get_focal_distance(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - Camera *c = camera_get_struct(tag); + const Camera *c = camera_get_struct(tag); if (c) result = c->focal_distance; else @@ -499,7 +499,7 @@ double wb_camera_get_focal_distance(WbDeviceTag tag) { double wb_camera_get_min_focal_distance(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - Camera *c = camera_get_struct(tag); + const Camera *c = camera_get_struct(tag); if (c) result = c->min_focal_distance; else @@ -511,7 +511,7 @@ double wb_camera_get_min_focal_distance(WbDeviceTag tag) { double wb_camera_get_max_focal_distance(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - Camera *c = camera_get_struct(tag); + const Camera *c = camera_get_struct(tag); if (c) result = c->max_focal_distance; else @@ -523,7 +523,7 @@ double wb_camera_get_max_focal_distance(WbDeviceTag tag) { void wb_camera_set_focal_distance(WbDeviceTag tag, double focal_distance) { bool in_range = true; robot_mutex_lock(); - AbstractCamera *ac = camera_get_abstract_camera_struct(tag); + const AbstractCamera *ac = camera_get_abstract_camera_struct(tag); Camera *c = camera_get_struct(tag); if (!c || !ac) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); @@ -544,11 +544,11 @@ void wb_camera_set_focal_distance(WbDeviceTag tag, double focal_distance) { } double wb_camera_get_near(WbDeviceTag tag) { - WbDevice *d = camera_get_device(tag); + const WbDevice *d = camera_get_device(tag); if (!d) fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); - return wb_abstract_camera_get_near(camera_get_device(tag)); + return wb_abstract_camera_get_near(d); } void wb_camera_recognition_enable(WbDeviceTag tag, int sampling_period) { @@ -575,7 +575,7 @@ void wb_camera_recognition_enable(WbDeviceTag tag, int sampling_period) { void wb_camera_recognition_disable(WbDeviceTag tag) { robot_mutex_lock(); - Camera *c = camera_get_struct(tag); + const Camera *c = camera_get_struct(tag); bool should_return = false; if (!c) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); @@ -592,7 +592,7 @@ void wb_camera_recognition_disable(WbDeviceTag tag) { int wb_camera_recognition_get_sampling_period(WbDeviceTag tag) { int sampling_period = 0; robot_mutex_lock(); - Camera *c = camera_get_struct(tag); + const Camera *c = camera_get_struct(tag); if (c) { if (!c->has_recognition) fprintf(stderr, "Error: %s() called on a Camera without Recognition node.\n", __FUNCTION__); @@ -607,7 +607,7 @@ int wb_camera_recognition_get_sampling_period(WbDeviceTag tag) { int wb_camera_recognition_get_number_of_objects(WbDeviceTag tag) { int result = 0; robot_mutex_lock(); - Camera *c = camera_get_struct(tag); + const Camera *c = camera_get_struct(tag); if (c) { if (!c->has_recognition) fprintf(stderr, "Error: %s() called on a Camera without Recognition node.\n", __FUNCTION__); @@ -624,7 +624,7 @@ int wb_camera_recognition_get_number_of_objects(WbDeviceTag tag) { bool wb_camera_has_recognition(WbDeviceTag tag) { bool has_recognition = false; robot_mutex_lock(); - Camera *c = camera_get_struct(tag); + const Camera *c = camera_get_struct(tag); if (c) has_recognition = c->has_recognition; else @@ -636,7 +636,7 @@ bool wb_camera_has_recognition(WbDeviceTag tag) { const WbCameraRecognitionObject *wb_camera_recognition_get_objects(WbDeviceTag tag) { const WbCameraRecognitionObject *result = 0; robot_mutex_lock(); - Camera *c = camera_get_struct(tag); + const Camera *c = camera_get_struct(tag); if (c) { if (!c->has_recognition) fprintf(stderr, "Error: %s() called on a Camera without Recognition node.\n", __FUNCTION__); @@ -716,7 +716,7 @@ int wb_camera_save_image(WbDeviceTag tag, const char *filename, int quality) { } const WbCameraRecognitionObject *wb_camera_recognition_get_object(WbDeviceTag tag, int index) { - Camera *c = camera_get_struct(tag); + const Camera *c = camera_get_struct(tag); if (!c) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return NULL; @@ -727,7 +727,7 @@ const WbCameraRecognitionObject *wb_camera_recognition_get_object(WbDeviceTag ta bool wb_camera_recognition_has_segmentation(WbDeviceTag tag) { bool has_segmentation; robot_mutex_lock(); - Camera *c = camera_get_struct(tag); + const Camera *c = camera_get_struct(tag); if (c) has_segmentation = c->segmentation; else { @@ -790,7 +790,7 @@ void wb_camera_recognition_disable_segmentation(WbDeviceTag tag) { bool wb_camera_recognition_is_segmentation_enabled(WbDeviceTag tag) { robot_mutex_lock(); - Camera *c = camera_get_struct(tag); + const Camera *c = camera_get_struct(tag); if (!c) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); robot_mutex_unlock(); @@ -853,7 +853,7 @@ int wb_camera_recognition_save_segmentation_image(WbDeviceTag tag, const char *f } robot_mutex_lock(); - AbstractCamera *ac = camera_get_abstract_camera_struct(tag); + const AbstractCamera *ac = camera_get_abstract_camera_struct(tag); Camera *c = camera_get_struct(tag); if (!c) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); diff --git a/src/controller/c/compass.c b/src/controller/c/compass.c index f12edabde3f..dd6496b9035 100644 --- a/src/controller/c/compass.c +++ b/src/controller/c/compass.c @@ -77,7 +77,7 @@ static void compass_read_answer(WbDevice *d, WbRequest *r) { int wb_compass_get_lookup_table_size(WbDeviceTag tag) { int result = 0; robot_mutex_lock(); - Compass *dev = compass_get_struct(tag); + const Compass *dev = compass_get_struct(tag); if (dev) result = dev->lookup_table_size; else @@ -156,7 +156,7 @@ void wb_compass_enable(WbDeviceTag tag, int sampling_period) { } void wb_compass_disable(WbDeviceTag tag) { - Compass *compass = compass_get_struct(tag); + const Compass *compass = compass_get_struct(tag); if (compass) wb_compass_enable(tag, 0); else @@ -166,7 +166,7 @@ void wb_compass_disable(WbDeviceTag tag) { int wb_compass_get_sampling_period(WbDeviceTag tag) { int sampling_period = 0; robot_mutex_lock(); - Compass *compass = compass_get_struct(tag); + const Compass *compass = compass_get_struct(tag); if (compass) sampling_period = compass->sampling_period; else @@ -178,7 +178,7 @@ int wb_compass_get_sampling_period(WbDeviceTag tag) { const double *wb_compass_get_values(WbDeviceTag tag) { const double *result = NULL; robot_mutex_lock(); - Compass *compass = compass_get_struct(tag); + const Compass *compass = compass_get_struct(tag); if (compass) { if (compass->sampling_period <= 0) fprintf(stderr, "Error: %s() called for a disabled device! Please use: wb_compass_enable().\n", __FUNCTION__); diff --git a/src/controller/c/connector.c b/src/controller/c/connector.c index 27e0481ccb4..939e0c87a82 100644 --- a/src/controller/c/connector.c +++ b/src/controller/c/connector.c @@ -117,7 +117,7 @@ void wb_connector_enable_presence(WbDeviceTag tag, int sampling_period) { } void wb_connector_disable_presence(WbDeviceTag tag) { - Connector *con = connector_get_struct(tag); + const Connector *con = connector_get_struct(tag); if (con) wb_connector_enable_presence(tag, 0); else @@ -127,7 +127,7 @@ void wb_connector_disable_presence(WbDeviceTag tag) { int wb_connector_get_presence_sampling_period(WbDeviceTag tag) { int sampling_period = 0; robot_mutex_lock(); - Connector *con = connector_get_struct(tag); + const Connector *con = connector_get_struct(tag); if (con) sampling_period = con->presence_sampling_period; else @@ -161,7 +161,7 @@ void wb_connector_unlock(WbDeviceTag tag) { int wb_connector_get_presence(WbDeviceTag tag) { int result = -1; robot_mutex_lock(); - Connector *con = connector_get_struct(tag); + const Connector *con = connector_get_struct(tag); if (con) { if (con->presence_sampling_period <= 0) fprintf(stderr, "Error: %s() called for a disabled device! Please use: wb_connector_enable_presence().\n", __FUNCTION__); @@ -175,7 +175,7 @@ int wb_connector_get_presence(WbDeviceTag tag) { bool wb_connector_is_locked(WbDeviceTag tag) { bool result; robot_mutex_lock(); - Connector *con = connector_get_struct(tag); + const Connector *con = connector_get_struct(tag); if (con) result = con->is_locked; else { diff --git a/src/controller/c/default_robot_window.c b/src/controller/c/default_robot_window.c index 329da286b19..dddaea8f3e2 100644 --- a/src/controller/c/default_robot_window.c +++ b/src/controller/c/default_robot_window.c @@ -228,7 +228,7 @@ static void ue_append(struct UpdateElement *ue, double update_time, const double ue->values[last_index][v] = value[v]; } -static int ue_number_of_values(struct UpdateElement *ue) { +static int ue_number_of_values(const struct UpdateElement *ue) { return ue->n_values; } @@ -277,7 +277,7 @@ static void ue_write_values(struct UpdateElement *ue) { else buffer_append_double(value); } else { - double *values = ue_value_at(ue, v); + const double *values = ue_value_at(ue, v); buffer_append("["); for (c = 0; c < ue->n_components; ++c) { if (c != 0) diff --git a/src/controller/c/display.c b/src/controller/c/display.c index da7d25a459d..74f235d6e4f 100644 --- a/src/controller/c/display.c +++ b/src/controller/c/display.c @@ -357,7 +357,7 @@ static void wb_display_set_property(WbDeviceTag tag, int primitive, void *data, } static void display_toggle_remote(WbDevice *d, WbRequest *r) { - Display *display = d->pdata; + const Display *display = d->pdata; if (display->hasBeenUsed) request_write_uchar(r, C_DISPLAY_IMAGE_GET_ALL); } @@ -386,7 +386,7 @@ void wb_display_init(WbDevice *d) { int wb_display_get_height(WbDeviceTag tag) { int result = -1; robot_mutex_lock(); - Display *d = wb_display_get_struct(tag); + const Display *d = wb_display_get_struct(tag); if (d) result = d->height; else @@ -398,7 +398,7 @@ int wb_display_get_height(WbDeviceTag tag) { int wb_display_get_width(WbDeviceTag tag) { int result = -1; robot_mutex_lock(); - Display *d = wb_display_get_struct(tag); + const Display *d = wb_display_get_struct(tag); if (d) result = d->width; else @@ -408,7 +408,7 @@ int wb_display_get_width(WbDeviceTag tag) { } void wb_display_set_color(WbDeviceTag tag, int color) { - Display *d = wb_display_get_struct(tag); + const Display *d = wb_display_get_struct(tag); if (!d) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return; @@ -421,7 +421,7 @@ void wb_display_set_color(WbDeviceTag tag, int color) { } void wb_display_set_alpha(WbDeviceTag tag, double alpha) { - Display *d = wb_display_get_struct(tag); + const Display *d = wb_display_get_struct(tag); if (!d) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return; @@ -434,7 +434,7 @@ void wb_display_set_alpha(WbDeviceTag tag, double alpha) { } void wb_display_set_opacity(WbDeviceTag tag, double opacity) { - Display *d = wb_display_get_struct(tag); + const Display *d = wb_display_get_struct(tag); if (!d) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return; @@ -452,7 +452,7 @@ void wb_display_set_font(WbDeviceTag tag, const char *font, int size, bool anti_ return; } robot_mutex_lock(); - Display *display = wb_display_get_struct(tag); + const Display *display = wb_display_get_struct(tag); if (!display) { fprintf(stderr, "Error: %s(): invalid display.\n", __FUNCTION__); robot_mutex_unlock(); @@ -465,7 +465,7 @@ void wb_display_set_font(WbDeviceTag tag, const char *font, int size, bool anti_ void wb_display_attach_camera(WbDeviceTag tag, WbDeviceTag camera_tag) { robot_mutex_lock(); Display *display = wb_display_get_struct(tag); - WbDevice *camera = robot_get_device_with_node(camera_tag, WB_NODE_CAMERA, true); + const WbDevice *camera = robot_get_device_with_node(camera_tag, WB_NODE_CAMERA, true); if (!display) { fprintf(stderr, "Error: %s(): invalid display.\n", __FUNCTION__); robot_mutex_unlock(); @@ -507,30 +507,30 @@ void wb_display_detach_camera(WbDeviceTag tag) { } void wb_display_draw_pixel(WbDeviceTag tag, int x, int y) { - Display *d = wb_display_get_struct(tag); + const Display *d = wb_display_get_struct(tag); if (!d) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return; } - int px[] = {x}; - int py[] = {y}; + const int px[] = {x}; + const int py[] = {y}; wb_display_draw_primitive(tag, C_DISPLAY_DRAW_PIXEL, px, py, 1, false, NULL); } void wb_display_draw_line(WbDeviceTag tag, int x1, int y1, int x2, int y2) { - Display *d = wb_display_get_struct(tag); + const Display *d = wb_display_get_struct(tag); if (!d) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return; } - int px[] = {x1, x2}; - int py[] = {y1, y2}; + const int px[] = {x1, x2}; + const int py[] = {y1, y2}; wb_display_draw_primitive(tag, C_DISPLAY_DRAW_LINE, px, py, 2, false, NULL); } void wb_display_draw_rectangle(WbDeviceTag tag, int x, int y, int width, int height) { - Display *d = wb_display_get_struct(tag); + const Display *d = wb_display_get_struct(tag); if (!d) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return; @@ -543,13 +543,13 @@ void wb_display_draw_rectangle(WbDeviceTag tag, int x, int y, int width, int hei fprintf(stderr, "Error: %s(): 'height' argument is negative or null.\n", __FUNCTION__); return; } - int px[] = {x, width}; - int py[] = {y, height}; + const int px[] = {x, width}; + const int py[] = {y, height}; wb_display_draw_primitive(tag, C_DISPLAY_DRAW_RECTANGLE, px, py, 2, false, NULL); } void wb_display_draw_oval(WbDeviceTag tag, int cx, int cy, int a, int b) { - Display *d = wb_display_get_struct(tag); + const Display *d = wb_display_get_struct(tag); if (!d) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return; @@ -562,13 +562,13 @@ void wb_display_draw_oval(WbDeviceTag tag, int cx, int cy, int a, int b) { fprintf(stderr, "Error: %s(): 'vertical_radius' argument is negative or null.\n", __FUNCTION__); return; } - int px[] = {cx, a}; - int py[] = {cy, b}; + const int px[] = {cx, a}; + const int py[] = {cy, b}; wb_display_draw_primitive(tag, C_DISPLAY_DRAW_OVAL, px, py, 2, false, NULL); } void wb_display_draw_polygon(WbDeviceTag tag, const int *x, const int *y, int size) { - Display *d = wb_display_get_struct(tag); + const Display *d = wb_display_get_struct(tag); if (!d) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return; @@ -581,7 +581,7 @@ void wb_display_draw_polygon(WbDeviceTag tag, const int *x, const int *y, int si } void wb_display_draw_text(WbDeviceTag tag, const char *text, int x, int y) { - Display *d = wb_display_get_struct(tag); + const Display *d = wb_display_get_struct(tag); if (!d) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return; @@ -590,13 +590,13 @@ void wb_display_draw_text(WbDeviceTag tag, const char *text, int x, int y) { fprintf(stderr, "Error: %s(): 'text' argument is NULL or empty.\n", __FUNCTION__); return; } - int px[] = {x}; - int py[] = {y}; + const int px[] = {x}; + const int py[] = {y}; wb_display_draw_primitive(tag, C_DISPLAY_DRAW_TEXT, px, py, 1, false, text); } void wb_display_fill_rectangle(WbDeviceTag tag, int x, int y, int width, int height) { - Display *d = wb_display_get_struct(tag); + const Display *d = wb_display_get_struct(tag); if (!d) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return; @@ -609,13 +609,13 @@ void wb_display_fill_rectangle(WbDeviceTag tag, int x, int y, int width, int hei fprintf(stderr, "Error: %s(): 'height' argument is negative or null.\n", __FUNCTION__); return; } - int px[] = {x, width}; - int py[] = {y, height}; + const int px[] = {x, width}; + const int py[] = {y, height}; wb_display_draw_primitive(tag, C_DISPLAY_DRAW_RECTANGLE, px, py, 2, true, NULL); } void wb_display_fill_oval(WbDeviceTag tag, int cx, int cy, int a, int b) { - Display *d = wb_display_get_struct(tag); + const Display *d = wb_display_get_struct(tag); if (!d) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return; @@ -628,13 +628,13 @@ void wb_display_fill_oval(WbDeviceTag tag, int cx, int cy, int a, int b) { fprintf(stderr, "Error: %s(): 'vertical_radius' argument is negative or null.\n", __FUNCTION__); return; } - int px[] = {cx, a}; - int py[] = {cy, b}; + const int px[] = {cx, a}; + const int py[] = {cy, b}; wb_display_draw_primitive(tag, C_DISPLAY_DRAW_OVAL, px, py, 2, true, NULL); } void wb_display_fill_polygon(WbDeviceTag tag, const int *x, const int *y, int size) { - Display *d = wb_display_get_struct(tag); + const Display *d = wb_display_get_struct(tag); if (!d) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return; @@ -746,7 +746,7 @@ WbImageRef wb_display_image_new(WbDeviceTag tag, int width, int height, const vo else { // channel == 4 int j; const int s = width * height; - unsigned char *img = (unsigned char *)data; + const unsigned char *img = (unsigned char *)data; for (j = 0; j < s; j++) ((uint32_t *)i->image)[j] = img[j * 4 + 3] << 24 | img[j * 4 + 2] << 16 | img[j * 4 + 1] << 8 | img[j * 4]; } diff --git a/src/controller/c/distance_sensor.c b/src/controller/c/distance_sensor.c index 49983ec1282..8a37d5ec69b 100644 --- a/src/controller/c/distance_sensor.c +++ b/src/controller/c/distance_sensor.c @@ -86,7 +86,7 @@ static void distance_sensor_read_answer(WbDevice *d, WbRequest *r) { int wb_distance_sensor_get_lookup_table_size(WbDeviceTag tag) { int result = 0; robot_mutex_lock(); - DistanceSensor *ds = distance_sensor_get_struct(tag); + const DistanceSensor *ds = distance_sensor_get_struct(tag); if (ds) result = ds->lookup_table_size; else @@ -167,7 +167,7 @@ void wb_distance_sensor_enable(WbDeviceTag tag, int sampling_period) { int wb_distance_sensor_get_sampling_period(WbDeviceTag tag) { int sampling_period = 0; robot_mutex_lock(); - DistanceSensor *ds = distance_sensor_get_struct(tag); + const DistanceSensor *ds = distance_sensor_get_struct(tag); if (ds) sampling_period = ds->sampling_period; else @@ -177,7 +177,7 @@ int wb_distance_sensor_get_sampling_period(WbDeviceTag tag) { } void wb_distance_sensor_disable(WbDeviceTag tag) { - DistanceSensor *ds = distance_sensor_get_struct(tag); + const DistanceSensor *ds = distance_sensor_get_struct(tag); if (ds) wb_distance_sensor_enable(tag, 0); else @@ -187,7 +187,7 @@ void wb_distance_sensor_disable(WbDeviceTag tag) { double wb_distance_sensor_get_value(WbDeviceTag tag) { double value = NAN; robot_mutex_lock(); - DistanceSensor *ds = distance_sensor_get_struct(tag); + const DistanceSensor *ds = distance_sensor_get_struct(tag); if (ds) { if (ds->sampling_period <= 0) fprintf(stderr, "Error: %s() called for a disabled device! Please use: wb_distance_sensor_enable().\n", __FUNCTION__); @@ -201,7 +201,7 @@ double wb_distance_sensor_get_value(WbDeviceTag tag) { double wb_distance_sensor_get_max_value(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - DistanceSensor *ds = distance_sensor_get_struct(tag); + const DistanceSensor *ds = distance_sensor_get_struct(tag); if (ds) result = ds->max_value; else @@ -213,7 +213,7 @@ double wb_distance_sensor_get_max_value(WbDeviceTag tag) { double wb_distance_sensor_get_min_value(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - DistanceSensor *ds = distance_sensor_get_struct(tag); + const DistanceSensor *ds = distance_sensor_get_struct(tag); if (ds) result = ds->min_value; else @@ -225,7 +225,7 @@ double wb_distance_sensor_get_min_value(WbDeviceTag tag) { double wb_distance_sensor_get_aperture(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - DistanceSensor *ds = distance_sensor_get_struct(tag); + const DistanceSensor *ds = distance_sensor_get_struct(tag); if (ds) result = ds->aperture; else @@ -237,7 +237,7 @@ double wb_distance_sensor_get_aperture(WbDeviceTag tag) { WbDistanceSensorType wb_distance_sensor_get_type(WbDeviceTag tag) { WbDistanceSensorType result = WB_DISTANCE_SENSOR_GENERIC; robot_mutex_lock(); - DistanceSensor *ds = distance_sensor_get_struct(tag); + const DistanceSensor *ds = distance_sensor_get_struct(tag); if (ds) result = ds->type; else diff --git a/src/controller/c/emitter.c b/src/controller/c/emitter.c index 68350b15d59..879f4653978 100644 --- a/src/controller/c/emitter.c +++ b/src/controller/c/emitter.c @@ -247,9 +247,9 @@ int wb_emitter_send(WbDeviceTag tag, const void *data, int size) { int wb_emitter_get_buffer_size(WbDeviceTag tag) { int result = -1; robot_mutex_lock(); - WbDevice *d = emitter_get_device(tag); + const WbDevice *d = emitter_get_device(tag); if (d) { - Emitter *es = d->pdata; + const Emitter *es = d->pdata; result = es->buffer_size; } else fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); @@ -260,9 +260,9 @@ int wb_emitter_get_buffer_size(WbDeviceTag tag) { int wb_emitter_get_channel(WbDeviceTag tag) { int result = -1; robot_mutex_lock(); - WbDevice *d = emitter_get_device(tag); + const WbDevice *d = emitter_get_device(tag); if (d) { - Emitter *es = d->pdata; + const Emitter *es = d->pdata; result = es->channel; } else fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); @@ -307,9 +307,9 @@ void wb_emitter_set_channel(WbDeviceTag tag, int channel) { double wb_emitter_get_range(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - WbDevice *d = emitter_get_device(tag); + const WbDevice *d = emitter_get_device(tag); if (d) { - Emitter *es = d->pdata; + const Emitter *es = d->pdata; result = es->range; } else fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); diff --git a/src/controller/c/g_image.c b/src/controller/c/g_image.c index 020012e96b2..54c3a7b7db0 100644 --- a/src/controller/c/g_image.c +++ b/src/controller/c/g_image.c @@ -129,7 +129,7 @@ static int g_image_png_save(GImage *img, const char *filename) { fprintf(stderr, "Insufficient permissions to write file: %s\n", filename); else { char cwd[256]; - char *r = getcwd(cwd, 256); + const char *r = getcwd(cwd, 256); if (r) fprintf(stderr, "Insufficient permissions to write file: %s%c%s\n", cwd, DIR_SEPARATOR, filename); else diff --git a/src/controller/c/g_pipe.c b/src/controller/c/g_pipe.c index 9c0b08c440a..0c9ceeafa11 100644 --- a/src/controller/c/g_pipe.c +++ b/src/controller/c/g_pipe.c @@ -141,7 +141,7 @@ int g_pipe_receive(GPipe *p, char *data, int size) { #endif } -size_t g_pipe_get_handle(GPipe *p) { +size_t g_pipe_get_handle(const GPipe *p) { if (p) return (size_t)p->handle; return 0; diff --git a/src/controller/c/g_pipe.h b/src/controller/c/g_pipe.h index 1fcd213d3c7..4a2ce30c1d8 100644 --- a/src/controller/c/g_pipe.h +++ b/src/controller/c/g_pipe.h @@ -46,7 +46,7 @@ GPipe *g_pipe_new(const char *); // named pipe on Windows, UNIX domain socket o void g_pipe_delete(GPipe *); void g_pipe_send(GPipe *, const char *data, int size); int g_pipe_receive(GPipe *, char *data, int size); -size_t g_pipe_get_handle(GPipe *); +size_t g_pipe_get_handle(const GPipe *); #ifdef __cplusplus } diff --git a/src/controller/c/gps.c b/src/controller/c/gps.c index c7849d269ed..96bdc40e09c 100644 --- a/src/controller/c/gps.c +++ b/src/controller/c/gps.c @@ -148,7 +148,7 @@ void wb_gps_enable(WbDeviceTag tag, int sampling_period) { } void wb_gps_disable(WbDeviceTag tag) { - GPS *gps = gps_get_struct(tag); + const GPS *gps = gps_get_struct(tag); if (gps) wb_gps_enable(tag, 0); else @@ -158,7 +158,7 @@ void wb_gps_disable(WbDeviceTag tag) { int wb_gps_get_sampling_period(WbDeviceTag tag) { int sampling_period = 0; robot_mutex_lock(); - GPS *gps = gps_get_struct(tag); + const GPS *gps = gps_get_struct(tag); if (gps) sampling_period = gps->sampling_period; else @@ -170,7 +170,7 @@ int wb_gps_get_sampling_period(WbDeviceTag tag) { const double *wb_gps_get_values(WbDeviceTag tag) { const double *result = NULL; robot_mutex_lock(); - GPS *gps = gps_get_struct(tag); + const GPS *gps = gps_get_struct(tag); if (gps) { if (gps->sampling_period <= 0) fprintf(stderr, "Error: %s() called for a disabled device! Please use: wb_gps_enable().\n", __FUNCTION__); @@ -184,7 +184,7 @@ const double *wb_gps_get_values(WbDeviceTag tag) { double wb_gps_get_speed(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - GPS *gps = gps_get_struct(tag); + const GPS *gps = gps_get_struct(tag); if (gps) { if (gps->sampling_period <= 0) fprintf(stderr, "Error: %s() called for a disabled device! Please use: wb_gps_enable().\n", __FUNCTION__); @@ -198,7 +198,7 @@ double wb_gps_get_speed(WbDeviceTag tag) { const double *wb_gps_get_speed_vector(WbDeviceTag tag) { const double *result = NULL; robot_mutex_lock(); - GPS *gps = gps_get_struct(tag); + const GPS *gps = gps_get_struct(tag); if (gps) { if (gps->sampling_period <= 0) fprintf(stderr, "Error: %s() called for a disabled device! Please use: wb_gps_enable().\n", __FUNCTION__); @@ -221,7 +221,7 @@ const char *wb_gps_convert_to_degrees_minutes_seconds(double decimal_degrees) { WbGpsCoordinateSystem wb_gps_get_coordinate_system(WbDeviceTag tag) { WbGpsCoordinateSystem result = WB_GPS_LOCAL_COORDINATE; robot_mutex_lock(); - GPS *gps = gps_get_struct(tag); + const GPS *gps = gps_get_struct(tag); if (gps) result = gps->coordinate_system; else diff --git a/src/controller/c/gyro.c b/src/controller/c/gyro.c index 9b83e9a50a6..72296b583ee 100644 --- a/src/controller/c/gyro.c +++ b/src/controller/c/gyro.c @@ -76,7 +76,7 @@ static void gyro_read_answer(WbDevice *d, WbRequest *r) { int wb_gyro_get_lookup_table_size(WbDeviceTag tag) { int result = 0; robot_mutex_lock(); - Gyro *dev = gyro_get_struct(tag); + const Gyro *dev = gyro_get_struct(tag); if (dev) result = dev->lookup_table_size; else @@ -157,7 +157,7 @@ void wb_gyro_enable(WbDeviceTag tag, int sampling_period) { } void wb_gyro_disable(WbDeviceTag tag) { - Gyro *gyro = gyro_get_struct(tag); + const Gyro *gyro = gyro_get_struct(tag); if (gyro) wb_gyro_enable(tag, 0); else @@ -167,7 +167,7 @@ void wb_gyro_disable(WbDeviceTag tag) { int wb_gyro_get_sampling_period(WbDeviceTag tag) { int sampling_period = 0; robot_mutex_lock(); - Gyro *gyro = gyro_get_struct(tag); + const Gyro *gyro = gyro_get_struct(tag); if (gyro) sampling_period = gyro->sampling_period; else @@ -179,7 +179,7 @@ int wb_gyro_get_sampling_period(WbDeviceTag tag) { const double *wb_gyro_get_values(WbDeviceTag tag) { const double *result = NULL; robot_mutex_lock(); - Gyro *gyro = gyro_get_struct(tag); + const Gyro *gyro = gyro_get_struct(tag); if (gyro) { if (gyro->sampling_period <= 0) fprintf(stderr, "Error: %s() called for a disabled device! Please use: wb_gyro_enable().\n", __FUNCTION__); diff --git a/src/controller/c/inertial_unit.c b/src/controller/c/inertial_unit.c index 6b565cde08f..406a994fe0a 100644 --- a/src/controller/c/inertial_unit.c +++ b/src/controller/c/inertial_unit.c @@ -67,7 +67,7 @@ static void inertial_unit_read_answer(WbDevice *d, WbRequest *r) { double wb_inertial_unit_get_noise(WbDeviceTag tag) { double result = 0; robot_mutex_lock(); - InertialUnit *dev = inertial_unit_get_struct(tag); + const InertialUnit *dev = inertial_unit_get_struct(tag); if (dev) result = dev->noise; else @@ -124,7 +124,7 @@ void wb_inertial_unit_enable(WbDeviceTag tag, int sampling_period) { } void wb_inertial_unit_disable(WbDeviceTag tag) { - InertialUnit *inertial_unit = inertial_unit_get_struct(tag); + const InertialUnit *inertial_unit = inertial_unit_get_struct(tag); if (inertial_unit) wb_inertial_unit_enable(tag, 0); else @@ -134,7 +134,7 @@ void wb_inertial_unit_disable(WbDeviceTag tag) { int wb_inertial_unit_get_sampling_period(WbDeviceTag tag) { int sampling_period = 0; robot_mutex_lock(); - InertialUnit *inertial_unit = inertial_unit_get_struct(tag); + const InertialUnit *inertial_unit = inertial_unit_get_struct(tag); if (inertial_unit) sampling_period = inertial_unit->sampling_period; else @@ -146,7 +146,7 @@ int wb_inertial_unit_get_sampling_period(WbDeviceTag tag) { const double *wb_inertial_unit_get_roll_pitch_yaw(WbDeviceTag tag) { static double result[3]; robot_mutex_lock(); - InertialUnit *inertial_unit = inertial_unit_get_struct(tag); + const InertialUnit *inertial_unit = inertial_unit_get_struct(tag); if (inertial_unit) { if (inertial_unit->sampling_period <= 0) fprintf(stderr, "Error: %s() called for a disabled device! Please use: wb_inertial_unit_enable().\n", __FUNCTION__); @@ -183,7 +183,7 @@ const double *wb_inertial_unit_get_roll_pitch_yaw(WbDeviceTag tag) { const double *wb_inertial_unit_get_quaternion(WbDeviceTag tag) { const double *result = NULL; robot_mutex_lock(); - InertialUnit *inertial_unit = inertial_unit_get_struct(tag); + const InertialUnit *inertial_unit = inertial_unit_get_struct(tag); if (inertial_unit) { if (inertial_unit->sampling_period <= 0) fprintf(stderr, "Error: %s() called for a disabled device! Please use: wb_inertial_unit_enable().\n", __FUNCTION__); diff --git a/src/controller/c/led.c b/src/controller/c/led.c index f5b2a039530..12106be2d1f 100644 --- a/src/controller/c/led.c +++ b/src/controller/c/led.c @@ -92,7 +92,7 @@ void wb_led_set(WbDeviceTag tag, int value) { int wb_led_get(WbDeviceTag tag) { int state = 0; robot_mutex_lock(); - LED *led = led_get_struct(tag); + const LED *led = led_get_struct(tag); if (led) state = led->state; else diff --git a/src/controller/c/lidar.c b/src/controller/c/lidar.c index dd653d2bfae..cd4f50a7c88 100644 --- a/src/controller/c/lidar.c +++ b/src/controller/c/lidar.c @@ -183,8 +183,8 @@ void wb_lidar_init(WbDevice *d) { // g_print("lidar init done\n"); } -int wb_lidar_get_unique_id(WbDevice *d) { - AbstractCamera *ac = d->pdata; +int wb_lidar_get_unique_id(const WbDevice *d) { + const AbstractCamera *ac = d->pdata; return ac->unique_id; } @@ -233,7 +233,7 @@ void wb_lidar_enable_point_cloud(WbDeviceTag tag) { } void wb_lidar_disable(WbDeviceTag tag) { - Lidar *l = lidar_get_struct(tag); + const Lidar *l = lidar_get_struct(tag); if (!l) fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); else @@ -254,7 +254,7 @@ void wb_lidar_disable_point_cloud(WbDeviceTag tag) { } int wb_lidar_get_sampling_period(WbDeviceTag tag) { - Lidar *l = lidar_get_struct(tag); + const Lidar *l = lidar_get_struct(tag); if (!l) fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); @@ -264,7 +264,7 @@ int wb_lidar_get_sampling_period(WbDeviceTag tag) { bool wb_lidar_is_point_cloud_enabled(WbDeviceTag tag) { bool result = false; robot_mutex_lock(); - Lidar *l = lidar_get_struct(tag); + const Lidar *l = lidar_get_struct(tag); if (l) result = l->point_cloud_enabled; else @@ -276,7 +276,7 @@ bool wb_lidar_is_point_cloud_enabled(WbDeviceTag tag) { int wb_lidar_get_number_of_layers(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - Lidar *l = lidar_get_struct(tag); + const Lidar *l = lidar_get_struct(tag); if (l) result = l->number_of_layers; else @@ -288,7 +288,7 @@ int wb_lidar_get_number_of_layers(WbDeviceTag tag) { double wb_lidar_get_min_frequency(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - Lidar *l = lidar_get_struct(tag); + const Lidar *l = lidar_get_struct(tag); if (l) result = l->min_frequency; else @@ -300,7 +300,7 @@ double wb_lidar_get_min_frequency(WbDeviceTag tag) { double wb_lidar_get_max_frequency(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - Lidar *l = lidar_get_struct(tag); + const Lidar *l = lidar_get_struct(tag); if (l) result = l->max_frequency; else @@ -312,7 +312,7 @@ double wb_lidar_get_max_frequency(WbDeviceTag tag) { double wb_lidar_get_frequency(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - Lidar *l = lidar_get_struct(tag); + const Lidar *l = lidar_get_struct(tag); if (l) result = l->frequency; else @@ -340,7 +340,7 @@ void wb_lidar_set_frequency(WbDeviceTag tag, double frequency) { int wb_lidar_get_horizontal_resolution(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - Lidar *l = lidar_get_struct(tag); + const Lidar *l = lidar_get_struct(tag); if (l) result = l->horizontal_resolution; else @@ -350,7 +350,7 @@ int wb_lidar_get_horizontal_resolution(WbDeviceTag tag) { } double wb_lidar_get_fov(WbDeviceTag tag) { - WbDevice *d = lidar_get_device(tag); + const WbDevice *d = lidar_get_device(tag); if (!d) fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return wb_abstract_camera_get_fov(d); @@ -359,7 +359,7 @@ double wb_lidar_get_fov(WbDeviceTag tag) { double wb_lidar_get_vertical_fov(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - Lidar *l = lidar_get_struct(tag); + const Lidar *l = lidar_get_struct(tag); if (l) result = l->vertical_fov; else @@ -369,7 +369,7 @@ double wb_lidar_get_vertical_fov(WbDeviceTag tag) { } double wb_lidar_get_min_range(WbDeviceTag tag) { - WbDevice *d = lidar_get_device(tag); + const WbDevice *d = lidar_get_device(tag); if (!d) fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return wb_abstract_camera_get_near(d); @@ -378,7 +378,7 @@ double wb_lidar_get_min_range(WbDeviceTag tag) { double wb_lidar_get_max_range(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - Lidar *l = lidar_get_struct(tag); + const Lidar *l = lidar_get_struct(tag); if (l) result = l->max_range; else @@ -411,7 +411,7 @@ const float *wb_lidar_get_range_image(WbDeviceTag tag) { } const float *wb_lidar_get_layer_range_image(WbDeviceTag tag, int layer) { - Lidar *l = lidar_get_struct(tag); + const Lidar *l = lidar_get_struct(tag); if (!l) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return NULL; @@ -438,7 +438,7 @@ const float *wb_lidar_get_layer_range_image(WbDeviceTag tag, int layer) { } const WbLidarPoint *wb_lidar_get_point_cloud(WbDeviceTag tag) { - Lidar *l = lidar_get_struct(tag); + const Lidar *l = lidar_get_struct(tag); if (!l) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return NULL; @@ -459,7 +459,7 @@ const WbLidarPoint *wb_lidar_get_point_cloud(WbDeviceTag tag) { } const WbLidarPoint *wb_lidar_get_layer_point_cloud(WbDeviceTag tag, int layer) { - Lidar *l = lidar_get_struct(tag); + const Lidar *l = lidar_get_struct(tag); if (!l) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return NULL; @@ -489,7 +489,7 @@ const WbLidarPoint *wb_lidar_get_layer_point_cloud(WbDeviceTag tag, int layer) { } int wb_lidar_get_number_of_points(WbDeviceTag tag) { - Lidar *l = lidar_get_struct(tag); + const Lidar *l = lidar_get_struct(tag); if (!l) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return 0; @@ -507,7 +507,7 @@ int wb_lidar_get_number_of_points(WbDeviceTag tag) { } const WbLidarPoint *wb_lidar_get_point(WbDeviceTag tag, int index) { - Lidar *l = lidar_get_struct(tag); + const Lidar *l = lidar_get_struct(tag); if (l) return (wb_lidar_get_point_cloud(tag) + index); diff --git a/src/controller/c/light_sensor.c b/src/controller/c/light_sensor.c index 56fc566497c..ca94855f09c 100644 --- a/src/controller/c/light_sensor.c +++ b/src/controller/c/light_sensor.c @@ -73,7 +73,7 @@ static void light_sensor_read_answer(WbDevice *d, WbRequest *r) { int wb_light_sensor_get_lookup_table_size(WbDeviceTag tag) { int result = 0; robot_mutex_lock(); - LightSensor *dev = light_sensor_get_struct(tag); + const LightSensor *dev = light_sensor_get_struct(tag); if (dev) result = dev->lookup_table_size; else @@ -152,7 +152,7 @@ void wb_light_sensor_enable(WbDeviceTag tag, int sampling_period) { } void wb_light_sensor_disable(WbDeviceTag tag) { - LightSensor *ls = light_sensor_get_struct(tag); + const LightSensor *ls = light_sensor_get_struct(tag); if (ls) wb_light_sensor_enable(tag, 0); else @@ -162,7 +162,7 @@ void wb_light_sensor_disable(WbDeviceTag tag) { int wb_light_sensor_get_sampling_period(WbDeviceTag tag) { int sampling_period = 0; robot_mutex_lock(); - LightSensor *ls = light_sensor_get_struct(tag); + const LightSensor *ls = light_sensor_get_struct(tag); if (ls) sampling_period = ls->sampling_period; else @@ -174,7 +174,7 @@ int wb_light_sensor_get_sampling_period(WbDeviceTag tag) { double wb_light_sensor_get_value(WbDeviceTag tag) { double value = NAN; robot_mutex_lock(); - LightSensor *ls = light_sensor_get_struct(tag); + const LightSensor *ls = light_sensor_get_struct(tag); if (ls) { if (ls->sampling_period <= 0) fprintf(stderr, "Error: %s() called for a disabled device! Please use: wb_light_sensor_enable().\n", __FUNCTION__); diff --git a/src/controller/c/microphone.c b/src/controller/c/microphone.c index 25e88d5bdb1..c1c22c078fa 100644 --- a/src/controller/c/microphone.c +++ b/src/controller/c/microphone.c @@ -90,7 +90,7 @@ static void microphone_cleanup(WbDevice *d) { int wb_microphone_get_sampling_period(WbDeviceTag tag) { int sampling_period = 0; robot_mutex_lock(); - Microphone *mic = microphone_get_struct(tag); + const Microphone *mic = microphone_get_struct(tag); if (mic) sampling_period = mic->sampling_period; else @@ -145,7 +145,7 @@ void wb_microphone_enable(WbDeviceTag tag, int sampling_period) { } void wb_microphone_disable(WbDeviceTag tag) { - Microphone *mic = microphone_get_struct(tag); + const Microphone *mic = microphone_get_struct(tag); if (mic) wb_microphone_enable(tag, 0); else @@ -155,7 +155,7 @@ void wb_microphone_disable(WbDeviceTag tag) { const void *wb_microphone_get_sample_data(WbDeviceTag tag) { const void *result = NULL; robot_mutex_lock(); - Microphone *mic = microphone_get_struct(tag); + const Microphone *mic = microphone_get_struct(tag); if (mic) { if (mic->sampling_period <= 0) fprintf(stderr, "Error: %s() called for a disabled device! Please use: wb_microphone_enable().\n", __FUNCTION__); @@ -169,7 +169,7 @@ const void *wb_microphone_get_sample_data(WbDeviceTag tag) { int wb_microphone_get_sample_size(WbDeviceTag tag) { int result = -1; robot_mutex_lock(); - Microphone *mic = microphone_get_struct(tag); + const Microphone *mic = microphone_get_struct(tag); if (mic) { if (mic->sampling_period <= 0) fprintf(stderr, "Error: %s() called for a disabled device! Please use: wb_microphone_enable().\n", __FUNCTION__); diff --git a/src/controller/c/motion.c b/src/controller/c/motion.c index 0f365f65c28..8f7f6212536 100644 --- a/src/controller/c/motion.c +++ b/src/controller/c/motion.c @@ -57,7 +57,7 @@ static int cleanup_done = 0; // returns UNDEFINED_TIME in case of syntax error static int str_to_time(const char *token) { // check for illegal characters - char cset[] = "0123456789:"; + const char cset[] = "0123456789:"; if (strspn(token, cset) < strlen(token)) return UNDEFINED_TIME; @@ -110,7 +110,7 @@ static bool motion_check_file(FILE *file, const char *filename, int *n_joints, i return false; } - char *token = next_token(buffer); + const char *token = next_token(buffer); if (!token) { fprintf(stderr, "Error: wbu_motion_new(): unexpected end of file '%s'.\n", filename); return false; @@ -217,7 +217,7 @@ static void motion_load(WbMotionRef ref, FILE *file) { rewind(file); char buffer[MAX_LINE]; - char *r = fgets(buffer, MAX_LINE, file); + const char *r = fgets(buffer, MAX_LINE, file); if (r == NULL) return; // should never happen @@ -227,7 +227,7 @@ static void motion_load(WbMotionRef ref, FILE *file) { int i; for (i = 0; i < ref->n_joints; i++) { - char *token = next_token(NULL); + const char *token = next_token(NULL); ref->joint_names[i] = malloc(strlen(token) + 1); strcpy(ref->joint_names[i], token); } @@ -236,7 +236,7 @@ static void motion_load(WbMotionRef ref, FILE *file) { r = fgets(buffer, MAX_LINE, file); if (r == NULL) return; // should never happen - char *token = next_token(buffer); + const char *token = next_token(buffer); ref->times[i] = str_to_time(token); next_token(NULL); // skip pose name int j; diff --git a/src/controller/c/motor.c b/src/controller/c/motor.c index 0314713797b..8a65051d587 100644 --- a/src/controller/c/motor.c +++ b/src/controller/c/motor.c @@ -261,7 +261,7 @@ void wb_motor_set_position(WbDeviceTag tag, double position) { return; } - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (!m) fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); else { @@ -305,7 +305,7 @@ void wb_motor_set_velocity(WbDeviceTag tag, double velocity) { double wb_motor_get_velocity(WbDeviceTag tag) { double vel = NAN; robot_mutex_lock(); - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) vel = m->velocity; else @@ -317,7 +317,7 @@ double wb_motor_get_velocity(WbDeviceTag tag) { double wb_motor_get_max_velocity(WbDeviceTag tag) { double vel = NAN; robot_mutex_lock(); - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) vel = m->max_velocity; else @@ -348,7 +348,7 @@ void wb_motor_set_acceleration(WbDeviceTag tag, double acceleration) { double wb_motor_get_acceleration(WbDeviceTag tag) { double acc = NAN; robot_mutex_lock(); - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) acc = m->acceleration; else @@ -404,7 +404,7 @@ void wb_motor_set_available_force(WbDeviceTag tag, double force) { double wb_motor_get_available_force(WbDeviceTag tag) { double force = NAN; robot_mutex_lock(); - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) force = m->available_force; else @@ -416,7 +416,7 @@ double wb_motor_get_available_force(WbDeviceTag tag) { double wb_motor_get_max_force(WbDeviceTag tag) { double force = NAN; robot_mutex_lock(); - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) force = m->max_force; else @@ -470,7 +470,7 @@ void wb_motor_enable_force_feedback(WbDeviceTag tag, int sampling_period) { } void wb_motor_disable_force_feedback(WbDeviceTag tag) { - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) wb_motor_enable_force_feedback(tag, 0); else @@ -492,7 +492,7 @@ double wb_motor_get_force_feedback(WbDeviceTag tag) { int wb_motor_get_force_feedback_sampling_period(WbDeviceTag tag) { int sampling_period = 0; robot_mutex_lock(); - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) sampling_period = m->force_feedback_sampling_period; else @@ -504,7 +504,7 @@ int wb_motor_get_force_feedback_sampling_period(WbDeviceTag tag) { double wb_motor_get_min_position(WbDeviceTag tag) { double pos = NAN; robot_mutex_lock(); - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) pos = m->min_position; else @@ -516,7 +516,7 @@ double wb_motor_get_min_position(WbDeviceTag tag) { double wb_motor_get_max_position(WbDeviceTag tag) { double pos = NAN; robot_mutex_lock(); - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) pos = m->max_position; else @@ -528,7 +528,7 @@ double wb_motor_get_max_position(WbDeviceTag tag) { double wb_motor_get_target_position(WbDeviceTag tag) { double pos = NAN; robot_mutex_lock(); - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) pos = m->position; else @@ -540,7 +540,7 @@ double wb_motor_get_target_position(WbDeviceTag tag) { WbJointType wb_motor_get_type(WbDeviceTag tag) { WbJointType type = WB_ROTATIONAL; robot_mutex_lock(); - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) type = m->type; else @@ -559,7 +559,7 @@ void wbr_motor_set_force_feedback(WbDeviceTag t, double value) { // Aliases void wb_motor_set_available_torque(WbDeviceTag tag, double torque) { - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) wb_motor_set_available_force(tag, torque); else @@ -567,7 +567,7 @@ void wb_motor_set_available_torque(WbDeviceTag tag, double torque) { } double wb_motor_get_available_torque(WbDeviceTag tag) { - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) return wb_motor_get_available_force(tag); @@ -578,7 +578,7 @@ double wb_motor_get_available_torque(WbDeviceTag tag) { double wb_motor_get_multiplier(WbDeviceTag tag) { double multiplier; robot_mutex_lock(); - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) multiplier = m->multiplier; else { @@ -590,7 +590,7 @@ double wb_motor_get_multiplier(WbDeviceTag tag) { } double wb_motor_get_max_torque(WbDeviceTag tag) { - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) return wb_motor_get_max_force(tag); @@ -599,7 +599,7 @@ double wb_motor_get_max_torque(WbDeviceTag tag) { } void wb_motor_set_torque(WbDeviceTag tag, double torque) { - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) wb_motor_set_force(tag, torque); else @@ -607,7 +607,7 @@ void wb_motor_set_torque(WbDeviceTag tag, double torque) { } void wb_motor_enable_torque_feedback(WbDeviceTag tag, int sampling_period) { - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) wb_motor_enable_force_feedback(tag, sampling_period); else @@ -615,7 +615,7 @@ void wb_motor_enable_torque_feedback(WbDeviceTag tag, int sampling_period) { } void wb_motor_disable_torque_feedback(WbDeviceTag tag) { - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) wb_motor_disable_force_feedback(tag); else @@ -623,7 +623,7 @@ void wb_motor_disable_torque_feedback(WbDeviceTag tag) { } int wb_motor_get_torque_feedback_sampling_period(WbDeviceTag tag) { - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) return wb_motor_get_force_feedback_sampling_period(tag); @@ -632,7 +632,7 @@ int wb_motor_get_torque_feedback_sampling_period(WbDeviceTag tag) { } double wb_motor_get_torque_feedback(WbDeviceTag tag) { - Motor *m = motor_get_struct(tag); + const Motor *m = motor_get_struct(tag); if (m) return wb_motor_get_force_feedback(tag); @@ -641,7 +641,7 @@ double wb_motor_get_torque_feedback(WbDeviceTag tag) { } void wbr_motor_set_torque_feedback(WbDeviceTag t, double value) { - Motor *m = motor_get_struct(t); + const Motor *m = motor_get_struct(t); if (m) wbr_motor_set_force_feedback(t, value); else diff --git a/src/controller/c/position_sensor.c b/src/controller/c/position_sensor.c index a9c3e9430a3..a8df39e55dc 100644 --- a/src/controller/c/position_sensor.c +++ b/src/controller/c/position_sensor.c @@ -132,7 +132,7 @@ void wb_position_sensor_enable(WbDeviceTag tag, int sampling_period) { } void wb_position_sensor_disable(WbDeviceTag tag) { - PositionSensor *p = position_sensor_get_struct(tag); + const PositionSensor *p = position_sensor_get_struct(tag); if (p) wb_position_sensor_enable(tag, 0); else @@ -142,7 +142,7 @@ void wb_position_sensor_disable(WbDeviceTag tag) { double wb_position_sensor_get_value(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - PositionSensor *p = position_sensor_get_struct(tag); + const PositionSensor *p = position_sensor_get_struct(tag); if (p) { if (p->sampling_period <= 0) fprintf(stderr, "Error: %s() called for a disabled device! Please use: wb_position_sensor_enable().\n", __FUNCTION__); @@ -156,7 +156,7 @@ double wb_position_sensor_get_value(WbDeviceTag tag) { int wb_position_sensor_get_sampling_period(WbDeviceTag tag) { int sampling_period = 0; robot_mutex_lock(); - PositionSensor *p = position_sensor_get_struct(tag); + const PositionSensor *p = position_sensor_get_struct(tag); if (p) { sampling_period = p->sampling_period; } else @@ -168,7 +168,7 @@ int wb_position_sensor_get_sampling_period(WbDeviceTag tag) { WbJointType wb_position_sensor_get_type(WbDeviceTag tag) { WbJointType type = WB_ROTATIONAL; robot_mutex_lock(); - PositionSensor *p = position_sensor_get_struct(tag); + const PositionSensor *p = position_sensor_get_struct(tag); if (p) { type = p->type; } else diff --git a/src/controller/c/radar.c b/src/controller/c/radar.c index eefa3b01336..6766f17d583 100644 --- a/src/controller/c/radar.c +++ b/src/controller/c/radar.c @@ -148,7 +148,7 @@ void wb_radar_enable(WbDeviceTag tag, int sampling_period) { } void wb_radar_disable(WbDeviceTag tag) { - Radar *radar = radar_get_struct(tag); + const Radar *radar = radar_get_struct(tag); if (radar) wb_radar_enable(tag, 0); else @@ -158,7 +158,7 @@ void wb_radar_disable(WbDeviceTag tag) { int wb_radar_get_sampling_period(WbDeviceTag tag) { int sampling_period = 0; robot_mutex_lock(); - Radar *radar = radar_get_struct(tag); + const Radar *radar = radar_get_struct(tag); if (radar) sampling_period = radar->sampling_period; else @@ -170,7 +170,7 @@ int wb_radar_get_sampling_period(WbDeviceTag tag) { int wb_radar_get_number_of_targets(WbDeviceTag tag) { int result = 0; robot_mutex_lock(); - Radar *radar = radar_get_struct(tag); + const Radar *radar = radar_get_struct(tag); if (radar) { if (radar->sampling_period == 0) fprintf(stderr, "Error: %s() called for a disabled device! Please use: wb_radar_enable().\n", __FUNCTION__); @@ -184,7 +184,7 @@ int wb_radar_get_number_of_targets(WbDeviceTag tag) { const WbRadarTarget *wb_radar_get_targets(WbDeviceTag tag) { const WbRadarTarget *result = 0; robot_mutex_lock(); - Radar *radar = radar_get_struct(tag); + const Radar *radar = radar_get_struct(tag); if (radar) { if (radar->sampling_period == 0) fprintf(stderr, "Error: %s() called for a disabled device! Please use: wb_radar_enable().\n", __FUNCTION__); @@ -198,7 +198,7 @@ const WbRadarTarget *wb_radar_get_targets(WbDeviceTag tag) { double wb_radar_get_min_range(WbDeviceTag tag) { double result = 0; robot_mutex_lock(); - Radar *radar = radar_get_struct(tag); + const Radar *radar = radar_get_struct(tag); if (radar) result = radar->min_range; else @@ -210,7 +210,7 @@ double wb_radar_get_min_range(WbDeviceTag tag) { double wb_radar_get_max_range(WbDeviceTag tag) { double result = 0; robot_mutex_lock(); - Radar *radar = radar_get_struct(tag); + const Radar *radar = radar_get_struct(tag); if (radar) result = radar->max_range; else @@ -222,7 +222,7 @@ double wb_radar_get_max_range(WbDeviceTag tag) { double wb_radar_get_horizontal_fov(WbDeviceTag tag) { double result = 0; robot_mutex_lock(); - Radar *radar = radar_get_struct(tag); + const Radar *radar = radar_get_struct(tag); if (radar) result = radar->horizontal_fov; else @@ -234,7 +234,7 @@ double wb_radar_get_horizontal_fov(WbDeviceTag tag) { double wb_radar_get_vertical_fov(WbDeviceTag tag) { double result = 0; robot_mutex_lock(); - Radar *radar = radar_get_struct(tag); + const Radar *radar = radar_get_struct(tag); if (radar) result = radar->vertical_fov; else @@ -244,7 +244,7 @@ double wb_radar_get_vertical_fov(WbDeviceTag tag) { } const WbRadarTarget *wb_radar_get_target(WbDeviceTag tag, int index) { - Radar *radar = radar_get_struct(tag); + const Radar *radar = radar_get_struct(tag); if (radar) return (wb_radar_get_targets(tag) + index); diff --git a/src/controller/c/radio.c b/src/controller/c/radio.c index 879f00b6f0b..be663e8690d 100644 --- a/src/controller/c/radio.c +++ b/src/controller/c/radio.c @@ -247,7 +247,7 @@ void wb_radio_enable(WbDeviceTag tag, int sampling_period) { } void wb_radio_disable(WbDeviceTag tag) { - WbDevice *d = radio_get_device(tag); + const WbDevice *d = radio_get_device(tag); if (d) wb_radio_enable(tag, 0); else @@ -461,7 +461,7 @@ char *wb_radio_event_get_data(const WbRadioEvent e) { } int wb_radio_event_get_data_size(const WbRadioEvent e) { - struct WebotsRadioEvent *ev = (struct WebotsRadioEvent *)e; + const struct WebotsRadioEvent *ev = (struct WebotsRadioEvent *)e; return ev->data_size; } @@ -471,6 +471,6 @@ char *wb_radio_event_get_emitter(const WbRadioEvent e) { } double wb_radio_event_get_rssi(const WbRadioEvent e) { - struct WebotsRadioEvent *ev = (struct WebotsRadioEvent *)e; + const struct WebotsRadioEvent *ev = (struct WebotsRadioEvent *)e; return ev->rssi; } diff --git a/src/controller/c/range_finder.c b/src/controller/c/range_finder.c index 7a2388a2856..b9704992248 100644 --- a/src/controller/c/range_finder.c +++ b/src/controller/c/range_finder.c @@ -126,13 +126,13 @@ void wb_range_finder_init(WbDevice *d) { // g_print("range_finder init done\n"); } -int wb_range_finder_get_unique_id(WbDevice *d) { - AbstractCamera *ac = d->pdata; +int wb_range_finder_get_unique_id(const WbDevice *d) { + const AbstractCamera *ac = d->pdata; return ac->unique_id; } void wbr_range_finder_set_image(WbDeviceTag t, const unsigned char *image) { - RangeFinder *rf = range_finder_get_struct(t); + const RangeFinder *rf = range_finder_get_struct(t); if (rf) wbr_abstract_camera_set_image(range_finder_get_device(t), image); else @@ -140,7 +140,7 @@ void wbr_range_finder_set_image(WbDeviceTag t, const unsigned char *image) { } unsigned char *wbr_range_finder_get_image_buffer(WbDeviceTag t) { - RangeFinder *rf = range_finder_get_struct(t); + const RangeFinder *rf = range_finder_get_struct(t); if (rf) return wbr_abstract_camera_get_image_buffer(range_finder_get_device(t)); @@ -166,7 +166,7 @@ void wb_range_finder_enable(WbDeviceTag tag, int sampling_period) { } void wb_range_finder_disable(WbDeviceTag tag) { - RangeFinder *rf = range_finder_get_struct(tag); + const RangeFinder *rf = range_finder_get_struct(tag); if (rf) wb_range_finder_enable(tag, 0); else @@ -174,7 +174,7 @@ void wb_range_finder_disable(WbDeviceTag tag) { } int wb_range_finder_get_sampling_period(WbDeviceTag tag) { - RangeFinder *rf = range_finder_get_struct(tag); + const RangeFinder *rf = range_finder_get_struct(tag); if (!rf) fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); @@ -182,7 +182,7 @@ int wb_range_finder_get_sampling_period(WbDeviceTag tag) { } int wb_range_finder_get_height(WbDeviceTag tag) { - RangeFinder *rf = range_finder_get_struct(tag); + const RangeFinder *rf = range_finder_get_struct(tag); if (!rf) fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); @@ -190,7 +190,7 @@ int wb_range_finder_get_height(WbDeviceTag tag) { } int wb_range_finder_get_width(WbDeviceTag tag) { - RangeFinder *rf = range_finder_get_struct(tag); + const RangeFinder *rf = range_finder_get_struct(tag); if (!rf) fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); @@ -198,7 +198,7 @@ int wb_range_finder_get_width(WbDeviceTag tag) { } double wb_range_finder_get_fov(WbDeviceTag tag) { - RangeFinder *rf = range_finder_get_struct(tag); + const RangeFinder *rf = range_finder_get_struct(tag); if (!rf) fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); @@ -206,7 +206,7 @@ double wb_range_finder_get_fov(WbDeviceTag tag) { } double wb_range_finder_get_min_range(WbDeviceTag tag) { - RangeFinder *rf = range_finder_get_struct(tag); + const RangeFinder *rf = range_finder_get_struct(tag); if (!rf) fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); @@ -216,7 +216,7 @@ double wb_range_finder_get_min_range(WbDeviceTag tag) { double wb_range_finder_get_max_range(WbDeviceTag tag) { double result = NAN; robot_mutex_lock(); - RangeFinder *rf = range_finder_get_struct(tag); + const RangeFinder *rf = range_finder_get_struct(tag); if (rf) result = rf->max_range; else @@ -263,7 +263,7 @@ int wb_range_finder_save_image(WbDeviceTag tag, const char *filename, int qualit robot_mutex_lock(); AbstractCamera *ac = range_finder_get_abstract_camera_struct(tag); - RangeFinder *rf = range_finder_get_struct(tag); + const RangeFinder *rf = range_finder_get_struct(tag); if (!ac) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); diff --git a/src/controller/c/receiver.c b/src/controller/c/receiver.c index 923d782d355..0e0470cffd3 100644 --- a/src/controller/c/receiver.c +++ b/src/controller/c/receiver.c @@ -217,7 +217,7 @@ void wb_receiver_enable(WbDeviceTag tag, int sampling_period) { } void wb_receiver_disable(WbDeviceTag tag) { - Receiver *rs = receiver_get_struct(tag); + const Receiver *rs = receiver_get_struct(tag); if (!rs) fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); else @@ -227,7 +227,7 @@ void wb_receiver_disable(WbDeviceTag tag) { int wb_receiver_get_sampling_period(WbDeviceTag tag) { int sampling_period; robot_mutex_lock(); - Receiver *rs = receiver_get_struct(tag); + const Receiver *rs = receiver_get_struct(tag); if (!rs) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); sampling_period = 0; @@ -276,7 +276,7 @@ void wb_receiver_set_channel(WbDeviceTag tag, int channel) { int wb_receiver_get_channel(WbDeviceTag tag) { int result; robot_mutex_lock(); - Receiver *rs = receiver_get_struct(tag); + const Receiver *rs = receiver_get_struct(tag); if (!rs) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); result = -1; @@ -299,7 +299,7 @@ void wb_receiver_next_packet(WbDeviceTag tag) { int wb_receiver_get_queue_length(WbDeviceTag tag) { int result; robot_mutex_lock(); - Receiver *rs = receiver_get_struct(tag); + const Receiver *rs = receiver_get_struct(tag); if (!rs) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); result = -1; diff --git a/src/controller/c/remote_control.c b/src/controller/c/remote_control.c index 3769a103737..c924afbd736 100644 --- a/src/controller/c/remote_control.c +++ b/src/controller/c/remote_control.c @@ -307,6 +307,7 @@ static void handleMessage(WbRequest *r, WbDeviceTag tag, WbNodeType type) { } break; case WB_NODE_RADIO: + // cppcheck-suppress incorrectStringBooleanError ROBOT_ASSERT(!"radio unimplemented"); break; default: @@ -318,6 +319,7 @@ static void handleMessage(WbRequest *r, WbDeviceTag tag, WbNodeType type) { handleRobotMessage(r, c); break; case WB_NODE_CONNECTOR: + // cppcheck-suppress incorrectStringBooleanError ROBOT_ASSERT(!"connector unimplemented"); break; case WB_NODE_DISPLAY: @@ -347,7 +349,9 @@ static void handleMessage(WbRequest *r, WbDeviceTag tag, WbNodeType type) { break; case WB_NODE_ROTATIONAL_MOTOR: case WB_NODE_LINEAR_MOTOR: + // cppcheck-suppress incorrectStringBooleanError REQUEST_ASSERT(!"Impossible fallback", tag, type, c); + break; default: REQUEST_ASSERT(0, tag, type, c); } diff --git a/src/controller/c/request.c b/src/controller/c/request.c index b2ac6ab675c..1c40ef54446 100644 --- a/src/controller/c/request.c +++ b/src/controller/c/request.c @@ -169,7 +169,7 @@ void *request_read_data(WbRequest *r, int size) { } char *request_read_string(WbRequest *r) { - char *src = r->data + r->pointer; + const char *src = r->data + r->pointer; const int l = strlen(src) + 1; char *dst = malloc(l); memcpy(dst, src, l); @@ -186,7 +186,7 @@ int request_get_size(WbRequest *r) { return *((int *)r->data); } -int request_get_position(WbRequest *r) { +int request_get_position(const WbRequest *r) { return r->pointer; } @@ -198,7 +198,7 @@ void request_set_immediate(WbRequest *r, bool immediate) { r->immediate = immediate; } -bool request_is_immediate(WbRequest *r) { +bool request_is_immediate(const WbRequest *r) { return r->immediate; } diff --git a/src/controller/c/request.h b/src/controller/c/request.h index de9f0bc57f3..bc537694618 100644 --- a/src/controller/c/request.h +++ b/src/controller/c/request.h @@ -62,10 +62,10 @@ void *request_read_data(WbRequest *, int size); char *request_read_string(WbRequest *); // to be released with g_free bool request_is_over(WbRequest *); int request_get_size(WbRequest *); -int request_get_position(WbRequest *); +int request_get_position(const WbRequest *); void request_set_position(WbRequest *, int pos); void request_set_immediate(WbRequest *, bool immediate); -bool request_is_immediate(WbRequest *); +bool request_is_immediate(const WbRequest *); void request_print(FILE *fd, WbRequest *); // for debug #define request_read_char(r) ((r)->data[(r)->pointer++]) diff --git a/src/controller/c/robot.c b/src/controller/c/robot.c index 82737af5e20..8b32ca8c1ef 100644 --- a/src/controller/c/robot.c +++ b/src/controller/c/robot.c @@ -1165,7 +1165,7 @@ static char *compute_socket_filename(char *error_buffer) { struct stat filestat; double timestamp = 0.0; int number = -1; - struct dirent *de; + const struct dirent *de; while ((de = readdir(dr)) != NULL) { #ifndef _WIN32 if (strcmp(de->d_name, ".") && strcmp(de->d_name, "..")) { @@ -1266,7 +1266,7 @@ static char *compute_socket_filename(char *error_buffer) { free(loading_file_path); free(robot_name); - char *sub_string = strstr(&WEBOTS_CONTROLLER_URL[6], "/"); + const char *sub_string = strstr(&WEBOTS_CONTROLLER_URL[6], "/"); robot_name = encode_robot_name(sub_string ? sub_string + 1 : NULL); if (robot_name) { #ifndef _WIN32 @@ -1291,7 +1291,7 @@ static char *compute_socket_filename(char *error_buffer) { } char **filenames = NULL; int count = 0; - struct dirent *de; + const struct dirent *de; while ((de = readdir(dr)) != NULL) { if (strcmp(de->d_name, ".") == 0 || strcmp(de->d_name, "..") == 0) continue; @@ -1303,7 +1303,7 @@ static char *compute_socket_filename(char *error_buffer) { DIR *d = opendir(subfolder); free(subfolder); if (d) { - struct dirent *sub; + const struct dirent *sub; while ((sub = readdir(d)) != NULL) { if (strcmp(sub->d_name, "extern") == 0) { found = true; diff --git a/src/controller/c/scheduler.c b/src/controller/c/scheduler.c index c223940db77..4073b8ee0c4 100644 --- a/src/controller/c/scheduler.c +++ b/src/controller/c/scheduler.c @@ -130,7 +130,7 @@ void scheduler_cleanup() { } } -void scheduler_send_request(WbRequest *r) { +void scheduler_send_request(const WbRequest *r) { if (scheduler_is_ipc()) g_pipe_send(scheduler_pipe, r->data, r->pointer); else { diff --git a/src/controller/c/scheduler.h b/src/controller/c/scheduler.h index ff96f7d4455..1cd32417a3d 100644 --- a/src/controller/c/scheduler.h +++ b/src/controller/c/scheduler.h @@ -31,7 +31,7 @@ extern unsigned int scheduler_actual_step; int scheduler_init_remote(const char *host, int port, const char *robot_name, char *buffer); int scheduler_init_local(const char *pipe); void scheduler_cleanup(); -void scheduler_send_request(WbRequest *); +void scheduler_send_request(const WbRequest *); WbRequest *scheduler_read_data(); WbRequest *scheduler_read_data_remote(); WbRequest *scheduler_read_data_local(); diff --git a/src/controller/c/skin.c b/src/controller/c/skin.c index 8f083f3a428..9663383355f 100644 --- a/src/controller/c/skin.c +++ b/src/controller/c/skin.c @@ -226,7 +226,7 @@ void wb_skin_set_bone_position(WbDeviceTag tag, int index, const double position int wb_skin_get_bone_count(WbDeviceTag tag) { int result = 0; robot_mutex_lock(); - Skin *skin = skin_get_struct(tag); + const Skin *skin = skin_get_struct(tag); if (skin) result = skin->bone_count; else diff --git a/src/controller/c/speaker.c b/src/controller/c/speaker.c index 640a09f8092..306d63bbb25 100644 --- a/src/controller/c/speaker.c +++ b/src/controller/c/speaker.c @@ -514,7 +514,7 @@ bool wb_speaker_set_language(WbDeviceTag tag, const char *language) { } const char *wb_speaker_get_engine(WbDeviceTag tag) { - Speaker *speaker = speaker_get_struct(tag); + const Speaker *speaker = speaker_get_struct(tag); if (!speaker) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return NULL; @@ -523,7 +523,7 @@ const char *wb_speaker_get_engine(WbDeviceTag tag) { } const char *wb_speaker_get_language(WbDeviceTag tag) { - Speaker *speaker = speaker_get_struct(tag); + const Speaker *speaker = speaker_get_struct(tag); if (!speaker) { fprintf(stderr, "Error: %s(): invalid device tag.\n", __FUNCTION__); return NULL; diff --git a/src/controller/c/string.c b/src/controller/c/string.c index 99970fadb7c..cff605c987b 100644 --- a/src/controller/c/string.c +++ b/src/controller/c/string.c @@ -47,7 +47,7 @@ char *wbu_string_strsep(char **stringp, const char *delim) { } // ref. https://stackoverflow.com/a/779960/2210777 -char *wbu_string_replace(char *value, char *before, char *after) { +char *wbu_string_replace(char *value, const char *before, const char *after) { char *result, *ins, *tmp; int len_before, len_after, count; diff --git a/src/controller/c/supervisor.c b/src/controller/c/supervisor.c index f35ff50aa81..b20574914ce 100644 --- a/src/controller/c/supervisor.c +++ b/src/controller/c/supervisor.c @@ -2100,7 +2100,7 @@ const double *wb_supervisor_node_get_contact_point(WbNodeRef node, int index) { const int descendants = node->contact_points_include_descendants; if (t <= node->contact_points[descendants].timestamp && node->contact_points[descendants].points) - return (node->contact_points[descendants].points && index < node->contact_points[descendants].n) ? + return index < node->contact_points[descendants].n ? node->contact_points[descendants].points[index].point : invalid_vector; // will be (NaN, NaN, NaN) if n is not a Solid or if there is no contact diff --git a/src/controller/c/tcp_client.c b/src/controller/c/tcp_client.c index 8a15f8a0f58..3303e1793c2 100644 --- a/src/controller/c/tcp_client.c +++ b/src/controller/c/tcp_client.c @@ -67,7 +67,7 @@ int tcp_client_open(char *buffer) { int tcp_client_connect(int fd, const char *host, int port, char *buffer) { struct sockaddr_in address; - struct hostent *server; + const struct hostent *server; // fill in the socket address memset(&address, 0, sizeof(struct sockaddr_in)); address.sin_family = AF_INET; diff --git a/src/controller/c/touch_sensor.c b/src/controller/c/touch_sensor.c index dc267e7319a..6d933425f4f 100644 --- a/src/controller/c/touch_sensor.c +++ b/src/controller/c/touch_sensor.c @@ -81,7 +81,7 @@ static void touch_sensor_read_answer(WbDevice *d, WbRequest *r) { int wb_touch_sensor_get_lookup_table_size(WbDeviceTag tag) { int result = 0; robot_mutex_lock(); - TouchSensor *dev = touch_sensor_get_struct(tag); + const TouchSensor *dev = touch_sensor_get_struct(tag); if (dev) result = dev->lookup_table_size; else @@ -180,7 +180,7 @@ void wb_touch_sensor_enable(WbDeviceTag tag, int sampling_period) { } void wb_touch_sensor_disable(WbDeviceTag tag) { - TouchSensor *ts = touch_sensor_get_struct(tag); + const TouchSensor *ts = touch_sensor_get_struct(tag); if (ts) wb_touch_sensor_enable(tag, 0); else @@ -190,7 +190,7 @@ void wb_touch_sensor_disable(WbDeviceTag tag) { int wb_touch_sensor_get_sampling_period(WbDeviceTag tag) { int sampling_period = 0; robot_mutex_lock(); - TouchSensor *ts = touch_sensor_get_struct(tag); + const TouchSensor *ts = touch_sensor_get_struct(tag); if (ts) sampling_period = ts->sampling_period; else @@ -241,7 +241,7 @@ const double *wb_touch_sensor_get_values(WbDeviceTag tag) { WbTouchSensorType wb_touch_sensor_get_type(WbDeviceTag tag) { WbTouchSensorType result = WB_TOUCH_SENSOR_BUMPER; robot_mutex_lock(); - TouchSensor *ts = touch_sensor_get_struct(tag); + const TouchSensor *ts = touch_sensor_get_struct(tag); if (ts) result = ts->type; else diff --git a/src/controller/c/vacuum_gripper.c b/src/controller/c/vacuum_gripper.c index 78c10780206..c245394c31d 100644 --- a/src/controller/c/vacuum_gripper.c +++ b/src/controller/c/vacuum_gripper.c @@ -117,7 +117,7 @@ void wb_vacuum_gripper_enable_presence(WbDeviceTag tag, int sampling_period) { } void wb_vacuum_gripper_disable_presence(WbDeviceTag tag) { - VacuumGripper *vc = vacuum_gripper_get_struct(tag); + const VacuumGripper *vc = vacuum_gripper_get_struct(tag); if (vc) wb_vacuum_gripper_enable_presence(tag, 0); else @@ -127,7 +127,7 @@ void wb_vacuum_gripper_disable_presence(WbDeviceTag tag) { int wb_vacuum_gripper_get_presence_sampling_period(WbDeviceTag tag) { int sampling_period = 0; robot_mutex_lock(); - VacuumGripper *vc = vacuum_gripper_get_struct(tag); + const VacuumGripper *vc = vacuum_gripper_get_struct(tag); if (vc) sampling_period = vc->presence_sampling_period; else @@ -161,7 +161,7 @@ void wb_vacuum_gripper_turn_off(WbDeviceTag tag) { bool wb_vacuum_gripper_get_presence(WbDeviceTag tag) { bool result = false; robot_mutex_lock(); - VacuumGripper *vc = vacuum_gripper_get_struct(tag); + const VacuumGripper *vc = vacuum_gripper_get_struct(tag); if (vc) { if (vc->presence_sampling_period <= 0) fprintf(stderr, "Error: %s() called for a disabled device! Please use: wb_vacuum_gripper_enable_presence().\n", @@ -176,7 +176,7 @@ bool wb_vacuum_gripper_get_presence(WbDeviceTag tag) { bool wb_vacuum_gripper_is_on(WbDeviceTag tag) { bool result; robot_mutex_lock(); - VacuumGripper *vc = vacuum_gripper_get_struct(tag); + const VacuumGripper *vc = vacuum_gripper_get_struct(tag); if (vc) result = vc->is_on; else { diff --git a/src/controller/cpp/Field.cpp b/src/controller/cpp/Field.cpp index 6d45c0e82bd..529cfdb4676 100644 --- a/src/controller/cpp/Field.cpp +++ b/src/controller/cpp/Field.cpp @@ -171,7 +171,7 @@ void Field::setSFRotation(const double values[4]) { wb_supervisor_field_set_sf_rotation(fieldRef, values); } -void Field::setSFColor(const double values[4]) { +void Field::setSFColor(const double values[3]) { wb_supervisor_field_set_sf_color(fieldRef, values); } diff --git a/src/controller/cpp/Makefile b/src/controller/cpp/Makefile index 0621c9268dc..89ccd7da9a2 100644 --- a/src/controller/cpp/Makefile +++ b/src/controller/cpp/Makefile @@ -130,11 +130,11 @@ $(TARGET): $(BUILD_GOAL_DIR)/x86_64/libCppController.dylib $(BUILD_GOAL_DIR)/arm $(BUILD_GOAL_DIR)/x86_64/libCppController.dylib: $(X86_64_OBJECTS) @echo "# linking" $@ "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 $(LDFLAGS) $(X86_64_OBJECTS) $(SHAREDLIBS) -o "$@" + @$(CXX) -target x86_64-apple-macos12 $(LDFLAGS) $(X86_64_OBJECTS) $(SHAREDLIBS) -o "$@" $(BUILD_GOAL_DIR)/arm64/libCppController.dylib: $(ARM64_OBJECTS) @echo "# linking" $@ "(arm64)" - @$(CXX) -target arm64-apple-macos11 $(LDFLAGS) $(ARM64_OBJECTS) $(SHAREDLIBS) -o "$@" + @$(CXX) -target arm64-apple-macos12 $(LDFLAGS) $(ARM64_OBJECTS) $(SHAREDLIBS) -o "$@" else @@ -154,11 +154,11 @@ $(OBJDIR)/%.o:%.cpp $(OBJDIR)/arm64/%.o:%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 $(CPPFLAGS) $(CPPINCLUDES) -o $@ $< + @$(CXX) -target arm64-apple-macos12 $(CPPFLAGS) $(CPPINCLUDES) -o $@ $< $(OBJDIR)/x86_64/%.o:%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 $(CPPFLAGS) $(CPPINCLUDES) -o $@ $< + @$(CXX) -target x86_64-apple-macos12 $(CPPFLAGS) $(CPPINCLUDES) -o $@ $< # dependency rule $(OBJDIR)/%.d:%.cpp diff --git a/src/controller/java/Makefile b/src/controller/java/Makefile index 3fd6faae51d..8f1057defae 100644 --- a/src/controller/java/Makefile +++ b/src/controller/java/Makefile @@ -147,19 +147,19 @@ $(WRAPPER_OBJECT): $(WRAPPER) $(WRAPPER_OBJECT_ARM64): $(WRAPPER) @echo "# compiling" $(notdir $^) "(arm64)" - $(CXX) -target arm64-apple-macos11 $(CFLAGS2) $(WEBOTS_INCLUDES) $(JAVA_INCLUDES) $< -o $@ + $(CXX) -target arm64-apple-macos12 $(CFLAGS2) $(WEBOTS_INCLUDES) $(JAVA_INCLUDES) $< -o $@ $(WRAPPER_OBJECT_X86_64): $(WRAPPER) @echo "# compiling" $(notdir $^) "(x86_64)" - $(CXX) -target x86_64-apple-macos11 $(CFLAGS2) $(WEBOTS_INCLUDES) $(JAVA_INCLUDES) $< -o $@ + $(CXX) -target x86_64-apple-macos12 $(CFLAGS2) $(WEBOTS_INCLUDES) $(JAVA_INCLUDES) $< -o $@ $(OBJDIR)/arm64/lib$(LIBNAME).jnilib: $(WRAPPER_OBJECT_ARM64) @echo "# linking" $(notdir $^) "(arm64)" - $(CXX) -target arm64-apple-macos11 $(CFLAGS1) $(JNILIB_FLAGS) -L$(WEBOTS_CONTROLLER_LIB_PATH) -lController -lCppController $^ -o "$@" + $(CXX) -target arm64-apple-macos12 $(CFLAGS1) $(JNILIB_FLAGS) -L$(WEBOTS_CONTROLLER_LIB_PATH) -lController -lCppController $^ -o "$@" $(OBJDIR)/x86_64/lib$(LIBNAME).jnilib: $(WRAPPER_OBJECT_X86_64) @echo "# linking" $(notdir $^) "(x86_64)" - $(CXX) -target x86_64-apple-macos11 $(CFLAGS1) $(JNILIB_FLAGS) -L$(WEBOTS_CONTROLLER_LIB_PATH) -lController -lCppController $^ -o "$@" + $(CXX) -target x86_64-apple-macos12 $(CFLAGS1) $(JNILIB_FLAGS) -L$(WEBOTS_CONTROLLER_LIB_PATH) -lController -lCppController $^ -o "$@" $(WEBOTS_CONTROLLER_LIB_PATH)/java/lib$(LIBNAME).jnilib: $(OBJDIR)/arm64/lib$(LIBNAME).jnilib $(OBJDIR)/x86_64/lib$(LIBNAME).jnilib @echo "# creating fat" $^ diff --git a/src/controller/launcher/webots_controller.c b/src/controller/launcher/webots_controller.c index 4a2a387adf8..44d3f216a27 100644 --- a/src/controller/launcher/webots_controller.c +++ b/src/controller/launcher/webots_controller.c @@ -72,7 +72,7 @@ static void remove_comment(char *string) { } // Replaces all occurrences of a character in a string with a different character. -static void replace_char(char *string, char occurrence, char replace) { +static void replace_char(const char *string, char occurrence, char replace) { char *current_pos = strchr(string, occurrence); while (current_pos) { *current_pos = replace; @@ -136,7 +136,7 @@ static void replace_substring(char **string, const char *substring, const char * } // Inserts a string into another string at a specified index. -static void insert_string(char **string, char *insert, int index) { +static void insert_string(char **string, const char *insert, int index) { const size_t new_size = strlen(*string) + strlen(insert) + 1; char *tmp = strdup(*string); *string = realloc(*string, new_size); @@ -168,7 +168,7 @@ static bool get_webots_home() { // Gets and stores the path to the latest installed version of Matlab on the system. static bool get_matlab_path() { - struct dirent *directory_entry; // Pointer for directory entry + const struct dirent *directory_entry; // Pointer for directory entry #ifdef __APPLE__ const char *matlab_directory = "/Applications/"; @@ -333,7 +333,7 @@ static bool parse_options(int nb_arguments, char **arguments) { // Write WEBOTS_CONTROLLER_URL in function of given options const char *robot_separator = robot_name ? "/" : ""; - char *robot_name_string = robot_name ? robot_name : ""; + const char *robot_name_string = robot_name ? robot_name : ""; if (strncmp(protocol, "tcp", 3) == 0) { if (!ip_address) { fprintf(stderr, "Specify the IP address of the Webots machine to connect to with '--ip-address=' option.\n"); @@ -564,7 +564,7 @@ static void format_ini_paths(char **string) { // Add absolute path to runtime.ini in front of all relative paths char *tmp = strdup(*string); - char *ptr = strtok(tmp, "="); + const char *ptr = strtok(tmp, "="); int offset = 0; while (ptr != NULL) { int index = ptr - tmp + offset; @@ -695,7 +695,7 @@ static void parse_runtime_ini() { } // Add a single string argument to the argument 'argv' array -static char **add_single_argument(char **argv, size_t *current_size, char *str) { +static char **add_single_argument(char **argv, size_t *current_size, const char *str) { (*current_size)++; argv = realloc(argv, *current_size * sizeof(char *)); if (!argv) diff --git a/src/ode/Makefile b/src/ode/Makefile index 0bdafa72fb2..34682b183e0 100644 --- a/src/ode/Makefile +++ b/src/ode/Makefile @@ -39,7 +39,9 @@ endif FILES_TO_REMOVE = $(MAIN_TARGET_COPY) libode.a ode.a CFLAGS = -DdTRIMESH_ENABLED -DdTRIMESH_OPCODE -DODE_MT -DODE_LIB -DODE_THREADMODE_PTHREAD -ifneq ($(OSTYPE),darwin) +ifeq ($(OSTYPE),darwin) + CFLAGS += -Wno-unused-but-set-variable +else CFLAGS += -Wno-misleading-indentation -Wno-nonnull-compare endif diff --git a/src/webots/Makefile b/src/webots/Makefile index 59a153b33dd..f0b2a0987c2 100644 --- a/src/webots/Makefile +++ b/src/webots/Makefile @@ -642,11 +642,11 @@ $(TARGET): $(OBJDIR)/x86_64/webots $(OBJDIR)/arm64/webots $(OBJDIR)/x86_64/webots: $(X86_64_OBJECTS) $(LIB_WREN) $(LIB_ODE) @echo "# linking " $@ "(x64_64)" - @$(CXX) -target x86_64-apple-macos11 $(LD_FLAGS) -o $@ $(X86_64_OBJECTS) $(LIBS) + @$(CXX) -target x86_64-apple-macos12 $(LD_FLAGS) -o $@ $(X86_64_OBJECTS) $(LIBS) $(OBJDIR)/arm64/webots: $(ARM64_OBJECTS) $(LIB_WREN) $(LIB_ODE) @echo "# linking " $@ "(arm64)" - @$(CXX) -target arm64-apple-macos11 $(LD_FLAGS) -o $@ $(ARM64_OBJECTS) $(LIBS) + @$(CXX) -target arm64-apple-macos12 $(LD_FLAGS) -o $@ $(ARM64_OBJECTS) $(LIBS) else @@ -775,164 +775,164 @@ webots.o:gui/webots.rc gui/webots.ico gui/manifest.xml $(OBJDIR)/x86_64/%.o: $(OBJDIR)/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(INCLUDE) $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(INCLUDE) $< -o $@ $(OBJDIR)/x86_64/%.o: app/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_APP_INCLUDE) $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_APP_INCLUDE) $< -o $@ $(OBJDIR)/x86_64/%.o: control/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_CONTROL_INCLUDE) $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_CONTROL_INCLUDE) $< -o $@ $(OBJDIR)/x86_64/%.o: core/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_CORE_INCLUDE) $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_CORE_INCLUDE) $< -o $@ $(OBJDIR)/x86_64/%.o: widgets/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_WIDGETS_INCLUDE) $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_WIDGETS_INCLUDE) $< -o $@ $(OBJDIR)/x86_64/%.o: editor/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_EDITOR_INCLUDE) $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_EDITOR_INCLUDE) $< -o $@ $(OBJDIR)/x86_64/%.o: engine/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_ENGINE_INCLUDE) $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_ENGINE_INCLUDE) $< -o $@ $(OBJDIR)/x86_64/%.o: external/siphash/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) -isystem external/siphash $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) -isystem external/siphash $< -o $@ $(OBJDIR)/x86_64/%.o: gui/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_GUI_INCLUDE) $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_GUI_INCLUDE) $< -o $@ $(OBJDIR)/x86_64/%.o: nodes/utils/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_NODES_INCLUDE) $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_NODES_INCLUDE) $< -o $@ $(OBJDIR)/x86_64/%.o: nodes/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_NODES_INCLUDE) $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_NODES_INCLUDE) $< -o $@ $(OBJDIR)/x86_64/%.o: maths/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_MATHS_INCLUDE) $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_MATHS_INCLUDE) $< -o $@ $(OBJDIR)/x86_64/%.o: ode/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_ODE_INCLUDE) $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_ODE_INCLUDE) $< -o $@ $(OBJDIR)/x86_64/%.o: wren/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_WREN_INCLUDE) $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_WREN_INCLUDE) $< -o $@ $(OBJDIR)/x86_64/%.o: util/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_UTIL_INCLUDE) $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_UTIL_INCLUDE) $< -o $@ $(OBJDIR)/x86_64/%.o: plugins/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_PLUGINS_INCLUDE) $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_PLUGINS_INCLUDE) $< -o $@ $(OBJDIR)/x86_64/%.o: scene_tree/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_SCENE_TREE_INCLUDE) $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_SCENE_TREE_INCLUDE) $< -o $@ $(OBJDIR)/x86_64/%.o: sound/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_SOUND_INCLUDE) $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_SOUND_INCLUDE) $< -o $@ $(OBJDIR)/x86_64/%.o: user_commands/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_USER_COMMANDS_INCLUDE) $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_USER_COMMANDS_INCLUDE) $< -o $@ $(OBJDIR)/x86_64/%.o: vrml/%.cpp @echo "# compiling" $< "(x86_64)" - @$(CXX) -target x86_64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_VRML_INCLUDE) $< -o $@ + @$(CXX) -target x86_64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_VRML_INCLUDE) $< -o $@ $(OBJDIR)/arm64/%.o: $(OBJDIR)/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(INCLUDE) $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(INCLUDE) $< -o $@ $(OBJDIR)/arm64/%.o: app/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_APP_INCLUDE) $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_APP_INCLUDE) $< -o $@ $(OBJDIR)/arm64/%.o: control/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_CONTROL_INCLUDE) $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_CONTROL_INCLUDE) $< -o $@ $(OBJDIR)/arm64/%.o: core/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_CORE_INCLUDE) $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_CORE_INCLUDE) $< -o $@ $(OBJDIR)/arm64/%.o: widgets/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_WIDGETS_INCLUDE) $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_WIDGETS_INCLUDE) $< -o $@ $(OBJDIR)/arm64/%.o: editor/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_EDITOR_INCLUDE) $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_EDITOR_INCLUDE) $< -o $@ $(OBJDIR)/arm64/%.o: engine/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_ENGINE_INCLUDE) $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_ENGINE_INCLUDE) $< -o $@ $(OBJDIR)/arm64/%.o: external/siphash/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) -isystem external/siphash $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) -isystem external/siphash $< -o $@ $(OBJDIR)/arm64/%.o: gui/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_GUI_INCLUDE) $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_GUI_INCLUDE) $< -o $@ $(OBJDIR)/arm64/%.o: nodes/utils/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_NODES_INCLUDE) $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_NODES_INCLUDE) $< -o $@ $(OBJDIR)/arm64/%.o: nodes/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_NODES_INCLUDE) $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_NODES_INCLUDE) $< -o $@ $(OBJDIR)/arm64/%.o: maths/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_MATHS_INCLUDE) $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_MATHS_INCLUDE) $< -o $@ $(OBJDIR)/arm64/%.o: ode/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_ODE_INCLUDE) $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_ODE_INCLUDE) $< -o $@ $(OBJDIR)/arm64/%.o: wren/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_WREN_INCLUDE) $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_WREN_INCLUDE) $< -o $@ $(OBJDIR)/arm64/%.o: util/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_UTIL_INCLUDE) $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_UTIL_INCLUDE) $< -o $@ $(OBJDIR)/arm64/%.o: plugins/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_PLUGINS_INCLUDE) $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_PLUGINS_INCLUDE) $< -o $@ $(OBJDIR)/arm64/%.o: scene_tree/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_SCENE_TREE_INCLUDE) $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_SCENE_TREE_INCLUDE) $< -o $@ $(OBJDIR)/arm64/%.o: sound/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_SOUND_INCLUDE) $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_SOUND_INCLUDE) $< -o $@ $(OBJDIR)/arm64/%.o: user_commands/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_USER_COMMANDS_INCLUDE) $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_USER_COMMANDS_INCLUDE) $< -o $@ $(OBJDIR)/arm64/%.o: vrml/%.cpp @echo "# compiling" $< "(arm64)" - @$(CXX) -target arm64-apple-macos11 -c $(CFLAGS) $(CXXFLAGS) $(WB_VRML_INCLUDE) $< -o $@ + @$(CXX) -target arm64-apple-macos12 -c $(CFLAGS) $(CXXFLAGS) $(WB_VRML_INCLUDE) $< -o $@ clean: diff --git a/src/webots/app/WbPerspective.cpp b/src/webots/app/WbPerspective.cpp index 6249fd54128..75a72a54594 100644 --- a/src/webots/app/WbPerspective.cpp +++ b/src/webots/app/WbPerspective.cpp @@ -106,7 +106,7 @@ bool WbPerspective::readContent(QTextStream &in, bool reloading) { const QString s = line.right(line.length() - 17).trimmed(); // remove label QStringList actionNamesList; splitUniqueNameList(s, actionNamesList); - foreach (const QString name, actionNamesList) + foreach (const QString &name, actionNamesList) mDisabledUserInteractionsMap[getActionFromString(name)] = true; } else if (key == "orthographicViewHeight:") { double value; @@ -261,7 +261,7 @@ bool WbPerspective::save() const { out << "textFiles: " << mSelectedTab; // convert to relative paths and save const QDir dir(WbProject::current()->dir()); - foreach (const QString file, mFilesList) + foreach (const QString &file, mFilesList) out << " \"" << dir.relativeFilePath(file) << "\""; out << "\n"; if (!mRobotWindowNodeNames.isEmpty()) @@ -295,7 +295,7 @@ bool WbPerspective::save() const { return true; } -void WbPerspective::setSimulationViewState(QList state) { +void WbPerspective::setSimulationViewState(const QList &state) { assert(state.size() == 2); mSimulationViewState = state[0]; mSceneTreeState = state[1]; diff --git a/src/webots/app/WbPerspective.hpp b/src/webots/app/WbPerspective.hpp index 09640e76982..a3513a1528c 100644 --- a/src/webots/app/WbPerspective.hpp +++ b/src/webots/app/WbPerspective.hpp @@ -60,7 +60,7 @@ class WbPerspective { bool centralWidgetVisible() const { return mCentralWidgetVisible; } // splitter state of the simulation view - void setSimulationViewState(QList state); + void setSimulationViewState(const QList &state); QList simulationViewState() const; // index of the selected tab in the text editor @@ -73,7 +73,7 @@ class WbPerspective { // list of opened files in the text editor void setFilesList(const QStringList &list) { mFilesList = list; } - QStringList filesList() const { return mFilesList; } + const QStringList &filesList() const { return mFilesList; } void setRobotWindowNodeNames(const QStringList &robotWindowNodeNames) { mRobotWindowNodeNames = robotWindowNodeNames; } const QStringList &enabledRobotWindowNodeNames() const { return mRobotWindowNodeNames; } @@ -104,7 +104,7 @@ class WbPerspective { void setUserInteractionDisabled(WbAction::WbActionKind action, bool disabled) { mDisabledUserInteractionsMap[action] = disabled; } - QMap disabledUserInteractionsMap() const { return mDisabledUserInteractionsMap; } + const QMap &disabledUserInteractionsMap() const { return mDisabledUserInteractionsMap; } bool isUserInteractionDisabled(WbAction::WbActionKind action) const { return mDisabledUserInteractionsMap.value(action, false); } diff --git a/src/webots/app/WbPhysicsVectorRepresentation.hpp b/src/webots/app/WbPhysicsVectorRepresentation.hpp index ef346d38695..eec154bb10c 100644 --- a/src/webots/app/WbPhysicsVectorRepresentation.hpp +++ b/src/webots/app/WbPhysicsVectorRepresentation.hpp @@ -77,7 +77,7 @@ class WbTorqueRepresentation : public WbPhysicsVectorRepresentation { Q_OBJECT public: WbTorqueRepresentation(); - virtual ~WbTorqueRepresentation(); + virtual ~WbTorqueRepresentation() override; private: void initializeSpinSymbol(); diff --git a/src/webots/app/WbSelection.cpp b/src/webots/app/WbSelection.cpp index b483212c339..7da55f040e6 100644 --- a/src/webots/app/WbSelection.cpp +++ b/src/webots/app/WbSelection.cpp @@ -128,9 +128,9 @@ bool WbSelection::isObjectMotionAllowed() const { return false; WbBaseNode *topNode = mSelectedAbstractPose->baseNode(); - WbAbstractPose *topPose = NULL; + const WbAbstractPose *topPose = NULL; if (!topNode->isTopLevel()) { - WbSolid *solid = WbNodeUtilities::findUppermostSolid(topNode); + const WbSolid *solid = WbNodeUtilities::findUppermostSolid(topNode); if (solid) topPose = dynamic_cast(topNode); else diff --git a/src/webots/control/WbControlledWorld.cpp b/src/webots/control/WbControlledWorld.cpp index 316380d1cfc..1407c608a6f 100644 --- a/src/webots/control/WbControlledWorld.cpp +++ b/src/webots/control/WbControlledWorld.cpp @@ -201,7 +201,7 @@ void WbControlledWorld::step() { } } - WbSimulationState *const simulationState = WbSimulationState::instance(); + const WbSimulationState *const simulationState = WbSimulationState::instance(); // starts controllers that were set by the user at the previous time step static QList justStartedControllers; @@ -260,7 +260,7 @@ void WbControlledWorld::step() { if (mRetryEnabled) { mRetryEnabled = false; - foreach (WbController *const controller, mControllers) + foreach (const WbController *const controller, mControllers) disconnect(controller, &WbController::requestReceived, this, &WbControlledWorld::step); emit stepBlocked(false); } @@ -288,14 +288,14 @@ void WbControlledWorld::step() { bool WbControlledWorld::needToWait(bool *waitForExternControllerStart) { if (waitForExternControllerStart) *waitForExternControllerStart = false; - foreach (WbController *const controller, mDisconnectedExternControllers) { + foreach (const WbController *const controller, mDisconnectedExternControllers) { if (controller->robot()->synchronization()) { if (waitForExternControllerStart) *waitForExternControllerStart = true; return true; } } - foreach (WbController *const controller, mControllers) { + foreach (const WbController *const controller, mControllers) { if (!controller->isRequestPending() || controller->isIncompleteRequest()) { mNeedToYield = true; if (controller->synchronization()) @@ -425,7 +425,7 @@ void WbControlledWorld::externConnection(WbController *controller, bool connect) QStringList WbControlledWorld::activeControllersNames() const { QStringList list; - foreach (WbController *const controller, mControllers) { + foreach (const WbController *const controller, mControllers) { if (controller && controller->isRunning()) list.append(controller->name()); } @@ -444,7 +444,7 @@ void WbControlledWorld::waitForRobotWindowIfNeededAndCompleteStep() { } } - WbSimulationState *const simulationState = WbSimulationState::instance(); + const WbSimulationState *const simulationState = WbSimulationState::instance(); for (int i = 0; i < controllersCount; ++i) { WbController *controller = mControllers[i]; if (!controller->isRequestPending()) diff --git a/src/webots/control/WbControlledWorld.hpp b/src/webots/control/WbControlledWorld.hpp index 4b186650cff..010461a747c 100644 --- a/src/webots/control/WbControlledWorld.hpp +++ b/src/webots/control/WbControlledWorld.hpp @@ -29,7 +29,7 @@ class WbControlledWorld : public WbSimulationWorld { // constructors and destructor explicit WbControlledWorld(WbTokenizer *tokenizer = NULL); - virtual ~WbControlledWorld(); + virtual ~WbControlledWorld() override; void startController(WbRobot *robot); void externConnection(WbController *controller, bool connect); @@ -41,8 +41,8 @@ class WbControlledWorld : public WbSimulationWorld { void step() override; - QList controllers() const { return mControllers; } - QList disconnectedExternControllers() const { return mDisconnectedExternControllers; } + const QList &controllers() const { return mControllers; } + const QList &disconnectedExternControllers() const { return mDisconnectedExternControllers; } public slots: void deleteController(WbController *controller); diff --git a/src/webots/control/WbController.cpp b/src/webots/control/WbController.cpp index c8a525e91d1..d84dae2b7aa 100644 --- a/src/webots/control/WbController.cpp +++ b/src/webots/control/WbController.cpp @@ -542,7 +542,7 @@ void WbController::setProcessEnvironment() { QList nodes = mRobot->subNodes(true, true, true); for (int i = 0; i < nodes.size(); ++i) { if (nodes.at(i)->isProtoInstance()) { - WbProtoModel *protoModel = nodes.at(i)->proto(); + const WbProtoModel *protoModel = nodes.at(i)->proto(); do { if (!protoModel->projectPath().isEmpty()) { QDir protoProjectDir(protoModel->projectPath()); diff --git a/src/webots/core/WbDownloadManager.cpp b/src/webots/core/WbDownloadManager.cpp index 6425ae256a1..496e9112934 100644 --- a/src/webots/core/WbDownloadManager.cpp +++ b/src/webots/core/WbDownloadManager.cpp @@ -52,7 +52,7 @@ void WbDownloadManager::abort() { WbDownloader *WbDownloadManager::createDownloader(const QUrl &url, QObject *parent) { WbSimulationState::instance()->pauseSimulation(); - WbDownloader *existingDownload = mUrlCache.value(url, NULL); + const WbDownloader *existingDownload = mUrlCache.value(url, NULL); WbDownloader *downloader = new WbDownloader(url, existingDownload, parent); connect(downloader, &WbDownloader::destroyed, this, &WbDownloadManager::removeDownloader); connect(downloader, &WbDownloader::complete, this, &WbDownloadManager::downloadCompleted); diff --git a/src/webots/core/WbFileUtil.cpp b/src/webots/core/WbFileUtil.cpp index ede8085b207..6f25971da43 100644 --- a/src/webots/core/WbFileUtil.cpp +++ b/src/webots/core/WbFileUtil.cpp @@ -38,7 +38,7 @@ bool WbFileUtil::copyAndReplaceString(const QString &sourcePath, const QString & } bool WbFileUtil::copyAndReplaceString(const QString &sourcePath, const QString &destinationPath, - QList> values) { + const QList> &values) { QFile sourceFile(sourcePath); if (!sourceFile.open(QIODevice::ReadOnly | QIODevice::Text)) { return false; @@ -89,7 +89,7 @@ int WbFileUtil::copyDir(const QString &sourcePath, const QString &destPath, bool // copy files int count = 0; QStringList files = sourceDir.entryList(QDir::Files | QDir::Hidden); - foreach (QString file, files) { + foreach (const QString &file, files) { QString srcName = sourcePath + "/" + file; QString destName = destPath + "/" + file; if (QFile::exists(destName)) { @@ -109,7 +109,8 @@ int WbFileUtil::copyDir(const QString &sourcePath, const QString &destPath, bool // recurse in subdirectories if (recurse) { QStringList dirs = sourceDir.entryList(QDir::AllDirs | QDir::NoDotAndDotDot); - foreach (QString dir, dirs) { + foreach (const QString &dir, dirs) { + // cppcheck-suppress variableScope QString srcName = sourcePath + "/" + dir; QString destName = destPath + "/" + dir; if (!QDir(destName).exists() || merge) diff --git a/src/webots/core/WbFileUtil.hpp b/src/webots/core/WbFileUtil.hpp index 2a5b770d068..443d0c32e8c 100644 --- a/src/webots/core/WbFileUtil.hpp +++ b/src/webots/core/WbFileUtil.hpp @@ -25,7 +25,7 @@ namespace WbFileUtil { // copy file from 'sourcePath' to 'destPath' while replacing a string pattern bool copyAndReplaceString(const QString &sourcePath, const QString &destinationPath, - QList> values); + const QList> &values); bool copyAndReplaceString(const QString &sourcePath, const QString &destinationPath, const QString &before, const QString &after); diff --git a/src/webots/core/WbLog.cpp b/src/webots/core/WbLog.cpp index 8b3fe62c088..83bf8c5c4c1 100644 --- a/src/webots/core/WbLog.cpp +++ b/src/webots/core/WbLog.cpp @@ -225,7 +225,7 @@ void WbLog::enqueueMessage(QList &list, const QString &message void WbLog::showPostponedPopUpMessages() { bool tmp = instance()->mPopUpMessagesPostponed; setPopUpPostponed(false); - foreach (PostponedMessage msg, instance()->mPostponedPopUpMessageQueue) { + foreach (const PostponedMessage &msg, instance()->mPostponedPopUpMessageQueue) { switch (msg.level) { case DEBUG: debug(msg.text, msg.name, true); @@ -249,7 +249,7 @@ void WbLog::showPostponedPopUpMessages() { } void WbLog::showPendingConsoleMessages() { - foreach (PostponedMessage msg, instance()->mPendingConsoleMessages) + foreach (const PostponedMessage &msg, instance()->mPendingConsoleMessages) emit instance()->logEmitted(msg.level, msg.text, false, msg.name); instance()->mPendingConsoleMessages.clear(); } @@ -261,7 +261,7 @@ void WbLog::toggle(FILE *std_stream) { assert(no >= 1); // it shouldn't be stdin fflush(std_stream); if (fd[no] == 0) { - static FILE *stream; // to make cppcheck happy about resource leak + static const FILE *stream; // to make cppcheck happy about resource leak fd[no] = dup(no); stream = freopen("/dev/null", "w", std_stream); if (!stream) diff --git a/src/webots/core/WbMacAddress.cpp b/src/webots/core/WbMacAddress.cpp index 5d75d9edc74..10b8f4312d1 100644 --- a/src/webots/core/WbMacAddress.cpp +++ b/src/webots/core/WbMacAddress.cpp @@ -151,7 +151,7 @@ WbMacAddress::WbMacAddress() { memset(&ifr, 0, sizeof(ifr)); strcpy(ifr.ifr_name, *interface); if (ioctl(fd, SIOCGIFHWADDR, &ifr) == 0) { - unsigned char *ch = reinterpret_cast(ifr.ifr_hwaddr.sa_data); + const unsigned char *ch = reinterpret_cast(ifr.ifr_hwaddr.sa_data); for (int i = 0; i < 6; i++) mAddress[i] = *ch++; } diff --git a/src/webots/core/WbPosixMemoryMappedFile.hpp b/src/webots/core/WbPosixMemoryMappedFile.hpp index e2183b0ce06..e742e8d443e 100644 --- a/src/webots/core/WbPosixMemoryMappedFile.hpp +++ b/src/webots/core/WbPosixMemoryMappedFile.hpp @@ -26,7 +26,7 @@ class WbPosixMemoryMappedFile { bool create(int size); int size() const { return mSize; } void *data() const { return mData; } - const QString nativeKey() const { return mName; } + const QString &nativeKey() const { return mName; } private: QString mName; diff --git a/src/webots/core/WbProject.cpp b/src/webots/core/WbProject.cpp index 39cb660c934..05b8a801af0 100644 --- a/src/webots/core/WbProject.cpp +++ b/src/webots/core/WbProject.cpp @@ -124,6 +124,7 @@ QString WbProject::projectPathFromWorldFile(const QString &fileName, bool &valid assert(info.suffix() == "wbt"); QDir directory = info.absoluteDir(); valid = directory.dirName() == "worlds"; + // cppcheck-suppress ignoredReturnErrorCode directory.cdUp(); // remove "worlds" return directory.absolutePath() + "/"; } @@ -133,6 +134,7 @@ QString WbProject::projectNameFromWorldFile(const QString &fileName) { assert(info.suffix() == "wbt"); QDir directory = info.absoluteDir(); if (directory.dirName() == "worlds") { + // cppcheck-suppress ignoredReturnErrorCode directory.cdUp(); // remove "worlds" return directory.dirName(); } diff --git a/src/webots/core/WbStandardPaths.cpp b/src/webots/core/WbStandardPaths.cpp index 7424ce39bc5..c2ce7daec91 100644 --- a/src/webots/core/WbStandardPaths.cpp +++ b/src/webots/core/WbStandardPaths.cpp @@ -48,7 +48,8 @@ const QString &WbStandardPaths::webotsHomePath() { if (path.isEmpty()) { QDir dir(QCoreApplication::applicationDirPath()); for (int i = 0; i < depth; i++) - dir.cdUp(); + if (!dir.cdUp()) + assert(false); path = dir.absolutePath() + "/"; } return path; @@ -243,7 +244,8 @@ bool WbStandardPaths::webotsTmpPathCreate(const int id) { #endif // cleanup old and unused tmp directories QDir directory(cWebotsTmpPath); - directory.cdUp(); + if (!directory.cdUp()) + assert(false); const QStringList &webotsTmp = directory.entryList(QStringList() << "webots-*", QDir::Dirs | QDir::Writable); foreach (const QString &dirname, webotsTmp) { const QString fullName(directory.absolutePath() + "/" + dirname); diff --git a/src/webots/core/WbSysInfo.cpp b/src/webots/core/WbSysInfo.cpp index b6a3500525c..249ef4ac3d9 100644 --- a/src/webots/core/WbSysInfo.cpp +++ b/src/webots/core/WbSysInfo.cpp @@ -291,7 +291,7 @@ const QString &WbSysInfo::linuxCpuModelName() { QFile cpuinfoFile("/proc/cpuinfo"); if (cpuinfoFile.open(QIODevice::ReadOnly)) { const QStringList lines = QString(cpuinfoFile.readAll()).split('\n'); - foreach (const QString line, lines) { + foreach (const QString &line, lines) { if (line.startsWith("model name")) { // 12 corresponds to the strlen("model name: ") cpuinfo = line.mid(12).trimmed(); // remove leading and trailing whitespace @@ -353,6 +353,7 @@ bool WbSysInfo::isVirtualMachine() { const int vendorIdLength = 13; using VendorIdStr = char[vendorIdLength]; VendorIdStr hyperVendorId = {}; + // cppcheck-suppress nullPointer memcpy(hyperVendorId + 0, &ebx, 4); memcpy(hyperVendorId + 4, &ecx, 4); memcpy(hyperVendorId + 8, &edx, 4); @@ -365,6 +366,7 @@ bool WbSysInfo::isVirtualMachine() { "prl hyperv ", // Parallels "VBoxVBoxVBox" // VirtualBox }; + // cppcheck-suppress constVariableReference for (const auto &vendor : vendors) { if (!memcmp(vendor, hyperVendorId, vendorIdLength)) { virtualMachine = 1; diff --git a/src/webots/editor/WbBuildEditor.cpp b/src/webots/editor/WbBuildEditor.cpp index 04fb6230071..9a805398696 100644 --- a/src/webots/editor/WbBuildEditor.cpp +++ b/src/webots/editor/WbBuildEditor.cpp @@ -508,11 +508,8 @@ void WbBuildEditor::jumpToError(QString fileName, int line, int column) { if (currentBuffer() && QDir::isRelativePath(fileName)) fileName = compileDir().absoluteFilePath(fileName); - if (openFile(fileName)) { - WbTextBuffer *buffer = currentBuffer(); - if (line != -1) - buffer->markError(line, column); - } + if (openFile(fileName) && line != -1) + currentBuffer()->markError(line, column); } void WbBuildEditor::unmarkError() { diff --git a/src/webots/editor/WbBuildEditor.hpp b/src/webots/editor/WbBuildEditor.hpp index 41d3a7a4873..961197e6e44 100644 --- a/src/webots/editor/WbBuildEditor.hpp +++ b/src/webots/editor/WbBuildEditor.hpp @@ -35,7 +35,7 @@ class WbBuildEditor : public WbTextEditor { static WbBuildEditor *instance(); explicit WbBuildEditor(QWidget *parent, const QString &toolBarAlign); - virtual ~WbBuildEditor(); + virtual ~WbBuildEditor() override; // open specified file, show line if specified, show exact word if column specified void jumpToError(QString fileName, int line = -1, int column = -1); diff --git a/src/webots/editor/WbProjectRelocationDialog.cpp b/src/webots/editor/WbProjectRelocationDialog.cpp index 6ad824804ca..19ec5ca7fde 100644 --- a/src/webots/editor/WbProjectRelocationDialog.cpp +++ b/src/webots/editor/WbProjectRelocationDialog.cpp @@ -80,6 +80,7 @@ WbProjectRelocationDialog::WbProjectRelocationDialog(WbProject *project, const Q } void WbProjectRelocationDialog::initCompleteRelocation() { + // cppcheck-suppress constVariablePointer QLabel *title = new QLabel(tr("Copy necessary files from source to target directory?"), this); const QString &sourcePath = QDir::toNativeSeparators(mProject->path()); @@ -116,6 +117,7 @@ void WbProjectRelocationDialog::initCompleteRelocation() { } void WbProjectRelocationDialog::initProtoSourceRelocation() { + // cppcheck-suppress constVariablePointer QLabel *title = new QLabel(tr("Copy necessary files from source to current project directory?"), this); mTargetPath = mProject->path(); @@ -220,7 +222,9 @@ void WbProjectRelocationDialog::copy() { mProject->setPath(dir.path()); // store the accepted project directory in the preferences - dir.cdUp(); // store the upper level, probably the path where the directories are stored + // store the upper level, probably the path where the directories are stored + if (!dir.cdUp()) + assert(false); WbPreferences::instance()->setValue("Directories/projects", dir.absolutePath() + '/'); const QList &robots = WbWorld::instance()->robots(); @@ -403,7 +407,7 @@ bool WbProjectRelocationDialog::validateLocation(QWidget *parent, QString &fileN if (!WbFileUtil::isLocatedInDirectory(fileName, current->path()) || WbFileUtil::isLocatedInDirectory(fileName, WbStandardPaths::resourcesPath())) { const QList &robots = WbWorld::instance()->robots(); - foreach (WbRobot *robot, robots) { + foreach (const WbRobot *robot, robots) { const WbProtoModel *proto = robot->proto(); if (!proto) continue; diff --git a/src/webots/editor/WbTextEditor.cpp b/src/webots/editor/WbTextEditor.cpp index 93a553c9764..afeb560bbff 100644 --- a/src/webots/editor/WbTextEditor.cpp +++ b/src/webots/editor/WbTextEditor.cpp @@ -308,7 +308,7 @@ bool WbTextEditor::openFile(const QString &path, const QString &title) { QFileInfo info(path); QString canonical = info.canonicalFilePath(); for (int i = 0; i < n; i++) { - WbTextBuffer *buf = buffer(i); + const WbTextBuffer *buf = buffer(i); if (canonical == buf->fileName()) { selectTab(i); return true; @@ -334,7 +334,7 @@ void WbTextEditor::openFileDialog() { // find a smart dir QString dir; - WbTextBuffer *textBuffer = currentBuffer(); + const WbTextBuffer *textBuffer = currentBuffer(); if (textBuffer) dir = textBuffer->path(); else if (WbProject::current()) @@ -608,7 +608,7 @@ QStringList WbTextEditor::openFiles() const { QStringList list; int count = mTabWidget->count(); for (int i = 0; i < count; i++) { - WbTextBuffer *buf = buffer(i); + const WbTextBuffer *buf = buffer(i); list << buf->fileName(); } @@ -618,7 +618,7 @@ QStringList WbTextEditor::openFiles() const { void WbTextEditor::openFiles(const QStringList &list, int selectedTab) { closeAllBuffers(); - foreach (QString file, list) { + foreach (const QString &file, list) { WbTextBuffer *newBuffer = new WbTextBuffer(this); connectBuffer(newBuffer); bool success = newBuffer->load(file); diff --git a/src/webots/editor/WbTextEditor.hpp b/src/webots/editor/WbTextEditor.hpp index 45496681373..2c91e63549f 100644 --- a/src/webots/editor/WbTextEditor.hpp +++ b/src/webots/editor/WbTextEditor.hpp @@ -41,7 +41,7 @@ class WbTextEditor : public WbDockWidget { public: explicit WbTextEditor(QWidget *parent, const QString &toolBarAlign); - virtual ~WbTextEditor(); + virtual ~WbTextEditor() override; // index of currently selected tab, or -1 if there is no tab int selectedTab() const; diff --git a/src/webots/editor/WbTextFind.hpp b/src/webots/editor/WbTextFind.hpp index c8b9b9d0164..cc7d3d7423c 100644 --- a/src/webots/editor/WbTextFind.hpp +++ b/src/webots/editor/WbTextFind.hpp @@ -41,8 +41,8 @@ class WbTextFind : public QObject { void replace(const QString &before, const QString &after, FindFlags findFlags); void replaceAll(const QString &before, const QString &after, FindFlags findFlags); - static QStringList findStringList() { return cFindStringList; } - static QStringList replaceStringList() { return cReplaceStringList; } + static QStringList &findStringList() { return cFindStringList; } + static QStringList &replaceStringList() { return cReplaceStringList; } static FindFlags lastFindFlags() { return cLastFindFlags; } signals: diff --git a/src/webots/engine/WbAnimationRecorder.cpp b/src/webots/engine/WbAnimationRecorder.cpp index 1888031d0fb..7716a49d7d9 100644 --- a/src/webots/engine/WbAnimationRecorder.cpp +++ b/src/webots/engine/WbAnimationRecorder.cpp @@ -254,15 +254,16 @@ void WbAnimationRecorder::populateCommands() { continue; const QStringList fields = node->fieldsToSynchronizeWithW3d(); if (fields.size() > 0) { + // cppcheck-suppress constVariablePointer WbAnimationCommand *command = new WbAnimationCommand(node, fields, !mStreamingServer); mCommands << command; } } const QList &robots = WbWorld::instance()->robots(); - foreach (WbRobot *const robot, robots) { + foreach (const WbRobot *const robot, robots) { if (robot->supervisor()) { - foreach (QString label, robot->supervisorUtilities()->labelsState()) + foreach (const QString &label, robot->supervisorUtilities()->labelsState()) addChangedLabelToList(label); connect(robot->supervisorUtilities(), &WbSupervisorUtilities::labelChanged, this, @@ -370,7 +371,7 @@ QString WbAnimationRecorder::computeUpdateData(bool force) { if (mChangedLabels.size() != 0) { out << ",\"labels\":["; - foreach (QString label, mChangedLabels) { + foreach (const QString &label, mChangedLabels) { out << "{"; out << label; mLabelsIds.insert(label.mid(5, label.indexOf("font") - 7)); @@ -463,6 +464,7 @@ void WbAnimationRecorder::stopRecording() { const double step = worldInfo->basicTimeStep() * ceil((1000.0 / worldInfo->fps()) / worldInfo->basicTimeStep()); out << QString(" \"basicTimeStep\":%1,\n").arg(step); QList commandsChangedFromStart; + // cppcheck-suppress constVariablePointer foreach (WbAnimationCommand *command, mCommands) { // store only ids of nodes that changed during the animation if (command->isChangedFromStart()) @@ -470,7 +472,7 @@ void WbAnimationRecorder::stopRecording() { } out << " \"labelsIds\":\""; bool firstLabel = true; - foreach (QString id, mLabelsIds) { + foreach (const QString &id, mLabelsIds) { // cppcheck-suppress knownConditionTrueFalse if (!firstLabel) out << ";"; @@ -489,7 +491,7 @@ void WbAnimationRecorder::stopRecording() { "If you just want a 3D environment file, consider exporting a scene instead.")); return; } - foreach (WbAnimationCommand *command, commandsChangedFromStart) { + foreach (const WbAnimationCommand *command, commandsChangedFromStart) { // store only initial state of nodes that changed during the animation if (command != commandsChangedFromStart.first()) out << ","; diff --git a/src/webots/engine/WbSimulationCluster.cpp b/src/webots/engine/WbSimulationCluster.cpp index 7f8dc4f1752..eec18e00ef9 100644 --- a/src/webots/engine/WbSimulationCluster.cpp +++ b/src/webots/engine/WbSimulationCluster.cpp @@ -439,7 +439,7 @@ void WbSimulationCluster::fillImmersionSurfaceParameters(const WbSolid *s, const surf->maxAngularVel = 1000.0; } -static bool needCollisionDetection(WbSolid *solid, bool isOtherRayGeom) { +static bool needCollisionDetection(const WbSolid *solid, bool isOtherRayGeom) { switch (solid->nodeType()) { case WB_NODE_TOUCH_SENSOR: if (isOtherRayGeom) @@ -456,6 +456,7 @@ static bool needCollisionDetection(WbSolid *solid, bool isOtherRayGeom) { return false; } +// cppcheck-suppress constParameterPointer void WbSimulationCluster::appendCollisionedRobot(WbKinematicDifferentialWheels *robot) { if (WbOdeContext::instance()->numberOfThreads() > 1) { QMutexLocker lock(&mCollisionedRobotsMutex); diff --git a/src/webots/engine/WbSimulationWorld.cpp b/src/webots/engine/WbSimulationWorld.cpp index 515d2007ecf..102d670b3ce 100644 --- a/src/webots/engine/WbSimulationWorld.cpp +++ b/src/webots/engine/WbSimulationWorld.cpp @@ -419,8 +419,8 @@ void WbSimulationWorld::storeAddedNodeIfNeeded(WbNode *node) { connect(node, &QObject::destroyed, this, &WbSimulationWorld::removeNodeFromAddedNodeList); } -void WbSimulationWorld::removeNodeFromAddedNodeList(QObject *node) { - WbNode *n = static_cast(node); +void WbSimulationWorld::removeNodeFromAddedNodeList(const QObject *node) { + const WbNode *n = static_cast(node); mAddedNode.removeAll(n); } diff --git a/src/webots/engine/WbSimulationWorld.hpp b/src/webots/engine/WbSimulationWorld.hpp index 8fd83b77ef7..6315102da09 100644 --- a/src/webots/engine/WbSimulationWorld.hpp +++ b/src/webots/engine/WbSimulationWorld.hpp @@ -86,7 +86,7 @@ protected slots: void propagateBoundingObjectMaterialUpdate(bool onMenuAction); private slots: - void removeNodeFromAddedNodeList(QObject *node); + void removeNodeFromAddedNodeList(const QObject *node); void propagateBoundingObjectUpdate() { propagateBoundingObjectMaterialUpdate(false); } void updateRandomSeed(); }; diff --git a/src/webots/gui/WbAbstractDragEvent.hpp b/src/webots/gui/WbAbstractDragEvent.hpp index 819bde41a20..ff0d19875e5 100644 --- a/src/webots/gui/WbAbstractDragEvent.hpp +++ b/src/webots/gui/WbAbstractDragEvent.hpp @@ -53,7 +53,7 @@ class WbDragEvent : public QObject { // WbDragView3DEvent class class WbDragView3DEvent : public WbDragEvent { public: - virtual ~WbDragView3DEvent() {} + virtual ~WbDragView3DEvent() override {} void apply(const QPoint ¤tMousePosition) override = 0; protected: @@ -72,7 +72,7 @@ class WbDragView3DEvent : public WbDragEvent { ///////////////////////////////////////// class WbDragKinematicsEvent : public WbDragView3DEvent { public: - virtual ~WbDragKinematicsEvent() {} + virtual ~WbDragKinematicsEvent() override {} void apply(const QPoint ¤tMousePosition) override = 0; protected: diff --git a/src/webots/gui/WbConsole.cpp b/src/webots/gui/WbConsole.cpp index add74f2efe0..480a5dc9397 100644 --- a/src/webots/gui/WbConsole.cpp +++ b/src/webots/gui/WbConsole.cpp @@ -162,7 +162,7 @@ void ConsoleEdit::handleFilterChange() { } } else if (action->text() == WbLog::filterName(WbLog::ALL_WEBOTS)) { // disable all the Webots filters - foreach (const QString filter, WbLog::webotsFilterNames()) + foreach (const QString &filter, WbLog::webotsFilterNames()) emit filterDisabled(filter); emit filterDisabled(WbLog::filterName(WbLog::ALL)); } else if (action->text() == WbLog::filterName(WbLog::ALL_CONTROLLERS)) { @@ -587,7 +587,7 @@ void WbConsole::handlePossibleAnsiEscapeSequences(const QString &msg, WbLog::Lev } const QStringList codes(sequence.split(";")); // handle multiple (e.g. sequence "ESC[0;39m" ) - foreach (const QString code, codes) { + foreach (const QString &code, codes) { // the stored sequence may be "0m" or "1m", "4m", "2J", "30m", "31m", "32m", etc. if (code == "0m") // reset to default resetFormat(); diff --git a/src/webots/gui/WbConsole.hpp b/src/webots/gui/WbConsole.hpp index 82d03096eb6..b25c698d022 100644 --- a/src/webots/gui/WbConsole.hpp +++ b/src/webots/gui/WbConsole.hpp @@ -36,7 +36,7 @@ class ConsoleEdit : public QPlainTextEdit { public: explicit ConsoleEdit(QWidget *parent); - virtual ~ConsoleEdit(); + virtual ~ConsoleEdit() override; void copy(); void mouseDoubleClickEvent(QMouseEvent *event) override; @@ -87,7 +87,7 @@ class WbConsole : public WbDockWidget { public: explicit WbConsole(QWidget *parent = NULL, const QString &name = QString("Console")); - virtual ~WbConsole() {} + virtual ~WbConsole() override {} // parse compilation error line void jumpToError(const QString &errorLine); @@ -116,13 +116,13 @@ class WbConsole : public WbDockWidget { void setAnsiCyan(const QString &color) { mAnsiCyan = color; } void setAnsiWhite(const QString &color) { mAnsiWhite = color; } - const QStringList getEnabledFilters() const { return mEnabledFilters; } + const QStringList &getEnabledFilters() const { return mEnabledFilters; } void setEnabledFilters(const QStringList &filters); - const QStringList getEnabledLevels() const { return mEnabledLevels; } + const QStringList &getEnabledLevels() const { return mEnabledLevels; } void setEnabledLevels(const QStringList &levels); - const QString name() const { return mConsoleName; } + const QString &name() const { return mConsoleName; } signals: void closed(); diff --git a/src/webots/gui/WbDragOverlayEvent.hpp b/src/webots/gui/WbDragOverlayEvent.hpp index 104092b154e..d2917488c40 100644 --- a/src/webots/gui/WbDragOverlayEvent.hpp +++ b/src/webots/gui/WbDragOverlayEvent.hpp @@ -28,7 +28,7 @@ class WbDragOverlayEvent : public WbDragEvent { public: enum DragOverlayType { TRANSLATE = 0, RESIZE }; WbDragOverlayEvent(const QPoint &initialMousePosition, WbRenderingDevice *renderingDevice); - virtual ~WbDragOverlayEvent(){}; + virtual ~WbDragOverlayEvent() override{}; virtual DragOverlayType type() = 0; void apply(const QPoint ¤tMousePosition) override = 0; @@ -42,7 +42,7 @@ class WbDragOverlayEvent : public WbDragEvent { class WbDragTranslateOverlayEvent : public WbDragOverlayEvent { public: WbDragTranslateOverlayEvent(const QPoint &initialMousePosition, const QPoint &windowSize, WbRenderingDevice *renderingDevice); - virtual ~WbDragTranslateOverlayEvent(){}; + virtual ~WbDragTranslateOverlayEvent() override{}; DragOverlayType type() override { return TRANSLATE; } void apply(const QPoint ¤tMousePosition) override; @@ -57,7 +57,7 @@ class WbDragTranslateOverlayEvent : public WbDragOverlayEvent { class WbDragResizeOverlayEvent : public WbDragOverlayEvent { public: WbDragResizeOverlayEvent(const QPoint &initialMousePosition, WbRenderingDevice *renderingDevice); - virtual ~WbDragResizeOverlayEvent(); + virtual ~WbDragResizeOverlayEvent() override; DragOverlayType type() override { return RESIZE; } void apply(const QPoint ¤tMousePosition) override; diff --git a/src/webots/gui/WbDragPoseEvent.hpp b/src/webots/gui/WbDragPoseEvent.hpp index ca611cfa864..7d706a5b6ba 100644 --- a/src/webots/gui/WbDragPoseEvent.hpp +++ b/src/webots/gui/WbDragPoseEvent.hpp @@ -39,7 +39,7 @@ class WbViewpoint; class WbDragPoseEvent : public WbDragKinematicsEvent { public: WbDragPoseEvent(WbViewpoint *viewpoint, WbAbstractPose *selectedPose); - virtual ~WbDragPoseEvent(); + virtual ~WbDragPoseEvent() override; void apply(const QPoint ¤tMousePosition) override = 0; protected: @@ -50,7 +50,7 @@ class WbDragPoseEvent : public WbDragKinematicsEvent { class WbTranslateEvent : public WbDragPoseEvent { public: WbTranslateEvent(WbViewpoint *viewpoint, WbAbstractPose *selectedPose); - virtual ~WbTranslateEvent(); + virtual ~WbTranslateEvent() override; void apply(const QPoint ¤tMousePosition) override = 0; protected: @@ -68,7 +68,7 @@ class WbTranslateEvent : public WbDragPoseEvent { class WbDragHorizontalEvent : public WbTranslateEvent { public: WbDragHorizontalEvent(const QPoint &initialPosition, WbViewpoint *viewpoint, WbAbstractPose *selectedPose); - virtual ~WbDragHorizontalEvent(); + virtual ~WbDragHorizontalEvent() override; void apply(const QPoint ¤tMousePosition) override; private: @@ -81,7 +81,7 @@ class WbDragHorizontalEvent : public WbTranslateEvent { class WbDragVerticalEvent : public WbTranslateEvent { public: WbDragVerticalEvent(const QPoint &initialPosition, WbViewpoint *viewpoint, WbAbstractPose *selectedPose); - virtual ~WbDragVerticalEvent(); + virtual ~WbDragVerticalEvent() override; void apply(const QPoint ¤tMousePosition) override; private: @@ -96,7 +96,7 @@ class WbDragTranslateAlongAxisEvent : public WbDragPoseEvent { public: WbDragTranslateAlongAxisEvent(const QPoint &initialMousePosition, const QSize &widgetSize, WbViewpoint *viewpoint, int handleNumber, WbAbstractPose *selectedPose); - virtual ~WbDragTranslateAlongAxisEvent(); + virtual ~WbDragTranslateAlongAxisEvent() override; void apply(const QPoint ¤tMousePosition) override; protected: @@ -122,7 +122,7 @@ class WbDragRotateAroundWorldVerticalAxisEvent : public WbDragPoseEvent { public: WbDragRotateAroundWorldVerticalAxisEvent(const QPoint &initialMousePosition, WbViewpoint *viewpoint, WbAbstractPose *selectedPose); - virtual ~WbDragRotateAroundWorldVerticalAxisEvent(); + virtual ~WbDragRotateAroundWorldVerticalAxisEvent() override; void apply(const QPoint ¤tMousePosition) override; protected: @@ -139,7 +139,7 @@ class WbDragRotateAroundAxisEvent : public WbDragPoseEvent { public: WbDragRotateAroundAxisEvent(const QPoint &initialMousePosition, const QSize &widgetSize, WbViewpoint *viewpoint, int handleNumber, WbAbstractPose *selectedPose); - virtual ~WbDragRotateAroundAxisEvent(); + virtual ~WbDragRotateAroundAxisEvent() override; void apply(const QPoint ¤tMousePosition) override; protected: diff --git a/src/webots/gui/WbDragResizeEvent.hpp b/src/webots/gui/WbDragResizeEvent.hpp index 4cd9f0107b0..ab7ecb4f80a 100644 --- a/src/webots/gui/WbDragResizeEvent.hpp +++ b/src/webots/gui/WbDragResizeEvent.hpp @@ -46,7 +46,7 @@ class WbDragResizeHandleEvent : public WbDragView3DEvent { public: WbDragResizeHandleEvent(const QPoint &initialMousePosition, WbViewpoint *viewpoint, int handleNumber, WbGeometry *selectedGeometry); - virtual ~WbDragResizeHandleEvent(); + virtual ~WbDragResizeHandleEvent() override; void apply(const QPoint ¤tMousePosition) override = 0; virtual void addActionInUndoStack() = 0; diff --git a/src/webots/gui/WbDragSolidEvent.hpp b/src/webots/gui/WbDragSolidEvent.hpp index 2a6ea041fa9..02689396732 100644 --- a/src/webots/gui/WbDragSolidEvent.hpp +++ b/src/webots/gui/WbDragSolidEvent.hpp @@ -38,7 +38,7 @@ class WbViewpoint; class WbDragHorizontalSolidEvent : public WbDragHorizontalEvent { public: WbDragHorizontalSolidEvent(const QPoint &initialPosition, WbViewpoint *viewpoint, WbSolid *selectedSolid); - virtual ~WbDragHorizontalSolidEvent(); + virtual ~WbDragHorizontalSolidEvent() override; void apply(const QPoint ¤tMousePosition) override; private: @@ -48,7 +48,7 @@ class WbDragHorizontalSolidEvent : public WbDragHorizontalEvent { class WbDragVerticalSolidEvent : public WbDragVerticalEvent { public: WbDragVerticalSolidEvent(const QPoint &initialPosition, WbViewpoint *viewpoint, WbSolid *selectedSolid); - virtual ~WbDragVerticalSolidEvent(); + virtual ~WbDragVerticalSolidEvent() override; void apply(const QPoint ¤tMousePosition) override; private: @@ -61,7 +61,7 @@ class WbDragTranslateAlongAxisSolidEvent : public WbDragTranslateAlongAxisEvent public: WbDragTranslateAlongAxisSolidEvent(const QPoint &initialMousePosition, const QSize &widgetSize, WbViewpoint *viewpoint, int handleNumber, WbSolid *selectedSolid); - virtual ~WbDragTranslateAlongAxisSolidEvent(); + virtual ~WbDragTranslateAlongAxisSolidEvent() override; void apply(const QPoint ¤tMousePosition) override; private: @@ -71,7 +71,7 @@ class WbDragTranslateAlongAxisSolidEvent : public WbDragTranslateAlongAxisEvent class WbDragRotateAroundWorldVerticalAxisSolidEvent : public WbDragRotateAroundWorldVerticalAxisEvent { public: WbDragRotateAroundWorldVerticalAxisSolidEvent(const QPoint &initialPosition, WbViewpoint *viewpoint, WbSolid *selectedSolid); - virtual ~WbDragRotateAroundWorldVerticalAxisSolidEvent(); + virtual ~WbDragRotateAroundWorldVerticalAxisSolidEvent() override; void apply(const QPoint ¤tMousePosition) override; private: @@ -84,7 +84,7 @@ class WbDragRotateAroundAxisSolidEvent : public WbDragRotateAroundAxisEvent { public: WbDragRotateAroundAxisSolidEvent(const QPoint &initialMousePosition, const QSize &widgetSize, WbViewpoint *viewpoint, int handleNumber, WbSolid *selectedSolid); - virtual ~WbDragRotateAroundAxisSolidEvent(); + virtual ~WbDragRotateAroundAxisSolidEvent() override; void apply(const QPoint ¤tMousePosition) override; private: @@ -101,7 +101,7 @@ class WbDragPhysicsEvent : public WbDragView3DEvent { public: WbDragPhysicsEvent(const QSize &widgetSize, WbViewpoint *viewpoint, WbSolid *selectedSolid); - virtual ~WbDragPhysicsEvent(); + virtual ~WbDragPhysicsEvent() override; void apply(const QPoint ¤tMousePosition) override; void lock(); // Accessor diff --git a/src/webots/gui/WbDragViewpointEvent.hpp b/src/webots/gui/WbDragViewpointEvent.hpp index 021c65d65c6..c4071578f06 100644 --- a/src/webots/gui/WbDragViewpointEvent.hpp +++ b/src/webots/gui/WbDragViewpointEvent.hpp @@ -30,7 +30,7 @@ class WbViewpoint; /////////////////////////////////////////////////////////////////////////////////// class WbDragViewpointEvent : public WbDragKinematicsEvent { public: - virtual ~WbDragViewpointEvent() {} + virtual ~WbDragViewpointEvent() override {} void apply(const QPoint ¤tMousePosition) override = 0; protected: @@ -43,7 +43,7 @@ class WbDragViewpointEvent : public WbDragKinematicsEvent { class WbTranslateViewpointEvent : public WbDragViewpointEvent { public: WbTranslateViewpointEvent(const QPoint &initialMousePosition, WbViewpoint *viewpoint, double scale); - virtual ~WbTranslateViewpointEvent(); + virtual ~WbTranslateViewpointEvent() override; void apply(const QPoint ¤tMousePosition) override; private: @@ -57,7 +57,7 @@ class WbTranslateViewpointEvent : public WbDragViewpointEvent { class WbRotateViewpointEvent : public WbDragViewpointEvent { public: WbRotateViewpointEvent(const QPoint &initialMousePosition, WbViewpoint *viewpoint, bool objectPicked); - virtual ~WbRotateViewpointEvent(); + virtual ~WbRotateViewpointEvent() override; void apply(const QPoint ¤tMousePosition) override; static void applyToViewpoint(const QPoint &delta, const WbVector3 &rotationCenter, const WbVector3 &worldUpVector, @@ -74,7 +74,7 @@ class WbRotateViewpointEvent : public WbDragViewpointEvent { class WbZoomAndRotateViewpointEvent : public WbDragViewpointEvent { public: WbZoomAndRotateViewpointEvent(const QPoint &initialMousePosition, WbViewpoint *viewpoint, const double scale); - virtual ~WbZoomAndRotateViewpointEvent(); + virtual ~WbZoomAndRotateViewpointEvent() override; void apply(const QPoint ¤tMousePosition) override; static void applyToViewpoint(double tiltAngle, double zoom, double scaleFactor, WbViewpoint *viewpoint); diff --git a/src/webots/gui/WbMainWindow.cpp b/src/webots/gui/WbMainWindow.cpp index 9130f91ea79..91638c2a306 100644 --- a/src/webots/gui/WbMainWindow.cpp +++ b/src/webots/gui/WbMainWindow.cpp @@ -1180,7 +1180,7 @@ void WbMainWindow::savePerspective(bool reloading, bool saveToFile, bool isSaveE void WbMainWindow::restorePerspective(bool reloading, bool firstLoad, bool loadingFromMemory) { WbWorld *world = WbWorld::instance(); - WbPerspective *perspective = world->perspective(); + const WbPerspective *perspective = world->perspective(); bool meansOfLoading = false; if (loadingFromMemory) meansOfLoading = true; @@ -1622,7 +1622,7 @@ void WbMainWindow::upload() { // add files content QMap map; - foreach (const QString fileName, fileNames) { + foreach (const QString &fileName, fileNames) { QHttpPart mainPart; if (fileName.contains("w3d")) { map["foldername"] = WbStandardPaths::webotsTmpPath(); @@ -1731,7 +1731,7 @@ void WbMainWindow::uploadFinished() { QJsonDocument doc(obj); QByteArray data = doc.toJson(); - QNetworkReply *uploadReply = manager->post(request, data); + const QNetworkReply *uploadReply = manager->post(request, data); QObject::connect(uploadReply, &QNetworkReply::finished, this, &WbMainWindow::uploadStatus); @@ -2617,7 +2617,7 @@ void WbMainWindow::disableAnimationAction() { } void WbMainWindow::logActiveControllersTermination() { - WbControlledWorld *controlledWorld = WbControlledWorld::instance(); + const WbControlledWorld *controlledWorld = WbControlledWorld::instance(); if (controlledWorld) { QStringList activeControllers = controlledWorld->activeControllersNames(); foreach (QString controllerName, activeControllers) diff --git a/src/webots/gui/WbMultimediaStreamingServer.cpp b/src/webots/gui/WbMultimediaStreamingServer.cpp index adb1fac6bf1..764a8645d0e 100644 --- a/src/webots/gui/WbMultimediaStreamingServer.cpp +++ b/src/webots/gui/WbMultimediaStreamingServer.cpp @@ -99,7 +99,7 @@ int WbMultimediaStreamingServer::bytesToWrite() { } void WbMultimediaStreamingServer::removeTcpClient() { - QTcpSocket *client = qobject_cast(sender()); + const QTcpSocket *client = qobject_cast(sender()); if (client) mTcpClients.removeAll(client); if (mTcpClients.isEmpty()) diff --git a/src/webots/gui/WbMultimediaStreamingServer.hpp b/src/webots/gui/WbMultimediaStreamingServer.hpp index 81cf6baf92a..f72ea43b8ba 100644 --- a/src/webots/gui/WbMultimediaStreamingServer.hpp +++ b/src/webots/gui/WbMultimediaStreamingServer.hpp @@ -30,7 +30,7 @@ class WbMultimediaStreamingServer : public WbTcpServer { public: WbMultimediaStreamingServer(); - ~WbMultimediaStreamingServer(); + ~WbMultimediaStreamingServer() override; void sendImage(const QImage &image); void setView3D(WbView3D *view3D); diff --git a/src/webots/gui/WbNewControllerWizard.cpp b/src/webots/gui/WbNewControllerWizard.cpp index b93eced8b25..5817dd5576a 100644 --- a/src/webots/gui/WbNewControllerWizard.cpp +++ b/src/webots/gui/WbNewControllerWizard.cpp @@ -169,6 +169,7 @@ const QString &WbNewControllerWizard::controllerName() const { QWizardPage *WbNewControllerWizard::createIntroPage() { QWizardPage *page = new QWizardPage(this); page->setTitle(tr("New controller creation")); + // cppcheck-suppress constVariablePointer QLabel *label = new QLabel(tr("This wizard will help you creating a new controller."), page); QVBoxLayout *layout = new QVBoxLayout(page); layout->addWidget(label); diff --git a/src/webots/gui/WbNewPhysicsPluginWizard.cpp b/src/webots/gui/WbNewPhysicsPluginWizard.cpp index 8c9eae4408c..973016f1bd3 100644 --- a/src/webots/gui/WbNewPhysicsPluginWizard.cpp +++ b/src/webots/gui/WbNewPhysicsPluginWizard.cpp @@ -113,6 +113,7 @@ QWizardPage *WbNewPhysicsPluginWizard::createIntroPage() { page->setTitle(tr("New physics plugin creation")); + // cppcheck-suppress constVariablePointer QLabel *label = new QLabel(tr("This wizard will help you creating a new physics plugin."), page); QVBoxLayout *layout = new QVBoxLayout(page); diff --git a/src/webots/gui/WbNewProjectWizard.cpp b/src/webots/gui/WbNewProjectWizard.cpp index 8915d7faf9f..78504ed4417 100644 --- a/src/webots/gui/WbNewProjectWizard.cpp +++ b/src/webots/gui/WbNewProjectWizard.cpp @@ -54,7 +54,8 @@ QString WbNewProjectWizard::proposeNewProjectPath() const { } } else { // otherwise propose new project dir as sibling of current project QDir dir(WbProject::current()->path()); - dir.cdUp(); + if (!dir.cdUp()) + assert(false); path = dir.absolutePath() + "/my_project"; } // propose only if this directory does not yet exist or is empty @@ -80,7 +81,9 @@ void WbNewProjectWizard::accept() { createWorldFile(); // store the accepted project directory in the preferences QDir dir(mProject->path()); - dir.cdUp(); // store the upper level, probably the path where the directories are stored + // store the upper level, probably the path where the directories are stored + if (!dir.cdUp()) + assert(false); WbPreferences::instance()->setValue("Directories/projects", dir.absolutePath() + "/"); QDialog::accept(); } diff --git a/src/webots/gui/WbNewProjectWizard.hpp b/src/webots/gui/WbNewProjectWizard.hpp index a40a95284b2..1b9c40f74fa 100644 --- a/src/webots/gui/WbNewProjectWizard.hpp +++ b/src/webots/gui/WbNewProjectWizard.hpp @@ -29,7 +29,7 @@ class WbNewProjectWizard : public WbNewWorldWizard { public: explicit WbNewProjectWizard(QWidget *parent = NULL); - virtual ~WbNewProjectWizard(); + virtual ~WbNewProjectWizard() override; void accept() override; bool validateCurrentPage() override; diff --git a/src/webots/gui/WbNewProtoWizard.cpp b/src/webots/gui/WbNewProtoWizard.cpp index b6b8ebdc771..a2a8dc119f9 100644 --- a/src/webots/gui/WbNewProtoWizard.cpp +++ b/src/webots/gui/WbNewProtoWizard.cpp @@ -293,6 +293,7 @@ QWizardPage *WbNewProtoWizard::createIntroPage() { page->setTitle(tr("New PROTO creation")); QVBoxLayout *layout = new QVBoxLayout(page); + // cppcheck-suppress constVariablePointer QLabel *label = new QLabel(tr("This wizard will help you creating a new PROTO."), page); layout->addWidget(label); @@ -489,7 +490,7 @@ void WbNewProtoWizard::updateBaseNode() { QStringList fieldNames; mCategory = topLevel->type(); if (mCategory == WbProtoManager::BASE_NODE) { - WbNodeModel *nodeModel = WbNodeModel::findModel(mBaseNode); + const WbNodeModel *nodeModel = WbNodeModel::findModel(mBaseNode); fieldNames = nodeModel->fieldNames(); mIsProtoNode = false; } else { diff --git a/src/webots/gui/WbNewWorldWizard.cpp b/src/webots/gui/WbNewWorldWizard.cpp index f40c73a2106..e33e3855239 100644 --- a/src/webots/gui/WbNewWorldWizard.cpp +++ b/src/webots/gui/WbNewWorldWizard.cpp @@ -148,6 +148,7 @@ QString WbNewWorldWizard::fileName() const { QWizardPage *WbNewWorldWizard::createIntroPage() { QWizardPage *page = new QWizardPage(this); page->setTitle(introTitle()); + // cppcheck-suppress constVariablePointer QLabel *label = new QLabel(introText(), page); QVBoxLayout *layout = new QVBoxLayout(page); layout->addWidget(label); diff --git a/src/webots/gui/WbPreferencesDialog.cpp b/src/webots/gui/WbPreferencesDialog.cpp index 9a1f097fc0f..0dc23bb8d6e 100644 --- a/src/webots/gui/WbPreferencesDialog.cpp +++ b/src/webots/gui/WbPreferencesDialog.cpp @@ -273,7 +273,7 @@ QWidget *WbPreferencesDialog::createGeneralTab() { QGridLayout *layout = new QGridLayout(widget); mLanguageCombo = new QComboBox(this); - WbTranslator *t = WbTranslator::instance(); + const WbTranslator *t = WbTranslator::instance(); const QString &languageKey = WbPreferences::instance()->value("General/language").toString(); const QStringList &languages = t->computeUserReadableLanguages(); foreach (const QString &language, languages) diff --git a/src/webots/gui/WbRecentFilesList.cpp b/src/webots/gui/WbRecentFilesList.cpp index 0126a541447..33d2f52fa51 100644 --- a/src/webots/gui/WbRecentFilesList.cpp +++ b/src/webots/gui/WbRecentFilesList.cpp @@ -96,7 +96,7 @@ void WbRecentFilesList::makeRecent(const QString &filename) { } void WbRecentFilesList::actionTriggered() { - QAction *action = qobject_cast(sender()); + const QAction *action = qobject_cast(sender()); if (!action) return; diff --git a/src/webots/gui/WbRenderingDeviceWindow.cpp b/src/webots/gui/WbRenderingDeviceWindow.cpp index 50d09698357..282d1731cc1 100644 --- a/src/webots/gui/WbRenderingDeviceWindow.cpp +++ b/src/webots/gui/WbRenderingDeviceWindow.cpp @@ -167,7 +167,7 @@ WbRenderingDeviceWindow::~WbRenderingDeviceWindow() { return; QOpenGLFunctions_3_3_Core *f = QOpenGLVersionFunctionsFactory::get(mContext); f->glDeleteVertexArrays(1, &mVaoId); - f->glDeleteBuffers(2, (GLuint *)&mVboId); + f->glDeleteBuffers(2, reinterpret_cast(&mVboId)); mContext->doneCurrent(); delete mVboId; } diff --git a/src/webots/gui/WbRenderingDeviceWindowFactory.cpp b/src/webots/gui/WbRenderingDeviceWindowFactory.cpp index ec0117610fb..236eb2e1ccf 100644 --- a/src/webots/gui/WbRenderingDeviceWindowFactory.cpp +++ b/src/webots/gui/WbRenderingDeviceWindowFactory.cpp @@ -72,7 +72,7 @@ void WbRenderingDeviceWindowFactory::showWindowForDevice(WbRenderingDevice *devi void WbRenderingDeviceWindowFactory::saveWindowsPerspective(WbPerspective &perspective) { for (int i = 0; i < mWindowsList.size(); ++i) { if (mWindowsList[i]->isVisible()) { - WbRenderingDeviceWindow *window = mWindowsList[i]; + const WbRenderingDeviceWindow *window = mWindowsList[i]; QStringList devicePerspective(window->device()->perspective()); devicePerspective << window->perspective(); perspective.setRenderingDevicePerspective(window->device()->computeShortUniqueName(), devicePerspective); diff --git a/src/webots/gui/WbRobotWindow.hpp b/src/webots/gui/WbRobotWindow.hpp index 43f87613568..a62192371b1 100644 --- a/src/webots/gui/WbRobotWindow.hpp +++ b/src/webots/gui/WbRobotWindow.hpp @@ -25,7 +25,7 @@ class WbRobotWindow : public QObject { explicit WbRobotWindow(WbRobot *); WbRobot *robot() { return mRobot; } - const QString getClientID() { return mClientID; } + const QString &getClientID() { return mClientID; } void setupPage(int port); public slots: diff --git a/src/webots/gui/WbShareWindow.cpp b/src/webots/gui/WbShareWindow.cpp index f6a66d394ab..1e95a22c076 100644 --- a/src/webots/gui/WbShareWindow.cpp +++ b/src/webots/gui/WbShareWindow.cpp @@ -99,7 +99,7 @@ void WbLinkWindow::reject() { QDir dir(WbStandardPaths::webotsTmpPath() + "textures/"); // remove tmp files dir.removeRecursively(); const QStringList extensions = {".html", ".w3d", ".json", ".jpg"}; - foreach (QString extension, extensions) + foreach (const QString &extension, extensions) QFile::remove(WbStandardPaths::webotsTmpPath() + "cloud_export" + extension); QDialog::reject(); diff --git a/src/webots/gui/WbSimulationView.cpp b/src/webots/gui/WbSimulationView.cpp index bc17307949f..b54e638e4f2 100644 --- a/src/webots/gui/WbSimulationView.cpp +++ b/src/webots/gui/WbSimulationView.cpp @@ -124,7 +124,7 @@ WbSimulationView::WbSimulationView(QWidget *parent, const QString &toolBarAlign) vlayout->addWidget(mToolBar); vlayout->addWidget(mSplitter, 1); - WbSimulationState *state = WbSimulationState::instance(); + const WbSimulationState *state = WbSimulationState::instance(); // show a black screen if rendering is turned off if (!state->isRendering()) @@ -697,7 +697,6 @@ void WbSimulationView::takeScreenshot() { WbSimulationState *simulationState = WbSimulationState::instance(); simulationState->pauseSimulation(); - static QStringList winFilters = QStringList() << tr("PNG (*.png)") << tr("JPEG (*.jpg *.jpeg)"); static QString otherFilters = tr("Images (*.png *.jpg *.jpeg)"); static QString dialogCaption = tr("Save as..."); diff --git a/src/webots/gui/WbSingleTaskApplication.cpp b/src/webots/gui/WbSingleTaskApplication.cpp index 8314003c391..059d9dbdee6 100644 --- a/src/webots/gui/WbSingleTaskApplication.cpp +++ b/src/webots/gui/WbSingleTaskApplication.cpp @@ -92,7 +92,7 @@ void WbSingleTaskApplication::convertProto() const { // Get user parameters strings QMap userParameters; - for (QString param : cliParser.values("p")) { + for (const QString ¶m : cliParser.values("p")) { QStringList pair = param.split("="); if (pair.size() != 2) { cerr << tr("A parameter is not properly formatted!\n").toUtf8().constData(); @@ -109,7 +109,7 @@ void WbSingleTaskApplication::convertProto() const { // Combine the user parameters with the default ones QVector fields; - for (WbFieldModel *fieldModel : model->fieldModels()) { + for (const WbFieldModel *fieldModel : model->fieldModels()) { WbField *field = new WbField(fieldModel); if (userParameters.contains(field->name())) { WbTokenizer tokenizer; @@ -130,7 +130,7 @@ void WbSingleTaskApplication::convertProto() const { // Generate a node structure WbNode::setInstantiateMode(true); - WbNode *node = WbNode::createProtoInstanceFromParameters(model, fields, ""); + const WbNode *node = WbNode::createProtoInstanceFromParameters(model, fields, ""); for (WbNode *subNode : node->subNodes(true)) { if (dynamic_cast(subNode)) cout << tr("Warning: Exporting a Joint node with a SolidReference endpoint (%1) to URDF is not supported.") diff --git a/src/webots/gui/WbTcpServer.cpp b/src/webots/gui/WbTcpServer.cpp index 925aecd9675..55daca1d189 100644 --- a/src/webots/gui/WbTcpServer.cpp +++ b/src/webots/gui/WbTcpServer.cpp @@ -110,7 +110,7 @@ void WbTcpServer::start(int port) { } void WbTcpServer::sendToJavascript(const QByteArray &string) { - WbRobot *robot = dynamic_cast(sender()); + const WbRobot *robot = dynamic_cast(sender()); if (robot) { QJsonObject jsonObject; jsonObject.insert("name", robot->name()); @@ -163,7 +163,7 @@ void WbTcpServer::destroy() { if (mWebSocketServer) mWebSocketServer->close(); - foreach (QWebSocket *c, mWebSocketClients) { + foreach (const QWebSocket *c, mWebSocketClients) { disconnect(c, &QWebSocket::textMessageReceived, this, &WbTcpServer::processTextMessage); disconnect(c, &QWebSocket::disconnected, this, &WbTcpServer::socketDisconnected); }; @@ -236,7 +236,7 @@ void WbTcpServer::addNewTcpController(QTcpSocket *socket) { const QList &availableControllers = WbControlledWorld::instance()->disconnectedExternControllers(); if (robotNameIndex) { // robot name is given const QString robotName = tokens[robotNameIndex]; - foreach (WbRobot *const robot, robots) { + foreach (const WbRobot *const robot, robots) { if (robot->encodedName() == robotName && robot->isControllerExtern()) { foreach (WbController *const controller, availableControllers) { if (controller->robot() == robot) { @@ -258,7 +258,7 @@ void WbTcpServer::addNewTcpController(QTcpSocket *socket) { socket->write(reply); } else { // no robot name given int nbExternRobots = 0; - WbRobot *targetRobot = NULL; + const WbRobot *targetRobot = NULL; foreach (WbRobot *const robot, robots) { if (robot->isControllerExtern()) { targetRobot = robot; @@ -548,7 +548,7 @@ void WbTcpServer::newWorld() { if (!prepareWorld()) return; const QList &robots = WbWorld::instance()->robots(); - foreach (WbRobot *const robot, robots) + foreach (const WbRobot *const robot, robots) connectNewRobot(robot); mWorldReady = true; diff --git a/src/webots/gui/WbVideoRecorderDialog.cpp b/src/webots/gui/WbVideoRecorderDialog.cpp index 6d74ad9e551..a9290ec9211 100644 --- a/src/webots/gui/WbVideoRecorderDialog.cpp +++ b/src/webots/gui/WbVideoRecorderDialog.cpp @@ -54,7 +54,7 @@ WbVideoRecorderDialog::WbVideoRecorderDialog(QWidget *parent, const QSize &curre tryToAddResolution(WbResolution(3840, 2160, "4K UHD"), fullScreen); tryToAddResolution(WbResolution(fullScreen.width(), fullScreen.height(), ""), fullScreen); - foreach (WbResolution r, mAvailableResolutions) + foreach (const WbResolution &r, mAvailableResolutions) mResolutionList.addItem(r.toString()); // quality diff --git a/src/webots/gui/WbView3D.cpp b/src/webots/gui/WbView3D.cpp index 9102a574d69..f7ce3bb2849 100644 --- a/src/webots/gui/WbView3D.cpp +++ b/src/webots/gui/WbView3D.cpp @@ -252,7 +252,7 @@ void WbView3D::onSelectionChanged(WbAbstractPose *selectedPose) { return; WbSolid *const selectedSolid = dynamic_cast(selectedPose); - WbViewpoint *const viewpoint = mWorld->viewpoint(); + const WbViewpoint *const viewpoint = mWorld->viewpoint(); if (selectedSolid) { setCheckedShowSupportPolygonAction(selectedSolid); @@ -1087,7 +1087,7 @@ void WbView3D::setWorld(WbSimulationWorld *w) { // connect supervisor scene tree modifications to graphical updates const QList &robots = mWorld->robots(); - foreach (WbRobot *const robot, robots) { + foreach (const WbRobot *const robot, robots) { if (robot->supervisor()) connect(robot->supervisorUtilities(), &WbSupervisorUtilities::worldModified, this, &WbView3D::handleWorldModificationFromSupervisor); @@ -2196,6 +2196,7 @@ void WbView3D::keyPressEvent(QKeyEvent *event) { #endif (((event->modifiers() & Qt::ALT) == 0) ? 0 : WbRobot::mapSpecialKey(Qt::ALT)); + // cppcheck-suppress constVariablePointer WbRobot *const currentRobot = getCurrentRobot(); QList robotList; if (currentRobot) @@ -2218,6 +2219,7 @@ void WbView3D::keyReleaseEvent(QKeyEvent *event) { // pass key event to robots if (mWorld) { + // cppcheck-suppress constVariablePointer WbRobot *const currentRobot = getCurrentRobot(); QList robotList; if (currentRobot) diff --git a/src/webots/gui/WbView3D.hpp b/src/webots/gui/WbView3D.hpp index f31ae947b92..d81d292a6c8 100644 --- a/src/webots/gui/WbView3D.hpp +++ b/src/webots/gui/WbView3D.hpp @@ -55,7 +55,7 @@ class WbView3D : public WbWrenWindow { public: explicit WbView3D(); - virtual ~WbView3D(); + virtual ~WbView3D() override; void setParentWidget(QWidget *widget) { mParentWidget = widget; } diff --git a/src/webots/gui/WbW3dStreamingServer.hpp b/src/webots/gui/WbW3dStreamingServer.hpp index 05af9dbaba2..a24735b2981 100644 --- a/src/webots/gui/WbW3dStreamingServer.hpp +++ b/src/webots/gui/WbW3dStreamingServer.hpp @@ -24,7 +24,7 @@ class WbW3dStreamingServer : public WbTcpServer { public: WbW3dStreamingServer(); - ~WbW3dStreamingServer(); + ~WbW3dStreamingServer() override; private slots: void propagateNodeAddition(WbNode *node) override; diff --git a/src/webots/gui/WbWheelEvent.hpp b/src/webots/gui/WbWheelEvent.hpp index 11f3ee629c7..e4d987a4b03 100644 --- a/src/webots/gui/WbWheelEvent.hpp +++ b/src/webots/gui/WbWheelEvent.hpp @@ -39,7 +39,7 @@ class WbWheelEvent { class WbWheelLiftSolidEvent : public WbWheelEvent { public: WbWheelLiftSolidEvent(WbViewpoint *viewpoint, WbSolid *selectedSolid); - virtual ~WbWheelLiftSolidEvent(); + virtual ~WbWheelLiftSolidEvent() override; void apply(int delta) override; private: diff --git a/src/webots/maths/WbMathsUtilities.hpp b/src/webots/maths/WbMathsUtilities.hpp index 77d15bc471f..e587dece93b 100644 --- a/src/webots/maths/WbMathsUtilities.hpp +++ b/src/webots/maths/WbMathsUtilities.hpp @@ -36,7 +36,7 @@ namespace WbMathsUtilities { return ((int)(value / resolution + 0.5)) * resolution; } inline double discretize(float value, float resolution) { - return ((int)(value / resolution + 0.5f)) * resolution; + return ((int)(value / resolution + 0.5f)) * ((double)resolution); } // performs two Graham scan and returns the indices of points in the convex hull diff --git a/src/webots/nodes/WbAbstractAppearance.cpp b/src/webots/nodes/WbAbstractAppearance.cpp index ebaf4a753b0..1206c38d7da 100644 --- a/src/webots/nodes/WbAbstractAppearance.cpp +++ b/src/webots/nodes/WbAbstractAppearance.cpp @@ -107,7 +107,7 @@ WbTextureTransform *WbAbstractAppearance::textureTransform() const { } WbVector2 WbAbstractAppearance::transformUVCoordinate(const WbVector2 &uv) const { - WbTextureTransform *tt = textureTransform(); + const WbTextureTransform *tt = textureTransform(); if (tt) return tt->transformUVCoordinate(uv); return uv; diff --git a/src/webots/nodes/WbAbstractAppearance.hpp b/src/webots/nodes/WbAbstractAppearance.hpp index c72dec1203d..d5060b971b8 100644 --- a/src/webots/nodes/WbAbstractAppearance.hpp +++ b/src/webots/nodes/WbAbstractAppearance.hpp @@ -29,7 +29,7 @@ class WbAbstractAppearance : public WbBaseNode { Q_OBJECT public: - virtual ~WbAbstractAppearance(); + virtual ~WbAbstractAppearance() override; void preFinalize() override; void postFinalize() override; diff --git a/src/webots/nodes/WbAbstractCamera.cpp b/src/webots/nodes/WbAbstractCamera.cpp index 2c5e2473a08..b5cdbfaa6ad 100644 --- a/src/webots/nodes/WbAbstractCamera.cpp +++ b/src/webots/nodes/WbAbstractCamera.cpp @@ -445,7 +445,7 @@ void WbAbstractCamera::setNodesVisibility(QList nodes, bool } void WbAbstractCamera::removeInvisibleNodeFromList(QObject *node) { - WbBaseNode *const baseNode = static_cast(node); + const WbBaseNode *const baseNode = static_cast(node); mInvisibleNodes.removeAll(baseNode); } @@ -529,7 +529,7 @@ void WbAbstractCamera::updateBackground() { if (!mWrenCamera) return; - WbBackground *background = WbBackground::firstInstance(); + const WbBackground *background = WbBackground::firstInstance(); if (background) mWrenCamera->setBackgroundColor(background->skyColor()); else diff --git a/src/webots/nodes/WbAbstractCamera.hpp b/src/webots/nodes/WbAbstractCamera.hpp index a7425600cc9..872a32b7bcd 100644 --- a/src/webots/nodes/WbAbstractCamera.hpp +++ b/src/webots/nodes/WbAbstractCamera.hpp @@ -44,7 +44,7 @@ class WbAbstractCamera : public WbRenderingDevice { WbAbstractCamera(const QString &modelName, WbTokenizer *tokenizer = NULL); WbAbstractCamera(const WbAbstractCamera &other); WbAbstractCamera(const WbNode &other); - virtual ~WbAbstractCamera(); + virtual ~WbAbstractCamera() override; // reimplemented public functions void createWrenObjects() override; diff --git a/src/webots/nodes/WbAccelerometer.hpp b/src/webots/nodes/WbAccelerometer.hpp index 5091ce4cd26..1662d812d4f 100644 --- a/src/webots/nodes/WbAccelerometer.hpp +++ b/src/webots/nodes/WbAccelerometer.hpp @@ -28,7 +28,7 @@ class WbAccelerometer : public WbSolidDevice { explicit WbAccelerometer(WbTokenizer *tokenizer = NULL); WbAccelerometer(const WbAccelerometer &other); explicit WbAccelerometer(const WbNode &other); - virtual ~WbAccelerometer(); + virtual ~WbAccelerometer() override; // reimplemented public functions int nodeType() const override { return WB_NODE_ACCELEROMETER; } diff --git a/src/webots/nodes/WbAltimeter.hpp b/src/webots/nodes/WbAltimeter.hpp index 37741764923..45cb632b5d8 100644 --- a/src/webots/nodes/WbAltimeter.hpp +++ b/src/webots/nodes/WbAltimeter.hpp @@ -30,7 +30,7 @@ class WbAltimeter : public WbSolidDevice { explicit WbAltimeter(WbTokenizer *tokenizer = NULL); WbAltimeter(const WbAltimeter &other); explicit WbAltimeter(const WbNode &other); - virtual ~WbAltimeter(); + virtual ~WbAltimeter() override; // reimplemented public functions int nodeType() const override { return WB_NODE_ALTIMETER; } diff --git a/src/webots/nodes/WbAnchorParameter.cpp b/src/webots/nodes/WbAnchorParameter.cpp index fe522d27c8e..d6d7ab01bd4 100644 --- a/src/webots/nodes/WbAnchorParameter.cpp +++ b/src/webots/nodes/WbAnchorParameter.cpp @@ -35,10 +35,6 @@ WbAnchorParameter::WbAnchorParameter(const WbNode &other) : WbBaseNode(other) { WbAnchorParameter::~WbAnchorParameter() { } -void WbAnchorParameter::preFinalize() { - WbBaseNode::preFinalize(); -} - void WbAnchorParameter::postFinalize() { WbBaseNode::postFinalize(); connect(mAnchor, &WbSFVector3::changed, this, &WbAnchorParameter::anchorChanged); diff --git a/src/webots/nodes/WbAnchorParameter.hpp b/src/webots/nodes/WbAnchorParameter.hpp index 7f521efa242..547f6785af2 100644 --- a/src/webots/nodes/WbAnchorParameter.hpp +++ b/src/webots/nodes/WbAnchorParameter.hpp @@ -22,10 +22,9 @@ class WbAnchorParameter : public WbBaseNode { Q_OBJECT public: - virtual ~WbAnchorParameter(); + virtual ~WbAnchorParameter() override; const WbVector3 &anchor() const { return mAnchor->value(); } - void preFinalize() override; void postFinalize() override; signals: diff --git a/src/webots/nodes/WbAppearance.hpp b/src/webots/nodes/WbAppearance.hpp index fdd73269afb..33ed0ee870f 100644 --- a/src/webots/nodes/WbAppearance.hpp +++ b/src/webots/nodes/WbAppearance.hpp @@ -32,7 +32,7 @@ class WbAppearance : public WbAbstractAppearance { explicit WbAppearance(WbTokenizer *tokenizer = NULL); WbAppearance(const WbAppearance &other); explicit WbAppearance(const WbNode &other); - virtual ~WbAppearance(); + virtual ~WbAppearance() override; // reimplemented public functions int nodeType() const override { return WB_NODE_APPEARANCE; } diff --git a/src/webots/nodes/WbBackground.hpp b/src/webots/nodes/WbBackground.hpp index 9a4abef4405..938baf43625 100644 --- a/src/webots/nodes/WbBackground.hpp +++ b/src/webots/nodes/WbBackground.hpp @@ -38,7 +38,7 @@ class WbBackground : public WbBaseNode { explicit WbBackground(WbTokenizer *tokenizer = NULL); WbBackground(const WbBackground &other); explicit WbBackground(const WbNode &other); - virtual ~WbBackground(); + virtual ~WbBackground() override; // reimplemented public functions int nodeType() const override { return WB_NODE_BACKGROUND; } diff --git a/src/webots/nodes/WbBallJoint.cpp b/src/webots/nodes/WbBallJoint.cpp index b5a7cc44919..c7f9aa92279 100644 --- a/src/webots/nodes/WbBallJoint.cpp +++ b/src/webots/nodes/WbBallJoint.cpp @@ -141,7 +141,7 @@ QVector WbBallJoint::devices() const { WbVector3 WbBallJoint::anchor() const { static const WbVector3 ZERO(0.0, 0.0, 0.0); - WbBallJointParameters *const p = ballJointParameters(); + const WbBallJointParameters *const p = ballJointParameters(); return p ? p->anchor() : ZERO; } diff --git a/src/webots/nodes/WbBallJoint.hpp b/src/webots/nodes/WbBallJoint.hpp index 50dd48ae485..7f1a6bb0ab3 100644 --- a/src/webots/nodes/WbBallJoint.hpp +++ b/src/webots/nodes/WbBallJoint.hpp @@ -27,7 +27,7 @@ class WbBallJoint : public WbHinge2Joint { Q_OBJECT public: - virtual ~WbBallJoint(); + virtual ~WbBallJoint() override; explicit WbBallJoint(WbTokenizer *tokenizer = NULL); WbBallJoint(const WbBallJoint &other); explicit WbBallJoint(const WbNode &other); diff --git a/src/webots/nodes/WbBallJointParameters.cpp b/src/webots/nodes/WbBallJointParameters.cpp index 135adfc42d5..bea7b8715be 100644 --- a/src/webots/nodes/WbBallJointParameters.cpp +++ b/src/webots/nodes/WbBallJointParameters.cpp @@ -33,10 +33,6 @@ WbBallJointParameters::WbBallJointParameters(const WbNode &other) : WbJointParam WbBallJointParameters::~WbBallJointParameters() { } -void WbBallJointParameters::preFinalize() { - WbJointParameters::preFinalize(); -} - void WbBallJointParameters::postFinalize() { WbJointParameters::postFinalize(); diff --git a/src/webots/nodes/WbBallJointParameters.hpp b/src/webots/nodes/WbBallJointParameters.hpp index 9baf21262a2..b3c43b4a732 100644 --- a/src/webots/nodes/WbBallJointParameters.hpp +++ b/src/webots/nodes/WbBallJointParameters.hpp @@ -28,14 +28,13 @@ class WbBallJointParameters : public WbJointParameters { Q_OBJECT public: - virtual ~WbBallJointParameters(); + virtual ~WbBallJointParameters() override; WbBallJointParameters(const QString &modelName, WbTokenizer *tokenizer); explicit WbBallJointParameters(WbTokenizer *tokenizer = NULL); WbBallJointParameters(const WbBallJointParameters &other); explicit WbBallJointParameters(const WbNode &other); int nodeType() const override { return WB_NODE_BALL_JOINT_PARAMETERS; } - void preFinalize() override; void postFinalize() override; virtual const WbVector3 &anchor() const { return mAnchor->value(); } diff --git a/src/webots/nodes/WbBaseNode.hpp b/src/webots/nodes/WbBaseNode.hpp index 01420f74be0..b83775b5a6a 100644 --- a/src/webots/nodes/WbBaseNode.hpp +++ b/src/webots/nodes/WbBaseNode.hpp @@ -41,7 +41,7 @@ class WbBaseNode : public WbNode { public: // destructor - virtual ~WbBaseNode(); + virtual ~WbBaseNode() override; virtual void downloadAssets() {} // finalize() assumes that the whole world node/field structure is complete diff --git a/src/webots/nodes/WbBasicJoint.cpp b/src/webots/nodes/WbBasicJoint.cpp index 510adc243e3..93d914a8fcd 100644 --- a/src/webots/nodes/WbBasicJoint.cpp +++ b/src/webots/nodes/WbBasicJoint.cpp @@ -256,7 +256,7 @@ void WbBasicJoint::updateEndPointPosition() { if (mIsEndPointPositionChangedByJoint) return; - WbSolid *const s = solidEndPoint(); + const WbSolid *const s = solidEndPoint(); if (s) updateEndPointZeroTranslationAndRotation(); @@ -292,15 +292,15 @@ void WbBasicJoint::setSolidEndPoint(WbSlot *slot) { } WbSolid *WbBasicJoint::solidEndPoint() const { - WbSlot *slot = dynamic_cast(mEndPoint->value()); + const WbSlot *slot = dynamic_cast(mEndPoint->value()); if (slot) { - WbSlot *childrenSlot = slot->slotEndPoint(); + const WbSlot *childrenSlot = slot->slotEndPoint(); if (childrenSlot) { WbSolid *solid = childrenSlot->solidEndPoint(); if (solid) return solid; - WbSolidReference *s = childrenSlot->solidReferenceEndPoint(); + const WbSolidReference *s = childrenSlot->solidReferenceEndPoint(); if (s) return s->solid(); } @@ -318,9 +318,9 @@ WbSolid *WbBasicJoint::solidEndPoint() const { } WbSolidReference *WbBasicJoint::solidReference() const { - WbSlot *slot = dynamic_cast(mEndPoint->value()); + const WbSlot *slot = dynamic_cast(mEndPoint->value()); if (slot) { - WbSlot *childrenSlot = slot->slotEndPoint(); + const WbSlot *childrenSlot = slot->slotEndPoint(); if (childrenSlot) return childrenSlot->solidReferenceEndPoint(); else @@ -472,7 +472,7 @@ void WbBasicJoint::write(WbWriter &writer) const { else { const WbSlot *slot = dynamic_cast(mEndPoint->value()); if (slot) { - WbSlot *childrenSlot = slot->slotEndPoint(); + const WbSlot *childrenSlot = slot->slotEndPoint(); if (childrenSlot) { const WbSolid *solidInSlot = childrenSlot->solidEndPoint(); if (solidInSlot) diff --git a/src/webots/nodes/WbBasicJoint.hpp b/src/webots/nodes/WbBasicJoint.hpp index 1b87cd5a676..185ea32f071 100644 --- a/src/webots/nodes/WbBasicJoint.hpp +++ b/src/webots/nodes/WbBasicJoint.hpp @@ -36,7 +36,7 @@ class WbBasicJoint : public WbBaseNode { Q_OBJECT public: - virtual ~WbBasicJoint(); + virtual ~WbBasicJoint() override; void downloadAssets() override; void preFinalize() override; diff --git a/src/webots/nodes/WbBillboard.cpp b/src/webots/nodes/WbBillboard.cpp index dfe46617644..7c90b4d0fcb 100644 --- a/src/webots/nodes/WbBillboard.cpp +++ b/src/webots/nodes/WbBillboard.cpp @@ -69,7 +69,7 @@ void WbBillboard::applyTranslationToWren() { void WbBillboard::applyRotationToWren() { const WbViewpoint *viewpoint = WbWorld::instance()->viewpoint(); - WbSFRotation *orientation = viewpoint->orientation(); + const WbSFRotation *orientation = viewpoint->orientation(); float rotation[4]; orientation->value().toFloatArray(rotation); wr_transform_set_orientation(wrenNode(), rotation); diff --git a/src/webots/nodes/WbBillboard.hpp b/src/webots/nodes/WbBillboard.hpp index 4b4b52fc535..dca86bb8ce3 100644 --- a/src/webots/nodes/WbBillboard.hpp +++ b/src/webots/nodes/WbBillboard.hpp @@ -25,7 +25,7 @@ class WbBillboard : public WbGroup { explicit WbBillboard(WbTokenizer *tokenizer = NULL); WbBillboard(const WbBillboard &other); explicit WbBillboard(const WbNode &other); - virtual ~WbBillboard(); + virtual ~WbBillboard() override; // reimplemented functions int nodeType() const override { return WB_NODE_BILLBOARD; } diff --git a/src/webots/nodes/WbBox.cpp b/src/webots/nodes/WbBox.cpp index db2f0d483e4..d60cfe2848c 100644 --- a/src/webots/nodes/WbBox.cpp +++ b/src/webots/nodes/WbBox.cpp @@ -350,8 +350,7 @@ WbVector2 WbBox::computeTextureCoordinate(const WbVector3 &minBound, const WbVec bool WbBox::pickUVCoordinate(WbVector2 &uv, const WbRay &ray, int textureCoordSet) const { WbVector3 localCollisionPoint; - int faceIndex; - double collisionDistance = computeLocalCollisionPoint(localCollisionPoint, faceIndex, ray); + double collisionDistance = computeLocalCollisionPoint(localCollisionPoint, ray); if (collisionDistance < 0) // no valid collision return false; @@ -364,11 +363,10 @@ bool WbBox::pickUVCoordinate(WbVector2 &uv, const WbRay &ray, int textureCoordSe double WbBox::computeDistance(const WbRay &ray) const { WbVector3 collisionPoint; - int faceIndex; - return computeLocalCollisionPoint(collisionPoint, faceIndex, ray); + return computeLocalCollisionPoint(collisionPoint, ray); } -double WbBox::computeLocalCollisionPoint(WbVector3 &point, int &faceIndex, const WbRay &ray) const { +double WbBox::computeLocalCollisionPoint(WbVector3 &point, const WbRay &ray) const { WbRay localRay(ray); const WbPose *const pose = upperPose(); if (pose) { diff --git a/src/webots/nodes/WbBox.hpp b/src/webots/nodes/WbBox.hpp index cf8806b4ffa..831f2f341c9 100644 --- a/src/webots/nodes/WbBox.hpp +++ b/src/webots/nodes/WbBox.hpp @@ -27,7 +27,7 @@ class WbBox : public WbGeometry { explicit WbBox(WbTokenizer *tokenizer = NULL); WbBox(const WbBox &other); explicit WbBox(const WbNode &other); - virtual ~WbBox(); + virtual ~WbBox() override; // reimplemented public functions int nodeType() const override { return WB_NODE_BOX; } @@ -92,7 +92,7 @@ class WbBox : public WbGeometry { // ray tracing // compute collision point and return distance - double computeLocalCollisionPoint(WbVector3 &point, int &faceIndex, const WbRay &ray) const; + double computeLocalCollisionPoint(WbVector3 &point, const WbRay &ray) const; private slots: void updateSize(); diff --git a/src/webots/nodes/WbBrake.cpp b/src/webots/nodes/WbBrake.cpp index 111d80f5894..13718a687be 100644 --- a/src/webots/nodes/WbBrake.cpp +++ b/src/webots/nodes/WbBrake.cpp @@ -66,7 +66,7 @@ void WbBrake::handleMessage(QDataStream &stream) { stream >> deviceType; assert(mRequestedDeviceTag == NULL); mRequestedDeviceTag = new WbDeviceTag[1]; - WbLogicalDevice *device = getSiblingDeviceByType(deviceType); + const WbLogicalDevice *device = getSiblingDeviceByType(deviceType); if (!device && deviceType == WB_NODE_ROTATIONAL_MOTOR) // check both motor types device = getSiblingDeviceByType(WB_NODE_LINEAR_MOTOR); diff --git a/src/webots/nodes/WbBrake.hpp b/src/webots/nodes/WbBrake.hpp index 810155c07ed..2d3375bf048 100644 --- a/src/webots/nodes/WbBrake.hpp +++ b/src/webots/nodes/WbBrake.hpp @@ -23,7 +23,7 @@ class WbBrake : public WbJointDevice { Q_OBJECT public: - virtual ~WbBrake() {} + virtual ~WbBrake() override {} explicit WbBrake(const QString &modelName, WbTokenizer *tokenizer = NULL); explicit WbBrake(WbTokenizer *tokenizer = NULL); WbBrake(const WbBrake &other); diff --git a/src/webots/nodes/WbCadShape.cpp b/src/webots/nodes/WbCadShape.cpp index 9b474c1f94f..3302d430992 100644 --- a/src/webots/nodes/WbCadShape.cpp +++ b/src/webots/nodes/WbCadShape.cpp @@ -113,7 +113,7 @@ void WbCadShape::retrieveMaterials() { mMaterialDownloaders.clear(); const QStringList rawMaterials = objMaterialList(completeUrl); - foreach (QString material, rawMaterials) { + foreach (const QString &material, rawMaterials) { const QString newUrl = WbUrl::combinePaths(material, completeUrl); if (!newUrl.isEmpty()) { mObjMaterials.insert(material, newUrl); @@ -132,7 +132,7 @@ void WbCadShape::retrieveMaterials() { void WbCadShape::materialDownloadTracker() { bool finished = true; - foreach (WbDownloader *downloader, mMaterialDownloaders) { + foreach (const WbDownloader *downloader, mMaterialDownloaders) { if (!downloader->hasFinished()) finished = false; @@ -223,7 +223,7 @@ void WbCadShape::updateUrl() { mObjMaterials.clear(); // generate mapping between referenced files and cached files const QStringList rawMaterials = objMaterialList(completeUrl); - foreach (QString material, rawMaterials) { + foreach (const QString &material, rawMaterials) { const QString adjustedUrl = WbUrl::combinePaths(material, completeUrl); assert(WbNetwork::instance()->isCachedNoMapUpdate(adjustedUrl)); if (!mObjMaterials.contains(material)) @@ -241,7 +241,7 @@ void WbCadShape::updateUrl() { bool WbCadShape::areMaterialAssetsAvailable(const QString &url) { QStringList rawMaterials = objMaterialList(url); // note: 'dae' files will generate an empty list - foreach (QString material, rawMaterials) { + foreach (const QString &material, rawMaterials) { if (!WbNetwork::instance()->isCachedWithMapUpdate(WbUrl::combinePaths(material, url))) return false; } @@ -264,7 +264,7 @@ QStringList WbCadShape::objMaterialList(const QString &url) const { content = content.replace("\r\n", "\n"); QStringList lines = content.split('\n', Qt::SkipEmptyParts); - foreach (QString line, lines) { + foreach (const QString &line, lines) { QString cleanLine = line.trimmed(); if (!cleanLine.startsWith("mtllib")) continue; @@ -386,7 +386,7 @@ void WbCadShape::createWrenObjects() { .arg(mesh->mName.C_Str())); aiMatrix4x4 transform; - aiNode *current = node; + const aiNode *current = node; while (current != NULL) { transform *= current->mTransformation; current = current->mParent; @@ -437,6 +437,7 @@ void WbCadShape::createWrenObjects() { if (currentIndexIndex == 0) // if all faces turned out to be invalid, ignore the mesh continue; + // cppcheck-suppress constVariablePointer WrStaticMesh *staticMesh = wr_static_mesh_new(vertices, currentIndexIndex, coordData, normalData, texCoordData, texCoordData, indexData, false); @@ -593,7 +594,7 @@ void WbCadShape::exportNodeFields(WbWriter &writer) const { // 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)); - for (QString material : objMaterialList(parentUrl)) { + for (const QString &material : objMaterialList(parentUrl)) { QString materialUrl = WbUrl::combinePaths(material, parentUrl); WbMFString *urlFieldValue = dynamic_cast(urlFieldCopy.value()); if (WbUrl::isLocalUrl(materialUrl)) diff --git a/src/webots/nodes/WbCadShape.hpp b/src/webots/nodes/WbCadShape.hpp index 26d6fd878a9..98bc5a13abe 100644 --- a/src/webots/nodes/WbCadShape.hpp +++ b/src/webots/nodes/WbCadShape.hpp @@ -41,7 +41,7 @@ class WbCadShape : public WbBaseNode { explicit WbCadShape(WbTokenizer *tokenizer = NULL); WbCadShape(const WbCadShape &other); explicit WbCadShape(const WbNode &other); - virtual ~WbCadShape(); + virtual ~WbCadShape() override; // reimplemented public functions int nodeType() const override { return WB_NODE_CAD_SHAPE; } diff --git a/src/webots/nodes/WbCamera.cpp b/src/webots/nodes/WbCamera.cpp index 9ecfe60562f..836ecefc607 100644 --- a/src/webots/nodes/WbCamera.cpp +++ b/src/webots/nodes/WbCamera.cpp @@ -72,17 +72,17 @@ class WbRecognizedObject : public WbObjectDetection { virtual ~WbRecognizedObject() {} int id() const { return mId; } - const QString model() const { return mModel; } - const WbRotation relativeOrientation() const { return mRelativeOrientation; } + const QString &model() const { return mModel; } + const WbRotation &relativeOrientation() const { return mRelativeOrientation; } const WbVector2 positionOnImage() const { return mPositionOnImage; } const WbVector2 pixelSize() const { return mPixelSize; } - const QList colors() const { return mColors; } + const QList &colors() const { return mColors; } void setModel(const QString &model) { mModel = model; } void setRelativeOrientation(const WbRotation &relativeOrientation) { mRelativeOrientation = relativeOrientation; } void setPositionOnImage(const WbVector2 &positionOnImage) { mPositionOnImage = positionOnImage; } void setPixelSize(const WbVector2 &pixelSize) { mPixelSize = pixelSize; } - void addColor(WbRgb colors) { mColors.append(colors); } + void addColor(const WbRgb &colors) { mColors.append(colors); } void clearColors() { mColors.clear(); } protected: @@ -771,10 +771,7 @@ WbVector2 WbCamera::projectOnImage(const WbVector3 &position) { const double fovY = WbWrenCamera::computeFieldOfViewY(fovX, (double)width() / (double)height()); const double theta1 = -atan2(position.y(), fabs(position.x())); const double theta2 = atan2(position.z(), fabs(position.x())); - if (mProjection->value() == "planar") - uv.setX(0.5 * tan(theta1) / tan(0.5 * fovX)); - else - uv.setX(theta1 * fovX); + uv.setX(0.5 * tan(theta1) / tan(0.5 * fovX)); uv.setY(-0.5 * tan(theta2) / tan(0.5 * fovY)); } } else if (mProjection->value() == "spherical") { diff --git a/src/webots/nodes/WbCamera.hpp b/src/webots/nodes/WbCamera.hpp index 71b40c69da5..c3ff86f804a 100644 --- a/src/webots/nodes/WbCamera.hpp +++ b/src/webots/nodes/WbCamera.hpp @@ -36,7 +36,7 @@ class WbCamera : public WbAbstractCamera { explicit WbCamera(WbTokenizer *tokenizer = NULL); WbCamera(const WbCamera &other); explicit WbCamera(const WbNode &other); - virtual ~WbCamera(); + virtual ~WbCamera() override; // reimplemented public functions void downloadAssets() override; diff --git a/src/webots/nodes/WbCapsule.hpp b/src/webots/nodes/WbCapsule.hpp index 6b06d14c10b..2328b158a66 100644 --- a/src/webots/nodes/WbCapsule.hpp +++ b/src/webots/nodes/WbCapsule.hpp @@ -26,7 +26,7 @@ class WbCapsule : public WbGeometry { explicit WbCapsule(WbTokenizer *tokenizer = NULL); WbCapsule(const WbCapsule &other); explicit WbCapsule(const WbNode &other); - virtual ~WbCapsule(); + virtual ~WbCapsule() override; // reimplemented public functions int nodeType() const override { return WB_NODE_CAPSULE; } diff --git a/src/webots/nodes/WbCharger.hpp b/src/webots/nodes/WbCharger.hpp index a43d082a7e2..83c402623db 100644 --- a/src/webots/nodes/WbCharger.hpp +++ b/src/webots/nodes/WbCharger.hpp @@ -35,7 +35,7 @@ class WbCharger : public WbSolid { explicit WbCharger(WbTokenizer *tokenizer = NULL); WbCharger(const WbCharger &other); explicit WbCharger(const WbNode &other); - virtual ~WbCharger(); + virtual ~WbCharger() override; // reimplemented public functions int nodeType() const override { return WB_NODE_CHARGER; } diff --git a/src/webots/nodes/WbColor.hpp b/src/webots/nodes/WbColor.hpp index 086c86650d1..a2640eceb0e 100644 --- a/src/webots/nodes/WbColor.hpp +++ b/src/webots/nodes/WbColor.hpp @@ -25,7 +25,7 @@ class WbColor : public WbBaseNode { explicit WbColor(WbTokenizer *tokenizer = NULL); WbColor(const WbColor &other); explicit WbColor(const WbNode &other); - virtual ~WbColor(); + virtual ~WbColor() override; // reimplemented public functions int nodeType() const override { return WB_NODE_COLOR; } diff --git a/src/webots/nodes/WbCompass.hpp b/src/webots/nodes/WbCompass.hpp index e3a899d932e..46a6b529ce0 100755 --- a/src/webots/nodes/WbCompass.hpp +++ b/src/webots/nodes/WbCompass.hpp @@ -28,7 +28,7 @@ class WbCompass : public WbSolidDevice { explicit WbCompass(WbTokenizer *tokenizer = NULL); explicit WbCompass(const WbCompass &other); explicit WbCompass(const WbNode &other); - virtual ~WbCompass(); + virtual ~WbCompass() override; // reimplemented public functions int nodeType() const override { return WB_NODE_COMPASS; } diff --git a/src/webots/nodes/WbCone.cpp b/src/webots/nodes/WbCone.cpp index d3fcb276fb1..1176dd828bc 100644 --- a/src/webots/nodes/WbCone.cpp +++ b/src/webots/nodes/WbCone.cpp @@ -353,9 +353,9 @@ double WbCone::computeLocalCollisionPoint(WbVector3 &point, const WbRay &ray) co const double t2 = (-b + discriminant) / (2 * a); const double z1 = origin.z() + t1 * direction.z(); const double z2 = origin.z() + t2 * direction.z(); - if (mSide->value() && t1 > 0.0 && z1 >= -halfH && z1 <= halfH) + if (t1 > 0.0 && z1 >= -halfH && z1 <= halfH) d = t1; - else if (mSide->value() && t2 > 0.0 && z2 >= -halfH && z2 <= halfH) + else if (t2 > 0.0 && z2 >= -halfH && z2 <= halfH) d = t2; } } diff --git a/src/webots/nodes/WbCone.hpp b/src/webots/nodes/WbCone.hpp index f089f111657..975971368e0 100644 --- a/src/webots/nodes/WbCone.hpp +++ b/src/webots/nodes/WbCone.hpp @@ -27,7 +27,7 @@ class WbCone : public WbGeometry { explicit WbCone(WbTokenizer *tokenizer = NULL); WbCone(const WbCone &other); explicit WbCone(const WbNode &other); - virtual ~WbCone(); + virtual ~WbCone() override; // reimplemented public functions int nodeType() const override { return WB_NODE_CONE; } diff --git a/src/webots/nodes/WbConnector.hpp b/src/webots/nodes/WbConnector.hpp index e98eaf2e511..31aaf996858 100644 --- a/src/webots/nodes/WbConnector.hpp +++ b/src/webots/nodes/WbConnector.hpp @@ -34,7 +34,7 @@ class WbConnector : public WbSolidDevice { explicit WbConnector(WbTokenizer *tokenizer = NULL); WbConnector(const WbConnector &other); explicit WbConnector(const WbNode &other); - virtual ~WbConnector(); + virtual ~WbConnector() override; // reimplemented public functions int nodeType() const override { return WB_NODE_CONNECTOR; } diff --git a/src/webots/nodes/WbContactProperties.hpp b/src/webots/nodes/WbContactProperties.hpp index 6ead235dfbe..8fe30c13046 100644 --- a/src/webots/nodes/WbContactProperties.hpp +++ b/src/webots/nodes/WbContactProperties.hpp @@ -34,7 +34,7 @@ class WbContactProperties : public WbBaseNode { explicit WbContactProperties(WbTokenizer *tokenizer = NULL); WbContactProperties(const WbContactProperties &other); explicit WbContactProperties(const WbNode &other); - virtual ~WbContactProperties(); + virtual ~WbContactProperties() override; // reimplemented public functions int nodeType() const override { return WB_NODE_CONTACT_PROPERTIES; } diff --git a/src/webots/nodes/WbCoordinate.hpp b/src/webots/nodes/WbCoordinate.hpp index 5ce02136c8d..88efa4e3e82 100644 --- a/src/webots/nodes/WbCoordinate.hpp +++ b/src/webots/nodes/WbCoordinate.hpp @@ -28,7 +28,7 @@ class WbCoordinate : public WbBaseNode { explicit WbCoordinate(WbTokenizer *tokenizer = NULL); WbCoordinate(const WbCoordinate &other); explicit WbCoordinate(const WbNode &other); - virtual ~WbCoordinate(); + virtual ~WbCoordinate() override; // reimplemented public functions int nodeType() const override { return WB_NODE_COORDINATE; } diff --git a/src/webots/nodes/WbCylinder.cpp b/src/webots/nodes/WbCylinder.cpp index cbe371dac6b..1d6de429b8d 100644 --- a/src/webots/nodes/WbCylinder.cpp +++ b/src/webots/nodes/WbCylinder.cpp @@ -388,6 +388,7 @@ bool WbCylinder::pickUVCoordinate(WbVector2 &uv, const WbRay &ray, int textureCo if (collisionDistance < 0) return false; + // cppcheck-suppress variableScope double h = scaledHeight(); double r = scaledRadius(); diff --git a/src/webots/nodes/WbCylinder.hpp b/src/webots/nodes/WbCylinder.hpp index 09d8da21bd4..ae78236877d 100644 --- a/src/webots/nodes/WbCylinder.hpp +++ b/src/webots/nodes/WbCylinder.hpp @@ -28,7 +28,7 @@ class WbCylinder : public WbGeometry { explicit WbCylinder(WbTokenizer *tokenizer = NULL); WbCylinder(const WbCylinder &other); explicit WbCylinder(const WbNode &other); - virtual ~WbCylinder(); + virtual ~WbCylinder() override; // reimplemented public functions int nodeType() const override { return WB_NODE_CYLINDER; } diff --git a/src/webots/nodes/WbDamping.hpp b/src/webots/nodes/WbDamping.hpp index 307f4a32f47..f36cc1c96f0 100644 --- a/src/webots/nodes/WbDamping.hpp +++ b/src/webots/nodes/WbDamping.hpp @@ -26,7 +26,7 @@ class WbDamping : public WbBaseNode { explicit WbDamping(WbTokenizer *tokenizer = NULL); WbDamping(const WbDamping &other); explicit WbDamping(const WbNode &other); - virtual ~WbDamping(); + virtual ~WbDamping() override; // reimplemented public functions int nodeType() const override { return WB_NODE_DAMPING; } diff --git a/src/webots/nodes/WbDirectionalLight.hpp b/src/webots/nodes/WbDirectionalLight.hpp index 18f688f19dd..271da667cd3 100644 --- a/src/webots/nodes/WbDirectionalLight.hpp +++ b/src/webots/nodes/WbDirectionalLight.hpp @@ -29,7 +29,7 @@ class WbDirectionalLight : public WbLight { explicit WbDirectionalLight(WbTokenizer *tokenizer = NULL); WbDirectionalLight(const WbDirectionalLight &other); explicit WbDirectionalLight(const WbNode &other); - virtual ~WbDirectionalLight(); + virtual ~WbDirectionalLight() override; // reimplemented public functions int nodeType() const override { return WB_NODE_DIRECTIONAL_LIGHT; } diff --git a/src/webots/nodes/WbDisplay.cpp b/src/webots/nodes/WbDisplay.cpp index 66702e6746f..398bf400cb8 100644 --- a/src/webots/nodes/WbDisplay.cpp +++ b/src/webots/nodes/WbDisplay.cpp @@ -167,15 +167,17 @@ void WbDisplay::findImageTextures() { return; WbNode *firstChild = children().item(0); - WbShape *shape = dynamic_cast(firstChild); + const WbShape *shape = dynamic_cast(firstChild); if (shape) { - WbAppearance *appearance = shape->appearance(); - WbPbrAppearance *pbrAppearance = shape->pbrAppearance(); + const WbAppearance *appearance = shape->appearance(); + const WbPbrAppearance *pbrAppearance = shape->pbrAppearance(); if (appearance) { + // cppcheck-suppress constVariablePointer WbImageTexture *theTexture = appearance->texture(); if (theTexture) mImageTextures.push_back(theTexture); } else if (pbrAppearance) { + // cppcheck-suppress constVariablePointer WbImageTexture *theTexture = pbrAppearance->baseColorMap(); if (theTexture) mImageTextures.push_back(theTexture); @@ -210,15 +212,17 @@ void WbDisplay::findImageTextures(WbGroup *group) { WbMFNode::Iterator i(group->children()); while (i.hasNext()) { WbNode *node = i.next(); - WbShape *shape = dynamic_cast(node); + const WbShape *shape = dynamic_cast(node); if (shape) { - WbAppearance *appearance = shape->appearance(); - WbPbrAppearance *pbrAppearance = shape->pbrAppearance(); + const WbAppearance *appearance = shape->appearance(); + const WbPbrAppearance *pbrAppearance = shape->pbrAppearance(); if (appearance) { + // cppcheck-suppress constVariablePointer WbImageTexture *theTexture = appearance->texture(); if (theTexture) mImageTextures.push_back(theTexture); } else if (pbrAppearance) { + // cppcheck-suppress constVariablePointer WbImageTexture *theTexture = pbrAppearance->baseColorMap(); if (theTexture) mImageTextures.push_back(theTexture); @@ -404,7 +408,7 @@ void WbDisplay::writeAnswer(WbDataStream &stream) { stream.writeRawData(reinterpret_cast(mImage), 4 * width() * height()); for (unsigned i = 0; i < number; i++) { - WbDisplayImage *di = mImages.at(i); + const WbDisplayImage *di = mImages.at(i); stream << (qint32)di->id(); stream << (quint16)di->width(); stream << (quint16)di->height(); @@ -536,6 +540,7 @@ void WbDisplay::drawRectangle(int x, int y, int w, int h, bool fill) { int displayWidth = width(); int displayHeight = height(); #ifndef NDEBUG + // cppcheck-suppress variableScope int size = displayWidth * displayHeight; #endif if (fill) { @@ -664,8 +669,8 @@ void WbDisplay::drawOval(int cx, int cy, int a, int b, bool fill) { my1 = cy; mx2 = cx + a; my2 = cy; - aq = a * a; - bq = b * b; + aq = (qint64)a * a; + bq = (qint64)b * b; dx = aq << 1; dy = bq << 1; r = a * bq; @@ -934,7 +939,7 @@ unsigned int *WbDisplay::imageCopy(short int x, short int y, short int &w, short void WbDisplay::imagePaste(int id, int x, int y, bool blend) { if (x >= width() || y >= height()) return; - WbDisplayImage *subImage = NULL; + const WbDisplayImage *subImage = NULL; for (int i = 0; i < mImages.size(); i++) if (mImages.at(i)->id() == id) { subImage = mImages.at(i); diff --git a/src/webots/nodes/WbDisplay.hpp b/src/webots/nodes/WbDisplay.hpp index 558abe8b88f..093cfc8412e 100644 --- a/src/webots/nodes/WbDisplay.hpp +++ b/src/webots/nodes/WbDisplay.hpp @@ -31,7 +31,7 @@ class WbDisplay : public WbRenderingDevice { explicit WbDisplay(WbTokenizer *tokenizer = NULL); WbDisplay(const WbDisplay &other); explicit WbDisplay(const WbNode &other); - virtual ~WbDisplay(); + virtual ~WbDisplay() override; // reimplemented public functions int nodeType() const override { return WB_NODE_DISPLAY; } diff --git a/src/webots/nodes/WbDistanceSensor.hpp b/src/webots/nodes/WbDistanceSensor.hpp index bb36f3e666b..bddd2b9b892 100644 --- a/src/webots/nodes/WbDistanceSensor.hpp +++ b/src/webots/nodes/WbDistanceSensor.hpp @@ -42,7 +42,7 @@ class WbDistanceSensor : public WbSolidDevice { explicit WbDistanceSensor(WbTokenizer *tokenizer = NULL); WbDistanceSensor(const WbDistanceSensor &other); explicit WbDistanceSensor(const WbNode &other); - virtual ~WbDistanceSensor(); + virtual ~WbDistanceSensor() override; // reimplemented public functions int nodeType() const override { return WB_NODE_DISTANCE_SENSOR; } diff --git a/src/webots/nodes/WbElevationGrid.hpp b/src/webots/nodes/WbElevationGrid.hpp index 33844a06744..e5294602af9 100644 --- a/src/webots/nodes/WbElevationGrid.hpp +++ b/src/webots/nodes/WbElevationGrid.hpp @@ -33,7 +33,7 @@ class WbElevationGrid : public WbGeometry { explicit WbElevationGrid(WbTokenizer *tokenizer = NULL); WbElevationGrid(const WbElevationGrid &other); explicit WbElevationGrid(const WbNode &other); - virtual ~WbElevationGrid(); + virtual ~WbElevationGrid() override; // field accessors // getters diff --git a/src/webots/nodes/WbEmitter.hpp b/src/webots/nodes/WbEmitter.hpp index 1d4fa08b3ac..044f536779c 100644 --- a/src/webots/nodes/WbEmitter.hpp +++ b/src/webots/nodes/WbEmitter.hpp @@ -32,7 +32,7 @@ class WbEmitter : public WbSolidDevice { explicit WbEmitter(WbTokenizer *tokenizer = NULL); WbEmitter(const WbEmitter &other); explicit WbEmitter(const WbNode &other); - virtual ~WbEmitter(); + virtual ~WbEmitter() override; // reimplemented public functions int nodeType() const override { return WB_NODE_EMITTER; } diff --git a/src/webots/nodes/WbFluid.hpp b/src/webots/nodes/WbFluid.hpp index 1db738bf4e4..ce53e33addb 100644 --- a/src/webots/nodes/WbFluid.hpp +++ b/src/webots/nodes/WbFluid.hpp @@ -25,7 +25,7 @@ class WbFluid : public WbMatter { explicit WbFluid(WbTokenizer *tokenizer = NULL); WbFluid(const WbFluid &other); explicit WbFluid(const WbNode &other); - virtual ~WbFluid() {} + virtual ~WbFluid() override {} // reimplemented public functions int nodeType() const override { return WB_NODE_FLUID; } diff --git a/src/webots/nodes/WbFocus.hpp b/src/webots/nodes/WbFocus.hpp index ab3b702b178..9b89c58a6cd 100644 --- a/src/webots/nodes/WbFocus.hpp +++ b/src/webots/nodes/WbFocus.hpp @@ -25,7 +25,7 @@ class WbFocus : public WbBaseNode { explicit WbFocus(WbTokenizer *tokenizer = NULL); WbFocus(const WbFocus &other); explicit WbFocus(const WbNode &other); - virtual ~WbFocus(); + virtual ~WbFocus() override; // reimplemented public functions int nodeType() const override { return WB_NODE_FOCUS; } diff --git a/src/webots/nodes/WbFog.hpp b/src/webots/nodes/WbFog.hpp index 067bb682ac6..2f30f14f588 100644 --- a/src/webots/nodes/WbFog.hpp +++ b/src/webots/nodes/WbFog.hpp @@ -32,7 +32,7 @@ class WbFog : public WbBaseNode { explicit WbFog(WbTokenizer *tokenizer = NULL); WbFog(const WbFog &other); explicit WbFog(const WbNode &other); - virtual ~WbFog(); + virtual ~WbFog() override; // reimplemented public functions int nodeType() const override { return WB_NODE_FOG; } diff --git a/src/webots/nodes/WbGeometry.hpp b/src/webots/nodes/WbGeometry.hpp index c4f8fa7050a..0b7af2ccaf6 100644 --- a/src/webots/nodes/WbGeometry.hpp +++ b/src/webots/nodes/WbGeometry.hpp @@ -46,7 +46,7 @@ class WbGeometry : public WbBaseNode { public: // Destructor - virtual ~WbGeometry(); + virtual ~WbGeometry() override; // Reimplemented public functions void postFinalize() override; diff --git a/src/webots/nodes/WbGps.hpp b/src/webots/nodes/WbGps.hpp index cf071cd95f5..62145324456 100644 --- a/src/webots/nodes/WbGps.hpp +++ b/src/webots/nodes/WbGps.hpp @@ -30,7 +30,7 @@ class WbGps : public WbSolidDevice { explicit WbGps(WbTokenizer *tokenizer = NULL); WbGps(const WbGps &other); explicit WbGps(const WbNode &other); - virtual ~WbGps(); + virtual ~WbGps() override; // reimplemented public functions int nodeType() const override { return WB_NODE_GPS; } diff --git a/src/webots/nodes/WbGroup.cpp b/src/webots/nodes/WbGroup.cpp index eaa4bc61e3b..b00eaf547da 100644 --- a/src/webots/nodes/WbGroup.cpp +++ b/src/webots/nodes/WbGroup.cpp @@ -167,6 +167,7 @@ void WbGroup::deleteAllSolids() { QList solids; while (it.hasNext()) { WbNode *const n = it.next(); + // cppcheck-suppress constVariablePointer WbSolid *s = dynamic_cast(n); if (s) solids << s; @@ -403,7 +404,7 @@ bool WbGroup::resetHiddenKinematicParameters() { void WbGroup::collectHiddenKinematicParameters(HiddenKinematicParametersMap &map, int &counter) const { WbMFNode::Iterator it(*mChildren); while (it.hasNext()) { - WbGroup *const g = dynamic_cast(it.next()); + const WbGroup *const g = dynamic_cast(it.next()); if (g) g->collectHiddenKinematicParameters(map, counter); } diff --git a/src/webots/nodes/WbGroup.hpp b/src/webots/nodes/WbGroup.hpp index 2fc098da4cb..d6655d11e1a 100644 --- a/src/webots/nodes/WbGroup.hpp +++ b/src/webots/nodes/WbGroup.hpp @@ -30,7 +30,7 @@ class WbGroup : public WbBaseNode { explicit WbGroup(WbTokenizer *tokenizer = NULL); WbGroup(const WbGroup &other); explicit WbGroup(const WbNode &other); - virtual ~WbGroup(); + virtual ~WbGroup() override; // reimplemented public functions int nodeType() const override { return WB_NODE_GROUP; } diff --git a/src/webots/nodes/WbGyro.hpp b/src/webots/nodes/WbGyro.hpp index bb6ea78a5b0..af830fec86c 100644 --- a/src/webots/nodes/WbGyro.hpp +++ b/src/webots/nodes/WbGyro.hpp @@ -30,7 +30,7 @@ class WbGyro : public WbSolidDevice { explicit WbGyro(WbTokenizer *tokenizer = NULL); WbGyro(const WbGyro &other); explicit WbGyro(const WbNode &other); - virtual ~WbGyro(); + virtual ~WbGyro() override; // reimplemented public functions int nodeType() const override { return WB_NODE_GYRO; } diff --git a/src/webots/nodes/WbHinge2Joint.cpp b/src/webots/nodes/WbHinge2Joint.cpp index 85bf2c7abf6..2094cccc790 100644 --- a/src/webots/nodes/WbHinge2Joint.cpp +++ b/src/webots/nodes/WbHinge2Joint.cpp @@ -409,8 +409,8 @@ void WbHinge2Joint::prePhysicsStep(double ms) { void WbHinge2Joint::postPhysicsStep() { assert(mJoint); - WbRotationalMotor *const rm = rotationalMotor(); - WbRotationalMotor *const rm2 = rotationalMotor2(); + const WbRotationalMotor *const rm = rotationalMotor(); + const WbRotationalMotor *const rm2 = rotationalMotor2(); // First update the position roughly based on the angular rate of the joint so that it is within pi radians... mPosition -= dJointGetHinge2Angle1Rate(mJoint) * mTimeStep / 1000.0; diff --git a/src/webots/nodes/WbHinge2Joint.hpp b/src/webots/nodes/WbHinge2Joint.hpp index d88f2b7b447..74475efc12b 100644 --- a/src/webots/nodes/WbHinge2Joint.hpp +++ b/src/webots/nodes/WbHinge2Joint.hpp @@ -31,7 +31,7 @@ class WbHinge2Joint : public WbHingeJoint { explicit WbHinge2Joint(WbTokenizer *tokenizer = NULL); WbHinge2Joint(const WbHinge2Joint &other); explicit WbHinge2Joint(const WbNode &other); - virtual ~WbHinge2Joint(); + virtual ~WbHinge2Joint() override; void preFinalize() override; void postFinalize() override; diff --git a/src/webots/nodes/WbHingeJoint.cpp b/src/webots/nodes/WbHingeJoint.cpp index 21b7bae1cf4..35d5066e061 100644 --- a/src/webots/nodes/WbHingeJoint.cpp +++ b/src/webots/nodes/WbHingeJoint.cpp @@ -358,7 +358,7 @@ void WbHingeJoint::prePhysicsStep(double ms) { void WbHingeJoint::postPhysicsStep() { assert(mJoint); - WbRotationalMotor *const rm = rotationalMotor(); + const WbRotationalMotor *const rm = rotationalMotor(); // First update the position roughly based on the angular rate of the joint so that it is within pi radians... double angleRate = dJointGetHingeAngleRate(mJoint); @@ -435,7 +435,7 @@ void WbHingeJoint::updateMinAndMaxStop(double min, double max) { if (max >= M_PI) p->parsingWarn(tr("HingeJoint 'maxStop' must be less than pi to be effective.")); - WbRotationalMotor *const rm = rotationalMotor(); + const WbRotationalMotor *const rm = rotationalMotor(); if (rm) { const double minPos = rm->minPosition(); const double maxPos = rm->maxPosition(); @@ -521,7 +521,7 @@ void WbHingeJoint::updateOdeWorldCoordinates() { if (!mJoint || !isPostFinalizedCalled()) return; - WbHingeJointParameters *p = hingeJointParameters(); + const WbHingeJointParameters *p = hingeJointParameters(); if (p && (p->suspensionSpringConstant() != 0.0 || p->suspensionDampingConstant() != 0.0)) // remove suspension effect by resetting the endPoint solid position updatePosition(mPosition); diff --git a/src/webots/nodes/WbHingeJoint.hpp b/src/webots/nodes/WbHingeJoint.hpp index 433b19791d3..59351308cb0 100644 --- a/src/webots/nodes/WbHingeJoint.hpp +++ b/src/webots/nodes/WbHingeJoint.hpp @@ -30,7 +30,7 @@ class WbHingeJoint : public WbJoint { explicit WbHingeJoint(WbTokenizer *tokenizer = NULL); WbHingeJoint(const WbHingeJoint &other); explicit WbHingeJoint(const WbNode &other); - virtual ~WbHingeJoint(); + virtual ~WbHingeJoint() override; int nodeType() const override { return WB_NODE_HINGE_JOINT; } void prePhysicsStep(double ms) override; diff --git a/src/webots/nodes/WbHingeJointParameters.cpp b/src/webots/nodes/WbHingeJointParameters.cpp index 9f25332fe02..fefe320d130 100644 --- a/src/webots/nodes/WbHingeJointParameters.cpp +++ b/src/webots/nodes/WbHingeJointParameters.cpp @@ -58,10 +58,6 @@ WbHingeJointParameters::WbHingeJointParameters(const WbNode &other, bool fromDep WbHingeJointParameters::~WbHingeJointParameters() { } -void WbHingeJointParameters::preFinalize() { - WbJointParameters::preFinalize(); -} - void WbHingeJointParameters::postFinalize() { WbJointParameters::postFinalize(); diff --git a/src/webots/nodes/WbHingeJointParameters.hpp b/src/webots/nodes/WbHingeJointParameters.hpp index 2ceae926689..46738e0c98c 100644 --- a/src/webots/nodes/WbHingeJointParameters.hpp +++ b/src/webots/nodes/WbHingeJointParameters.hpp @@ -26,10 +26,9 @@ class WbHingeJointParameters : public WbJointParameters { explicit WbHingeJointParameters(WbTokenizer *tokenizer = NULL, bool fromDeprecatedHinge2JointParameters = false); WbHingeJointParameters(const WbHingeJointParameters &other); explicit WbHingeJointParameters(const WbNode &other, bool fromDeprecatedHinge2JointParameters = false); - virtual ~WbHingeJointParameters(); + virtual ~WbHingeJointParameters() override; int nodeType() const override { return WB_NODE_HINGE_JOINT_PARAMETERS; } - void preFinalize() override; void postFinalize() override; double suspensionSpringConstant() const { return mSuspensionSpringConstant->value(); } diff --git a/src/webots/nodes/WbImageTexture.hpp b/src/webots/nodes/WbImageTexture.hpp index 1ede7fc1277..c96bf9adfd6 100644 --- a/src/webots/nodes/WbImageTexture.hpp +++ b/src/webots/nodes/WbImageTexture.hpp @@ -41,7 +41,7 @@ class WbImageTexture : public WbBaseNode { WbImageTexture(const WbImageTexture &other); explicit WbImageTexture(const WbNode &other); WbImageTexture(const aiMaterial *material, aiTextureType textureType, const QString &parentPath); - virtual ~WbImageTexture(); + virtual ~WbImageTexture() override; // reimplemented public functions int nodeType() const override { return WB_NODE_IMAGE_TEXTURE; } diff --git a/src/webots/nodes/WbImmersionProperties.hpp b/src/webots/nodes/WbImmersionProperties.hpp index 94a454f7410..6f1ffad519e 100644 --- a/src/webots/nodes/WbImmersionProperties.hpp +++ b/src/webots/nodes/WbImmersionProperties.hpp @@ -28,7 +28,7 @@ class WbImmersionProperties : public WbBaseNode { explicit WbImmersionProperties(WbTokenizer *tokenizer = NULL); WbImmersionProperties(const WbImmersionProperties &other); explicit WbImmersionProperties(const WbNode &other); - virtual ~WbImmersionProperties(); + virtual ~WbImmersionProperties() override; // reimplemented public functions int nodeType() const override { return WB_NODE_IMMERSION_PROPERTIES; } diff --git a/src/webots/nodes/WbIndexedFaceSet.cpp b/src/webots/nodes/WbIndexedFaceSet.cpp index 4e60814a2fa..b642b2fcda0 100644 --- a/src/webots/nodes/WbIndexedFaceSet.cpp +++ b/src/webots/nodes/WbIndexedFaceSet.cpp @@ -109,7 +109,7 @@ void WbIndexedFaceSet::updateTriangleMesh(bool issueWarnings) { texCoord() ? &(texCoord()->point()) : NULL, mTexCoordIndex, mCreaseAngle->value(), mNormalPerVertex->value()); if (issueWarnings) { - foreach (QString warning, mTriangleMesh->warnings()) + foreach (const QString &warning, mTriangleMesh->warnings()) parsingWarn(warning); if (!mTriangleMeshError.isEmpty()) diff --git a/src/webots/nodes/WbIndexedFaceSet.hpp b/src/webots/nodes/WbIndexedFaceSet.hpp index bbde7bed383..77f4bac561b 100644 --- a/src/webots/nodes/WbIndexedFaceSet.hpp +++ b/src/webots/nodes/WbIndexedFaceSet.hpp @@ -30,7 +30,7 @@ class WbIndexedFaceSet : public WbTriangleMeshGeometry { explicit WbIndexedFaceSet(WbTokenizer *tokenizer = NULL); WbIndexedFaceSet(const WbIndexedFaceSet &other); explicit WbIndexedFaceSet(const WbNode &other); - virtual ~WbIndexedFaceSet(); + virtual ~WbIndexedFaceSet() override; // reimplemented public functions int nodeType() const override { return WB_NODE_INDEXED_FACE_SET; } diff --git a/src/webots/nodes/WbIndexedLineSet.hpp b/src/webots/nodes/WbIndexedLineSet.hpp index 835a2cb4b85..cf9da087132 100644 --- a/src/webots/nodes/WbIndexedLineSet.hpp +++ b/src/webots/nodes/WbIndexedLineSet.hpp @@ -29,7 +29,7 @@ class WbIndexedLineSet : public WbGeometry { explicit WbIndexedLineSet(WbTokenizer *tokenizer = NULL); WbIndexedLineSet(const WbIndexedLineSet &other); explicit WbIndexedLineSet(const WbNode &other); - virtual ~WbIndexedLineSet(); + virtual ~WbIndexedLineSet() override; // field accessors WbCoordinate *coord() const; diff --git a/src/webots/nodes/WbInertialUnit.hpp b/src/webots/nodes/WbInertialUnit.hpp index caf27a90648..f0505c40d02 100644 --- a/src/webots/nodes/WbInertialUnit.hpp +++ b/src/webots/nodes/WbInertialUnit.hpp @@ -29,7 +29,7 @@ class WbInertialUnit : public WbSolidDevice { explicit WbInertialUnit(WbTokenizer *tokenizer = NULL); WbInertialUnit(const WbInertialUnit &other); explicit WbInertialUnit(const WbNode &other); - virtual ~WbInertialUnit(); + virtual ~WbInertialUnit() override; // reimplemented public functions int nodeType() const override { return WB_NODE_INERTIAL_UNIT; } diff --git a/src/webots/nodes/WbJoint.hpp b/src/webots/nodes/WbJoint.hpp index fed074b1414..e033250ce2b 100644 --- a/src/webots/nodes/WbJoint.hpp +++ b/src/webots/nodes/WbJoint.hpp @@ -34,7 +34,7 @@ class WbJoint : public WbBasicJoint { Q_OBJECT public: - virtual ~WbJoint(); + virtual ~WbJoint() override; void downloadAssets() override; void preFinalize() override; diff --git a/src/webots/nodes/WbJointDevice.cpp b/src/webots/nodes/WbJointDevice.cpp index 16eb3cbb91b..9c6bba42aec 100644 --- a/src/webots/nodes/WbJointDevice.cpp +++ b/src/webots/nodes/WbJointDevice.cpp @@ -76,7 +76,7 @@ WbTrack *WbJointDevice::track() const { WbLogicalDevice *WbJointDevice::getSiblingDeviceByType(int nodeType) const { WbJoint *j = joint(); if (j) { - WbBallJoint *ballJoint = dynamic_cast(j); + const WbBallJoint *ballJoint = dynamic_cast(j); if (ballJoint) { // special case for nodes in devices3 field bool isDevice3 = false; @@ -95,7 +95,7 @@ WbLogicalDevice *WbJointDevice::getSiblingDeviceByType(int nodeType) const { return NULL; } } - WbHinge2Joint *hinge2 = dynamic_cast(j); + const WbHinge2Joint *hinge2 = dynamic_cast(j); if (hinge2) { // special case for nodes in devices2 field bool isDevice2 = false; @@ -123,7 +123,7 @@ WbLogicalDevice *WbJointDevice::getSiblingDeviceByType(int nodeType) const { return NULL; } - WbTrack *t = track(); + const WbTrack *t = track(); if (t) { foreach (WbLogicalDevice *device, t->devices()) { if (device && device->nodeType() == nodeType) diff --git a/src/webots/nodes/WbJointDevice.hpp b/src/webots/nodes/WbJointDevice.hpp index 3ee21e5f002..9e80327d198 100644 --- a/src/webots/nodes/WbJointDevice.hpp +++ b/src/webots/nodes/WbJointDevice.hpp @@ -28,7 +28,7 @@ class WbJointDevice : public WbLogicalDevice { Q_OBJECT public: - virtual ~WbJointDevice(); + virtual ~WbJointDevice() override; // inherited from WbBaseNode void preFinalize() override; diff --git a/src/webots/nodes/WbJointParameters.hpp b/src/webots/nodes/WbJointParameters.hpp index 431b34efe34..d7df1fa4c1d 100644 --- a/src/webots/nodes/WbJointParameters.hpp +++ b/src/webots/nodes/WbJointParameters.hpp @@ -27,7 +27,7 @@ class WbJointParameters : public WbBaseNode { explicit WbJointParameters(WbTokenizer *tokenizer = NULL); WbJointParameters(const WbJointParameters &other); explicit WbJointParameters(const WbNode &other); - virtual ~WbJointParameters(); + virtual ~WbJointParameters() override; int nodeType() const override { return WB_NODE_JOINT_PARAMETERS; } void preFinalize() override; diff --git a/src/webots/nodes/WbLed.cpp b/src/webots/nodes/WbLed.cpp index 25482791359..ce81dce6bad 100644 --- a/src/webots/nodes/WbLed.cpp +++ b/src/webots/nodes/WbLed.cpp @@ -50,10 +50,6 @@ WbLed::~WbLed() { clearMaterialsAndLights(); } -void WbLed::preFinalize() { - WbSolidDevice::preFinalize(); -} - void WbLed::postFinalize() { WbSolidDevice::postFinalize(); @@ -109,12 +105,14 @@ void WbLed::findMaterialsAndLights(const WbGroup *group) { for (int i = 0; i < size; ++i) { WbBaseNode *const n = group->child(i); + // cppcheck-suppress constVariablePointer WbLight *lightChild = dynamic_cast(n); WbGroup *groupChild = dynamic_cast(n); if (n->nodeType() == WB_NODE_SHAPE) { - WbAppearance *appearance = dynamic_cast(n)->appearance(); + const WbAppearance *appearance = dynamic_cast(n)->appearance(); if (appearance) { + // cppcheck-suppress constVariablePointer WbMaterial *material = appearance->material(); if (material) mMaterials.append(material); diff --git a/src/webots/nodes/WbLed.hpp b/src/webots/nodes/WbLed.hpp index 7972471714d..f853ffb602b 100644 --- a/src/webots/nodes/WbLed.hpp +++ b/src/webots/nodes/WbLed.hpp @@ -35,11 +35,10 @@ class WbLed : public WbSolidDevice { explicit WbLed(WbTokenizer *tokenizer = NULL); WbLed(const WbLed &other); explicit WbLed(const WbNode &other); - virtual ~WbLed(); + virtual ~WbLed() override; // reimplemented public functions int nodeType() const override { return WB_NODE_LED; } - void preFinalize() override; void postFinalize() override; void reset(const QString &id) override; diff --git a/src/webots/nodes/WbLens.hpp b/src/webots/nodes/WbLens.hpp index 39eda40a053..1713f3d2fcb 100644 --- a/src/webots/nodes/WbLens.hpp +++ b/src/webots/nodes/WbLens.hpp @@ -25,7 +25,7 @@ class WbLens : public WbBaseNode { explicit WbLens(WbTokenizer *tokenizer = NULL); WbLens(const WbLens &other); explicit WbLens(const WbNode &other); - virtual ~WbLens(); + virtual ~WbLens() override; // reimplemented public functions int nodeType() const override { return WB_NODE_LENS; } diff --git a/src/webots/nodes/WbLensFlare.hpp b/src/webots/nodes/WbLensFlare.hpp index 3b25c510eab..f2612be37ab 100644 --- a/src/webots/nodes/WbLensFlare.hpp +++ b/src/webots/nodes/WbLensFlare.hpp @@ -32,7 +32,7 @@ class WbLensFlare : public WbBaseNode { explicit WbLensFlare(WbTokenizer *tokenizer = NULL); WbLensFlare(const WbLensFlare &other); explicit WbLensFlare(const WbNode &other); - virtual ~WbLensFlare(); + virtual ~WbLensFlare() override; // reimplemented public functions int nodeType() const override { return WB_NODE_LENS; } diff --git a/src/webots/nodes/WbLidar.cpp b/src/webots/nodes/WbLidar.cpp index 8758232758d..c33281376aa 100644 --- a/src/webots/nodes/WbLidar.cpp +++ b/src/webots/nodes/WbLidar.cpp @@ -242,7 +242,7 @@ void WbLidar::exportNodeSubNodes(WbWriter &writer) const { if (writer.isWebots() || writer.isUrdf()) return; - WbSolid *s = solidEndPoint(); + const WbSolid *s = solidEndPoint(); if (s) s->write(writer); } @@ -1005,7 +1005,7 @@ void WbLidar::attachResizeManipulator() { void WbLidar::detachResizeManipulator() const { WbAbstractCamera::detachResizeManipulator(); - WbSolid *s = solidEndPoint(); + const WbSolid *s = solidEndPoint(); if (s) s->detachResizeManipulator(); } diff --git a/src/webots/nodes/WbLidar.hpp b/src/webots/nodes/WbLidar.hpp index 83fa2bad51d..24c0d5ad159 100644 --- a/src/webots/nodes/WbLidar.hpp +++ b/src/webots/nodes/WbLidar.hpp @@ -33,7 +33,7 @@ class WbLidar : public WbAbstractCamera { explicit WbLidar(WbTokenizer *tokenizer = NULL); WbLidar(const WbLidar &other); explicit WbLidar(const WbNode &other); - virtual ~WbLidar(); + virtual ~WbLidar() override; // reimplemented public functions void createOdeObjects() override; diff --git a/src/webots/nodes/WbLight.hpp b/src/webots/nodes/WbLight.hpp index e05d0a46b87..883533599b0 100644 --- a/src/webots/nodes/WbLight.hpp +++ b/src/webots/nodes/WbLight.hpp @@ -31,7 +31,7 @@ class WbLight : public WbBaseNode { public: // destructor - virtual ~WbLight(); + virtual ~WbLight() override; // reimplemented public functions void createWrenObjects() override; diff --git a/src/webots/nodes/WbLightSensor.hpp b/src/webots/nodes/WbLightSensor.hpp index 1c7329ae3e9..34280cec7a3 100644 --- a/src/webots/nodes/WbLightSensor.hpp +++ b/src/webots/nodes/WbLightSensor.hpp @@ -36,7 +36,7 @@ class WbLightSensor : public WbSolidDevice { explicit WbLightSensor(WbTokenizer *tokenizer = NULL); WbLightSensor(const WbLightSensor &other); explicit WbLightSensor(const WbNode &other); - virtual ~WbLightSensor(); + virtual ~WbLightSensor() override; // reimplemented public functions int nodeType() const override { return WB_NODE_LIGHT_SENSOR; } diff --git a/src/webots/nodes/WbLinearMotor.hpp b/src/webots/nodes/WbLinearMotor.hpp index 0d2a39a78cd..0fc47d84a1c 100644 --- a/src/webots/nodes/WbLinearMotor.hpp +++ b/src/webots/nodes/WbLinearMotor.hpp @@ -24,7 +24,7 @@ class WbLinearMotor : public WbMotor { explicit WbLinearMotor(WbTokenizer *tokenizer = NULL); WbLinearMotor(const WbLinearMotor &other); explicit WbLinearMotor(const WbNode &other); - virtual ~WbLinearMotor(); + virtual ~WbLinearMotor() override; int nodeType() const override { return WB_NODE_LINEAR_MOTOR; } double force() const { return mMotorForceOrTorque; } double computeFeedback() const override; diff --git a/src/webots/nodes/WbLogicalDevice.hpp b/src/webots/nodes/WbLogicalDevice.hpp index ab8f6946f63..fd3ce8b0502 100644 --- a/src/webots/nodes/WbLogicalDevice.hpp +++ b/src/webots/nodes/WbLogicalDevice.hpp @@ -23,7 +23,7 @@ class WbLogicalDevice : public WbBaseNode, public WbDevice { public: - virtual ~WbLogicalDevice(); + virtual ~WbLogicalDevice() override; const QString &deviceName() const override { return mDeviceName->value(); } int deviceNodeType() const override { return nodeType(); } diff --git a/src/webots/nodes/WbMaterial.hpp b/src/webots/nodes/WbMaterial.hpp index 0e899d4a64d..7c52194a698 100644 --- a/src/webots/nodes/WbMaterial.hpp +++ b/src/webots/nodes/WbMaterial.hpp @@ -28,7 +28,7 @@ class WbMaterial : public WbBaseNode { explicit WbMaterial(WbTokenizer *tokenizer = NULL); WbMaterial(const WbMaterial &other); explicit WbMaterial(const WbNode &other); - virtual ~WbMaterial(); + virtual ~WbMaterial() override; // reimplemented public functions int nodeType() const override { return WB_NODE_MATERIAL; } diff --git a/src/webots/nodes/WbMatter.cpp b/src/webots/nodes/WbMatter.cpp index 3294cb04366..6c4306fab01 100644 --- a/src/webots/nodes/WbMatter.cpp +++ b/src/webots/nodes/WbMatter.cpp @@ -137,7 +137,7 @@ void WbMatter::postFinalize() { WbNode *parameter = protoParameterNode(); while (parameter->protoParameterNode()) parameter = parameter->protoParameterNode(); - WbMatter *matter = dynamic_cast(parameter); + const WbMatter *matter = dynamic_cast(parameter); if (matter) matter->connectNameUpdates(); } @@ -251,7 +251,7 @@ dGeomID WbMatter::odeGeom() const { if (bo == NULL) return NULL; - WbGeometry *g = NULL; + const WbGeometry *g = NULL; const WbPose *const p = dynamic_cast(bo); // cppcheck-suppress knownConditionTrueFalse @@ -523,7 +523,7 @@ void WbMatter::updateLineScale() { } void WbMatter::updateName() { - QString nameValue = mName->value(); + const QString &nameValue = mName->value(); if (nameValue.isEmpty()) { const QString &defaultName = dynamic_cast(findField("name")->defaultValue())->value(); parsingWarn(tr("'name' cannot be empty. Default node name '%1' is automatically set.").arg(defaultName)); diff --git a/src/webots/nodes/WbMatter.hpp b/src/webots/nodes/WbMatter.hpp index da05bc6678c..d4aebaec82d 100644 --- a/src/webots/nodes/WbMatter.hpp +++ b/src/webots/nodes/WbMatter.hpp @@ -31,7 +31,7 @@ class WbMatter : public WbPose { public: // constructors and destructor - virtual ~WbMatter(); + virtual ~WbMatter() override; // reimplemented public functions void createWrenObjects() override; diff --git a/src/webots/nodes/WbMesh.cpp b/src/webots/nodes/WbMesh.cpp index f950f42ba57..1ccbbb98cd4 100644 --- a/src/webots/nodes/WbMesh.cpp +++ b/src/webots/nodes/WbMesh.cpp @@ -219,7 +219,7 @@ void WbMesh::updateTriangleMesh(bool issueWarnings) { // compute absolute transform of this node from all the parents aiMatrix4x4 transform; - aiNode *current = node; + const aiNode *current = node; while (current != NULL) { transform *= current->mTransformation; current = current->mParent; @@ -286,7 +286,7 @@ void WbMesh::updateTriangleMesh(bool issueWarnings) { mTriangleMeshError = mTriangleMesh->init(coordData, normalData, texCoordData, indexData, totalVertices, currentIndexIndex); if (issueWarnings) { - foreach (QString warning, mTriangleMesh->warnings()) + foreach (const QString &warning, mTriangleMesh->warnings()) warn(warning); if (!mTriangleMeshError.isEmpty()) diff --git a/src/webots/nodes/WbMesh.hpp b/src/webots/nodes/WbMesh.hpp index e9c428110c7..14d0787bc6d 100644 --- a/src/webots/nodes/WbMesh.hpp +++ b/src/webots/nodes/WbMesh.hpp @@ -29,7 +29,7 @@ class WbMesh : public WbTriangleMeshGeometry { explicit WbMesh(WbTokenizer *tokenizer = NULL); WbMesh(const WbMesh &other); explicit WbMesh(const WbNode &other); - virtual ~WbMesh(); + virtual ~WbMesh() override; void updateTriangleMesh(bool issueWarnings = true) override; diff --git a/src/webots/nodes/WbMicrophone.hpp b/src/webots/nodes/WbMicrophone.hpp index adae34a694b..c314df7e81f 100644 --- a/src/webots/nodes/WbMicrophone.hpp +++ b/src/webots/nodes/WbMicrophone.hpp @@ -28,7 +28,7 @@ class WbMicrophone : public WbSolidDevice { explicit WbMicrophone(WbTokenizer *tokenizer = NULL); WbMicrophone(const WbMicrophone &other); explicit WbMicrophone(const WbNode &other); - virtual ~WbMicrophone(); + virtual ~WbMicrophone() override; // reimplemented public functions int nodeType() const override { return WB_NODE_MICROPHONE; } diff --git a/src/webots/nodes/WbMotor.cpp b/src/webots/nodes/WbMotor.cpp index 1271c5a8aba..55672c34171 100644 --- a/src/webots/nodes/WbMotor.cpp +++ b/src/webots/nodes/WbMotor.cpp @@ -579,7 +579,7 @@ void WbMotor::enforceMotorLimitsInsideJointLimits() { if (isPositionUnlimited()) return; - WbJoint *parentJoint = dynamic_cast(parentNode()); + const WbJoint *parentJoint = dynamic_cast(parentNode()); double p = 0.0; if (parentJoint) { if (positionIndex() == 1 && parentJoint->parameters()) @@ -767,7 +767,7 @@ void WbMotor::handleMessage(QDataStream &stream) { stream >> deviceType; assert(mRequestedDeviceTag == NULL); mRequestedDeviceTag = new WbDeviceTag[1]; - WbLogicalDevice *device = getSiblingDeviceByType(deviceType); + const WbLogicalDevice *device = getSiblingDeviceByType(deviceType); mRequestedDeviceTag[0] = device ? device->tag() : 0; break; } diff --git a/src/webots/nodes/WbMotor.hpp b/src/webots/nodes/WbMotor.hpp index 8077978688e..ceed7e671ee 100644 --- a/src/webots/nodes/WbMotor.hpp +++ b/src/webots/nodes/WbMotor.hpp @@ -34,7 +34,7 @@ class WbMotor : public WbJointDevice { Q_OBJECT public: - virtual ~WbMotor(); + virtual ~WbMotor() override; // Accessors bool userControl() const { return mUserControl; } diff --git a/src/webots/nodes/WbMuscle.hpp b/src/webots/nodes/WbMuscle.hpp index 9169ef8a552..85fb8840016 100644 --- a/src/webots/nodes/WbMuscle.hpp +++ b/src/webots/nodes/WbMuscle.hpp @@ -42,7 +42,7 @@ class WbMuscle : public WbBaseNode { explicit WbMuscle(WbTokenizer *tokenizer = NULL); WbMuscle(const WbMuscle &other); explicit WbMuscle(const WbNode &other); - virtual ~WbMuscle(); + virtual ~WbMuscle() override; // reimplemented public functions int nodeType() const override { return WB_NODE_MUSCLE; } diff --git a/src/webots/nodes/WbNormal.hpp b/src/webots/nodes/WbNormal.hpp index 411b035fecb..6563e349c50 100644 --- a/src/webots/nodes/WbNormal.hpp +++ b/src/webots/nodes/WbNormal.hpp @@ -28,7 +28,7 @@ class WbNormal : public WbBaseNode { explicit WbNormal(WbTokenizer *tokenizer = NULL); WbNormal(const WbNormal &other); explicit WbNormal(const WbNode &other); - virtual ~WbNormal(); + virtual ~WbNormal() override; // reimplemented public functions int nodeType() const override { return WB_NODE_NORMAL; } diff --git a/src/webots/nodes/WbPbrAppearance.hpp b/src/webots/nodes/WbPbrAppearance.hpp index 007ac747839..4ff17febdb2 100644 --- a/src/webots/nodes/WbPbrAppearance.hpp +++ b/src/webots/nodes/WbPbrAppearance.hpp @@ -33,7 +33,7 @@ class WbPbrAppearance : public WbAbstractAppearance { WbPbrAppearance(const WbPbrAppearance &other); explicit WbPbrAppearance(const WbNode &other); WbPbrAppearance(const aiMaterial *material, const QString &filePath); - virtual ~WbPbrAppearance(); + virtual ~WbPbrAppearance() override; // reimplemented public functions int nodeType() const override { return WB_NODE_PBR_APPEARANCE; } diff --git a/src/webots/nodes/WbPen.hpp b/src/webots/nodes/WbPen.hpp index f9ab0cbbc8b..f20d8671d57 100644 --- a/src/webots/nodes/WbPen.hpp +++ b/src/webots/nodes/WbPen.hpp @@ -27,7 +27,7 @@ class WbPen : public WbSolidDevice { explicit WbPen(WbTokenizer *tokenizer = NULL); WbPen(const WbPen &other); explicit WbPen(const WbNode &other); - virtual ~WbPen(); + virtual ~WbPen() override; // reimplemented public functions int nodeType() const override { return WB_NODE_PEN; } diff --git a/src/webots/nodes/WbPhysics.hpp b/src/webots/nodes/WbPhysics.hpp index 1819d6c3c91..c8ba0e368f0 100644 --- a/src/webots/nodes/WbPhysics.hpp +++ b/src/webots/nodes/WbPhysics.hpp @@ -42,7 +42,7 @@ class WbPhysics : public WbBaseNode { explicit WbPhysics(WbTokenizer *tokenizer = NULL); WbPhysics(const WbPhysics &other); explicit WbPhysics(const WbNode &other); - virtual ~WbPhysics(); + virtual ~WbPhysics() override; // reimplemented public functions int nodeType() const override { return WB_NODE_PHYSICS; } diff --git a/src/webots/nodes/WbPlane.cpp b/src/webots/nodes/WbPlane.cpp index 9bc2be26be8..407f615b889 100644 --- a/src/webots/nodes/WbPlane.cpp +++ b/src/webots/nodes/WbPlane.cpp @@ -238,7 +238,7 @@ void WbPlane::updateOdePlanePosition() { } void WbPlane::computePlaneParams(WbVector3 &n, double &d) { - WbPose *pose = upperPose(); + const WbPose *pose = upperPose(); // initial values with identity matrices n.setXyz(0.0, 0.0, 1.0); // plane normal diff --git a/src/webots/nodes/WbPlane.hpp b/src/webots/nodes/WbPlane.hpp index 9c545924749..557c0d8bdc9 100644 --- a/src/webots/nodes/WbPlane.hpp +++ b/src/webots/nodes/WbPlane.hpp @@ -25,7 +25,7 @@ class WbPlane : public WbGeometry { explicit WbPlane(WbTokenizer *tokenizer = NULL); WbPlane(const WbPlane &other); explicit WbPlane(const WbNode &other); - virtual ~WbPlane(); + virtual ~WbPlane() override; // reimplemented public functions int nodeType() const override { return WB_NODE_PLANE; } diff --git a/src/webots/nodes/WbPointLight.hpp b/src/webots/nodes/WbPointLight.hpp index 6425fe38fff..74afefb58b4 100644 --- a/src/webots/nodes/WbPointLight.hpp +++ b/src/webots/nodes/WbPointLight.hpp @@ -32,7 +32,7 @@ class WbPointLight : public WbLight { explicit WbPointLight(WbTokenizer *tokenizer = NULL); WbPointLight(const WbPointLight &other); explicit WbPointLight(const WbNode &other); - virtual ~WbPointLight(); + virtual ~WbPointLight() override; // reimplemented public functions int nodeType() const override { return WB_NODE_POINT_LIGHT; } @@ -50,6 +50,7 @@ class WbPointLight : public WbLight { protected slots: void updateAmbientIntensity() override; + // cppcheck-suppress uselessOverride void updateIntensity() override; void updateOn() override; diff --git a/src/webots/nodes/WbPointSet.hpp b/src/webots/nodes/WbPointSet.hpp index dfeb322b21b..5e07ad020ca 100644 --- a/src/webots/nodes/WbPointSet.hpp +++ b/src/webots/nodes/WbPointSet.hpp @@ -30,7 +30,7 @@ class WbPointSet : public WbGeometry { explicit WbPointSet(WbTokenizer *tokenizer = NULL); WbPointSet(const WbPointSet &other); explicit WbPointSet(const WbNode &other); - virtual ~WbPointSet(); + virtual ~WbPointSet() override; // field accessors WbCoordinate *coord() const; diff --git a/src/webots/nodes/WbPose.cpp b/src/webots/nodes/WbPose.cpp index 9dd0f9a1d98..6fbd3fab1d7 100644 --- a/src/webots/nodes/WbPose.cpp +++ b/src/webots/nodes/WbPose.cpp @@ -377,7 +377,7 @@ WbVector3 WbPose::translationFrom(const WbNode *fromNode) const { assert(parentNode); } - WbPose *previousPose = const_cast(poseList.takeLast()); + const WbPose *previousPose = const_cast(poseList.takeLast()); WbVector3 translationResult = previousPose->translation(); while (poseList.size() > 0) { const WbPose *pose = poseList.takeLast(); diff --git a/src/webots/nodes/WbPose.hpp b/src/webots/nodes/WbPose.hpp index 76460585706..1f5439068df 100644 --- a/src/webots/nodes/WbPose.hpp +++ b/src/webots/nodes/WbPose.hpp @@ -33,7 +33,7 @@ class WbPose : public WbGroup, public WbAbstractPose { explicit WbPose(WbTokenizer *tokenizer = NULL); WbPose(const WbPose &other); explicit WbPose(const WbNode &other); - virtual ~WbPose(); + virtual ~WbPose() override; // reimplemented functions int nodeType() const override { return WB_NODE_POSE; } diff --git a/src/webots/nodes/WbPositionSensor.cpp b/src/webots/nodes/WbPositionSensor.cpp index 233ea5eb01f..215d2be12c8 100644 --- a/src/webots/nodes/WbPositionSensor.cpp +++ b/src/webots/nodes/WbPositionSensor.cpp @@ -92,7 +92,7 @@ void WbPositionSensor::handleMessage(QDataStream &stream) { stream >> deviceType; assert(mRequestedDeviceTag == NULL); mRequestedDeviceTag = new WbDeviceTag[1]; - WbLogicalDevice *device = getSiblingDeviceByType(deviceType); + const WbLogicalDevice *device = getSiblingDeviceByType(deviceType); if (!device && deviceType == WB_NODE_ROTATIONAL_MOTOR) // check both motor types device = getSiblingDeviceByType(WB_NODE_LINEAR_MOTOR); diff --git a/src/webots/nodes/WbPositionSensor.hpp b/src/webots/nodes/WbPositionSensor.hpp index 837dfde6958..ccb1520363f 100644 --- a/src/webots/nodes/WbPositionSensor.hpp +++ b/src/webots/nodes/WbPositionSensor.hpp @@ -28,7 +28,7 @@ class WbPositionSensor : public WbJointDevice { Q_OBJECT public: - virtual ~WbPositionSensor() { delete mSensor; } + virtual ~WbPositionSensor() override { delete mSensor; } explicit WbPositionSensor(const QString &modelName, WbTokenizer *tokenizer = NULL); explicit WbPositionSensor(WbTokenizer *tokenizer = NULL); WbPositionSensor(const WbPositionSensor &other); diff --git a/src/webots/nodes/WbPropeller.cpp b/src/webots/nodes/WbPropeller.cpp index 00625b25df5..e86685e7530 100644 --- a/src/webots/nodes/WbPropeller.cpp +++ b/src/webots/nodes/WbPropeller.cpp @@ -365,8 +365,8 @@ void WbPropeller::write(WbWriter &writer) const { if (writer.isWebots()) WbBaseNode::write(writer); else { - WbSolid *const fastHelix = helix(FAST_HELIX); - WbSolid *const slowHelix = helix(SLOW_HELIX); + const WbSolid *const fastHelix = helix(FAST_HELIX); + const WbSolid *const slowHelix = helix(SLOW_HELIX); if (writer.isW3d()) writer << ""; else { diff --git a/src/webots/nodes/WbPropeller.hpp b/src/webots/nodes/WbPropeller.hpp index d028754d0ea..0e035002f34 100644 --- a/src/webots/nodes/WbPropeller.hpp +++ b/src/webots/nodes/WbPropeller.hpp @@ -37,7 +37,7 @@ class WbPropeller : public WbBaseNode { explicit WbPropeller(WbTokenizer *tokenizer = NULL); WbPropeller(const WbPropeller &other); explicit WbPropeller(const WbNode &other); - virtual ~WbPropeller(); + virtual ~WbPropeller() override; // reimplemented public functions int nodeType() const override { return WB_NODE_PROPELLER; } diff --git a/src/webots/nodes/WbRadar.cpp b/src/webots/nodes/WbRadar.cpp index e1cad056d6d..d5aec75b055 100644 --- a/src/webots/nodes/WbRadar.cpp +++ b/src/webots/nodes/WbRadar.cpp @@ -538,6 +538,7 @@ bool WbRadar::refreshSensorIfNeeded() { mRadarTargetsPreviousTranslations.clear(); QList targets = WbWorld::instance()->radarTargetSolids(); for (int i = 0; i < targets.size(); ++i) { + // cppcheck-suppress constVariablePointer WbSolid *target = targets.at(i); if (target != this) mRadarTargetsPreviousTranslations.insert(target, target->position()); diff --git a/src/webots/nodes/WbRadar.hpp b/src/webots/nodes/WbRadar.hpp index a0f9accd12c..de57595f812 100644 --- a/src/webots/nodes/WbRadar.hpp +++ b/src/webots/nodes/WbRadar.hpp @@ -34,7 +34,7 @@ class WbRadar : public WbSolidDevice { explicit WbRadar(WbTokenizer *tokenizer = NULL); WbRadar(const WbRadar &other); explicit WbRadar(const WbNode &other); - virtual ~WbRadar(); + virtual ~WbRadar() override; // reimplemented public functions int nodeType() const override { return WB_NODE_RADAR; } diff --git a/src/webots/nodes/WbRadio.cpp b/src/webots/nodes/WbRadio.cpp index 6ab5a77ad7d..7a8542d2275 100644 --- a/src/webots/nodes/WbRadio.cpp +++ b/src/webots/nodes/WbRadio.cpp @@ -304,6 +304,7 @@ static void radio_event_destroy(struct WebotsRadioEvent *p) { void WbRadio::receiveCallback(const struct WebotsRadioEvent *event) { // yvan: Radio N>2 bug was fixed here: a *deep* copy of WebotsRadioEvent is required + // cppcheck-suppress constVariablePointer struct WebotsRadioEvent *copy = radio_event_duplicate(event); mReceivedEvents.append(copy); } diff --git a/src/webots/nodes/WbRadio.hpp b/src/webots/nodes/WbRadio.hpp index d79333968a6..3ac3f685716 100644 --- a/src/webots/nodes/WbRadio.hpp +++ b/src/webots/nodes/WbRadio.hpp @@ -27,7 +27,7 @@ class WbRadio : public WbSolidDevice { explicit WbRadio(WbTokenizer *tokenizer = NULL); WbRadio(const WbRadio &other); explicit WbRadio(const WbNode &other); - virtual ~WbRadio(); + virtual ~WbRadio() override; // reimplemented public functions int nodeType() const override { return WB_NODE_RADIO; } diff --git a/src/webots/nodes/WbRangeFinder.hpp b/src/webots/nodes/WbRangeFinder.hpp index fca59132368..8bbe4d7165e 100644 --- a/src/webots/nodes/WbRangeFinder.hpp +++ b/src/webots/nodes/WbRangeFinder.hpp @@ -25,7 +25,7 @@ class WbRangeFinder : public WbAbstractCamera { explicit WbRangeFinder(WbTokenizer *tokenizer = NULL); WbRangeFinder(const WbRangeFinder &other); explicit WbRangeFinder(const WbNode &other); - virtual ~WbRangeFinder(); + virtual ~WbRangeFinder() override; // reimplemented public functions void preFinalize() override; diff --git a/src/webots/nodes/WbReceiver.hpp b/src/webots/nodes/WbReceiver.hpp index 816732d635a..94acd554ea0 100644 --- a/src/webots/nodes/WbReceiver.hpp +++ b/src/webots/nodes/WbReceiver.hpp @@ -37,7 +37,7 @@ class WbReceiver : public WbSolidDevice { explicit WbReceiver(WbTokenizer *tokenizer = NULL); WbReceiver(const WbReceiver &other); explicit WbReceiver(const WbNode &other); - virtual ~WbReceiver(); + virtual ~WbReceiver() override; // reimplemented public functions int nodeType() const override { return WB_NODE_RECEIVER; } diff --git a/src/webots/nodes/WbRecognition.hpp b/src/webots/nodes/WbRecognition.hpp index 85d81ad48d1..72c73a04baa 100644 --- a/src/webots/nodes/WbRecognition.hpp +++ b/src/webots/nodes/WbRecognition.hpp @@ -28,7 +28,7 @@ class WbRecognition : public WbBaseNode { explicit WbRecognition(WbTokenizer *tokenizer = NULL); WbRecognition(const WbRecognition &other); explicit WbRecognition(const WbNode &other); - virtual ~WbRecognition(); + virtual ~WbRecognition() override; // reimplemented public functions int nodeType() const override { return WB_NODE_RECOGNITION; } diff --git a/src/webots/nodes/WbRenderingDevice.hpp b/src/webots/nodes/WbRenderingDevice.hpp index e285c7006e5..990f30f3407 100644 --- a/src/webots/nodes/WbRenderingDevice.hpp +++ b/src/webots/nodes/WbRenderingDevice.hpp @@ -28,7 +28,7 @@ class WbRenderingDevice : public WbSolidDevice { Q_OBJECT public: - virtual ~WbRenderingDevice(); + virtual ~WbRenderingDevice() override; // reimplemented public functions void preFinalize() override; @@ -62,7 +62,7 @@ class WbRenderingDevice : public WbSolidDevice { // static functions static WbRenderingDevice *fromMousePosition(int x, int y); - static QList renderingDevices() { return cRenderingDevices; } + static const QList &renderingDevices() { return cRenderingDevices; } enum TextureRole { BACKGROUND_TEXTURE = 0, MAIN_TEXTURE, MASK_TEXTURE, FOREGROUND_TEXTURE }; diff --git a/src/webots/nodes/WbRobot.cpp b/src/webots/nodes/WbRobot.cpp index ba1173c4afd..143047aa5f3 100644 --- a/src/webots/nodes/WbRobot.cpp +++ b/src/webots/nodes/WbRobot.cpp @@ -274,6 +274,7 @@ void WbRobot::addDevices(WbNode *node) { WbGroup *group = dynamic_cast(node); if (group) { + // cppcheck-suppress constVariablePointer WbSolidDevice *solidDevice = dynamic_cast(node); if (solidDevice) { mDevices.append(solidDevice); @@ -293,7 +294,7 @@ void WbRobot::addDevices(WbNode *node) { } } - WbTrack *const track = dynamic_cast(group); + const WbTrack *const track = dynamic_cast(group); if (track) { const QVector trackDevices = track->devices(); for (int i = 0; i < trackDevices.size(); ++i) { @@ -317,7 +318,7 @@ void WbRobot::addDevices(WbNode *node) { return; } - WbSlot *const slot = dynamic_cast(node); + const WbSlot *const slot = dynamic_cast(node); if (slot) { addDevices(slot->endPoint()); return; @@ -325,7 +326,7 @@ void WbRobot::addDevices(WbNode *node) { WbBasicJoint *const basicJoint = dynamic_cast(node); if (basicJoint) { - WbJoint *const joint = dynamic_cast(basicJoint); + const WbJoint *const joint = dynamic_cast(basicJoint); if (joint) { const QVector &jointDevices = joint->devices(); foreach (WbLogicalDevice *const jointDevice, jointDevices) { @@ -355,8 +356,8 @@ void WbRobot::addDevices(WbNode *node) { // check if there are duplicated names, and print a warning if necessary if (dynamic_cast(node)) { // top node QStringList displayedWarnings; - foreach (WbDevice *deviceA, mDevices) { - foreach (WbDevice *deviceB, mDevices) { + foreach (const WbDevice *deviceA, mDevices) { + foreach (const WbDevice *deviceB, mDevices) { if (deviceA != deviceB && deviceA->deviceName() == deviceB->deviceName() && !displayedWarnings.contains(deviceA->deviceName())) { parsingWarn(tr("At least two devices are sharing the same name (\"%1\") while unique names are required.") @@ -441,7 +442,7 @@ QString WbRobot::searchDynamicLibraryAbsolutePath(const QString &key, const QStr } } // search in project folder associated with parent PROTO models - WbProtoModel *protoModel = proto(); + const WbProtoModel *protoModel = proto(); while (protoModel) { if (!protoModel->projectPath().isEmpty()) { QDir protoDir(protoModel->projectPath() + "/plugins/" + pluginSubdirectory + "/" + key); @@ -670,7 +671,7 @@ double WbRobot::energyUploadSpeed() const { double WbRobot::energyConsumption() const { double e = mCpuConsumption->value(); - foreach (WbDevice *deviceObject, mDevices) // add energy consumption for each device + foreach (const WbDevice *deviceObject, mDevices) // add energy consumption for each device e += deviceObject->energyConsumption(); return e; } @@ -1376,7 +1377,7 @@ QString WbRobot::windowFile(const QString &extension) const { if (file.exists() && file.isFile() && file.isReadable()) return path; // search in project folder associated with parent PROTO models - WbProtoModel *protoModel = proto(); + const WbProtoModel *protoModel = proto(); while (protoModel) { if (!protoModel->projectPath().isEmpty()) { path = protoModel->projectPath() + "/plugins/robot_windows/" + fileName; @@ -1532,7 +1533,7 @@ const QString WbRobot::urdfName() const { } int WbRobot::computeSimulationMode() { - WbSimulationState *state = WbSimulationState::instance(); + const WbSimulationState *state = WbSimulationState::instance(); switch (state->mode()) { case WbSimulationState::REALTIME: return WB_SUPERVISOR_SIMULATION_MODE_REAL_TIME; diff --git a/src/webots/nodes/WbRobot.hpp b/src/webots/nodes/WbRobot.hpp index 0fd0e318480..925c8d57c32 100644 --- a/src/webots/nodes/WbRobot.hpp +++ b/src/webots/nodes/WbRobot.hpp @@ -49,7 +49,7 @@ class WbRobot : public WbSolid { explicit WbRobot(WbTokenizer *tokenizer = NULL); WbRobot(const WbRobot &other); explicit WbRobot(const WbNode &other); - virtual ~WbRobot(); + virtual ~WbRobot() override; // reimplemented public functions int nodeType() const override { return WB_NODE_ROBOT; } @@ -99,7 +99,7 @@ class WbRobot : public WbSolid { WbDevice *device(int index) const { return mDevices[index]; } WbDevice *findDevice(WbDeviceTag tag) const; void descendantNodeInserted(WbBaseNode *decendant) override; - QList renderingDevices() { return mRenderingDevices; } + const QList &renderingDevices() { return mRenderingDevices; } // update sensors in case of no answer needs to be written at this step virtual void updateSensors(); diff --git a/src/webots/nodes/WbRotationalMotor.hpp b/src/webots/nodes/WbRotationalMotor.hpp index 6763f1fc721..dfffea50f97 100644 --- a/src/webots/nodes/WbRotationalMotor.hpp +++ b/src/webots/nodes/WbRotationalMotor.hpp @@ -25,7 +25,7 @@ class WbRotationalMotor : public WbMotor { Q_OBJECT public: - virtual ~WbRotationalMotor(); + virtual ~WbRotationalMotor() override; explicit WbRotationalMotor(WbTokenizer *tokenizer = NULL); WbRotationalMotor(const WbRotationalMotor &other); explicit WbRotationalMotor(const WbNode &other); diff --git a/src/webots/nodes/WbShape.cpp b/src/webots/nodes/WbShape.cpp index 591f689a654..81cf366c3b3 100644 --- a/src/webots/nodes/WbShape.cpp +++ b/src/webots/nodes/WbShape.cpp @@ -306,9 +306,9 @@ void WbShape::applyMaterialToGeometry() { // using uv mapping, paint color and diffuse color // could be improved by computing the exact openGL computing including lighting void WbShape::pickColor(const WbRay &ray, WbRgb &pickedColor, double *roughness, double *occlusion) const { - WbAppearance *const app = appearance(); - WbPbrAppearance *const pbrApp = pbrAppearance(); - WbGeometry *const geom = geometry(); + const WbAppearance *const app = appearance(); + const WbPbrAppearance *const pbrApp = pbrAppearance(); + const WbGeometry *const geom = geometry(); WbRgb diffuseColor(1.0f, 1.0f, 1.0f); WbRgb textureColor(1.0f, 1.0f, 1.0f); diff --git a/src/webots/nodes/WbShape.hpp b/src/webots/nodes/WbShape.hpp index 3ac03c49e60..cba11f112e5 100644 --- a/src/webots/nodes/WbShape.hpp +++ b/src/webots/nodes/WbShape.hpp @@ -32,7 +32,7 @@ class WbShape : public WbBaseNode { explicit WbShape(WbTokenizer *tokenizer = NULL); WbShape(const WbShape &other); explicit WbShape(const WbNode &other); - virtual ~WbShape(); + virtual ~WbShape() override; // reimplemented public functions int nodeType() const override { return WB_NODE_SHAPE; } diff --git a/src/webots/nodes/WbSkin.cpp b/src/webots/nodes/WbSkin.cpp index 3d1860d0ccd..8c03e4e403c 100644 --- a/src/webots/nodes/WbSkin.cpp +++ b/src/webots/nodes/WbSkin.cpp @@ -730,7 +730,7 @@ bool WbSkin::createSkeletonFromWebotsNodes() { QMap boneToSolidMap; int validBoneCount = 0; for (int i = 0; i < mBonesField->size(); ++i) { - WbSolidReference *ref = dynamic_cast(mBonesField->item(i)); + const WbSolidReference *ref = dynamic_cast(mBonesField->item(i)); if (ref->solid() == NULL) continue; diff --git a/src/webots/nodes/WbSkin.hpp b/src/webots/nodes/WbSkin.hpp index 45c5ac59ea7..7ed2da520ed 100644 --- a/src/webots/nodes/WbSkin.hpp +++ b/src/webots/nodes/WbSkin.hpp @@ -37,7 +37,7 @@ class WbSkin : public WbBaseNode, public WbAbstractPose, public WbDevice { explicit WbSkin(WbTokenizer *tokenizer = NULL); WbSkin(const WbSkin &other); explicit WbSkin(const WbNode &other); - virtual ~WbSkin(); + virtual ~WbSkin() override; WbMFNode *appearanceField() const { return mAppearanceField; } diff --git a/src/webots/nodes/WbSliderJoint.cpp b/src/webots/nodes/WbSliderJoint.cpp index a4f3a7a51c0..125decb1c60 100644 --- a/src/webots/nodes/WbSliderJoint.cpp +++ b/src/webots/nodes/WbSliderJoint.cpp @@ -138,7 +138,7 @@ void WbSliderJoint::updatePosition(double position) { void WbSliderJoint::updateMinAndMaxStop(double min, double max) { const WbJointParameters *const p = dynamic_cast(sender()); - WbLinearMotor *const lm = linearMotor(); + const WbLinearMotor *const lm = linearMotor(); if (lm) { const double minPos = lm->minPosition(); const double maxPos = lm->maxPosition(); @@ -267,7 +267,7 @@ void WbSliderJoint::postPhysicsStep() { p->setPositionFromOde(mPosition); if (isEnabled()) { - WbLinearMotor *const lm = linearMotor(); + const WbLinearMotor *const lm = linearMotor(); if (lm && lm->hasMuscles() && !lm->userControl()) // dynamic position or velocity control emit updateMuscleStretch(-lm->computeFeedback() / lm->maxForceOrTorque(), false, 1); diff --git a/src/webots/nodes/WbSliderJoint.hpp b/src/webots/nodes/WbSliderJoint.hpp index 2f9bcfa185f..61424ad45ba 100644 --- a/src/webots/nodes/WbSliderJoint.hpp +++ b/src/webots/nodes/WbSliderJoint.hpp @@ -32,7 +32,7 @@ class WbSliderJoint : public WbJoint { explicit WbSliderJoint(WbTokenizer *tokenizer = NULL); WbSliderJoint(const WbSliderJoint &other); explicit WbSliderJoint(const WbNode &other); - virtual ~WbSliderJoint(); + virtual ~WbSliderJoint() override; int nodeType() const override { return WB_NODE_SLIDER_JOINT; } void prePhysicsStep(double ms) override; @@ -56,6 +56,7 @@ public slots: void writeExport(WbWriter &writer) const override; protected slots: + // cppcheck-suppress uselessOverride void updateParameters() override; void updateMinAndMaxStop(double min, double max) override; diff --git a/src/webots/nodes/WbSlot.cpp b/src/webots/nodes/WbSlot.cpp index c82ad875b6b..64d19eada45 100644 --- a/src/webots/nodes/WbSlot.cpp +++ b/src/webots/nodes/WbSlot.cpp @@ -167,7 +167,7 @@ void WbSlot::setSleepMaterial() { } WbBoundingSphere *WbSlot::boundingSphere() const { - WbBaseNode *const baseNode = static_cast(mEndPoint->value()); + const WbBaseNode *const baseNode = static_cast(mEndPoint->value()); if (baseNode) return baseNode->boundingSphere(); @@ -225,7 +225,7 @@ void WbSlot::attachResizeManipulator() { } void WbSlot::detachResizeManipulator() const { - WbBaseNode *const e = static_cast(mEndPoint->value()); + const WbBaseNode *const e = static_cast(mEndPoint->value()); if (e) e->detachResizeManipulator(); } diff --git a/src/webots/nodes/WbSlot.hpp b/src/webots/nodes/WbSlot.hpp index 205211efb19..c30054cf32a 100644 --- a/src/webots/nodes/WbSlot.hpp +++ b/src/webots/nodes/WbSlot.hpp @@ -30,7 +30,7 @@ class WbSlot : public WbBaseNode { explicit WbSlot(WbTokenizer *tokenizer = NULL); WbSlot(const WbSlot &other); explicit WbSlot(const WbNode &other); - virtual ~WbSlot(); + virtual ~WbSlot() override; // reimplemented public functions int nodeType() const override { return WB_NODE_SLOT; } diff --git a/src/webots/nodes/WbSolid.cpp b/src/webots/nodes/WbSolid.cpp index c775b8c9bf1..68f2e10a20f 100644 --- a/src/webots/nodes/WbSolid.cpp +++ b/src/webots/nodes/WbSolid.cpp @@ -233,7 +233,7 @@ WbSolid::~WbSolid() { mJoint = NULL; // disconnecting descendants - foreach (WbSolid *const solid, mSolidChildren) + foreach (const WbSolid *const solid, mSolidChildren) disconnect(solid, &WbSolid::destroyed, this, 0); } @@ -250,7 +250,7 @@ void WbSolid::validateProtoNode() { if (!(checkTranslation || checkRotation)) return; - foreach (WbField *parameter, parameters()) { + foreach (const WbField *parameter, parameters()) { if (checkTranslation && parameter->name() == "translation" && parameter->isTemplateRegenerator()) { parsingWarn(tr("template regenerator field named 'translation' found. " "It is recommended not to use template statements to update the top Solid 'translation' field")); @@ -530,7 +530,7 @@ void WbSolid::resolveNameClashIfNeeded(bool automaticallyChange, bool recursive, bool found = false; re.setPattern(QString("%1\\((\\d+)\\)").arg(QRegularExpression::escape(nameWithoutIndex))); - foreach (WbSolid *s, siblings) { + foreach (const WbSolid *s, siblings) { if (!s || s == this) continue; @@ -1476,15 +1476,18 @@ void WbSolid::collectSolidChildren(const WbGroup *group, bool connectSignals, QV while (it.hasNext()) { WbNode *const n = it.next(); + // cppcheck-suppress constVariablePointer WbSolid *const solid = dynamic_cast(n); if (solid) { solidChildren.append(solid); continue; } + // cppcheck-suppress constVariablePointer WbBasicJoint *j = dynamic_cast(n); if (j) { jointChildren.append(j); + // cppcheck-suppress constVariablePointer WbSolid *const ep = j->solidEndPoint(); if (ep && j->solidReference() == NULL) { solidChildren.append(ep); @@ -1492,6 +1495,7 @@ void WbSolid::collectSolidChildren(const WbGroup *group, bool connectSignals, QV } } + // cppcheck-suppress constVariablePointer WbPropeller *propeller = dynamic_cast(n); if (propeller) { propellerChildren.append(propeller); @@ -1520,6 +1524,7 @@ void WbSolid::collectSolidChildren(const WbGroup *group, bool connectSignals, QV j = dynamic_cast(slot->endPoint()); if (j) { jointChildren.append(j); + // cppcheck-suppress constVariablePointer WbSolid *const ep = j->solidEndPoint(); if (ep && j->solidReference() == NULL) { solidChildren.append(ep); @@ -1543,7 +1548,7 @@ void WbSolid::collectSolidChildren(const WbGroup *group, bool connectSignals, QV void WbSolid::updateDynamicSolidDescendantFlag() { mHasDynamicSolidDescendant = false; - foreach (WbSolid *s, mSolidChildren) { + foreach (const WbSolid *s, mSolidChildren) { if (!s->isPostFinalizedCalled()) // postpone flag update after finalization return; @@ -2012,9 +2017,9 @@ void WbSolid::prePhysicsStep(double ms) { // Accessors to relatives WbBasicJoint *WbSolid::jointParent() const { - WbSlot *parentSlot = dynamic_cast(parentNode()); + const WbSlot *parentSlot = dynamic_cast(parentNode()); if (parentSlot) { - WbSlot *granParentSlot = dynamic_cast(parentSlot->parentNode()); + const WbSlot *granParentSlot = dynamic_cast(parentSlot->parentNode()); if (granParentSlot) return dynamic_cast(granParentSlot->parentNode()); } @@ -2191,9 +2196,9 @@ void WbSolid::jerk(bool resetVelocities, bool rootJerk) { } void WbSolid::notifyChildJerk(WbPose *childNode) { - WbNode *node = childNode->parentNode(); + const WbNode *node = childNode->parentNode(); while (node != this && node != NULL) { - if (mMovedChildren.contains(dynamic_cast(node))) + if (mMovedChildren.contains(dynamic_cast(node))) return; node = node->parentNode(); } @@ -2203,7 +2208,7 @@ void WbSolid::notifyChildJerk(WbPose *childNode) { void WbSolid::childrenJerk() { updateOdeGeomPosition(); - foreach (WbPose *childNode, mMovedChildren) { + foreach (const WbPose *childNode, mMovedChildren) { QVector solidChildrenList; QVector jointChildrenList; QVector propellerChildrenList; @@ -2744,7 +2749,7 @@ void WbSolid::collectSolidDescendantNames(QStringList &items, const WbSolid *con items << name(); // Recurses through all first level solid descendants - foreach (WbSolid *const solid, mSolidChildren) + foreach (const WbSolid *const solid, mSolidChildren) solid->collectSolidDescendantNames(items, solidException); } @@ -2765,7 +2770,7 @@ void WbSolid::collectHiddenKinematicParameters(HiddenKinematicParametersMap &map if (mSolidMerger == NULL || merger) { // TODO: implement an mIsVisible flag in WbNode for sake of efficiency - WbBasicJoint *parentJoint = jointParent(); + const WbBasicJoint *parentJoint = jointParent(); if (parentJoint) { // remove unquantified ODE effects on the endPoint Solid parentJoint->computeEndPointSolidPositionFromParameters(translationToBeCopied, rotationToBeCopied); @@ -2843,7 +2848,7 @@ void WbSolid::collectHiddenKinematicParameters(HiddenKinematicParametersMap &map ++counter; // Recurses through all first level solid descendants - foreach (WbSolid *const solid, mSolidChildren) + foreach (const WbSolid *const solid, mSolidChildren) solid->collectHiddenKinematicParameters(map, counter); } diff --git a/src/webots/nodes/WbSolid.hpp b/src/webots/nodes/WbSolid.hpp index eb2c963f42b..0336a2fbd66 100644 --- a/src/webots/nodes/WbSolid.hpp +++ b/src/webots/nodes/WbSolid.hpp @@ -47,7 +47,7 @@ class WbSolid : public WbMatter { explicit WbSolid(WbTokenizer *tokenizer = NULL); WbSolid(const WbSolid &other); explicit WbSolid(const WbNode &other); - virtual ~WbSolid(); + virtual ~WbSolid() override; // list of finalized solids static const QList &solids() { return cSolids; } diff --git a/src/webots/nodes/WbSolidDevice.cpp b/src/webots/nodes/WbSolidDevice.cpp index b805452dc07..e5a07eccbd5 100644 --- a/src/webots/nodes/WbSolidDevice.cpp +++ b/src/webots/nodes/WbSolidDevice.cpp @@ -53,7 +53,7 @@ void WbSolidDevice::subscribeToRaysUpdate(dGeomID ray) { } QString WbSolidDevice::computeShortUniqueName() const { - WbSolid *robot = WbNodeUtilities::findRobotAncestor(this); + const WbSolid *robot = WbNodeUtilities::findRobotAncestor(this); if (robot) return QString("%1:%2").arg(robot->computeUniqueName()).arg(WbSolid::name()); return computeUniqueName(); diff --git a/src/webots/nodes/WbSolidDevice.hpp b/src/webots/nodes/WbSolidDevice.hpp index f11e2f235e3..23e5ac50f8a 100644 --- a/src/webots/nodes/WbSolidDevice.hpp +++ b/src/webots/nodes/WbSolidDevice.hpp @@ -26,7 +26,7 @@ class WbSolidDevice : public WbDevice, public WbSolid { public: // destructor - virtual ~WbSolidDevice(); + virtual ~WbSolidDevice() override; const QString &deviceName() const override { return WbSolid::name(); } int deviceNodeType() const override { return nodeType(); } diff --git a/src/webots/nodes/WbSolidReference.cpp b/src/webots/nodes/WbSolidReference.cpp index 3d1e604a599..4d913f004f8 100644 --- a/src/webots/nodes/WbSolidReference.cpp +++ b/src/webots/nodes/WbSolidReference.cpp @@ -43,10 +43,6 @@ WbSolidReference::WbSolidReference(const WbNode &other) : WbBaseNode(other) { WbSolidReference::~WbSolidReference() { } -void WbSolidReference::preFinalize() { - WbBaseNode::preFinalize(); -} - void WbSolidReference::postFinalize() { WbBaseNode::postFinalize(); connect(mName, &WbSFString::changed, this, &WbSolidReference::changed); diff --git a/src/webots/nodes/WbSolidReference.hpp b/src/webots/nodes/WbSolidReference.hpp index f94902879d3..79833b7c1a6 100644 --- a/src/webots/nodes/WbSolidReference.hpp +++ b/src/webots/nodes/WbSolidReference.hpp @@ -35,10 +35,9 @@ class WbSolidReference : public WbBaseNode { explicit WbSolidReference(WbTokenizer *tokenizer = NULL); WbSolidReference(const WbSolidReference &other); explicit WbSolidReference(const WbNode &other); - virtual ~WbSolidReference(); + virtual ~WbSolidReference() override; int nodeType() const override { return WB_NODE_SOLID_REFERENCE; } - void preFinalize() override; void postFinalize() override; QPointer solid() const { return mSolid; } diff --git a/src/webots/nodes/WbSpeaker.cpp b/src/webots/nodes/WbSpeaker.cpp index 570a311049f..b4b8bfc0fce 100644 --- a/src/webots/nodes/WbSpeaker.cpp +++ b/src/webots/nodes/WbSpeaker.cpp @@ -183,7 +183,7 @@ void WbSpeaker::playText(const char *text, double volume) { QDir initialDir = QDir::current(); if (!QDir::setCurrent(mControllerDir)) this->warn(tr("Cannot change directory to: '%1'").arg(mControllerDir)); - WbSoundClip *soundClip = WbSoundEngine::soundFromText(text, mEngine, mLanguage); + const WbSoundClip *soundClip = WbSoundEngine::soundFromText(text, mEngine, mLanguage); QDir::setCurrent(initialDir.path()); if (soundClip) { source->setSoundClip(soundClip); @@ -221,7 +221,7 @@ void WbSpeaker::playSound(const char *file, double volume, double pitch, double WbSoundSource *source = WbSoundEngine::createSource(); updateSoundSource(source); const QString extension = filename.mid(filename.lastIndexOf('.') + 1).toLower(); - WbSoundClip *soundClip = WbSoundEngine::sound(path, extension, NULL, balance, side); + const WbSoundClip *soundClip = WbSoundEngine::sound(path, extension, NULL, balance, side); if (!soundClip) { this->warn(tr("Impossible to play '%1'. Make sure the file format is supported (8 or 16 bits, mono or stereo wave).\n") .arg(filename)); diff --git a/src/webots/nodes/WbSpeaker.hpp b/src/webots/nodes/WbSpeaker.hpp index bde1eb2b3e4..af76aa1695f 100644 --- a/src/webots/nodes/WbSpeaker.hpp +++ b/src/webots/nodes/WbSpeaker.hpp @@ -29,7 +29,7 @@ class WbSpeaker : public WbSolidDevice { explicit WbSpeaker(WbTokenizer *tokenizer = NULL); WbSpeaker(const WbSpeaker &other); explicit WbSpeaker(const WbNode &other); - virtual ~WbSpeaker(); + virtual ~WbSpeaker() override; // reimplemented public functions int nodeType() const override { return WB_NODE_SPEAKER; } diff --git a/src/webots/nodes/WbSphere.hpp b/src/webots/nodes/WbSphere.hpp index 40e98f2f957..a3c8510b878 100644 --- a/src/webots/nodes/WbSphere.hpp +++ b/src/webots/nodes/WbSphere.hpp @@ -28,7 +28,7 @@ class WbSphere : public WbGeometry { explicit WbSphere(WbTokenizer *tokenizer = NULL); WbSphere(const WbSphere &other); explicit WbSphere(const WbNode &other); - virtual ~WbSphere(); + virtual ~WbSphere() override; // field accessors double radius() const { return mRadius->value(); } diff --git a/src/webots/nodes/WbSpotLight.hpp b/src/webots/nodes/WbSpotLight.hpp index 2a2031132bf..db3a9e94e16 100644 --- a/src/webots/nodes/WbSpotLight.hpp +++ b/src/webots/nodes/WbSpotLight.hpp @@ -31,7 +31,7 @@ class WbSpotLight : public WbLight { explicit WbSpotLight(WbTokenizer *tokenizer = NULL); WbSpotLight(const WbSpotLight &other); explicit WbSpotLight(const WbNode &other); - virtual ~WbSpotLight(); + virtual ~WbSpotLight() override; // reimplemented public functions int nodeType() const override { return WB_NODE_SPOT_LIGHT; } @@ -51,8 +51,10 @@ class WbSpotLight : public WbLight { protected slots: void updateAmbientIntensity() override; + // cppcheck-suppress uselessOverride void updateIntensity() override; void updateOn() override; + // cppcheck-suppress uselessOverride void updateColor() override; private: diff --git a/src/webots/nodes/WbTextureCoordinate.hpp b/src/webots/nodes/WbTextureCoordinate.hpp index d05ff358e48..71764bb6648 100644 --- a/src/webots/nodes/WbTextureCoordinate.hpp +++ b/src/webots/nodes/WbTextureCoordinate.hpp @@ -28,7 +28,7 @@ class WbTextureCoordinate : public WbBaseNode { explicit WbTextureCoordinate(WbTokenizer *tokenizer = NULL); WbTextureCoordinate(const WbTextureCoordinate &other); explicit WbTextureCoordinate(const WbNode &other); - virtual ~WbTextureCoordinate(); + virtual ~WbTextureCoordinate() override; // reimplemented public functions int nodeType() const override { return WB_NODE_TEXTURE_COORDINATE; } diff --git a/src/webots/nodes/WbTextureTransform.hpp b/src/webots/nodes/WbTextureTransform.hpp index eb5b222ddc1..79cb164780a 100644 --- a/src/webots/nodes/WbTextureTransform.hpp +++ b/src/webots/nodes/WbTextureTransform.hpp @@ -31,7 +31,7 @@ class WbTextureTransform : public WbBaseNode { explicit WbTextureTransform(WbTokenizer *tokenizer = NULL); WbTextureTransform(const WbTextureTransform &other); explicit WbTextureTransform(const WbNode &other); - virtual ~WbTextureTransform(); + virtual ~WbTextureTransform() override; // reimplemented public functions int nodeType() const override { return WB_NODE_TEXTURE_TRANSFORM; } diff --git a/src/webots/nodes/WbTouchSensor.cpp b/src/webots/nodes/WbTouchSensor.cpp index 7628627634c..88880ff55d5 100644 --- a/src/webots/nodes/WbTouchSensor.cpp +++ b/src/webots/nodes/WbTouchSensor.cpp @@ -229,18 +229,18 @@ void WbTouchSensor::computeValue() { } } -void WbTouchSensor::setODEDynamicFlag(WbBaseNode *_node) { - WbGeometry *geom = dynamic_cast(_node); +void WbTouchSensor::setODEDynamicFlag(const WbBaseNode *_node) { + const WbGeometry *geom = dynamic_cast(_node); if (!geom) { - WbShape *shape = dynamic_cast(_node); + const WbShape *shape = dynamic_cast(_node); if (shape) geom = shape->geometry(); } if (geom) dGeomSetDynamicFlag(geom->odeGeom()); else { - WbGroup *group = dynamic_cast(_node); + const WbGroup *group = dynamic_cast(_node); if (group) { for (int i = 0; i < group->childCount(); i++) setODEDynamicFlag(group->child(i)); @@ -250,7 +250,7 @@ void WbTouchSensor::setODEDynamicFlag(WbBaseNode *_node) { void WbTouchSensor::createOdeObjects() { WbSolidDevice::createOdeObjects(); - WbBaseNode *node = WbSolidDevice::boundingObject(); + const WbBaseNode *node = WbSolidDevice::boundingObject(); setODEDynamicFlag(node); } diff --git a/src/webots/nodes/WbTouchSensor.hpp b/src/webots/nodes/WbTouchSensor.hpp index f0a2a60d79a..ce3963d8724 100644 --- a/src/webots/nodes/WbTouchSensor.hpp +++ b/src/webots/nodes/WbTouchSensor.hpp @@ -29,7 +29,7 @@ class WbTouchSensor : public WbSolidDevice { explicit WbTouchSensor(WbTokenizer *tokenizer = NULL); WbTouchSensor(const WbTouchSensor &other); explicit WbTouchSensor(const WbNode &other); - virtual ~WbTouchSensor(); + virtual ~WbTouchSensor() override; void setTouching(bool touching) { mIsTouching = touching; } void setGuiTouch(bool touching) { mIsGuiTouch = touching; } @@ -75,7 +75,7 @@ class WbTouchSensor : public WbSolidDevice { void init(); void computeValue(); bool forceBehavior() const; - void setODEDynamicFlag(WbBaseNode *_node); + void setODEDynamicFlag(const WbBaseNode *_node); void addConfigure(WbDataStream &); private slots: diff --git a/src/webots/nodes/WbTrack.cpp b/src/webots/nodes/WbTrack.cpp index dc6ee46d34b..39a87c3563d 100644 --- a/src/webots/nodes/WbTrack.cpp +++ b/src/webots/nodes/WbTrack.cpp @@ -219,6 +219,7 @@ void WbTrack::updateDevices() { } bool WbTrack::findAndConnectAnimatedGeometries(bool connectSignals, QList *shapeList) { + // cppcheck-suppress constVariablePointer WbBaseNode *geometry = dynamic_cast(mGeometryField->value()); if (!geometry) return false; @@ -267,10 +268,11 @@ bool WbTrack::findAndConnectAnimatedGeometries(bool connectSignals, QList(node); + const WbSlot *slot = dynamic_cast(node); if (slot) { - WbSlot *slot2 = slot->slotEndPoint(); + const WbSlot *slot2 = slot->slotEndPoint(); if (slot2) { + // cppcheck-suppress constVariablePointer WbBaseNode *endPoint = dynamic_cast(slot2->endPoint()); if (endPoint) geometryNodes.append(endPoint); @@ -305,7 +307,7 @@ void WbTrack::updateShapeNode() { WbBaseNode *firstChild = child(0); mShape = dynamic_cast(firstChild); if (!mShape) { - WbGroup *group = dynamic_cast(firstChild); + const WbGroup *group = dynamic_cast(firstChild); if (group && group->children().size() > 0) mShape = dynamic_cast(group->child(0)); } @@ -378,6 +380,7 @@ void WbTrack::clearWheelsList() { QVector WbTrack::devices() const { QVector devices; + // cppcheck-suppress constVariablePointer WbLogicalDevice *device = NULL; WbMFNode::Iterator it(*mDeviceField); while (it.hasNext()) { @@ -466,7 +469,7 @@ void WbTrack::updateAnimatedGeometries() { return; int numGeometries = mGeometriesCountField->value(); - WbBaseNode *geometry = dynamic_cast(mGeometryField->value()); + const WbBaseNode *geometry = dynamic_cast(mGeometryField->value()); if (numGeometries <= 0 || !geometry) return; @@ -528,7 +531,7 @@ void WbTrack::updateAnimatedGeometries() { wr_transform_set_orientation(transform, r); for (int j = 0; j < mAnimatedObjectList.size(); ++j) { - WbGeometry *geom = mAnimatedObjectList[j]->geometry; + const WbGeometry *geom = mAnimatedObjectList[j]->geometry; WbMatrix4 geomMatrix = geom->matrix() * matrix().pseudoInversed(); @@ -868,7 +871,7 @@ void WbTrack::exportAnimatedGeometriesMesh(WbWriter &writer) const { if (mAnimatedObjectList.size() == 0 || writer.isUrdf()) return; - WbNode *node = mGeometryField->value(); + const WbNode *node = mGeometryField->value(); QString positionString = QString("%1").arg(WbPrecision::doubleToString(mBeltPositions[0].position.x(), WbPrecision::DOUBLE_MAX)) + " 0 " + @@ -911,7 +914,7 @@ void WbTrack::exportNodeSubNodes(WbWriter &writer) const { return; } - foreach (WbField *field, fields()) { + foreach (const WbField *field, fields()) { if (!field->isDeprecated() && (field->isW3d() && field->singleType() == WB_SF_NODE)) { const WbSFNode *const node = dynamic_cast(field->value()); if (node == NULL || node->value() == NULL || node->value()->shallExport()) { @@ -935,7 +938,7 @@ void WbTrack::exportNodeSubNodes(WbWriter &writer) const { } // write children nodes - WbBaseNode *subNode = NULL; + const WbBaseNode *subNode = NULL; for (int i = 0; i < childCount(); ++i) { subNode = child(i); if (subNode->shallExport()) { diff --git a/src/webots/nodes/WbTrack.hpp b/src/webots/nodes/WbTrack.hpp index 28e010ddbfe..1b27b023cdf 100644 --- a/src/webots/nodes/WbTrack.hpp +++ b/src/webots/nodes/WbTrack.hpp @@ -42,7 +42,7 @@ class WbTrack : public WbSolid { explicit WbTrack(WbTokenizer *tokenizer = NULL); WbTrack(const WbTrack &other); explicit WbTrack(const WbNode &other); - virtual ~WbTrack(); + virtual ~WbTrack() override; // reimplemented public functions int nodeType() const override { return WB_NODE_TRACK; } diff --git a/src/webots/nodes/WbTrackWheel.hpp b/src/webots/nodes/WbTrackWheel.hpp index 08b66482e0f..9e05b5f51fd 100644 --- a/src/webots/nodes/WbTrackWheel.hpp +++ b/src/webots/nodes/WbTrackWheel.hpp @@ -34,7 +34,7 @@ class WbTrackWheel : public WbPose { explicit WbTrackWheel(WbTokenizer *tokenizer = NULL); WbTrackWheel(const WbTrackWheel &other); explicit WbTrackWheel(const WbNode &other); - virtual ~WbTrackWheel(); + virtual ~WbTrackWheel() override; // reimplemented public functions int nodeType() const override { return WB_NODE_TRACK_WHEEL; } diff --git a/src/webots/nodes/WbTriangleMeshGeometry.cpp b/src/webots/nodes/WbTriangleMeshGeometry.cpp index caa4f727328..5e5a4d8a436 100644 --- a/src/webots/nodes/WbTriangleMeshGeometry.cpp +++ b/src/webots/nodes/WbTriangleMeshGeometry.cpp @@ -101,7 +101,7 @@ void WbTriangleMeshGeometry::clearTrimeshResources() { } void WbTriangleMeshGeometry::createWrenObjects() { - foreach (QString warning, mTriangleMesh->warnings()) + foreach (const QString &warning, mTriangleMesh->warnings()) parsingWarn(warning); if (!mTriangleMeshError.isEmpty()) diff --git a/src/webots/nodes/WbTriangleMeshGeometry.hpp b/src/webots/nodes/WbTriangleMeshGeometry.hpp index 2acb3395c8a..d23697d84d1 100644 --- a/src/webots/nodes/WbTriangleMeshGeometry.hpp +++ b/src/webots/nodes/WbTriangleMeshGeometry.hpp @@ -34,7 +34,7 @@ class WbTriangleMeshGeometry : public WbGeometry { public: // constructors and destructor - virtual ~WbTriangleMeshGeometry(); + virtual ~WbTriangleMeshGeometry() override; // reimplemented public functions void preFinalize() override; diff --git a/src/webots/nodes/WbVacuumGripper.hpp b/src/webots/nodes/WbVacuumGripper.hpp index 6e7ae21be9b..f2d9c8a9913 100644 --- a/src/webots/nodes/WbVacuumGripper.hpp +++ b/src/webots/nodes/WbVacuumGripper.hpp @@ -28,7 +28,7 @@ class WbVacuumGripper : public WbSolidDevice { explicit WbVacuumGripper(WbTokenizer *tokenizer = NULL); WbVacuumGripper(const WbVacuumGripper &other); explicit WbVacuumGripper(const WbNode &other); - virtual ~WbVacuumGripper(); + virtual ~WbVacuumGripper() override; // reimplemented public functions int nodeType() const override { return WB_NODE_VACUUM_GRIPPER; } diff --git a/src/webots/nodes/WbViewpoint.hpp b/src/webots/nodes/WbViewpoint.hpp index 471854e471f..4b7b7f8aca2 100644 --- a/src/webots/nodes/WbViewpoint.hpp +++ b/src/webots/nodes/WbViewpoint.hpp @@ -51,7 +51,7 @@ class WbViewpoint : public WbBaseNode { explicit WbViewpoint(WbTokenizer *tokenizer = NULL); WbViewpoint(const WbViewpoint &other); explicit WbViewpoint(const WbNode &other); - virtual ~WbViewpoint(); + virtual ~WbViewpoint() override; // reimplemented public functions int nodeType() const override { return WB_NODE_VIEWPOINT; } @@ -132,7 +132,7 @@ class WbViewpoint : public WbBaseNode { void updateOrthographicViewHeight(); void setNodesVisibility(QList nodes, bool visible); - QList getInvisibleNodes() const { return mInvisibleNodes; } + const QList &getInvisibleNodes() const { return mInvisibleNodes; } void enableNodeVisibility(bool enabled); // Ray picking based on current projection mode diff --git a/src/webots/nodes/WbWorldInfo.hpp b/src/webots/nodes/WbWorldInfo.hpp index ff7fa78f4fb..8a2ae5f908d 100644 --- a/src/webots/nodes/WbWorldInfo.hpp +++ b/src/webots/nodes/WbWorldInfo.hpp @@ -35,7 +35,7 @@ class WbWorldInfo : public WbBaseNode { explicit WbWorldInfo(WbTokenizer *tokenizer = NULL); WbWorldInfo(const WbWorldInfo &other); explicit WbWorldInfo(const WbNode &other); - virtual ~WbWorldInfo(); + virtual ~WbWorldInfo() override; // reimplemented public functions int nodeType() const override { return WB_NODE_WORLD_INFO; } diff --git a/src/webots/nodes/WbZoom.hpp b/src/webots/nodes/WbZoom.hpp index 8b974443478..cd847a195f3 100644 --- a/src/webots/nodes/WbZoom.hpp +++ b/src/webots/nodes/WbZoom.hpp @@ -25,7 +25,7 @@ class WbZoom : public WbBaseNode { explicit WbZoom(WbTokenizer *tokenizer = NULL); WbZoom(const WbZoom &other); explicit WbZoom(const WbNode &other); - virtual ~WbZoom(); + virtual ~WbZoom() override; // reimplemented public functions int nodeType() const override { return WB_NODE_ZOOM; } diff --git a/src/webots/nodes/utils/WbBoundingSphere.cpp b/src/webots/nodes/utils/WbBoundingSphere.cpp index 62c68626e1c..fb90a2e0c45 100644 --- a/src/webots/nodes/utils/WbBoundingSphere.cpp +++ b/src/webots/nodes/utils/WbBoundingSphere.cpp @@ -29,6 +29,7 @@ bool gUpdatesEnabled = false; bool gRayTracingEnabled = false; +// cppcheck-suppress constParameterPointer void WbBoundingSphere::enableUpdates(bool enabled, WbBoundingSphere *root) { gUpdatesEnabled = enabled; if (enabled && root) { @@ -248,7 +249,7 @@ void WbBoundingSphere::recomputeSphereInParentCoordinates() { mParentCoordinatesDirty = false; } -void WbBoundingSphere::computeSphereInGlobalCoordinates(WbVector3 ¢er, double &radius) { +void WbBoundingSphere::computeSphereInGlobalCoordinates(WbVector3 ¢er, double &radius) const { const WbPose *upperPose = dynamic_cast(mPoseOwner); if (upperPose == NULL) upperPose = WbNodeUtilities::findUpperPose(mOwner); diff --git a/src/webots/nodes/utils/WbBoundingSphere.hpp b/src/webots/nodes/utils/WbBoundingSphere.hpp index 4d80fd5ae12..dbc35eb9e5a 100644 --- a/src/webots/nodes/utils/WbBoundingSphere.hpp +++ b/src/webots/nodes/utils/WbBoundingSphere.hpp @@ -68,7 +68,7 @@ class WbBoundingSphere { double scaledRadius(); const WbVector3 ¢er(); - void computeSphereInGlobalCoordinates(WbVector3 ¢er, double &radius); + void computeSphereInGlobalCoordinates(WbVector3 ¢er, double &radius) const; // Set the bound space to be empty. void empty(); diff --git a/src/webots/nodes/utils/WbConcreteNodeFactory.hpp b/src/webots/nodes/utils/WbConcreteNodeFactory.hpp index cef7b26352a..b8a599fb0cb 100644 --- a/src/webots/nodes/utils/WbConcreteNodeFactory.hpp +++ b/src/webots/nodes/utils/WbConcreteNodeFactory.hpp @@ -38,7 +38,7 @@ class WbConcreteNodeFactory : public WbNodeFactory { private: WbConcreteNodeFactory() {} - virtual ~WbConcreteNodeFactory() {} + virtual ~WbConcreteNodeFactory() override {} static WbConcreteNodeFactory gFactory; }; diff --git a/src/webots/nodes/utils/WbDictionary.cpp b/src/webots/nodes/utils/WbDictionary.cpp index e10f8172589..6e111906ae2 100644 --- a/src/webots/nodes/utils/WbDictionary.cpp +++ b/src/webots/nodes/utils/WbDictionary.cpp @@ -226,7 +226,7 @@ bool WbDictionary::updateDef(WbBaseNode *&node, WbSFNode *sfNode, WbMFNode *mfNo } const QVector &fields = node->fieldsOrParameters(); - foreach (WbField *const field, fields) { + foreach (const WbField *const field, fields) { WbValue *const value = field->value(); WbSFNode *const sf = dynamic_cast(value); if (sf) { @@ -296,8 +296,6 @@ void WbDictionary::updateProtosPrivateDef(WbBaseNode *&node) { void WbDictionary::updateProtosDef(WbBaseNode *&node, WbSFNode *sfNode, WbMFNode *mfNode, int index) { const QString &defName = node->defName(); - const int nestingDegree = mNestedDictionaries.size() - 1; - int lookupDegree = nestingDegree; // Solid, Device, BasicJoint and JointParameters DEF nodes are allowed but not registered in the dictionary, // Solid, Device, BasicJoint and JointParameters USE nodes are prohibited @@ -306,6 +304,8 @@ void WbDictionary::updateProtosDef(WbBaseNode *&node, WbSFNode *sfNode, WbMFNode // Handles nodes in protos if (mNestedProtos.size() > 0) { + const int nestingDegree = mNestedDictionaries.size() - 1; + int lookupDegree = nestingDegree; if (!defName.isEmpty() && isAValidUseableNode) { if (node->isProtoInstance()) lookupDegree--; @@ -329,7 +329,7 @@ void WbDictionary::updateProtosDef(WbBaseNode *&node, WbSFNode *sfNode, WbMFNode WbNode *upperDefinition = upperUseNode->defNode(); if (mNestedProtos.last()->isAnAncestorOf(upperDefinition)) { int childIndex = WbNode::subNodeIndex(node, upperUseNode); - WbNode *matchingUse = WbNode::findNodeFromSubNodeIndex(childIndex, upperDefinition); + const WbNode *matchingUse = WbNode::findNodeFromSubNodeIndex(childIndex, upperDefinition); definitionNode = static_cast(matchingUse->defNode()); } } @@ -361,7 +361,7 @@ void WbDictionary::updateProtosDef(WbBaseNode *&node, WbSFNode *sfNode, WbMFNode // Handles non-parameter fields only const QVector &fields = node->fields(); - foreach (WbField *const field, fields) { + foreach (const WbField *const field, fields) { if (field->parameter()) continue; @@ -496,7 +496,7 @@ bool WbDictionary::checkChargerAndLedConstraints(WbNode *useNodeParent, const Wb // In case of Material or Light USE node inserted in first child of Charger or LED nodes: // the corresponding DEF node has also to be a descendant of first child WbNode *upperLedOrCharger; - WbBaseNode *parentBaseNode = dynamic_cast(useNodeParent); + const WbBaseNode *parentBaseNode = dynamic_cast(useNodeParent); if (parentBaseNode->nodeType() == WB_NODE_LED) upperLedOrCharger = useNodeParent; else @@ -519,6 +519,7 @@ bool WbDictionary::checkChargerAndLedConstraints(WbNode *useNodeParent, const Wb if (!types.contains(defNode->nodeType()) && !WbNodeUtilities::hasDescendantNodesOfType(defNode, types)) return true; + // cppcheck-suppress constVariablePointer WbNode *firstChild = dynamic_cast(upperLedOrCharger)->child(0); QList firstChildDescendants = firstChild->subNodes(true); firstChildDescendants.prepend(firstChild); @@ -652,7 +653,7 @@ void WbDictionary::updateNodeDefName(WbNode *node, bool fromUseToDef) { update(false); } -void WbDictionary::removeNodeFromDictionary(WbNode *node) { +void WbDictionary::removeNodeFromDictionary(const WbNode *node) { if (node->useCount() > 0) // dictionary will be completely recomputed return; diff --git a/src/webots/nodes/utils/WbDictionary.hpp b/src/webots/nodes/utils/WbDictionary.hpp index 7d64127a2dd..7d9aad229a9 100644 --- a/src/webots/nodes/utils/WbDictionary.hpp +++ b/src/webots/nodes/utils/WbDictionary.hpp @@ -53,7 +53,7 @@ class WbDictionary { // Get node from DEF name WbNode *getNodeFromDEF(const QString &defName) const; void updateNodeDefName(WbNode *node, bool fromUseToDef); - void removeNodeFromDictionary(WbNode *node); + void removeNodeFromDictionary(const WbNode *node); private: static WbDictionary *cInstance; diff --git a/src/webots/nodes/utils/WbDisplayFont.hpp b/src/webots/nodes/utils/WbDisplayFont.hpp index 14311bea035..f80d22f4015 100644 --- a/src/webots/nodes/utils/WbDisplayFont.hpp +++ b/src/webots/nodes/utils/WbDisplayFont.hpp @@ -35,7 +35,7 @@ class WbDisplayFont { unsigned int verticalSpace() const; unsigned int fontSize() const { return mFontSize; } - QString error() const { return mError; } + const QString &error() const { return mError; } private: void loadFace(FT_Face *face, const QString &filename, unsigned int size); diff --git a/src/webots/nodes/utils/WbHiddenKinematicParameters.cpp b/src/webots/nodes/utils/WbHiddenKinematicParameters.cpp index 2c2bf49ca3f..e22dbda26ba 100644 --- a/src/webots/nodes/utils/WbHiddenKinematicParameters.cpp +++ b/src/webots/nodes/utils/WbHiddenKinematicParameters.cpp @@ -24,7 +24,7 @@ #include void WbHiddenKinematicParameters::createHiddenKinematicParameter( - WbField *field, WbHiddenKinematicParameters::HiddenKinematicParametersMap &map) { + const WbField *field, WbHiddenKinematicParameters::HiddenKinematicParametersMap &map) { // Extract solid and joint indices static const QRegularExpression rx1("(_\\d+)+$"); // looks for a substring of the form _7 or _13_1 at the end of the // parameter name, e.g. as in rotation_7, position2_13_1 diff --git a/src/webots/nodes/utils/WbHiddenKinematicParameters.hpp b/src/webots/nodes/utils/WbHiddenKinematicParameters.hpp index ca2e8ff1beb..9ca2deb9a35 100644 --- a/src/webots/nodes/utils/WbHiddenKinematicParameters.hpp +++ b/src/webots/nodes/utils/WbHiddenKinematicParameters.hpp @@ -78,6 +78,7 @@ namespace WbHiddenKinematicParameters { delete mAngularVelocity; mAngularVelocity = new WbVector3(x, y, z); } + // cppcheck-suppress constParameterPointer void insertPositions(int index, WbVector3 *positions) { if (mPositions == NULL) mPositions = new PositionMap; @@ -96,7 +97,7 @@ namespace WbHiddenKinematicParameters { }; typedef QMap HiddenKinematicParametersMap; - void createHiddenKinematicParameter(WbField *field, HiddenKinematicParametersMap &map); + void createHiddenKinematicParameter(const WbField *field, HiddenKinematicParametersMap &map); }; // namespace WbHiddenKinematicParameters #endif // WB_HIDDEN_KINEMATIC_PARAMETERS_HPP diff --git a/src/webots/nodes/utils/WbJoystickInterface.hpp b/src/webots/nodes/utils/WbJoystickInterface.hpp index c5b5d11a457..979a58591b4 100644 --- a/src/webots/nodes/utils/WbJoystickInterface.hpp +++ b/src/webots/nodes/utils/WbJoystickInterface.hpp @@ -54,7 +54,7 @@ class WbJoystickInterface : public QObject { void setConstantForceDuration(double duration) { mConstantForceDuration = duration; } void setForceAxis(int axis); - QString initializationError() const { return mError; } + const QString &initializationError() const { return mError; } bool isCorrectlyInitialized() const { return mCorrectlyInitialized; } bool hasForceFeedback() const { return mHasForceFeedback; } bool supportConstantForceFeedbackEffect() const { return mSupportConstantForceFeedbackEffect; } diff --git a/src/webots/nodes/utils/WbKinematicDifferentialWheels.cpp b/src/webots/nodes/utils/WbKinematicDifferentialWheels.cpp index 96f8936fa7c..841d0f896b6 100644 --- a/src/webots/nodes/utils/WbKinematicDifferentialWheels.cpp +++ b/src/webots/nodes/utils/WbKinematicDifferentialWheels.cpp @@ -65,7 +65,7 @@ WbCylinder *WbKinematicDifferentialWheels::getRecursivelyBigestCylinder(WbBaseNo WbCylinder *cylinder = dynamic_cast(node); if (cylinder) return cylinder; - WbGroup *group = dynamic_cast(node); + const WbGroup *group = dynamic_cast(node); if (group) { for (int i = 0; i < group->childCount(); ++i) { cylinder = getRecursivelyBigestCylinder(group->child(i)); @@ -77,7 +77,7 @@ WbCylinder *WbKinematicDifferentialWheels::getRecursivelyBigestCylinder(WbBaseNo } } } - WbShape *shape = dynamic_cast(node); + const WbShape *shape = dynamic_cast(node); if (shape) { cylinder = dynamic_cast(shape->geometry()); if (cylinder) @@ -96,6 +96,7 @@ WbKinematicDifferentialWheels *WbKinematicDifferentialWheels::createKinematicDif const QVector joints = robot->jointChildren(); QVector motorizedJoints; for (int i = 0; i < joints.size(); ++i) { + // cppcheck-suppress constVariablePointer WbHingeJoint *joint = dynamic_cast(joints.at(i)); if (!joint || !joint->motor() || !joint->solidEndPoint()) continue; @@ -106,7 +107,7 @@ WbKinematicDifferentialWheels *WbKinematicDifferentialWheels::createKinematicDif // check all the possible pairs of joints for (int i = 0; i < motorizedJoints.size(); ++i) { leftJoint = motorizedJoints.at(i); - WbCylinder *leftWheelCylinder = getRecursivelyBigestCylinder(leftJoint->solidEndPoint()->boundingObject()); + const WbCylinder *leftWheelCylinder = getRecursivelyBigestCylinder(leftJoint->solidEndPoint()->boundingObject()); // make sure this joint has a cylinder bounding object if (!leftWheelCylinder || leftWheelCylinder->radius() <= 0.0) continue; @@ -115,7 +116,7 @@ WbKinematicDifferentialWheels *WbKinematicDifferentialWheels::createKinematicDif for (int j = i + 1; j < motorizedJoints.size(); ++j) { rightJoint = motorizedJoints.at(j); // make sure this joint has a cylinder bounding object - WbCylinder *rightWheelCylinder = getRecursivelyBigestCylinder(rightJoint->solidEndPoint()->boundingObject()); + const WbCylinder *rightWheelCylinder = getRecursivelyBigestCylinder(rightJoint->solidEndPoint()->boundingObject()); if (!rightWheelCylinder || rightWheelCylinder->radius() <= 0.0) continue; // make sure both cylinders have the same size diff --git a/src/webots/nodes/utils/WbMouse.hpp b/src/webots/nodes/utils/WbMouse.hpp index 7fad4fbfcc4..b7c6f820b15 100644 --- a/src/webots/nodes/utils/WbMouse.hpp +++ b/src/webots/nodes/utils/WbMouse.hpp @@ -26,7 +26,7 @@ class WbMouse : public QObject { public: static WbMouse *create(); static void destroy(WbMouse *mouse); // Note: it calls the mouse destructor - static QList mouses() { return mMouses; } + static QList &mouses() { return mMouses; } bool left() const { return mLeft; } bool middle() const { return mMiddle; } diff --git a/src/webots/nodes/utils/WbNodeOperations.cpp b/src/webots/nodes/utils/WbNodeOperations.cpp index c566770613a..9a8f9239662 100644 --- a/src/webots/nodes/utils/WbNodeOperations.cpp +++ b/src/webots/nodes/utils/WbNodeOperations.cpp @@ -46,7 +46,7 @@ #include static bool isRegionOccupied(const WbVector3 &pos) { - WbWorld *const world = WbWorld::instance(); + const WbWorld *const world = WbWorld::instance(); const double ls = world->worldInfo()->lineScale(); const QList &l = world->topSolids(); foreach (const WbSolid *const solid, l) { @@ -287,6 +287,7 @@ void WbNodeOperations::resolveSolidNameClashIfNeeded(WbNode *node) const { return; } QList solidNodes; + // cppcheck-suppress constVariablePointer WbSolid *solidNode = dynamic_cast(node); if (solidNode) solidNodes << solidNode; diff --git a/src/webots/nodes/utils/WbNodeUtilities.cpp b/src/webots/nodes/utils/WbNodeUtilities.cpp index 27381ab913c..bc92a156b77 100644 --- a/src/webots/nodes/utils/WbNodeUtilities.cpp +++ b/src/webots/nodes/utils/WbNodeUtilities.cpp @@ -647,7 +647,7 @@ WbSolid *WbNodeUtilities::findUpperSolid(const WbNode *node) { return NULL; WbMatter *upperMatter = findUpperMatter(node); // in the case of slot we want to return the parent node of the first slot - WbSlot *slot = dynamic_cast(upperMatter); + const WbSlot *slot = dynamic_cast(upperMatter); while (slot) { upperMatter = findUpperMatter(upperMatter); slot = dynamic_cast(upperMatter); @@ -766,7 +766,7 @@ bool WbNodeUtilities::hasADeviceDescendant(const WbNode *node, bool ignoreConnec } bool WbNodeUtilities::hasARobotAncestor(const WbNode *node) { - WbRobot *robot = findRobotAncestor(node); + const WbRobot *robot = findRobotAncestor(node); return robot != NULL; } @@ -792,7 +792,7 @@ bool WbNodeUtilities::isDescendantOfBillboard(const WbNode *node) { WbNode *n = const_cast(node); while (n && !n->isWorldRoot()) { - WbBaseNode *baseNode = dynamic_cast(n); + const WbBaseNode *baseNode = dynamic_cast(n); if (!baseNode) return false; @@ -830,7 +830,7 @@ WbNode::NodeUse WbNodeUtilities::checkNodeUse(const WbNode *n) { WbNode::NodeUse nodeUse = WbNode::UNKNOWN_USE; if (n->isDefNode()) { // check if at least one of the USE node is in bounding object - foreach (WbNode *useNode, n->useNodes()) { + foreach (const WbNode *useNode, n->useNodes()) { nodeUse = static_cast(nodeUse | checkNodeUse(useNode)); if (nodeUse == WbNode::BOTH_USE) return nodeUse; @@ -840,7 +840,7 @@ WbNode::NodeUse WbNodeUtilities::checkNodeUse(const WbNode *n) { if (n->isProtoParameterNode()) { QVector instances = n->protoParameterNodeInstances(); // check if at least one of the instances is in bounding object - foreach (WbNode *instance, instances) { + foreach (const WbNode *instance, instances) { nodeUse = static_cast(nodeUse | checkNodeUse(instance)); if (nodeUse == WbNode::BOTH_USE) return nodeUse; @@ -1121,6 +1121,8 @@ QList WbNodeUtilities::findSolidDescendants(WbNode *node) { return solidsList; } +// cppcheck-suppress constParameterPointer +// cppcheck-suppress constParameterReference QList WbNodeUtilities::findDescendantNodesOfType(WbNode *node, bool (&typeCondition)(WbBaseNode *), bool recursive) { QList result; QList queue; @@ -1136,7 +1138,7 @@ QList WbNodeUtilities::findDescendantNodesOfType(WbNode *node, bool (& continue; } - WbGroup *const group = dynamic_cast(n); + const WbGroup *const group = dynamic_cast(n); if (group) { int childCount = group->childCount(); for (int i = 0; i < childCount; ++i) @@ -1146,6 +1148,7 @@ QList WbNodeUtilities::findDescendantNodesOfType(WbNode *node, bool (& const WbSlot *const slot = dynamic_cast(n); if (slot) { + // cppcheck-suppress constVariablePointer WbNode *baseEndPoint = slot->endPoint(); if (baseEndPoint && (!slot->solidReferenceEndPoint() || !visited.contains(baseEndPoint))) queue.append(baseEndPoint); @@ -1154,6 +1157,7 @@ QList WbNodeUtilities::findDescendantNodesOfType(WbNode *node, bool (& const WbBasicJoint *const joint = dynamic_cast(n); if (joint) { + // cppcheck-suppress constVariablePointer WbSolid *endPoint = joint->solidEndPoint(); if (endPoint && (!joint->solidReference() || !visited.contains(endPoint))) queue.append(endPoint); @@ -1175,14 +1179,14 @@ bool WbNodeUtilities::isTemplateRegeneratorField(const WbField *field) { return false; } -bool WbNodeUtilities::isNodeOrAncestorLocked(WbNode *node) { - WbNode *n = node; +bool WbNodeUtilities::isNodeOrAncestorLocked(const WbNode *node) { + const WbNode *n = node; while (n && !n->isWorldRoot()) { - WbBaseNode *baseNode = dynamic_cast(n); + const WbBaseNode *baseNode = dynamic_cast(n); if (baseNode && baseNode->nodeType() == WB_NODE_BILLBOARD) return true; - WbMatter *matter = dynamic_cast(n); + const WbMatter *matter = dynamic_cast(n); if (matter && matter->isLocked()) return true; @@ -1377,6 +1381,7 @@ bool WbNodeUtilities::isSlotTypeMatch(const QString &firstType, const QString &s return false; } +// cppcheck-suppress constParameterPointer bool WbNodeUtilities::validateInsertedNode(WbField *field, const WbNode *newNode, const WbNode *parentNode, bool isInBoundingObject) { if (newNode == NULL || field == NULL || parentNode == NULL) @@ -1405,7 +1410,7 @@ bool WbNodeUtilities::validateInsertedNode(WbField *field, const WbNode *newNode QString errorMessage; if (parentSlot && lowerSlot) errorMessage = QObject::tr("Cannot insert %1 node in '%2' field of %3 node, because a trio of slot is not allowed."); - else if (!parentSlot && !lowerSlot && slot->endPoint()) + else if (!parentSlot && !lowerSlot) errorMessage = QObject::tr("Cannot insert %1 node in '%2' field of %3 node: only a slot can be added in the parent slot."); @@ -1419,7 +1424,7 @@ bool WbNodeUtilities::validateInsertedNode(WbField *field, const WbNode *newNode lowerSlot->validate(internalParentNode, internalField, isInBoundingObject); else if (dynamic_cast(internalParentNode)) { // upper slot - WbField *internalParentField = internalParentNode->parentField(true); + const WbField *internalParentField = internalParentNode->parentField(true); internalParentNode = internalParentNode->parentNode(); newNode->validate(internalParentNode, internalParentField, isInBoundingObject); } else // invalid structure diff --git a/src/webots/nodes/utils/WbNodeUtilities.hpp b/src/webots/nodes/utils/WbNodeUtilities.hpp index 87969f605f1..9433530640b 100644 --- a/src/webots/nodes/utils/WbNodeUtilities.hpp +++ b/src/webots/nodes/utils/WbNodeUtilities.hpp @@ -139,7 +139,7 @@ namespace WbNodeUtilities { bool isSelected(const WbNode *node); // is this node or a WbMatter ancestor of the current node locked - bool isNodeOrAncestorLocked(WbNode *node); + bool isNodeOrAncestorLocked(const WbNode *node); // tests node types bool isGeometryTypeName(const QString &modelName); diff --git a/src/webots/nodes/utils/WbObjectDetection.cpp b/src/webots/nodes/utils/WbObjectDetection.cpp index 7e2b2ec4a81..180ad688422 100644 --- a/src/webots/nodes/utils/WbObjectDetection.cpp +++ b/src/webots/nodes/utils/WbObjectDetection.cpp @@ -154,7 +154,7 @@ bool WbObjectDetection::doesChildrenHaveBoundingObject(const WbSolid *solid) { if (solid->boundingObject()) return true; else { - foreach (WbSolid *sc, solid->solidChildren()) { + foreach (const WbSolid *sc, solid->solidChildren()) { if (doesChildrenHaveBoundingObject(sc)) return true; } @@ -433,7 +433,7 @@ bool WbObjectDetection::isWithinBounds(const WbAffinePlane *frustumPlanes, const return true; } -bool WbObjectDetection::recursivelyCheckIfWithinBounds(WbSolid *solid, const bool boundsInitialized, +bool WbObjectDetection::recursivelyCheckIfWithinBounds(const WbSolid *solid, const bool boundsInitialized, const WbAffinePlane *frustumPlanes) { bool initialized = boundsInitialized; if (initialized) { @@ -442,7 +442,7 @@ bool WbObjectDetection::recursivelyCheckIfWithinBounds(WbSolid *solid, const boo mergeBounds(mObjectSize, mObjectRelativePosition, newObjectSize, newObjectRelativePosition); } else initialized = isWithinBounds(frustumPlanes, solid->boundingObject(), mObjectSize, mObjectRelativePosition, solid); - foreach (WbSolid *s, solid->solidChildren()) + foreach (const WbSolid *s, solid->solidChildren()) initialized = recursivelyCheckIfWithinBounds(s, initialized, frustumPlanes); return initialized; } diff --git a/src/webots/nodes/utils/WbObjectDetection.hpp b/src/webots/nodes/utils/WbObjectDetection.hpp index 3a1e7033631..d7b3db70dbc 100644 --- a/src/webots/nodes/utils/WbObjectDetection.hpp +++ b/src/webots/nodes/utils/WbObjectDetection.hpp @@ -82,7 +82,7 @@ class WbObjectDetection { bool isWithinBounds(const WbAffinePlane *frustumPlanes, const WbBaseNode *boundingObject, WbVector3 &objectSize, WbVector3 &objectRelativePosition, const WbBaseNode *rootObject = NULL); // Checks whether the object and its solid children are inside the `frustumPlanes` frustum. - bool recursivelyCheckIfWithinBounds(WbSolid *solid, const bool boundsInitialized, const WbAffinePlane *frustumPlanes); + bool recursivelyCheckIfWithinBounds(const WbSolid *solid, const bool boundsInitialized, const WbAffinePlane *frustumPlanes); virtual double distance() = 0; void createRays(const WbVector3 &origin, const QList &directions, const WbVector3 &offset); diff --git a/src/webots/nodes/utils/WbPaintTexture.cpp b/src/webots/nodes/utils/WbPaintTexture.cpp index 4dfb5a0f680..bde4ce914bd 100644 --- a/src/webots/nodes/utils/WbPaintTexture.cpp +++ b/src/webots/nodes/utils/WbPaintTexture.cpp @@ -105,8 +105,8 @@ WbPaintTexture::WbPaintTexture(const WbShape *shape) : mShape(shape), mEvaporati mTexture = wr_drawable_texture_new(); // add painting layer - WbAppearance *appearance = shape->appearance(); - WbPbrAppearance *pbrAppearance = shape->pbrAppearance(); + const WbAppearance *appearance = shape->appearance(); + const WbPbrAppearance *pbrAppearance = shape->pbrAppearance(); if (appearance && appearance->texture() && appearance->texture()->wrenTexture()) mTextureSize = computeTextureSize(appearance->texture()->width(), appearance->texture()->height()); else if (pbrAppearance && pbrAppearance->baseColorMap() && pbrAppearance->baseColorMap()->wrenTexture()) @@ -156,7 +156,7 @@ WbPaintTexture::~WbPaintTexture() { } void WbPaintTexture::prePhysicsStep(double ms) { - WbWorldInfo *wi = WbWorld::instance()->worldInfo(); + const WbWorldInfo *wi = WbWorld::instance()->worldInfo(); double ie = wi->inkEvaporation(); if (ie) { diff --git a/src/webots/nodes/utils/WbSupervisorUtilities.cpp b/src/webots/nodes/utils/WbSupervisorUtilities.cpp index 62ccb54bb1c..f929554cd1e 100644 --- a/src/webots/nodes/utils/WbSupervisorUtilities.cpp +++ b/src/webots/nodes/utils/WbSupervisorUtilities.cpp @@ -525,7 +525,7 @@ void WbSupervisorUtilities::updateProtoRegeneratedFlag(WbNode *node) { if (mWatchedFields.isEmpty()) return; const int nodeId = node->uniqueId(); - foreach (const WbUpdatedFieldInfo info, mWatchedFields) { + foreach (const WbUpdatedFieldInfo &info, mWatchedFields) { if (info.nodeId == nodeId) { const WbField *field = node->findField(info.fieldName, false); assert(field->isMultiple() || field->type() == WB_SF_NODE); @@ -699,7 +699,7 @@ void WbSupervisorUtilities::handleMessage(QDataStream &stream) { return; } - WbWrenLabelOverlay *existingLabel = WbWrenLabelOverlay::retrieveById(labelId); + const WbWrenLabelOverlay *existingLabel = WbWrenLabelOverlay::retrieveById(labelId); if (existingLabel && x == existingLabel->x() && y == existingLabel->y() && size == existingLabel->size() && filename == existingLabel->font() && text == existingLabel->text()) { const float *oldColors = existingLabel->color(); @@ -789,7 +789,7 @@ void WbSupervisorUtilities::handleMessage(QDataStream &stream) { const QString &nodeName = readString(stream); int parentProtoId; stream >> parentProtoId; // if > 0, then search for a PROTO internal node - WbNode *proto = parentProtoId > 0 ? WbNode::findNode(parentProtoId) : NULL; + const WbNode *proto = parentProtoId > 0 ? WbNode::findNode(parentProtoId) : NULL; const WbBaseNode *baseNode = dynamic_cast(getNodeFromDEF(nodeName, proto != NULL, proto)); if (!proto && baseNode && !baseNode->parentField()) // make sure the parent field is visible baseNode = NULL; @@ -1147,7 +1147,7 @@ void WbSupervisorUtilities::handleMessage(QDataStream &stream) { case C_SUPERVISOR_NODE_EXPORT_STRING: { unsigned int nodeId; stream >> nodeId; - WbNode *node = WbNode::findNode(nodeId); + const WbNode *node = WbNode::findNode(nodeId); mNodeExportString = WbVrmlNodeUtilities::exportNodeToString(node); mNodeExportStringRequest = true; @@ -1183,7 +1183,7 @@ void WbSupervisorUtilities::handleMessage(QDataStream &stream) { stream >> nodeId; stream >> allowSearchInProto; - WbNode *const node = WbNode::findNode(nodeId); + const WbNode *const node = WbNode::findNode(nodeId); if (node) mNodeFieldCount = allowSearchInProto == 1 ? node->fields().size() : node->numFields(); else @@ -1400,7 +1400,7 @@ void WbSupervisorUtilities::handleMessage(QDataStream &stream) { if (enable) stream >> samplingPeriod; - WbNode *const node = WbNode::findNode(nodeId); + const WbNode *const node = WbNode::findNode(nodeId); if (!node) { mRobot->warn(tr("'wb_supervisor_field_%1_sf_tracking' called for an invalid node.").arg(enable ? "enable" : "disable")); return; @@ -1454,7 +1454,7 @@ void WbSupervisorUtilities::handleMessage(QDataStream &stream) { stream >> fieldId; stream >> internal; - WbNode *const node = WbNode::findNode(uniqueId); + const WbNode *const node = WbNode::findNode(uniqueId); WbField *field = NULL; if (node) { @@ -1479,7 +1479,7 @@ void WbSupervisorUtilities::handleMessage(QDataStream &stream) { stream >> fieldId; stream >> fieldType; stream >> index; - WbNode *const node = WbNode::findNode(uniqueId); + const WbNode *const node = WbNode::findNode(uniqueId); WbField *field = node ? node->field(fieldId) : NULL; // we read the data depending on the field type @@ -1550,8 +1550,8 @@ void WbSupervisorUtilities::handleMessage(QDataStream &stream) { // apply queued set field operations processImmediateMessages(true); - WbNode *const node = WbNode::findNode(nodeId); - WbField *field = node->field(fieldId); + const WbNode *const node = WbNode::findNode(nodeId); + const WbField *field = node->field(fieldId); switch (field->type()) { // import value case WB_MF_BOOL: { @@ -1669,7 +1669,7 @@ void WbSupervisorUtilities::handleMessage(QDataStream &stream) { processImmediateMessages(true); bool modified = false; - WbNode *parentNode = WbNode::findNode(nodeId); + const WbNode *parentNode = WbNode::findNode(nodeId); WbField *field = parentNode->field(fieldId); switch (field->type()) { // remove value case WB_MF_BOOL: @@ -1687,12 +1687,12 @@ void WbSupervisorUtilities::handleMessage(QDataStream &stream) { break; } case WB_MF_NODE: { - WbMFNode *mfNode = dynamic_cast(field->value()); + const WbMFNode *mfNode = dynamic_cast(field->value()); assert(mfNode->size() > index); WbNode *node = mfNode->item(index); - WbViewpoint *viewpoint = dynamic_cast(node); - WbWorldInfo *worldInfo = dynamic_cast(node); + const WbViewpoint *viewpoint = dynamic_cast(node); + const WbWorldInfo *worldInfo = dynamic_cast(node); if (viewpoint || worldInfo) { node = NULL; mRobot->warn(tr( @@ -1710,7 +1710,7 @@ void WbSupervisorUtilities::handleMessage(QDataStream &stream) { break; } case WB_SF_NODE: { - WbSFNode *sfNode = dynamic_cast(field->value()); + const WbSFNode *sfNode = dynamic_cast(field->value()); if (sfNode->value()) { if (sfNode->value() == mRobot) mShouldRemoveNode = true; @@ -2145,7 +2145,7 @@ void WbSupervisorUtilities::writeAnswer(WbDataStream &stream) { mFieldGetRequest = NULL; } if (!mUpdatedFields.isEmpty()) { - foreach (const WbUpdatedFieldInfo info, mUpdatedFields) { + foreach (const WbUpdatedFieldInfo &info, mUpdatedFields) { stream << (short unsigned int)0; stream << (unsigned char)C_SUPERVISOR_FIELD_COUNT_CHANGED; stream << (int)info.nodeId; diff --git a/src/webots/nodes/utils/WbTemplateManager.cpp b/src/webots/nodes/utils/WbTemplateManager.cpp index 25ae0411858..3bfda1e37c6 100644 --- a/src/webots/nodes/utils/WbTemplateManager.cpp +++ b/src/webots/nodes/utils/WbTemplateManager.cpp @@ -91,7 +91,7 @@ void WbTemplateManager::blockRegeneration(bool block) { } void WbTemplateManager::clear() { - foreach (WbNode *node, mTemplates) + foreach (const WbNode *node, mTemplates) disconnect(node, &WbNode::regenerationRequired, this, &WbTemplateManager::nodeNeedRegeneration); mTemplates.clear(); } @@ -121,7 +121,7 @@ bool WbTemplateManager::nodeNeedsToSubscribe(WbNode *node) { if (!node->isProtoInstance()) return false; - foreach (WbField *field, node->fieldsOrParameters()) { + foreach (const WbField *field, node->fieldsOrParameters()) { if (!field->alias().isEmpty()) return true; } @@ -237,7 +237,7 @@ void WbTemplateManager::regenerateNode(WbNode *node, bool restarted) { WbField *parentField = node->parentField(); QVector parameters; WbNode::setRestoreUniqueIdOnClone(true); - foreach (WbField *parameter, node->parameters()) { + foreach (const WbField *parameter, node->parameters()) { parameters << new WbField(*parameter, NULL); if (parameter->parameter() != NULL) previousParentRedirections.append(parameter->parameter()); @@ -299,7 +299,7 @@ void WbTemplateManager::regenerateNode(WbNode *node, bool restarted) { if (node->isProtoParameterNode()) { // internal PROTO child could be regenerated due to a parameter exposed in the parent PROTO node // so for parent PROTO instances both fields and parameters needs to be checked - const QList parentFields = (parent->isProtoInstance() ? parent->parameters() : QList()) + const QList parentFields = (parent->isProtoInstance() ? QList(parent->parameters()) : QList()) << parent->fields(); foreach (WbField *const pf, parentFields) { if (pf->type() == WB_SF_NODE) { @@ -321,7 +321,7 @@ void WbTemplateManager::regenerateNode(WbNode *node, bool restarted) { WbMFNode *mfnode = static_cast(pf->value()); bool found = false; for (int i = 0; i < mfnode->size(); ++i) { - WbNode *n = mfnode->item(i); + const WbNode *n = mfnode->item(i); if (n == node) { if (ancestorTemplateRegeneration) mfnode->blockSignals(true); @@ -351,7 +351,7 @@ void WbTemplateManager::regenerateNode(WbNode *node, bool restarted) { WbGroup *const parentGroup = dynamic_cast(parent); WbBasicJoint *const parentJoint = dynamic_cast(parent); WbShape *const parentShape = dynamic_cast(parent); - WbSkin *const parentSkin = dynamic_cast(parent); + const WbSkin *const parentSkin = dynamic_cast(parent); WbSlot *const parentSlot = dynamic_cast(parent); WbAppearance *const newAppearance = dynamic_cast(newNode); WbPbrAppearance *const newPbrAppearance = dynamic_cast(newNode); diff --git a/src/webots/nodes/utils/WbTriangleMeshCache.cpp b/src/webots/nodes/utils/WbTriangleMeshCache.cpp index 3b748ffddf5..dbecb2a6413 100644 --- a/src/webots/nodes/utils/WbTriangleMeshCache.cpp +++ b/src/webots/nodes/utils/WbTriangleMeshCache.cpp @@ -44,11 +44,11 @@ namespace WbTriangleMeshCache { TriangleMeshGeometryKey::TriangleMeshGeometryKey() { mHash = 0; } - TriangleMeshGeometryKey::TriangleMeshGeometryKey(WbTriangleMeshGeometry *triangleMeshGeometry) { + TriangleMeshGeometryKey::TriangleMeshGeometryKey(const WbTriangleMeshGeometry *triangleMeshGeometry) { set(triangleMeshGeometry); } - void TriangleMeshGeometryKey::set(WbTriangleMeshGeometry *triangleMeshGeometry) { + void TriangleMeshGeometryKey::set(const WbTriangleMeshGeometry *triangleMeshGeometry) { mHash = triangleMeshGeometry->computeHash(); } diff --git a/src/webots/nodes/utils/WbTriangleMeshCache.hpp b/src/webots/nodes/utils/WbTriangleMeshCache.hpp index 70f90c70df5..5e3185f96e3 100644 --- a/src/webots/nodes/utils/WbTriangleMeshCache.hpp +++ b/src/webots/nodes/utils/WbTriangleMeshCache.hpp @@ -39,9 +39,9 @@ namespace WbTriangleMeshCache { // Key type for an instance of WbTriangleMeshGeometry. Instances can share a WbTriangleMesh if their keys compare equal. struct TriangleMeshGeometryKey { TriangleMeshGeometryKey(); - explicit TriangleMeshGeometryKey(WbTriangleMeshGeometry *triangleMeshGeometry); + explicit TriangleMeshGeometryKey(const WbTriangleMeshGeometry *triangleMeshGeometry); - void set(WbTriangleMeshGeometry *triangleMeshGeometry); + void set(const WbTriangleMeshGeometry *triangleMeshGeometry); bool operator==(const TriangleMeshGeometryKey &rhs) const; uint64_t mHash; diff --git a/src/webots/nodes/utils/WbVirtualRealityHeadset.cpp b/src/webots/nodes/utils/WbVirtualRealityHeadset.cpp index fddc8196dad..07f7653fce8 100644 --- a/src/webots/nodes/utils/WbVirtualRealityHeadset.cpp +++ b/src/webots/nodes/utils/WbVirtualRealityHeadset.cpp @@ -335,7 +335,7 @@ void WbVirtualRealityHeadset::createWrenObjects(WrTransform *node, bool antiAlia connect(mTimer, &QTimer::timeout, this, &WbVirtualRealityHeadset::renderRequired); - WbSimulationState *simulationState = WbSimulationState::instance(); + const WbSimulationState *simulationState = WbSimulationState::instance(); connect(WbSimulationState::instance(), &WbSimulationState::modeChanged, this, &WbVirtualRealityHeadset::updateTimer); if (simulationState->isPaused() || simulationState->isStep()) mTimer->start(1000.0 / WbWorld::instance()->worldInfo()->fps()); @@ -419,7 +419,7 @@ void WbVirtualRealityHeadset::updateOrientationAndPosition() { } void WbVirtualRealityHeadset::updateTimer() { - WbSimulationState *simulationState = WbSimulationState::instance(); + const WbSimulationState *simulationState = WbSimulationState::instance(); if (simulationState->isPaused() || simulationState->isStep()) mTimer->start(1000.0 / WbWorld::instance()->worldInfo()->fps()); else diff --git a/src/webots/nodes/utils/WbVisualBoundingSphere.cpp b/src/webots/nodes/utils/WbVisualBoundingSphere.cpp index d537e23e36f..721e8197b1d 100644 --- a/src/webots/nodes/utils/WbVisualBoundingSphere.cpp +++ b/src/webots/nodes/utils/WbVisualBoundingSphere.cpp @@ -120,7 +120,7 @@ void WbVisualBoundingSphere::show(const WbBaseNode *node) { return; } - WbBoundingSphere *boundingSphere = node ? node->boundingSphere() : NULL; + const WbBoundingSphere *boundingSphere = node ? node->boundingSphere() : NULL; if (!boundingSphere) { if (mInitialized) wr_node_set_visible(WR_NODE(mWrenScaleTransform), false); diff --git a/src/webots/nodes/utils/WbWorld.cpp b/src/webots/nodes/utils/WbWorld.cpp index 2e12687f4d0..5f57f617ee2 100644 --- a/src/webots/nodes/utils/WbWorld.cpp +++ b/src/webots/nodes/utils/WbWorld.cpp @@ -124,7 +124,7 @@ WbWorld::WbWorld(WbTokenizer *tokenizer) : return; } WbTemplateManager::instance()->blockRegeneration(true); - WbField *childrenField = mRoot->findField("children"); + const WbField *childrenField = mRoot->findField("children"); int index = 0; WbApplication::instance()->setWorldLoadingStatus(tr("Creating nodes")); foreach (WbNode *node, nodes) { @@ -460,6 +460,7 @@ QList WbWorld::findSolids(bool visibleNodes) const { QList allSolids; foreach (WbNode *const node, allNodes) { + // cppcheck-suppress constVariablePointer WbSolid *const solid = dynamic_cast(node); if (solid) allSolids.append(solid); @@ -561,7 +562,7 @@ void WbWorld::retrieveNodeNamesWithOptionalRendering(QStringList ¢erOfMassNo centerOfBuoyancyNodeNames.clear(); supportPolygonNodeNames.clear(); - WbSolid *solid = NULL; + const WbSolid *solid = NULL; const QList &allNodes = mRoot->subNodes(true); for (int i = 0; i < allNodes.size(); ++i) { solid = dynamic_cast(allNodes[i]); @@ -583,17 +584,17 @@ QString WbWorld::logWorldMetrics() const { int jointCount = 0; int geomCount = 0; const QList &allNodes = mRoot->subNodes(true); - foreach (WbNode *node, allNodes) { - if (dynamic_cast(node)) { + foreach (const WbNode *node, allNodes) { + if (dynamic_cast(node)) { jointCount++; continue; } - WbSolid *solid = dynamic_cast(node); + const WbSolid *solid = dynamic_cast(node); if (solid && (solid->isKinematic() || solid->isSolidMerger())) { solidCount++; continue; } - WbGeometry *geometry = dynamic_cast(node); + const WbGeometry *geometry = dynamic_cast(node); if (geometry && !geometry->isInBoundingObject()) geomCount++; } diff --git a/src/webots/nodes/utils/WbWorld.hpp b/src/webots/nodes/utils/WbWorld.hpp index 61d2b4e308b..f84d4054152 100644 --- a/src/webots/nodes/utils/WbWorld.hpp +++ b/src/webots/nodes/utils/WbWorld.hpp @@ -106,18 +106,18 @@ class WbWorld : public QObject { QList findSolids(bool visibleNodes = false) const; // return the list of all robots - QList robots() const { return mRobots; } + const QList &robots() const { return mRobots; } // return the list of all top solids (not looking recursively) - QList topSolids() const { return mTopSolids; } + const QList &topSolids() const { return mTopSolids; } // return the list of all solids that have a positive radar cross-section (radar target) - QList radarTargetSolids() const { return mRadarTargets; } + const QList &radarTargetSolids() const { return mRadarTargets; } void addRadarTarget(WbSolid *target) { mRadarTargets.append(target); } void removeRadarTarget(WbSolid *target) { mRadarTargets.removeAll(target); } // return the list of all solids that have a non-empty 'recognitionColors' field - QList cameraRecognitionObjects() const { return mCameraRecognitionObjects; } + const QList &cameraRecognitionObjects() const { return mCameraRecognitionObjects; } void addCameraRecognitionObject(WbSolid *object) { mCameraRecognitionObjects.append(object); } void removeCameraRecognitionObject(WbSolid *object) { mCameraRecognitionObjects.removeAll(object); } diff --git a/src/webots/nodes/utils/WbWrenVertexArrayFrameListener.cpp b/src/webots/nodes/utils/WbWrenVertexArrayFrameListener.cpp index caa43fa8428..aa82509167a 100644 --- a/src/webots/nodes/utils/WbWrenVertexArrayFrameListener.cpp +++ b/src/webots/nodes/utils/WbWrenVertexArrayFrameListener.cpp @@ -53,6 +53,7 @@ WbWrenVertexArrayFrameListener::~WbWrenVertexArrayFrameListener() { wr_scene_remove_frame_listener(wr_scene_get_instance(), &processEvent); } +// cppcheck-suppress constParameterPointer void WbWrenVertexArrayFrameListener::subscribeTrack(WbTrack *track) { if (mTrackList.contains(track)) return; @@ -60,6 +61,7 @@ void WbWrenVertexArrayFrameListener::subscribeTrack(WbTrack *track) { updateListening(); } +// cppcheck-suppress constParameterPointer void WbWrenVertexArrayFrameListener::subscribeMuscle(WbMuscle *muscle) { if (mMuscleList.contains(muscle)) return; @@ -67,11 +69,13 @@ void WbWrenVertexArrayFrameListener::subscribeMuscle(WbMuscle *muscle) { updateListening(); } +// cppcheck-suppress constParameterPointer void WbWrenVertexArrayFrameListener::unsubscribeTrack(WbTrack *track) { mTrackList.removeAll(track); updateListening(); } +// cppcheck-suppress constParameterPointer void WbWrenVertexArrayFrameListener::unsubscribeMuscle(WbMuscle *muscle) { mMuscleList.removeAll(muscle); updateListening(); diff --git a/src/webots/plugins/WbPhysicsPlugin.cpp b/src/webots/plugins/WbPhysicsPlugin.cpp index 60dda490af5..c471d09630f 100644 --- a/src/webots/plugins/WbPhysicsPlugin.cpp +++ b/src/webots/plugins/WbPhysicsPlugin.cpp @@ -281,7 +281,7 @@ QString WbPhysicsPlugin::findSourceFileForPlugin(const QString &name) { return path; // search in projects folder of loaded PROTOs - foreach (WbProtoModel *model, WbProtoManager::instance()->models()) { + foreach (const WbProtoModel *model, WbProtoManager::instance()->models()) { if (!model->path().isEmpty()) { path = model->path() + "../" + fileName; if (QFile::exists(path)) diff --git a/src/webots/plugins/WbPhysicsPlugin.hpp b/src/webots/plugins/WbPhysicsPlugin.hpp index 7b3239a4682..9f27e8bd9c6 100644 --- a/src/webots/plugins/WbPhysicsPlugin.hpp +++ b/src/webots/plugins/WbPhysicsPlugin.hpp @@ -33,7 +33,7 @@ class WbPhysicsPlugin : public WbPlugin { // constructor & destructor // name: name of the plugin, e.g. "salamander_physics" explicit WbPhysicsPlugin(const QString &name); - virtual ~WbPhysicsPlugin(); + virtual ~WbPhysicsPlugin() override; // reimplemented public functions bool load() override; diff --git a/src/webots/plugins/WbPlugin.cpp b/src/webots/plugins/WbPlugin.cpp index ef8be18bc24..606adf80d65 100644 --- a/src/webots/plugins/WbPlugin.cpp +++ b/src/webots/plugins/WbPlugin.cpp @@ -86,7 +86,7 @@ bool WbPlugin::load() { QStringList possibleDirPaths; possibleDirPaths << WbProject::current()->path() + pluginName; - foreach (WbProtoModel *model, WbProtoManager::instance()->models()) + foreach (const WbProtoModel *model, WbProtoManager::instance()->models()) possibleDirPaths << QDir(model->path() + "../" + pluginName).absolutePath() + "/"; possibleDirPaths << WbStandardPaths::projectsPath() + "default/" + pluginName; possibleDirPaths << WbStandardPaths::resourcesProjectsPath() + pluginName; diff --git a/src/webots/plugins/WbRadioPlugin.hpp b/src/webots/plugins/WbRadioPlugin.hpp index 3399cd59d87..78a2930a8c7 100644 --- a/src/webots/plugins/WbRadioPlugin.hpp +++ b/src/webots/plugins/WbRadioPlugin.hpp @@ -54,7 +54,7 @@ class WbRadioPlugin : public WbPlugin { // constructor & destructor // name: name of the plugin, e.g. "omnet" explicit WbRadioPlugin(const QString &name); - virtual ~WbRadioPlugin(); + virtual ~WbRadioPlugin() override; protected: // reimplemented protected functions diff --git a/src/webots/scene_tree/WbBoolEditor.cpp b/src/webots/scene_tree/WbBoolEditor.cpp index 32088681e77..011b0e59ec3 100644 --- a/src/webots/scene_tree/WbBoolEditor.cpp +++ b/src/webots/scene_tree/WbBoolEditor.cpp @@ -91,12 +91,12 @@ void WbBoolEditor::apply() { mBool = field()->hasRestrictedValues() ? mComboBox->currentText() == "TRUE" : mCheckBox->checkState(); if (singleValue()) { - WbSFBool *const sfBool = static_cast(singleValue()); + const WbSFBool *const sfBool = static_cast(singleValue()); if (sfBool->value() == mBool) return; mPreviousValue->setBool(sfBool->value()); } else if (multipleValue()) { - WbMFBool *const mfBool = static_cast(multipleValue()); + const WbMFBool *const mfBool = static_cast(multipleValue()); if (mfBool->item(index()) == mBool) return; mPreviousValue->setBool(mfBool->item(index())); diff --git a/src/webots/scene_tree/WbBoolEditor.hpp b/src/webots/scene_tree/WbBoolEditor.hpp index fa3576b5612..0826248e229 100644 --- a/src/webots/scene_tree/WbBoolEditor.hpp +++ b/src/webots/scene_tree/WbBoolEditor.hpp @@ -28,7 +28,7 @@ class WbBoolEditor : public WbValueEditor { public: explicit WbBoolEditor(QWidget *parent = NULL); - virtual ~WbBoolEditor(); + virtual ~WbBoolEditor() override; void recursiveBlockSignals(bool block) override; diff --git a/src/webots/scene_tree/WbColorEditor.cpp b/src/webots/scene_tree/WbColorEditor.cpp index 275719122a1..2e35ec98aff 100644 --- a/src/webots/scene_tree/WbColorEditor.cpp +++ b/src/webots/scene_tree/WbColorEditor.cpp @@ -164,14 +164,14 @@ void WbColorEditor::apply() { updateButton(); if (singleValue()) { - WbSFColor *const sfColor = static_cast(singleValue()); + const WbSFColor *const sfColor = static_cast(singleValue()); if (sfColor->value() == mRgb) return; mPreviousValue->setColor(sfColor->value()); } else if (multipleValue()) { - WbMFColor *const mfColor = static_cast(multipleValue()); + const WbMFColor *const mfColor = static_cast(multipleValue()); if (mfColor->item(index()) == mRgb) return; diff --git a/src/webots/scene_tree/WbColorEditor.hpp b/src/webots/scene_tree/WbColorEditor.hpp index 353bab362a0..d18050d120f 100644 --- a/src/webots/scene_tree/WbColorEditor.hpp +++ b/src/webots/scene_tree/WbColorEditor.hpp @@ -31,7 +31,7 @@ class WbColorEditor : public WbValueEditor { public: explicit WbColorEditor(QWidget *parent = NULL); - virtual ~WbColorEditor(); + virtual ~WbColorEditor() override; void recursiveBlockSignals(bool block) override; diff --git a/src/webots/scene_tree/WbDoubleEditor.cpp b/src/webots/scene_tree/WbDoubleEditor.cpp index 4bf94f9eee7..a1af6e2a6b6 100644 --- a/src/webots/scene_tree/WbDoubleEditor.cpp +++ b/src/webots/scene_tree/WbDoubleEditor.cpp @@ -83,14 +83,14 @@ void WbDoubleEditor::apply() { mDouble = field()->hasRestrictedValues() ? mComboBox->currentText().toDouble() : WbPrecision::roundValue(mSpinBox->value(), WbPrecision::GUI_MEDIUM); if (singleValue()) { - WbSFDouble *const sfDouble = static_cast(singleValue()); + const WbSFDouble *const sfDouble = static_cast(singleValue()); if (sfDouble->value() == mDouble) return; mPreviousValue->setDouble(sfDouble->value()); } else if (multipleValue()) { - WbMFDouble *const mfDouble = static_cast(multipleValue()); + const WbMFDouble *const mfDouble = static_cast(multipleValue()); if (mfDouble->item(index()) == mDouble) return; diff --git a/src/webots/scene_tree/WbDoubleEditor.hpp b/src/webots/scene_tree/WbDoubleEditor.hpp index 26684db0b0a..106a15ff75d 100644 --- a/src/webots/scene_tree/WbDoubleEditor.hpp +++ b/src/webots/scene_tree/WbDoubleEditor.hpp @@ -28,7 +28,7 @@ class WbDoubleEditor : public WbValueEditor { public: explicit WbDoubleEditor(QWidget *parent = NULL); - virtual ~WbDoubleEditor(); + virtual ~WbDoubleEditor() override; void recursiveBlockSignals(bool block) override; diff --git a/src/webots/scene_tree/WbExtendedStringEditor.cpp b/src/webots/scene_tree/WbExtendedStringEditor.cpp index eb0af442ecc..0f9709048a2 100644 --- a/src/webots/scene_tree/WbExtendedStringEditor.cpp +++ b/src/webots/scene_tree/WbExtendedStringEditor.cpp @@ -214,7 +214,7 @@ void WbExtendedStringEditor::editInTextEditor() { // Searches into the controllers/plugins associated with selected proto instance if (dirLocation == noFile && node()->isProtoInstance()) { - WbProtoModel *proto = node()->proto(); + const WbProtoModel *proto = node()->proto(); if (!proto->projectPath().isEmpty()) { QDir protoDir(proto->projectPath() + "/" + ITEM_LIST_INFO[mStringType].at(0) + stringValue()); if (protoDir.exists()) { @@ -231,7 +231,7 @@ void WbExtendedStringEditor::editInTextEditor() { // Searches into the protos/../plugins of all the loaded protos // needed to load physics plugins if (dirLocation == noFile && isWorldInfoPluginType(mStringType)) { - foreach (WbProtoModel *model, WbProtoManager::instance()->models()) { + foreach (const WbProtoModel *model, WbProtoManager::instance()->models()) { QDir protoDir(model->path() + "../" + ITEM_LIST_INFO[mStringType].at(0) + stringValue()); if (protoDir.exists()) { dirLocation = externalProtoFile; @@ -331,7 +331,7 @@ void WbExtendedStringEditor::editInTextEditor() { dirPath += fileType + stringValue(); QStringList files = QFileDialog::getOpenFileNames(this, ITEM_LIST_INFO[mStringType].at(1), dirPath); - foreach (QString fileName, files) + foreach (const QString &fileName, files) emit editRequested(fileName); } @@ -360,7 +360,7 @@ void WbExtendedStringEditor::select() { // needed only for physics plugins // add protos/../plugins if (isWorldInfoPluginType(mStringType)) { - foreach (WbProtoModel *model, WbProtoManager::instance()->models()) { + foreach (const WbProtoModel *model, WbProtoManager::instance()->models()) { if (!model->path().isEmpty()) { QDir dir(model->path() + "../" + ITEM_LIST_INFO[mStringType].at(0)); items += dir.entryList(FILTERS); @@ -452,7 +452,7 @@ void WbExtendedStringEditor::edit(bool copyOriginalValue) { WbStringEditor::edit(copyOriginalValue); if (copyOriginalValue) { - WbField *effectiveField = field(); + const WbField *effectiveField = field(); if (effectiveField->isParameter()) effectiveField = effectiveField->internalFields().at(0); @@ -475,8 +475,8 @@ void WbExtendedStringEditor::selectFile(const QString &folder, const QString &ti if (!stringValue().isEmpty()) { QDir dir(QDir::cleanPath(worldPath.absoluteFilePath(stringValue()))); - dir.cdUp(); - path = dir.absolutePath(); + if (dir.cdUp()) + path = dir.absolutePath(); } else { if (worldPath.exists(folder)) path += folder + '/'; @@ -497,7 +497,7 @@ bool WbExtendedStringEditor::populateItems(QStringList &items) { const WbNode *const np = field()->parentNode(); assert(np); const WbSolid *const upperSolid = WbNodeUtilities::findUpperSolid(np); - WbSolid *const topSolid = upperSolid->topSolid(); + const WbSolid *const topSolid = upperSolid->topSolid(); items << WbSolidReference::STATIC_ENVIRONMENT; topSolid->collectSolidDescendantNames(items, upperSolid); break; diff --git a/src/webots/scene_tree/WbExtendedStringEditor.hpp b/src/webots/scene_tree/WbExtendedStringEditor.hpp index db23706b3fe..ce3cc33bd21 100644 --- a/src/webots/scene_tree/WbExtendedStringEditor.hpp +++ b/src/webots/scene_tree/WbExtendedStringEditor.hpp @@ -28,7 +28,7 @@ class WbExtendedStringEditor : public WbStringEditor { public: explicit WbExtendedStringEditor(QWidget *parent = NULL); - virtual ~WbExtendedStringEditor(); + virtual ~WbExtendedStringEditor() override; void recursiveBlockSignals(bool block) override; diff --git a/src/webots/scene_tree/WbExternProtoEditor.hpp b/src/webots/scene_tree/WbExternProtoEditor.hpp index b89bb45d965..a6f875cbf26 100644 --- a/src/webots/scene_tree/WbExternProtoEditor.hpp +++ b/src/webots/scene_tree/WbExternProtoEditor.hpp @@ -28,7 +28,7 @@ class WbExternProtoEditor : public WbValueEditor { public: explicit WbExternProtoEditor(QWidget *parent = NULL); - virtual ~WbExternProtoEditor(); + virtual ~WbExternProtoEditor() override; void recursiveBlockSignals(bool block) override {} void edit(WbNode *node, WbField *field, int index) override {} diff --git a/src/webots/scene_tree/WbFieldDoubleSpinBox.hpp b/src/webots/scene_tree/WbFieldDoubleSpinBox.hpp index 429f5c6eda6..7f0abd9d02e 100644 --- a/src/webots/scene_tree/WbFieldDoubleSpinBox.hpp +++ b/src/webots/scene_tree/WbFieldDoubleSpinBox.hpp @@ -33,7 +33,7 @@ class WbFieldDoubleSpinBox : public WbDoubleSpinBox { public: enum { NORMAL, RADIANS, AXIS, RGB }; explicit WbFieldDoubleSpinBox(QWidget *parent = NULL, int mode = NORMAL); - virtual ~WbFieldDoubleSpinBox(); + virtual ~WbFieldDoubleSpinBox() override; void setValueNoSignals(double value); void setMode(int mode); diff --git a/src/webots/scene_tree/WbFieldEditor.cpp b/src/webots/scene_tree/WbFieldEditor.cpp index d4b15f23471..1d72afafb74 100644 --- a/src/webots/scene_tree/WbFieldEditor.cpp +++ b/src/webots/scene_tree/WbFieldEditor.cpp @@ -179,7 +179,7 @@ void WbFieldEditor::updateTitle() { else if (mField->type() == WB_SF_NODE) title = mField->name() + " " + nodeAsTitle(static_cast(value)->value()); else { - WbMultipleValue *multipleValue = dynamic_cast(value); + const WbMultipleValue *multipleValue = dynamic_cast(value); if (multipleValue) { if (mItem == -1) { int size = multipleValue->size(); @@ -305,7 +305,7 @@ void WbFieldEditor::computeFieldInformation() { // check and store field type information WbValue *const value = mField->value(); WbMultipleValue *const multipleValue = dynamic_cast(value); - WbMFNode *mfNode = NULL; + const WbMFNode *mfNode = NULL; if (multipleValue) { mIsValidItemIndex = (mItem >= 0) && (mItem < multipleValue->size()); @@ -316,7 +316,7 @@ void WbFieldEditor::computeFieldInformation() { mNodeItem = mfNode->item(mItem); } } else { - WbSFNode *const sfNode = dynamic_cast(value); + const WbSFNode *const sfNode = dynamic_cast(value); if (sfNode) mNodeItem = sfNode->value(); } diff --git a/src/webots/scene_tree/WbFieldIntSpinBox.hpp b/src/webots/scene_tree/WbFieldIntSpinBox.hpp index e1e11d781db..3ca3432f35c 100644 --- a/src/webots/scene_tree/WbFieldIntSpinBox.hpp +++ b/src/webots/scene_tree/WbFieldIntSpinBox.hpp @@ -28,7 +28,7 @@ class WbFieldIntSpinBox : public WbIntSpinBox { public: explicit WbFieldIntSpinBox(QWidget *parent = NULL); - virtual ~WbFieldIntSpinBox(); + virtual ~WbFieldIntSpinBox() override; void stepBy(int steps) override; void setValueNoSignals(int value); diff --git a/src/webots/scene_tree/WbFieldLineEdit.hpp b/src/webots/scene_tree/WbFieldLineEdit.hpp index d759b6c4074..34005e11198 100644 --- a/src/webots/scene_tree/WbFieldLineEdit.hpp +++ b/src/webots/scene_tree/WbFieldLineEdit.hpp @@ -26,7 +26,7 @@ class WbFieldLineEdit : public WbLineEdit { public: explicit WbFieldLineEdit(QWidget *parent = 0); - virtual ~WbFieldLineEdit(); + virtual ~WbFieldLineEdit() override; signals: void focusLeft(); diff --git a/src/webots/scene_tree/WbIntEditor.cpp b/src/webots/scene_tree/WbIntEditor.cpp index c7f7ac9c56d..000882d5891 100644 --- a/src/webots/scene_tree/WbIntEditor.cpp +++ b/src/webots/scene_tree/WbIntEditor.cpp @@ -82,14 +82,14 @@ void WbIntEditor::apply() { mInt = field()->hasRestrictedValues() ? mComboBox->currentText().toInt() : mSpinBox->value(); if (singleValue()) { - WbSFInt *const sfInt = static_cast(singleValue()); + const WbSFInt *const sfInt = static_cast(singleValue()); if (sfInt->value() == mInt) return; mPreviousValue->setInt(sfInt->value()); } else if (multipleValue()) { - WbMFInt *const mfInt = static_cast(multipleValue()); + const WbMFInt *const mfInt = static_cast(multipleValue()); if (mfInt->item(index()) == mInt) return; diff --git a/src/webots/scene_tree/WbIntEditor.hpp b/src/webots/scene_tree/WbIntEditor.hpp index 6dadfdb1ab7..36f33dcb4b2 100644 --- a/src/webots/scene_tree/WbIntEditor.hpp +++ b/src/webots/scene_tree/WbIntEditor.hpp @@ -28,7 +28,7 @@ class WbIntEditor : public WbValueEditor { public: explicit WbIntEditor(QWidget *parent = NULL); - virtual ~WbIntEditor(); + virtual ~WbIntEditor() override; void recursiveBlockSignals(bool block) override; diff --git a/src/webots/scene_tree/WbNodePane.hpp b/src/webots/scene_tree/WbNodePane.hpp index 4b70ef64c23..55907bcf013 100644 --- a/src/webots/scene_tree/WbNodePane.hpp +++ b/src/webots/scene_tree/WbNodePane.hpp @@ -34,7 +34,7 @@ class WbNodePane : public WbValueEditor { public: explicit WbNodePane(QWidget *parent = NULL); - virtual ~WbNodePane(); + virtual ~WbNodePane() override; void recursiveBlockSignals(bool block) override; diff --git a/src/webots/scene_tree/WbRotationEditor.cpp b/src/webots/scene_tree/WbRotationEditor.cpp index bac7426dfd5..ec829032195 100644 --- a/src/webots/scene_tree/WbRotationEditor.cpp +++ b/src/webots/scene_tree/WbRotationEditor.cpp @@ -148,14 +148,14 @@ void WbRotationEditor::apply() { mRotation = WbRotation(mComboBox->currentText()); if (singleValue()) { - WbSFRotation *const sfRotation = static_cast(singleValue()); + const WbSFRotation *const sfRotation = static_cast(singleValue()); if (sfRotation->value() == mRotation) return; mPreviousValue->setRotation(sfRotation->value()); } else if (multipleValue()) { - WbMFRotation *const mfRotation = static_cast(multipleValue()); + const WbMFRotation *const mfRotation = static_cast(multipleValue()); if (mfRotation->item(index()) == mRotation) return; diff --git a/src/webots/scene_tree/WbRotationEditor.hpp b/src/webots/scene_tree/WbRotationEditor.hpp index 1acff725033..4981d105518 100644 --- a/src/webots/scene_tree/WbRotationEditor.hpp +++ b/src/webots/scene_tree/WbRotationEditor.hpp @@ -31,7 +31,7 @@ class WbRotationEditor : public WbValueEditor { public: explicit WbRotationEditor(QWidget *parent = NULL); - virtual ~WbRotationEditor(); + virtual ~WbRotationEditor() override; enum RotationType { AXIS_ANGLE = 0, QUATERNIONS }; diff --git a/src/webots/scene_tree/WbSceneTree.cpp b/src/webots/scene_tree/WbSceneTree.cpp index dfc7d50af95..2448eb46774 100644 --- a/src/webots/scene_tree/WbSceneTree.cpp +++ b/src/webots/scene_tree/WbSceneTree.cpp @@ -320,8 +320,8 @@ void WbSceneTree::copy() { row = mSelectedItem->row(); } - WbSingleValue *singleValue = dynamic_cast(value); - WbMultipleValue *multipleValue = dynamic_cast(value); + const WbSingleValue *singleValue = dynamic_cast(value); + const WbMultipleValue *multipleValue = dynamic_cast(value); if (mSelectedItem->isNode() || mSelectedItem->isSFNode()) { const QList clipboardNodes = WbVrmlNodeUtilities::protoNodesInWorldFile(mSelectedItem->node()); if (!WbProtoManager::instance()->externProtoClipboardBuffer().isEmpty()) @@ -453,7 +453,7 @@ void WbSceneTree::pasteInMFValue() { void WbSceneTree::del(WbNode *nodeToDel) { WbNode *node = nodeToDel; - WbTreeItem *deletedItem; + const WbTreeItem *deletedItem; if (node == NULL) { node = mSelectedItem->node(); deletedItem = mSelectedItem; @@ -521,8 +521,8 @@ void WbSceneTree::reset() { // check if referred DEF node is going to be deleted bool containsReferredNode = false; - WbSFNode *sfnode = dynamic_cast(field->value()); - WbMFNode *mfnode = dynamic_cast(field->value()); + const WbSFNode *sfnode = dynamic_cast(field->value()); + const WbMFNode *mfnode = dynamic_cast(field->value()); if (sfnode) { mRowsAreAboutToBeRemoved = sfnode->value(); containsReferredNode = sfnode->value() && WbVrmlNodeUtilities::hasAreferredDefNodeDescendant(sfnode->value()); @@ -669,7 +669,7 @@ void WbSceneTree::transform(const QString &modelName) { // copy fields and adopt children WbNode::setGlobalParentNode(newNode); QVector fields = currentNode->fieldsOrParameters(); - foreach (WbField *originalField, fields) { + foreach (const WbField *originalField, fields) { // copy field if it exists WbField *const newField = newNode->findField(originalField->name()); if (newField) @@ -680,7 +680,7 @@ void WbSceneTree::transform(const QString &modelName) { // reassign pointer in parent WbField *parentField = selectedItem->parent()->field(); - WbNode *upperTemplate = + const WbNode *upperTemplate = WbVrmlNodeUtilities::findUpperTemplateNeedingRegenerationFromField(parentField, currentNode->parentNode()); bool isInsideATemplateRegenerator = upperTemplate && upperTemplate != currentNode; if (selectedItem->isSFNode()) { @@ -823,7 +823,7 @@ void WbSceneTree::moveViewpointToObject() { if (!mSelectedItem) return; - WbTreeItem *itemToMoveTo = mSelectedItem; + const WbTreeItem *itemToMoveTo = mSelectedItem; while (true) { if (itemToMoveTo->isNode() || itemToMoveTo->isSFNode()) { WbNode *node = itemToMoveTo->node(); @@ -914,7 +914,7 @@ void WbSceneTree::addNew() { } // set selected WbField and WbNode - WbTreeItem *selectedFieldItem = NULL; + const WbTreeItem *selectedFieldItem = NULL; WbField *selectedField = NULL; WbNode *selectedNodeParent = NULL; int newNodeIndex = 0; @@ -933,7 +933,7 @@ void WbSceneTree::addNew() { // if multiple item field // directly add item without opening the dialog WbMultipleValue *const mvalue = dynamic_cast(selectedField->value()); - WbMFNode *const mfnode = dynamic_cast(selectedField->value()); + const WbMFNode *const mfnode = dynamic_cast(selectedField->value()); if (mvalue && !mfnode) { if (insertInertiaMatrix(selectedField)) return; @@ -1335,7 +1335,7 @@ void WbSceneTree::prepareNodeRegeneration(WbNode *node, bool nested) { // Store the selected item only if not inside the node which will be regenerated. // Indeed this node (and its WbTreeItem(s)) will be destroyed and recreated. - WbNode *n = NULL; + const WbNode *n = NULL; if (mSelectedItem && !mSelectedItem->isInvalid()) { if (mSelectedItem->isField()) { const WbSFNode *const sfnode = dynamic_cast(mSelectedItem->field()->value()); diff --git a/src/webots/scene_tree/WbSceneTreeModel.cpp b/src/webots/scene_tree/WbSceneTreeModel.cpp index 9a21085dd18..a4559f2a333 100644 --- a/src/webots/scene_tree/WbSceneTreeModel.cpp +++ b/src/webots/scene_tree/WbSceneTreeModel.cpp @@ -412,7 +412,7 @@ QModelIndex WbSceneTreeModel::findModelIndexFromField(WbField *field, WbTreeItem ///////////////////////////////////////////// int WbSceneTreeModel::itemToTreeIndex(WbTreeItem *item) const { - WbTreeItem *const targetItem = item; + const WbTreeItem *const targetItem = item; bool itemFound = false; int itemIndex = 0; const int n = mRootItem->childCount(); diff --git a/src/webots/scene_tree/WbStringEditor.cpp b/src/webots/scene_tree/WbStringEditor.cpp index 614a96fecba..494951bd3cc 100644 --- a/src/webots/scene_tree/WbStringEditor.cpp +++ b/src/webots/scene_tree/WbStringEditor.cpp @@ -74,14 +74,14 @@ void WbStringEditor::apply() { mString = field()->hasRestrictedValues() ? mComboBox->currentText() : mLineEdit->text(); if (singleValue()) { - WbSFString *const sfString = static_cast(singleValue()); + const WbSFString *const sfString = static_cast(singleValue()); if (sfString->value() == mString) return; mPreviousValue->setString(sfString->value()); } else if (multipleValue()) { - WbMFString *const mfString = static_cast(multipleValue()); + const WbMFString *const mfString = static_cast(multipleValue()); if (mfString->item(index()) == mString) return; diff --git a/src/webots/scene_tree/WbStringEditor.hpp b/src/webots/scene_tree/WbStringEditor.hpp index 9ad35e9c0dc..78cc287781e 100644 --- a/src/webots/scene_tree/WbStringEditor.hpp +++ b/src/webots/scene_tree/WbStringEditor.hpp @@ -28,7 +28,7 @@ class WbStringEditor : public WbValueEditor { public: explicit WbStringEditor(QWidget *parent = NULL); - virtual ~WbStringEditor(); + virtual ~WbStringEditor() override; void recursiveBlockSignals(bool block) override; diff --git a/src/webots/scene_tree/WbTreeItem.cpp b/src/webots/scene_tree/WbTreeItem.cpp index cc5795dbfce..1591a07b165 100644 --- a/src/webots/scene_tree/WbTreeItem.cpp +++ b/src/webots/scene_tree/WbTreeItem.cpp @@ -235,7 +235,7 @@ bool WbTreeItem::isFixedRowsMFitem() const { if (f == NULL) return false; - foreach (const QString name, FIXED_ROWS_MFFIELD) { + foreach (const QString &name, FIXED_ROWS_MFFIELD) { if (f->name() == name) return true; } @@ -244,7 +244,7 @@ bool WbTreeItem::isFixedRowsMFitem() const { f = f->internalFields().at(0); if (f == NULL) return false; - foreach (const QString name, FIXED_ROWS_MFFIELD) { + foreach (const QString &name, FIXED_ROWS_MFFIELD) { if (f->name() == name) return true; } @@ -260,7 +260,7 @@ bool WbTreeItem::isNonEmptyFixedRowsMFfield() const { if (f == NULL || !f->isMultiple()) return false; - foreach (const QString name, FIXED_ROWS_MFFIELD) { + foreach (const QString &name, FIXED_ROWS_MFFIELD) { if (f->name() == name) return !dynamic_cast(f->value())->isEmpty(); } @@ -270,7 +270,7 @@ bool WbTreeItem::isNonEmptyFixedRowsMFfield() const { if (f == NULL) return false; - foreach (const QString name, FIXED_ROWS_MFFIELD) { + foreach (const QString &name, FIXED_ROWS_MFFIELD) { if (f->name() == name) return !dynamic_cast(f->value())->isEmpty(); } @@ -345,7 +345,7 @@ bool WbTreeItem::canCut() const { return false; return true; case FIELD: { - WbSFNode *sfnode = dynamic_cast(mField->value()); + const WbSFNode *sfnode = dynamic_cast(mField->value()); return sfnode && sfnode->value() && !sfnode->value()->isUseNode(); } case ITEM: @@ -370,7 +370,7 @@ bool WbTreeItem::canDelete() const { return true; } case FIELD: { - WbSFNode *sfnode = dynamic_cast(mField->value()); + const WbSFNode *sfnode = dynamic_cast(mField->value()); return sfnode && sfnode->value() != NULL; } case ITEM: { @@ -446,8 +446,8 @@ void WbTreeItem::deleteAllChildren() { void WbTreeItem::sfnodeChanged() { assert(mType == FIELD); - WbSFNode *sfnode = static_cast(mField->value()); - WbNode *nodeObject = sfnode->value(); + const WbSFNode *sfnode = static_cast(mField->value()); + const WbNode *nodeObject = sfnode->value(); // delete previous children items int count = 0; @@ -470,7 +470,7 @@ WbNode *WbTreeItem::node() const { if (mType == NODE) return mNode; - WbSFNode *sfNode = dynamic_cast(mField->value()); + const WbSFNode *sfNode = dynamic_cast(mField->value()); if (!sfNode) return NULL; diff --git a/src/webots/scene_tree/WbTreeView.cpp b/src/webots/scene_tree/WbTreeView.cpp index ba939a9edb7..e635b474f42 100644 --- a/src/webots/scene_tree/WbTreeView.cpp +++ b/src/webots/scene_tree/WbTreeView.cpp @@ -29,7 +29,7 @@ class WbTreeItemDelegate : public QStyledItemDelegate { void paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const override { QStyleOptionViewItem itemOption(option); - WbTreeItem *item = static_cast(index.internalPointer()); + const WbTreeItem *item = static_cast(index.internalPointer()); if (item->isDefault()) // paint unmodified tree items in black itemOption.palette.setColor(QPalette::Text, mDefaultColor); diff --git a/src/webots/scene_tree/WbVector2Editor.cpp b/src/webots/scene_tree/WbVector2Editor.cpp index 340de5b885a..97abca811e7 100644 --- a/src/webots/scene_tree/WbVector2Editor.cpp +++ b/src/webots/scene_tree/WbVector2Editor.cpp @@ -100,14 +100,14 @@ void WbVector2Editor::apply() { WbPrecision::roundValue(mSpinBoxes[1]->value(), WbPrecision::GUI_MEDIUM)); mVector2.clamp(); if (singleValue()) { - WbSFVector2 *const sfVector2 = static_cast(singleValue()); + const WbSFVector2 *const sfVector2 = static_cast(singleValue()); if (sfVector2->value() == mVector2) return; mPreviousValue->setVector2(sfVector2->value()); } else if (multipleValue()) { - WbMFVector2 *const mfVector2 = static_cast(multipleValue()); + const WbMFVector2 *const mfVector2 = static_cast(multipleValue()); if (mfVector2->item(index()) == mVector2) return; diff --git a/src/webots/scene_tree/WbVector2Editor.hpp b/src/webots/scene_tree/WbVector2Editor.hpp index 18889be2dcf..14749c33c10 100644 --- a/src/webots/scene_tree/WbVector2Editor.hpp +++ b/src/webots/scene_tree/WbVector2Editor.hpp @@ -30,7 +30,7 @@ class WbVector2Editor : public WbValueEditor { public: explicit WbVector2Editor(QWidget *parent = NULL); - virtual ~WbVector2Editor(); + virtual ~WbVector2Editor() override; void recursiveBlockSignals(bool block) override; diff --git a/src/webots/scene_tree/WbVector3Editor.cpp b/src/webots/scene_tree/WbVector3Editor.cpp index 1f4c33cf206..7527698fd6b 100644 --- a/src/webots/scene_tree/WbVector3Editor.cpp +++ b/src/webots/scene_tree/WbVector3Editor.cpp @@ -111,14 +111,14 @@ void WbVector3Editor::apply() { WbPrecision::roundValue(mSpinBoxes[2]->value(), WbPrecision::GUI_MEDIUM)); mVector3.clamp(); if (singleValue()) { - WbSFVector3 *const sfVector3 = static_cast(singleValue()); + const WbSFVector3 *const sfVector3 = static_cast(singleValue()); if (sfVector3->value() == mVector3) return; mPreviousValue->setVector3(sfVector3->value()); } else if (multipleValue()) { - WbMFVector3 *const mfVector3 = static_cast(multipleValue()); + const WbMFVector3 *const mfVector3 = static_cast(multipleValue()); if (mfVector3->item(index()) == mVector3) return; diff --git a/src/webots/scene_tree/WbVector3Editor.hpp b/src/webots/scene_tree/WbVector3Editor.hpp index 6f4389308af..106a93734d6 100644 --- a/src/webots/scene_tree/WbVector3Editor.hpp +++ b/src/webots/scene_tree/WbVector3Editor.hpp @@ -30,7 +30,7 @@ class WbVector3Editor : public WbValueEditor { public: explicit WbVector3Editor(QWidget *parent = NULL); - virtual ~WbVector3Editor(); + virtual ~WbVector3Editor() override; void recursiveBlockSignals(bool block) override; diff --git a/src/webots/scene_tree/WbVelocityViewer.cpp b/src/webots/scene_tree/WbVelocityViewer.cpp index 2033b2227ce..d8f3fcd0a49 100644 --- a/src/webots/scene_tree/WbVelocityViewer.cpp +++ b/src/webots/scene_tree/WbVelocityViewer.cpp @@ -100,7 +100,7 @@ void WbVelocityViewer::requestUpdate() { void WbVelocityViewer::update() { if (mIsSelected && mSolid) { - WbSolid *solid = mSolid; + const WbSolid *solid = mSolid; if (mRelativeToComboBox->currentIndex() == 0) solid = NULL; else { diff --git a/src/webots/sound/WbMicrosoftTextToSpeech.cpp b/src/webots/sound/WbMicrosoftTextToSpeech.cpp index 3d795f409bf..26cd717dde1 100644 --- a/src/webots/sound/WbMicrosoftTextToSpeech.cpp +++ b/src/webots/sound/WbMicrosoftTextToSpeech.cpp @@ -40,11 +40,11 @@ WbMicrosoftTextToSpeech::WbMicrosoftTextToSpeech() { gError = "Failed to initialize Microsoft COM."; return; } - if (FAILED(CoCreateInstance(CLSID_SpStream, NULL, CLSCTX_ALL, __uuidof(ISpStream), (void **)&gStream))) { + if (FAILED(CoCreateInstance(CLSID_SpStream, NULL, CLSCTX_ALL, __uuidof(ISpStream), reinterpret_cast(&gStream)))) { gError = "Failed to create COM instance for Stream."; return; } - if (FAILED(CoCreateInstance(CLSID_SpVoice, NULL, CLSCTX_ALL, IID_ISpVoice, (void **)&gVoice))) { + if (FAILED(CoCreateInstance(CLSID_SpVoice, NULL, CLSCTX_ALL, IID_ISpVoice, reinterpret_cast(&gVoice)))) { gError = "Failed to create COM instance for Voice."; return; } diff --git a/src/webots/sound/WbMicrosoftTextToSpeech.hpp b/src/webots/sound/WbMicrosoftTextToSpeech.hpp index f43bbec1a8b..3d65f7e16c5 100644 --- a/src/webots/sound/WbMicrosoftTextToSpeech.hpp +++ b/src/webots/sound/WbMicrosoftTextToSpeech.hpp @@ -22,7 +22,7 @@ class WbMicrosoftTextToSpeech : public WbTextToSpeech { public: WbMicrosoftTextToSpeech(); - ~WbMicrosoftTextToSpeech(); + ~WbMicrosoftTextToSpeech() override; qint16 *generateBufferFromText(const QString &text, int *size, const QString &language) override; const QString error() override; }; diff --git a/src/webots/sound/WbPicoTextToSpeech.hpp b/src/webots/sound/WbPicoTextToSpeech.hpp index 4ba43e68bb7..d14f6a2348f 100644 --- a/src/webots/sound/WbPicoTextToSpeech.hpp +++ b/src/webots/sound/WbPicoTextToSpeech.hpp @@ -22,7 +22,7 @@ class WbPicoTextToSpeech : public WbTextToSpeech { public: WbPicoTextToSpeech(); - ~WbPicoTextToSpeech(); + ~WbPicoTextToSpeech() override; qint16 *generateBufferFromText(const QString &text, int *size, const QString &language) override; const QString error() override; }; diff --git a/src/webots/sound/WbWaveFile.cpp b/src/webots/sound/WbWaveFile.cpp index e6a80ecf1dc..039695b7f3e 100644 --- a/src/webots/sound/WbWaveFile.cpp +++ b/src/webots/sound/WbWaveFile.cpp @@ -86,7 +86,7 @@ void WbWaveFile::loadConvertedFile(int side) { while (1) { // read chunks one by one Chunk chunk; - qint64 readSize = mDevice->read((char *)&chunk, sizeof(Chunk)); + qint64 readSize = mDevice->read(reinterpret_cast(&chunk), sizeof(Chunk)); if (readSize <= 0) break; // end of file if (readSize != sizeof(Chunk)) @@ -94,7 +94,7 @@ void WbWaveFile::loadConvertedFile(int side) { if (strncmp(chunk.id, "RIFF", 4) == 0) { RIFFChunkData riffChunk; - readSize = mDevice->read((char *)&riffChunk, sizeof(RIFFChunkData)); + readSize = mDevice->read(reinterpret_cast(&riffChunk), sizeof(RIFFChunkData)); if (readSize != sizeof(RIFFChunkData)) throw QObject::tr("Cannot read RIFF chunk"); @@ -105,7 +105,7 @@ void WbWaveFile::loadConvertedFile(int side) { } else if (strncmp(chunk.id, "fmt ", 4) == 0) { FormatChunkData formatChunk; - readSize = mDevice->read((char *)&formatChunk, sizeof(FormatChunkData)); + readSize = mDevice->read(reinterpret_cast(&formatChunk), sizeof(FormatChunkData)); if (readSize != sizeof(FormatChunkData)) throw QObject::tr("Cannot read format chunk"); @@ -160,7 +160,7 @@ void WbWaveFile::loadConvertedFile(int side) { int newSize = mBufferSize / 2; qint16 *newBuffer = static_cast(malloc(sizeof(qint16) * newSize)); if (mBitsPerSample == 8) { - qint8 *currentBuffer = reinterpret_cast(mBuffer); + const qint8 *currentBuffer = reinterpret_cast(mBuffer); qint8 *outBuffer = reinterpret_cast(newBuffer); for (int i = 0; i < newSize; i += 1) { if (side == 1) @@ -205,13 +205,10 @@ void WbWaveFile::loadFromFile(const QString &extension, int side) { #ifdef __linux__ static QString ffmpeg("avconv"); - static QString percentageChar = "%"; #elif defined(__APPLE__) static QString ffmpeg(QString("%1Contents/util/ffmpeg").arg(WbStandardPaths::webotsHomePath())); - static QString percentageChar = "%"; #else // _WIN32 static QString ffmpeg = "ffmpeg.exe"; - static QString percentageChar = "%%"; #endif const QString outputFilename = WbStandardPaths::webotsTmpPath() + "output.wav"; diff --git a/src/webots/sound/WbWaveFile.hpp b/src/webots/sound/WbWaveFile.hpp index 8016f4a7c1b..659fe9f7926 100644 --- a/src/webots/sound/WbWaveFile.hpp +++ b/src/webots/sound/WbWaveFile.hpp @@ -41,7 +41,7 @@ class WbWaveFile { int nChannels() const { return mNChannels; } int bitsPerSample() const { return mBitsPerSample; } int rate() const { return mRate; } - QString filename() const { return mFilename; } + const QString &filename() const { return mFilename; } private: QString mFilename; diff --git a/src/webots/user_commands/WbActionManager.cpp b/src/webots/user_commands/WbActionManager.cpp index 3b78dcbc613..a452434fffc 100644 --- a/src/webots/user_commands/WbActionManager.cpp +++ b/src/webots/user_commands/WbActionManager.cpp @@ -1189,7 +1189,7 @@ void WbActionManager::updateRenderingButton() { } void WbActionManager::forwardTransformToActionToSceneTree() { - QAction *senderAction = static_cast(sender()); + const QAction *senderAction = static_cast(sender()); if (!senderAction) return; @@ -1197,7 +1197,7 @@ void WbActionManager::forwardTransformToActionToSceneTree() { } void WbActionManager::dispatchUserCommand() { - QAction *senderAction = static_cast(sender()); + const QAction *senderAction = static_cast(sender()); if (!senderAction) return; diff --git a/src/webots/user_commands/WbClipboard.cpp b/src/webots/user_commands/WbClipboard.cpp index df2ed8d560b..ee66b2c9253 100644 --- a/src/webots/user_commands/WbClipboard.cpp +++ b/src/webots/user_commands/WbClipboard.cpp @@ -161,7 +161,7 @@ void WbClipboard::setNode(WbNode *n, bool persistent) { // store all the required external DEF nodes data in order to work correctly // independently if other nodes are deleted for (int i = 0; i < externalDefNodes.size(); ++i) { - WbBaseNode *node = dynamic_cast(externalDefNodes[i].first); + const WbBaseNode *node = dynamic_cast(externalDefNodes[i].first); LinkedDefNodeDefinitions *data = new LinkedDefNodeDefinitions(); data->position = externalDefNodes[i].second; data->type = node->nodeType(); @@ -211,7 +211,7 @@ QString WbClipboard::computeNodeExportStringForInsertion(WbNode *parentNode, WbF for (int i = mLinkedDefNodeDefinitions.size() - 1; i >= 0; --i) { bool found = false; for (int j = 0; j < existingDefNodesSize && !found; ++j) { - WbBaseNode *node = dynamic_cast(existingDefNodes[j]); + const WbBaseNode *node = dynamic_cast(existingDefNodes[j]); found = node->defName() == mLinkedDefNodeDefinitions[i]->defName && node->nodeType() == mLinkedDefNodeDefinitions[i]->type; } diff --git a/src/webots/user_commands/WbContextMenuGenerator.cpp b/src/webots/user_commands/WbContextMenuGenerator.cpp index 1ef6a45aa7d..5859353fc00 100644 --- a/src/webots/user_commands/WbContextMenuGenerator.cpp +++ b/src/webots/user_commands/WbContextMenuGenerator.cpp @@ -148,7 +148,7 @@ namespace WbContextMenuGenerator { if (!suitableTransformToModels.isEmpty()) { foreach (const QString &model, suitableTransformToModels) { - QAction *action = subMenu->addAction(model); + const QAction *action = subMenu->addAction(model); QObject::connect(action, &QAction::triggered, WbActionManager::instance(), &WbActionManager::forwardTransformToActionToSceneTree); } diff --git a/src/webots/util/WbPerformanceLog.cpp b/src/webots/util/WbPerformanceLog.cpp index d8059173a8b..7b437b6d037 100644 --- a/src/webots/util/WbPerformanceLog.cpp +++ b/src/webots/util/WbPerformanceLog.cpp @@ -193,9 +193,9 @@ void WbPerformanceLog::writeTotalValues() { headers.append(s); } headers.append(""); - foreach (QString key, devicesKeys) + foreach (const QString &key, devicesKeys) headers.append(""); - foreach (QString key, controllersKeys) + foreach (const QString &key, controllersKeys) headers.append(""); out << " " << headers.join(" "); @@ -213,9 +213,9 @@ void WbPerformanceLog::writeTotalValues() { out << justifiedNumber(value, headers[i].size()) << " "; } out << justifiedNumber(mAverageFPS, headers[i++].size()) << " "; - foreach (QString key, devicesKeys) + foreach (const QString &key, devicesKeys) out << justifiedNumber(mRenderingDevicesValues.value(key)->averageValue(), headers[i++].size()) << " "; - foreach (QString key, controllersKeys) + foreach (const QString &key, controllersKeys) out << justifiedNumber(mControllersValues.value(key)->averageValue(), headers[i++].size()) << " "; // total @@ -229,9 +229,9 @@ void WbPerformanceLog::writeTotalValues() { out << justifiedNumber(value, headers[i].size()) << " "; } out << justifiedNumber(mAverageFPS, headers[i++].size()) << " "; - foreach (QString key, devicesKeys) + foreach (const QString &key, devicesKeys) out << justifiedNumber(mRenderingDevicesValues.value(key)->totalValue(), headers[i++].size()) << " "; - foreach (QString key, controllersKeys) + foreach (const QString &key, controllersKeys) out << justifiedNumber(mControllersValues.value(key)->totalValue(), headers[i++].size()) << " "; out << "\n"; out << "\n"; diff --git a/src/webots/vrml/WbField.cpp b/src/webots/vrml/WbField.cpp index ddf6f0dfca1..23838c6ec6b 100644 --- a/src/webots/vrml/WbField.cpp +++ b/src/webots/vrml/WbField.cpp @@ -319,7 +319,7 @@ void WbField::redirectTo(WbField *parameter, bool skipCopy) { if (mParameter) { // remove previous connections - WbMFNode *mfnode = dynamic_cast(mParameter->value()); + const WbMFNode *mfnode = dynamic_cast(mParameter->value()); if (mfnode) { disconnect(mfnode, &WbMFNode::itemInserted, mParameter, &WbField::parameterNodeInserted); disconnect(mfnode, &WbMFNode::itemRemoved, mParameter, &WbField::parameterNodeRemoved); diff --git a/src/webots/vrml/WbFieldModel.cpp b/src/webots/vrml/WbFieldModel.cpp index bfdb253c4f8..03334922ce3 100644 --- a/src/webots/vrml/WbFieldModel.cpp +++ b/src/webots/vrml/WbFieldModel.cpp @@ -100,7 +100,7 @@ WbFieldModel::WbFieldModel(WbTokenizer *tokenizer, const QString &worldPath) { bool defaultValueIsValid = true; while (!isValueAccepted(mDefaultValue, &refusedIndex)) { defaultValueIsValid = false; - WbMultipleValue *multipleValue = dynamic_cast(mDefaultValue); + const WbMultipleValue *multipleValue = dynamic_cast(mDefaultValue); if (multipleValue) mAcceptedValues << multipleValue->variantValue(refusedIndex); else { diff --git a/src/webots/vrml/WbFieldModel.hpp b/src/webots/vrml/WbFieldModel.hpp index 907a9619404..17e783e118d 100644 --- a/src/webots/vrml/WbFieldModel.hpp +++ b/src/webots/vrml/WbFieldModel.hpp @@ -54,7 +54,7 @@ class WbFieldModel { // accepted values bool isValueAccepted(const WbValue *value, int *refusedIndex) const; bool hasRestrictedValues() const { return !mAcceptedValues.isEmpty(); } - const QList acceptedValues() const { return mAcceptedValues; } + const QList &acceptedValues() const { return mAcceptedValues; } // field type WbFieldType type() const { return mDefaultValue->type(); } diff --git a/src/webots/vrml/WbMFBool.hpp b/src/webots/vrml/WbMFBool.hpp index 324536ecaa9..cb156934e82 100644 --- a/src/webots/vrml/WbMFBool.hpp +++ b/src/webots/vrml/WbMFBool.hpp @@ -35,7 +35,7 @@ class WbMFBool : public WbMultipleValue { WbMFBool() {} WbMFBool(WbTokenizer *tokenizer, const QString &worldPath) { read(tokenizer, worldPath); } WbMFBool(const WbMFBool &other) : mVector(other.mVector) {} - virtual ~WbMFBool() {} + virtual ~WbMFBool() override {} WbValue *clone() const override { return new WbMFBool(*this); } bool equals(const WbValue *other) const override; void copyFrom(const WbValue *other) override; diff --git a/src/webots/vrml/WbMFColor.hpp b/src/webots/vrml/WbMFColor.hpp index 0f70f518e45..9f571ec8e19 100644 --- a/src/webots/vrml/WbMFColor.hpp +++ b/src/webots/vrml/WbMFColor.hpp @@ -35,7 +35,7 @@ class WbMFColor : public WbMultipleValue { WbMFColor(WbTokenizer *tokenizer, const QString &worldPath) { read(tokenizer, worldPath); } WbMFColor(const WbMFColor &other) : mVector(other.mVector) {} - virtual ~WbMFColor() {} + virtual ~WbMFColor() override {} WbValue *clone() const override { return new WbMFColor(*this); } bool equals(const WbValue *other) const override; void copyFrom(const WbValue *other) override; diff --git a/src/webots/vrml/WbMFDouble.hpp b/src/webots/vrml/WbMFDouble.hpp index 77c1ea8ce33..87099343d83 100644 --- a/src/webots/vrml/WbMFDouble.hpp +++ b/src/webots/vrml/WbMFDouble.hpp @@ -36,7 +36,7 @@ class WbMFDouble : public WbMultipleValue { WbMFDouble(WbTokenizer *tokenizer, const QString &worldPath) { read(tokenizer, worldPath); } WbMFDouble(const WbMFDouble &other) : mVector(other.mVector) {} - virtual ~WbMFDouble() {} + virtual ~WbMFDouble() override {} WbValue *clone() const override { return new WbMFDouble(*this); } bool equals(const WbValue *other) const override; void copyFrom(const WbValue *other) override; diff --git a/src/webots/vrml/WbMFInt.hpp b/src/webots/vrml/WbMFInt.hpp index 020c7b5b38e..18831278aba 100644 --- a/src/webots/vrml/WbMFInt.hpp +++ b/src/webots/vrml/WbMFInt.hpp @@ -35,7 +35,7 @@ class WbMFInt : public WbMultipleValue { WbMFInt() {} WbMFInt(WbTokenizer *tokenizer, const QString &worldPath) { read(tokenizer, worldPath); } WbMFInt(const WbMFInt &other) : mVector(other.mVector) {} - virtual ~WbMFInt() {} + virtual ~WbMFInt() override {} WbValue *clone() const override { return new WbMFInt(*this); } bool equals(const WbValue *other) const override; void copyFrom(const WbValue *other) override; diff --git a/src/webots/vrml/WbMFNode.hpp b/src/webots/vrml/WbMFNode.hpp index b690a76c242..58610ca4480 100644 --- a/src/webots/vrml/WbMFNode.hpp +++ b/src/webots/vrml/WbMFNode.hpp @@ -36,13 +36,14 @@ class WbMFNode : public WbMultipleValue { WbMFNode(WbTokenizer *tokenizer, const QString &worldPath) { read(tokenizer, worldPath); } WbMFNode(const WbMFNode &other); - virtual ~WbMFNode(); + virtual ~WbMFNode() override; WbValue *clone() const override { return new WbMFNode(*this); } bool equals(const WbValue *other) const override; void copyFrom(const WbValue *other) override; int size() const override { return mVector.size(); } void clear() override; void insertDefaultItem(int index) override; + // cppcheck-suppress knownPointerToBool WbVariant defaultNewVariant() const override { return WbVariant((WbNode *)NULL); } void removeItem(int index) override; // remove and delete the node instance bool removeNode(WbNode *node); // remove without deleting the node instance diff --git a/src/webots/vrml/WbMFRotation.hpp b/src/webots/vrml/WbMFRotation.hpp index 67573d60141..e24d18f2d86 100644 --- a/src/webots/vrml/WbMFRotation.hpp +++ b/src/webots/vrml/WbMFRotation.hpp @@ -36,7 +36,7 @@ class WbMFRotation : public WbMultipleValue { WbMFRotation() {} WbMFRotation(WbTokenizer *tokenizer, const QString &worldPath) { read(tokenizer, worldPath); } WbMFRotation(const WbMFRotation &other) : mVector(other.mVector) {} - virtual ~WbMFRotation() {} + virtual ~WbMFRotation() override {} WbValue *clone() const override { return new WbMFRotation(*this); } bool equals(const WbValue *other) const override; void copyFrom(const WbValue *other) override; diff --git a/src/webots/vrml/WbMFString.hpp b/src/webots/vrml/WbMFString.hpp index 37056a8997f..0c1138ba823 100644 --- a/src/webots/vrml/WbMFString.hpp +++ b/src/webots/vrml/WbMFString.hpp @@ -35,7 +35,7 @@ class WbMFString : public WbMultipleValue { WbMFString(WbTokenizer *tokenizer, const QString &worldPath) { read(tokenizer, worldPath); } WbMFString(const WbMFString &other) : mValue(other.mValue) {} explicit WbMFString(const QStringList &value) : mValue(value) {} - virtual ~WbMFString() {} + virtual ~WbMFString() override {} WbValue *clone() const override { return new WbMFString(*this); } bool equals(const WbValue *other) const override; void copyFrom(const WbValue *other) override; diff --git a/src/webots/vrml/WbMFVector2.hpp b/src/webots/vrml/WbMFVector2.hpp index 320fc1cc7ff..bd7a42d8cd0 100644 --- a/src/webots/vrml/WbMFVector2.hpp +++ b/src/webots/vrml/WbMFVector2.hpp @@ -35,7 +35,7 @@ class WbMFVector2 : public WbMultipleValue { WbMFVector2(WbTokenizer *tokenizer, const QString &worldPath) { read(tokenizer, worldPath); } WbMFVector2(const WbMFVector2 &other) : mVector(other.mVector) {} - virtual ~WbMFVector2() {} + virtual ~WbMFVector2() override {} WbValue *clone() const override { return new WbMFVector2(*this); } bool equals(const WbValue *other) const override; void copyFrom(const WbValue *other) override; diff --git a/src/webots/vrml/WbMFVector3.hpp b/src/webots/vrml/WbMFVector3.hpp index c0e368c7c92..3306920ad42 100644 --- a/src/webots/vrml/WbMFVector3.hpp +++ b/src/webots/vrml/WbMFVector3.hpp @@ -36,7 +36,7 @@ class WbMFVector3 : public WbMultipleValue { WbMFVector3() {} WbMFVector3(WbTokenizer *tokenizer, const QString &worldPath) { read(tokenizer, worldPath); } WbMFVector3(const WbMFVector3 &other) : mVector(other.mVector) {} - virtual ~WbMFVector3() {} + virtual ~WbMFVector3() override {} WbValue *clone() const override { return new WbMFVector3(*this); } bool equals(const WbValue *other) const override; void copyFrom(const WbValue *other) override; diff --git a/src/webots/vrml/WbMultipleValue.hpp b/src/webots/vrml/WbMultipleValue.hpp index d71f4b7f4f9..b00ffb6f65c 100644 --- a/src/webots/vrml/WbMultipleValue.hpp +++ b/src/webots/vrml/WbMultipleValue.hpp @@ -29,7 +29,7 @@ class WbMultipleValue : public WbValue { Q_OBJECT public: - virtual ~WbMultipleValue() {} + virtual ~WbMultipleValue() override {} void read(WbTokenizer *tokenizer, const QString &worldPath) override; virtual int size() const = 0; bool isEmpty() const { return size() == 0; }; diff --git a/src/webots/vrml/WbNode.cpp b/src/webots/vrml/WbNode.cpp index c0022993058..96cb4cce56b 100644 --- a/src/webots/vrml/WbNode.cpp +++ b/src/webots/vrml/WbNode.cpp @@ -207,7 +207,7 @@ WbNode::WbNode(const WbNode &other) : mHasUseAncestor = true; // copy fields - foreach (WbField *f, other.fields()) { + foreach (const WbField *f, other.fields()) { WbField *copy = new WbField(*f, this); mFields.append(copy); connect(copy, &WbField::valueChanged, this, &WbNode::notifyFieldChanged); @@ -215,7 +215,7 @@ WbNode::WbNode(const WbNode &other) : // copy parameters if (other.mProto) { - foreach (WbField *parameter, other.parameters()) { + foreach (const WbField *parameter, other.parameters()) { WbField *copy = new WbField(*parameter, this); mParameters.append(copy); connect(copy, &WbField::valueChanged, this, &WbNode::notifyParameterChanged); @@ -523,7 +523,7 @@ WbField *WbNode::parentFieldAndIndex(int &index, bool internal) const { } WbValue *WbNode::findValue(const QString &fieldName) const { - foreach (WbField *const f, mFields) { + foreach (const WbField *const f, mFields) { if (fieldName == f->name()) return f->value(); } @@ -682,7 +682,7 @@ void WbNode::notifyFieldChanged() { if (index >= 0) { WbNode *parent = NULL; // apply changes to the same field in each USE node - foreach (WbNode *const useNode, n->mUseNodes) { + foreach (const WbNode *const useNode, n->mUseNodes) { WbField *const subField = useNode->findSubField(index, parent); if (!subField || subField->type() != f->type() || subField->name() != f->name()) continue; @@ -722,7 +722,7 @@ int WbNode::findSubFieldIndex(const WbField *const searched) const { int count = 0; QList list(subNodes(true, true, false)); list.prepend(const_cast(this)); - foreach (WbNode *const node, list) { + foreach (const WbNode *const node, list) { foreach (const WbField *const f, node->mFields) { if (f == searched) return count; @@ -761,7 +761,7 @@ void WbNode::validate(const WbNode *upperNode, const WbField *upperField, bool i if (sfnode) { if (f->name() == "boundingObject") isInBoundingObject = true; - WbNode *child = sfnode->value(); + const WbNode *child = sfnode->value(); if (child) { QString errorMessage; if (!WbNodeFactory::instance()->validateExistingChildNode(f, child, parent, isInBoundingObject, errorMessage)) { @@ -791,7 +791,7 @@ void WbNode::validate(const WbNode *upperNode, const WbField *upperField, bool i } } else if (mfnode) { for (int i = 0; i < mfnode->size(); ++i) { - WbNode *child = mfnode->item(i); + const WbNode *child = mfnode->item(i); QString errorMessage; if (!WbNodeFactory::instance()->validateExistingChildNode(f, child, parent, isInBoundingObject, errorMessage)) { bool emptyErrorMessage = errorMessage.isEmpty(); @@ -850,7 +850,7 @@ void WbNode::readFields(WbTokenizer *tokenizer, const QString &worldPath) { tokenizer->skipToken("IS"); const QString &alias = tokenizer->nextWord(); bool exists = false; - foreach (WbField *p, *(gProtoParameterList.last()->params)) { + foreach (const WbField *p, *(gProtoParameterList.last()->params)) { if (p->name() == alias) { exists = true; break; @@ -889,7 +889,7 @@ QList> *WbNode::externalUseNodesPositionsInWrite() { } void WbNode::writeParameters(WbWriter &writer) const { - foreach (WbField *parameter, parameters()) + foreach (const WbField *parameter, parameters()) parameter->write(writer); } @@ -966,7 +966,7 @@ void WbNode::write(WbWriter &writer) const { if (isProtoInstance()) writeParameters(writer); else - foreach (WbField *f, fields()) + foreach (const WbField *f, fields()) if (!f->isDeprecated()) f->write(writer); @@ -1086,14 +1086,14 @@ void WbNode::exportNodeFields(WbWriter &writer) const { if (writer.isUrdf()) return; - foreach (WbField *f, fields()) { + foreach (const WbField *f, fields()) { if (!f->isDeprecated() && ((f->isW3d() || writer.isProto()) && f->singleType() != WB_SF_NODE)) f->write(writer); } } void WbNode::exportNodeSubNodes(WbWriter &writer) const { - foreach (WbField *f, fields()) { + foreach (const WbField *f, fields()) { if (!f->isDeprecated() && ((f->isW3d() || writer.isProto() || writer.isUrdf()) && f->singleType() == WB_SF_NODE)) { const WbSFNode *const node = dynamic_cast(f->value()); if (node == NULL || node->value() == NULL || node->value()->shallExport() || writer.isProto() || writer.isUrdf()) { @@ -1174,7 +1174,6 @@ void WbNode::addExternProtoFromFile(const WbProtoModel *proto, WbWriter &writer) const QRegularExpressionMatch match = it.next(); if (match.hasMatch()) { const QString subProto = match.captured(1); - const QString url = path; const QString subProtoUrl = WbUrl::combinePaths(subProto, path); if (subProtoUrl.isEmpty()) @@ -1247,7 +1246,7 @@ bool WbNode::operator==(const WbNode &other) const { bool WbNode::isDefault() const { QList fieldsList = fieldsOrParameters(); - foreach (WbField *f, fieldsList) { + foreach (const WbField *f, fieldsList) { if (!(f->isDeprecated() || f->isDefault())) return false; } @@ -1455,7 +1454,7 @@ void WbNode::copyAliasValue(WbField *field, const QString &alias) { // this avoids double setup of the parameter and is particularly // helpful for nested PROTOs if (!gProtoParameterList.isEmpty()) { - foreach (WbField *p, *(gProtoParameterList.last()->params)) { + foreach (const WbField *p, *(gProtoParameterList.last()->params)) { if (p->name() == alias && p->type() == field->type()) field->copyValueFrom(p); } @@ -1500,7 +1499,7 @@ WbNode *WbNode::createProtoInstance(WbProtoModel *proto, WbTokenizer *tokenizer, bool fieldOrderWarning = true; while (tokenizer->peekWord() != "}") { QString parameterName = tokenizer->nextWord(); - WbFieldModel *parameterModel = NULL; + const WbFieldModel *parameterModel = NULL; const bool hidden = parameterName == "hidden"; if (hidden) { static const QRegularExpression rx1("(_\\d+)+$"); // looks for a substring of the form _7 or _13_1 at the end of @@ -1770,7 +1769,7 @@ void WbNode::updateNestedProtoFlag(bool hasAProtoAncestorFlag) { return; // flag already set mIsNestedProtoNode = newValue; const QList fieldList = fields() + parameters(); - foreach (WbField *f, fieldList) { + foreach (const WbField *f, fieldList) { const WbSFNode *const sfnode = dynamic_cast(f->value()); const WbMFNode *const mfnode = dynamic_cast(f->value()); if (sfnode) { @@ -1808,7 +1807,7 @@ bool WbNode::isProtoParameterChild(const WbNode *node) const { if (node->mProtoParameterParentNode) return node->mProtoParameterParentNode == this; - foreach (WbField *const p, parameters()) { + foreach (const WbField *const p, parameters()) { const WbSFNode *const sfnode = dynamic_cast(p->value()); if (sfnode && sfnode->value() == node) { node->mProtoParameterParentNode = this; @@ -1832,7 +1831,7 @@ bool WbNode::isProtoParameterNode() const { if (mIsProtoParameterNode) return mIsProtoParameterNode[0]; mIsProtoParameterNode = new bool[1]; - WbNode *parent = parentNode(); + const WbNode *parent = parentNode(); if (!parent || parent->isWorldRoot()) { mIsProtoParameterNode[0] = false; return false; @@ -1869,6 +1868,7 @@ QList WbNode::subNodes(const WbField *field, bool recurse, bool search const WbValue *const value = field->value(); const WbSFNode *const sfnode = dynamic_cast(value); if (sfnode && sfnode->value()) { + // cppcheck-suppress constVariablePointer WbNode *const node = sfnode->value(); result.append(node); if (recurse) @@ -1877,6 +1877,7 @@ QList WbNode::subNodes(const WbField *field, bool recurse, bool search const WbMFNode *const mfnode = dynamic_cast(value); if (mfnode) { for (int i = 0; i < mfnode->size(); ++i) { + // cppcheck-suppress constVariablePointer WbNode *const node = mfnode->item(i); result.append(node); if (recurse) @@ -1906,7 +1907,7 @@ bool WbNode::hasAProtoAncestor() const { if (currentNode->isProtoInstance()) return true; - WbNode *ppn = currentNode->protoParameterNode(); + const WbNode *ppn = currentNode->protoParameterNode(); if (ppn && ppn->isProtoInstance()) return true; @@ -1966,19 +1967,19 @@ int WbNode::subNodeIndex(const WbNode *subNode, const WbNode *root) { int result = 0; const QList &fieldsList = root->fields(); - foreach (WbField *f, fieldsList) { - WbValue *value = f->value(); - WbSFNode *sfNode = dynamic_cast(value); + foreach (const WbField *f, fieldsList) { + const WbValue *value = f->value(); + const WbSFNode *sfNode = dynamic_cast(value); if (sfNode) { - WbNode *node = sfNode->value(); + const WbNode *node = sfNode->value(); if (node) subNodeIndex(node, subNode, result, subNodeFound); } else { - WbMFNode *mfNode = dynamic_cast(value); + const WbMFNode *mfNode = dynamic_cast(value); if (mfNode) { const int n = mfNode->size(); for (int i = 0; !subNodeFound && (i < n); ++i) { - WbNode *node = mfNode->item(i); + const WbNode *node = mfNode->item(i); subNodeIndex(node, subNode, result, subNodeFound); } } @@ -2000,19 +2001,19 @@ void WbNode::subNodeIndex(const WbNode *currentNode, const WbNode *targetNode, i } const QList &fieldsList = currentNode->fields(); - foreach (WbField *f, fieldsList) { - WbValue *value = f->value(); - WbSFNode *sfNode = dynamic_cast(value); + foreach (const WbField *f, fieldsList) { + const WbValue *value = f->value(); + const WbSFNode *sfNode = dynamic_cast(value); if (sfNode) { - WbNode *node = sfNode->value(); + const WbNode *node = sfNode->value(); if (node) subNodeIndex(node, targetNode, index, subNodeFound); } else { - WbMFNode *mfNode = dynamic_cast(value); + const WbMFNode *mfNode = dynamic_cast(value); if (mfNode) { const int n = mfNode->size(); for (int i = 0; !subNodeFound && (i < n); i++) { - WbNode *node = mfNode->item(i); + const WbNode *node = mfNode->item(i); subNodeIndex(node, targetNode, index, subNodeFound); } } @@ -2023,7 +2024,7 @@ void WbNode::subNodeIndex(const WbNode *currentNode, const WbNode *targetNode, i } } -WbNode *WbNode::findNodeFromSubNodeIndices(QList indices, WbNode *root) { +WbNode *WbNode::findNodeFromSubNodeIndices(const QList &indices, WbNode *root) { WbNode *n = root; for (int i = 0; i < indices.size() && n != NULL; ++i) n = findNodeFromSubNodeIndex(indices[i], n); @@ -2035,9 +2036,9 @@ WbNode *WbNode::findNodeFromSubNodeIndex(int index, WbNode *root) { return root; const QList &fieldsList = root->fields(); - foreach (WbField *f, fieldsList) { - WbValue *value = f->value(); - WbSFNode *sfNode = dynamic_cast(value); + foreach (const WbField *f, fieldsList) { + const WbValue *value = f->value(); + const WbSFNode *sfNode = dynamic_cast(value); if (sfNode) { WbNode *node = sfNode->value(); if (node) { @@ -2046,7 +2047,7 @@ WbNode *WbNode::findNodeFromSubNodeIndex(int index, WbNode *root) { return returnNode; } } else { - WbMFNode *mfNode = dynamic_cast(value); + const WbMFNode *mfNode = dynamic_cast(value); if (mfNode) { const int n = mfNode->size(); for (int i = 0; (index > 0) && (i < n); i++) { @@ -2069,9 +2070,9 @@ WbNode *WbNode::findNode(int &index, WbNode *root) { return root; const QList &fieldsList = root->fields(); - foreach (WbField *f, fieldsList) { - WbValue *value = f->value(); - WbSFNode *sfNode = dynamic_cast(value); + foreach (const WbField *f, fieldsList) { + const WbValue *value = f->value(); + const WbSFNode *sfNode = dynamic_cast(value); if (sfNode) { WbNode *node = sfNode->value(); if (node) { @@ -2080,7 +2081,7 @@ WbNode *WbNode::findNode(int &index, WbNode *root) { return returnNode; } } else { - WbMFNode *mfNode = dynamic_cast(value); + const WbMFNode *mfNode = dynamic_cast(value); if (mfNode) { const int n = mfNode->size(); for (int i = 0; (index > 0) && (i < n); i++) { @@ -2096,7 +2097,7 @@ WbNode *WbNode::findNode(int &index, WbNode *root) { } void WbNode::disconnectFieldNotification(const WbValue *value) { - foreach (WbField *f, mFields) { + foreach (const WbField *f, mFields) { if (f->value() == value) disconnect(f, &WbField::valueChanged, this, &WbNode::notifyFieldChanged); } diff --git a/src/webots/vrml/WbNode.hpp b/src/webots/vrml/WbNode.hpp index 7f84c79d7a7..4d0fe855de4 100644 --- a/src/webots/vrml/WbNode.hpp +++ b/src/webots/vrml/WbNode.hpp @@ -157,7 +157,7 @@ class WbNode : public QObject { static WbNode *findNodeFromSubNodeIndex(int index, WbNode *root); // find descendant node from a list of parent indices // indices are listed from the ancestor parent node (position 0) to the searched node index (position indices.size()-1) - static WbNode *findNodeFromSubNodeIndices(QList indices, WbNode *root); + static WbNode *findNodeFromSubNodeIndices(const QList &indices, WbNode *root); // PROTO static WbNode *createProtoInstance(WbProtoModel *proto, WbTokenizer *tokenizer, const QString &worldPath); @@ -170,7 +170,7 @@ class WbNode : public QObject { void setRegenerationRequired(bool required); bool isRegenerationRequired() const { return mRegenerationRequired; } const QByteArray &protoInstanceTemplateContent() const { return mProtoInstanceTemplateContent; } - QList parameters() const { return mParameters; } + const QList ¶meters() const { return mParameters; } void setProtoInstanceTemplateContent(const QByteArray &content) { mProtoInstanceTemplateContent = content; } // pass argument if we know that a PROTO ancestor exists, otherwise if hasAProtoAncestorFlag is FALSE it will be computed void updateNestedProtoFlag(bool hasAProtoAncestorFlag = false); @@ -180,7 +180,7 @@ class WbNode : public QObject { // is a parameter node contained in a PROTO instance bool isProtoParameterNode() const; // return the node instances redirected to this PROTO parameter node - QList protoParameterNodeInstances() const { return mProtoParameterNodeInstances; } + const QList &protoParameterNodeInstances() const { return mProtoParameterNodeInstances; } bool hasAProtoAncestor() const; WbNode *protoAncestor() const; // connect nested PROTO parameters @@ -202,7 +202,7 @@ class WbNode : public QObject { // fields or proto parameters bool isDefault() const; // true if all fields have default values - QList fields() const { return mFields; } + const QList &fields() const { return mFields; } const QList &fieldsOrParameters() const { return isProtoInstance() ? mParameters : mFields; } int numFields() const { return fieldsOrParameters().size(); } WbField *field(int index, bool internal = false) const; diff --git a/src/webots/vrml/WbNodeModel.cpp b/src/webots/vrml/WbNodeModel.cpp index c8aabe7e287..5532d8e0e95 100644 --- a/src/webots/vrml/WbNodeModel.cpp +++ b/src/webots/vrml/WbNodeModel.cpp @@ -38,6 +38,7 @@ WbNodeModel::WbNodeModel(WbTokenizer *tokenizer) : mInfo(tokenizer->info()), mNa tokenizer->skipToken("{"); while (tokenizer->peekWord() != "}") { + // cppcheck-suppress constVariablePointer WbFieldModel *fieldModel = new WbFieldModel(tokenizer, ""); fieldModel->ref(); mFieldModels.append(fieldModel); @@ -47,7 +48,7 @@ WbNodeModel::WbNodeModel(WbTokenizer *tokenizer) : mInfo(tokenizer->info()), mNa } WbNodeModel::~WbNodeModel() { - foreach (WbFieldModel *fieldModel, mFieldModels) + foreach (const WbFieldModel *fieldModel, mFieldModels) fieldModel->unref(); mFieldModels.clear(); } @@ -72,7 +73,8 @@ WbNodeModel *WbNodeModel::readModel(const QString &fileName) { void WbNodeModel::readAllModels() { QString path = WbStandardPaths::resourcesPath() + "nodes/"; QStringList list = QDir(path, "*.wrl").entryList(); - foreach (QString modelName, list) { + foreach (const QString &modelName, list) { + // cppcheck-suppress constVariablePointer WbNodeModel *model = readModel(path + modelName); if (model) cModels.insert(model->name(), model); @@ -148,9 +150,9 @@ bool WbNodeModel::fuzzyParseNode(const QString &fileName, QString &nodeInfo) { return true; } -QStringList WbNodeModel::fieldNames() { +QStringList WbNodeModel::fieldNames() const { QStringList names; - foreach (WbFieldModel *fieldModel, mFieldModels) + foreach (const WbFieldModel *fieldModel, mFieldModels) names.append(fieldModel->name()); return names; } diff --git a/src/webots/vrml/WbNodeModel.hpp b/src/webots/vrml/WbNodeModel.hpp index a2ee4a4fac1..cb821f00fc6 100644 --- a/src/webots/vrml/WbNodeModel.hpp +++ b/src/webots/vrml/WbNodeModel.hpp @@ -49,7 +49,7 @@ class WbNodeModel { // field models WbFieldModel *findFieldModel(const QString &fieldName) const; const QList &fieldModels() const { return mFieldModels; } - QStringList fieldNames(); + QStringList fieldNames() const; QStringList documentationBookAndPage() const { return QStringList() << "reference" << mName.toLower(); } diff --git a/src/webots/vrml/WbNodeReader.cpp b/src/webots/vrml/WbNodeReader.cpp index 5d231caf150..b3d3845f835 100644 --- a/src/webots/vrml/WbNodeReader.cpp +++ b/src/webots/vrml/WbNodeReader.cpp @@ -130,6 +130,7 @@ QList WbNodeReader::readNodes(WbTokenizer *tokenizer, const QString &w mReadNodesCanceled = false; return nodes; } + // cppcheck-suppress constVariablePointer WbNode *node = readNode(tokenizer, worldPath); if (node) nodes.append(node); diff --git a/src/webots/vrml/WbParser.cpp b/src/webots/vrml/WbParser.cpp index 19b7ca7cab4..96411fa2a30 100644 --- a/src/webots/vrml/WbParser.cpp +++ b/src/webots/vrml/WbParser.cpp @@ -155,7 +155,7 @@ void WbParser::parseFieldAcceptedValues(WbFieldType type, const QString &worldPa } void WbParser::parseFieldDeclaration(const QString &worldPath) { - WbToken *const token = nextToken(); + const WbToken *const token = nextToken(); if (token->word() != "field" && token->word() != "w3dField" && token->word() != "hiddenField" && token->word() != "deprecatedField" && token->word() != "unconnectedField") reportUnexpected(QObject::tr("'field', 'unconnectedField', 'w3dField' or 'hiddenField' keywords")); @@ -274,7 +274,7 @@ void WbParser::parseEof() { } const QString &WbParser::parseIdentifier(const QString &expected) { - WbToken *token = nextToken(); + const WbToken *token = nextToken(); if (!token->isIdentifier()) reportUnexpected(expected); diff --git a/src/webots/vrml/WbProtoManager.cpp b/src/webots/vrml/WbProtoManager.cpp index 9d7676a50c5..8f35e87d683 100644 --- a/src/webots/vrml/WbProtoManager.cpp +++ b/src/webots/vrml/WbProtoManager.cpp @@ -484,6 +484,7 @@ void WbProtoManager::loadWebotsProtoMap() { } } description = description.replace("\\n", "\n"); + // cppcheck-suppress constVariablePointer WbProtoInfo *const info = new WbProtoInfo(url, baseType, license, licenseUrl, documentationUrl, description, slotType, tags, parameters, needsRobotAncestor); mWebotsProtoList.insert(name, info); @@ -628,6 +629,7 @@ QStringList WbProtoManager::listProtoInCategory(int category) const { } const QMap &WbProtoManager::protoInfoMap(int category) const { + // cppcheck-suppress unassignedVariable static QMap empty; switch (category) { @@ -718,7 +720,7 @@ WbProtoInfo *WbProtoManager::generateInfoFromProtoFile(const QString &protoFileN bool needsRobotAncestor = false; // establish if it requires a Robot ancestor by checking if it contains devices while (tokenizer.hasMoreTokens()) { - WbToken *token = tokenizer.nextToken(); + const WbToken *token = tokenizer.nextToken(); if (token->isIdentifier() && mNeedsRobotAncestorCallback(token->word())) { needsRobotAncestor = true; break; @@ -840,14 +842,14 @@ void WbProtoManager::clearExternProtoClipboardBuffer() { QList WbProtoManager::externProtoClipboardBufferUrls() const { QList list; - foreach (WbExternProto *proto, mExternProtoClipboardBuffer) + foreach (const WbExternProto *proto, mExternProtoClipboardBuffer) list << proto->url(); return list; } void WbProtoManager::resetExternProtoClipboardBuffer(const QList &bufferUrls) { clearExternProtoClipboardBuffer(); - foreach (QString url, bufferUrls) + foreach (const QString &url, bufferUrls) saveToExternProtoClipboardBuffer(url); } diff --git a/src/webots/vrml/WbProtoManager.hpp b/src/webots/vrml/WbProtoManager.hpp index 6c2073d7437..79d48235a62 100644 --- a/src/webots/vrml/WbProtoManager.hpp +++ b/src/webots/vrml/WbProtoManager.hpp @@ -150,7 +150,7 @@ class WbProtoManager : public QObject { void retrieveLocalProtoDependencies(); // used primarily when populating the dialog windows - QMap webotsProtoList() { return mWebotsProtoList; }; + const QMap &webotsProtoList() { return mWebotsProtoList; }; // generates meta info from a PROTO file (license, tags, ...) WbProtoInfo *generateInfoFromProtoFile(const QString &protoFileName); diff --git a/src/webots/vrml/WbProtoModel.cpp b/src/webots/vrml/WbProtoModel.cpp index b78fa5e7834..4a2a13cccc8 100644 --- a/src/webots/vrml/WbProtoModel.cpp +++ b/src/webots/vrml/WbProtoModel.cpp @@ -246,7 +246,7 @@ WbProtoModel::WbProtoModel(WbTokenizer *tokenizer, const QString &worldPath, con QStringList derivedParameterNames = parameterNames(); QStringList baseParameterNames = baseProtoModel->parameterNames(); baseTypeSlotType = baseProtoModel->slotType(); - foreach (QString derivedName, derivedParameterNames) { + foreach (const QString &derivedName, derivedParameterNames) { if (baseParameterNames.contains(derivedName)) sharedParameterNames.append(derivedName); } @@ -265,6 +265,7 @@ WbProtoModel::WbProtoModel(WbTokenizer *tokenizer, const QString &worldPath, con } } else if (sharedParameterNames.contains(token->word()) && !previousRedirectedFieldName.isEmpty()) { // check that derived parameter is only redirected to corresponding base parameter + // cppcheck-suppress variableScope QString parameterName = token->word(); if (previousRedirectedFieldName != token->word()) { tokenizer->reportError( @@ -330,7 +331,7 @@ WbProtoModel::WbProtoModel(WbTokenizer *tokenizer, const QString &worldPath, con } WbProtoModel::~WbProtoModel() { - foreach (WbFieldModel *model, mFieldModels) + foreach (const WbFieldModel *model, mFieldModels) model->unref(); mFieldModels.clear(); mDeterministicContentMap.clear(); @@ -350,7 +351,7 @@ WbNode *WbProtoModel::generateRoot(const QVector ¶meters, const Q if (mTemplate) { QString key; if (mIsDeterministic) { - foreach (WbField *parameter, parameters) { + foreach (const WbField *parameter, parameters) { if (parameter->isTemplateRegenerator()) { QString statement = WbProtoTemplateEngine::convertFieldValueToJavaScriptStatement(parameter); if (mTemplateLanguage == "lua") @@ -468,6 +469,7 @@ const QString WbProtoModel::projectPath() const { if (protoProjectDir.isRoot()) return QString(); } + // cppcheck-suppress ignoredReturnErrorCode protoProjectDir.cdUp(); return protoProjectDir.absolutePath(); } @@ -476,7 +478,7 @@ const QString WbProtoModel::projectPath() const { QStringList WbProtoModel::parameterNames() const { QStringList names; - foreach (WbFieldModel *fieldModel, mFieldModels) + foreach (const WbFieldModel *fieldModel, mFieldModels) names.append(fieldModel->name()); return names; } @@ -497,7 +499,7 @@ void WbProtoModel::verifyNodeAliasing(WbNode *node, WbFieldModel *param, WbToken fields = node->fields(); // search self - foreach (WbField *field, fields) { + foreach (const WbField *field, fields) { if (field->alias() == param->name()) { if (field->type() == param->type()) ok = true; diff --git a/src/webots/vrml/WbProtoTemplateEngine.hpp b/src/webots/vrml/WbProtoTemplateEngine.hpp index 04cd3692d0c..fe1f52cc073 100644 --- a/src/webots/vrml/WbProtoTemplateEngine.hpp +++ b/src/webots/vrml/WbProtoTemplateEngine.hpp @@ -32,7 +32,7 @@ class WbProtoTemplateEngine : public WbTemplateEngine { public: explicit WbProtoTemplateEngine(const QString &templateContent); - virtual ~WbProtoTemplateEngine() {} + virtual ~WbProtoTemplateEngine() override {} bool generate(const QString &logHeaderName, const QVector ¶meters, const QString &protoPath, const QString &worldPath, int id, const QString &templateLanguage); diff --git a/src/webots/vrml/WbProtoTreeItem.cpp b/src/webots/vrml/WbProtoTreeItem.cpp index a7048eebb2d..dc0409a67a6 100644 --- a/src/webots/vrml/WbProtoTreeItem.cpp +++ b/src/webots/vrml/WbProtoTreeItem.cpp @@ -99,6 +99,7 @@ void WbProtoTreeItem::parseItem() { continue; } + // cppcheck-suppress constVariablePointer WbProtoTreeItem *child = new WbProtoTreeItem(subProtoUrl, this, hasImportableKeyword); mChildren.append(child); } @@ -163,7 +164,7 @@ void WbProtoTreeItem::downloadUpdate() { void WbProtoTreeItem::readyCheck() { mIsReady = true; - foreach (WbProtoTreeItem *subProto, mChildren) + foreach (const WbProtoTreeItem *subProto, mChildren) mIsReady = mIsReady && subProto->isReady(); if (mIsReady) { @@ -199,6 +200,7 @@ void WbProtoTreeItem::generateSessionProtoList(QStringList &sessionList) { void WbProtoTreeItem::insert(const QString &url) { // since the insert function is used to inject missing declarations, by default they have to be considered as non-importable + // cppcheck-suppress constVariablePointer WbProtoTreeItem *child = new WbProtoTreeItem(url, this, false); mChildren.append(child); } diff --git a/src/webots/vrml/WbProtoTreeItem.hpp b/src/webots/vrml/WbProtoTreeItem.hpp index 27b10b1207a..e30d363998d 100644 --- a/src/webots/vrml/WbProtoTreeItem.hpp +++ b/src/webots/vrml/WbProtoTreeItem.hpp @@ -35,7 +35,7 @@ class WbProtoTreeItem : public QObject { const QString &url() const { return mUrl; } const QStringList &error() const { return mError; } const WbProtoTreeItem *parent() const { return mParent; } - const QList children() const { return mChildren; } + const QList &children() const { return mChildren; } bool isImportable() const { return mImportable; } void setImportable(bool value) { mImportable = value; } diff --git a/src/webots/vrml/WbSFBool.hpp b/src/webots/vrml/WbSFBool.hpp index a8c8873bdc9..b102bedaa51 100644 --- a/src/webots/vrml/WbSFBool.hpp +++ b/src/webots/vrml/WbSFBool.hpp @@ -29,7 +29,7 @@ class WbSFBool : public WbSingleValue { WbSFBool(WbTokenizer *tokenizer, const QString &worldPath) { readSFBool(tokenizer, worldPath); } WbSFBool(const WbSFBool &other); explicit WbSFBool(bool value) : mValue(value) {} - virtual ~WbSFBool() {} + virtual ~WbSFBool() override {} void read(WbTokenizer *tokenizer, const QString &worldPath) override { readSFBool(tokenizer, worldPath); } void write(WbWriter &writer) const override { writer << toString(WbPrecision::DOUBLE_MAX); } WbValue *clone() const override { return new WbSFBool(*this); } diff --git a/src/webots/vrml/WbSFColor.hpp b/src/webots/vrml/WbSFColor.hpp index 1755055e860..892a68c840d 100644 --- a/src/webots/vrml/WbSFColor.hpp +++ b/src/webots/vrml/WbSFColor.hpp @@ -30,7 +30,7 @@ class WbSFColor : public WbSingleValue { explicit WbSFColor(double r, double g, double b) : mValue(WbRgb(r, g, b)) {} WbSFColor(WbTokenizer *tokenizer, const QString &worldPath) { readSFColor(tokenizer, worldPath); } WbSFColor(const WbSFColor &other) : mValue(other.mValue) {} - virtual ~WbSFColor() {} + virtual ~WbSFColor() override {} void read(WbTokenizer *tokenizer, const QString &worldPath) override { readSFColor(tokenizer, worldPath); } void write(WbWriter &writer) const override { writer << toString(writer.isWebots() ? WbPrecision::DOUBLE_MAX : WbPrecision::FLOAT_MAX); diff --git a/src/webots/vrml/WbSFDouble.hpp b/src/webots/vrml/WbSFDouble.hpp index 3c7a9286609..02521488228 100644 --- a/src/webots/vrml/WbSFDouble.hpp +++ b/src/webots/vrml/WbSFDouble.hpp @@ -31,7 +31,7 @@ class WbSFDouble : public WbSingleValue { WbSFDouble(WbTokenizer *tokenizer, const QString &worldPath) { readSFDouble(tokenizer, worldPath); } WbSFDouble(const WbSFDouble &other) : mValue(other.mValue) {} explicit WbSFDouble(double d) : mValue(d) {} - virtual ~WbSFDouble() {} + virtual ~WbSFDouble() override {} void read(WbTokenizer *tokenizer, const QString &worldPath) override { readSFDouble(tokenizer, worldPath); } void write(WbWriter &writer) const override { writer << toString(writer.isWebots() ? WbPrecision::DOUBLE_MAX : WbPrecision::FLOAT_MAX); diff --git a/src/webots/vrml/WbSFInt.hpp b/src/webots/vrml/WbSFInt.hpp index 0a1e13ce4cc..1b5589d9cb0 100644 --- a/src/webots/vrml/WbSFInt.hpp +++ b/src/webots/vrml/WbSFInt.hpp @@ -29,7 +29,7 @@ class WbSFInt : public WbSingleValue { WbSFInt(WbTokenizer *tokenizer, const QString &worldPath) { readSFInt(tokenizer, worldPath); } WbSFInt(const WbSFInt &other); explicit WbSFInt(int value) : mValue(value) {} - virtual ~WbSFInt() {} + virtual ~WbSFInt() override {} void read(WbTokenizer *tokenizer, const QString &worldPath) override { readSFInt(tokenizer, worldPath); } void write(WbWriter &writer) const override { writer << mValue; } WbValue *clone() const override { return new WbSFInt(*this); } diff --git a/src/webots/vrml/WbSFNode.hpp b/src/webots/vrml/WbSFNode.hpp index c515947c5b9..0f3edf3ee5f 100644 --- a/src/webots/vrml/WbSFNode.hpp +++ b/src/webots/vrml/WbSFNode.hpp @@ -30,7 +30,7 @@ class WbSFNode : public WbSingleValue { WbSFNode(WbTokenizer *tokenizer, const QString &worldPath); WbSFNode(const WbSFNode &other); explicit WbSFNode(WbNode *node); - virtual ~WbSFNode(); + virtual ~WbSFNode() override; void read(WbTokenizer *tokenizer, const QString &worldPath) override { readSFNode(tokenizer, worldPath); } void write(WbWriter &writer) const override; WbValue *clone() const override { return new WbSFNode(*this); } diff --git a/src/webots/vrml/WbSFRotation.hpp b/src/webots/vrml/WbSFRotation.hpp index 621d1a550c0..582eb60871e 100644 --- a/src/webots/vrml/WbSFRotation.hpp +++ b/src/webots/vrml/WbSFRotation.hpp @@ -31,7 +31,7 @@ class WbSFRotation : public WbSingleValue { WbSFRotation(WbTokenizer *tokenizer, const QString &worldPath) { readSFRotation(tokenizer, worldPath); } WbSFRotation(const WbSFRotation &other) : mValue(other.mValue) {} explicit WbSFRotation(const WbRotation &r) : mValue(r) {} - virtual ~WbSFRotation() {} + virtual ~WbSFRotation() override {} void read(WbTokenizer *tokenizer, const QString &worldPath) override { readSFRotation(tokenizer, worldPath); } void write(WbWriter &writer) const override { writer << toString(writer.isWebots() ? WbPrecision::DOUBLE_MAX : WbPrecision::FLOAT_MAX); diff --git a/src/webots/vrml/WbSFString.hpp b/src/webots/vrml/WbSFString.hpp index 047c2ef6bd6..cfd3fa4173b 100644 --- a/src/webots/vrml/WbSFString.hpp +++ b/src/webots/vrml/WbSFString.hpp @@ -29,7 +29,7 @@ class WbSFString : public WbSingleValue { explicit WbSFString(const QString &s) : mValue(s) {} WbSFString(WbTokenizer *tokenizer, const QString &worldPath) { readSFString(tokenizer, worldPath); } WbSFString(const WbSFString &other) : mValue(other.mValue) {} - virtual ~WbSFString() {} + virtual ~WbSFString() override {} void read(WbTokenizer *tokenizer, const QString &worldPath) override { readSFString(tokenizer, worldPath); } void write(WbWriter &writer) const override { writer.writeLiteralString(mValue); } WbValue *clone() const override { return new WbSFString(*this); } diff --git a/src/webots/vrml/WbSFVector2.hpp b/src/webots/vrml/WbSFVector2.hpp index 3546893cd36..b0247813a1c 100644 --- a/src/webots/vrml/WbSFVector2.hpp +++ b/src/webots/vrml/WbSFVector2.hpp @@ -29,7 +29,7 @@ class WbSFVector2 : public WbSingleValue { public: WbSFVector2(WbTokenizer *tokenizer, const QString &worldPath) { readSFVector2(tokenizer, worldPath); } WbSFVector2(const WbSFVector2 &other) : mValue(other.mValue) {} - virtual ~WbSFVector2() {} + virtual ~WbSFVector2() override {} void read(WbTokenizer *tokenizer, const QString &worldPath) override { readSFVector2(tokenizer, worldPath); } void write(WbWriter &writer) const override { writer << toString(writer.isWebots() ? WbPrecision::DOUBLE_MAX : WbPrecision::FLOAT_MAX); diff --git a/src/webots/vrml/WbSFVector3.hpp b/src/webots/vrml/WbSFVector3.hpp index dab2a9c78e2..768ce5b0c3b 100644 --- a/src/webots/vrml/WbSFVector3.hpp +++ b/src/webots/vrml/WbSFVector3.hpp @@ -31,7 +31,7 @@ class WbSFVector3 : public WbSingleValue { WbSFVector3(WbTokenizer *tokenizer, const QString &worldPath) { readSFVector3(tokenizer, worldPath); } WbSFVector3(const WbSFVector3 &other) : mValue(other.mValue) {} explicit WbSFVector3(const WbVector3 &v) : mValue(v) {} - virtual ~WbSFVector3() {} + virtual ~WbSFVector3() override {} void read(WbTokenizer *tokenizer, const QString &worldPath) override { readSFVector3(tokenizer, worldPath); }; void write(WbWriter &writer) const override { writer << toString(writer.isWebots() ? WbPrecision::DOUBLE_MAX : WbPrecision::FLOAT_MAX); diff --git a/src/webots/vrml/WbSingleValue.hpp b/src/webots/vrml/WbSingleValue.hpp index 5e634743e1d..e7602f8ae98 100644 --- a/src/webots/vrml/WbSingleValue.hpp +++ b/src/webots/vrml/WbSingleValue.hpp @@ -29,7 +29,7 @@ class WbSingleValue : public WbValue { Q_OBJECT public: - virtual ~WbSingleValue(); + virtual ~WbSingleValue() override; // return generic value virtual WbVariant variantValue() const = 0; diff --git a/src/webots/vrml/WbTokenizer.cpp b/src/webots/vrml/WbTokenizer.cpp index 8b35fc9096e..7281a98d706 100644 --- a/src/webots/vrml/WbTokenizer.cpp +++ b/src/webots/vrml/WbTokenizer.cpp @@ -58,7 +58,7 @@ void WbTokenizer::skipToken(const char *expectedWord) { throw 0; } - WbToken *token = nextToken(); + const WbToken *token = nextToken(); if (token->word() != expectedWord) { reportError(QObject::tr("Expected '%1' but found '%2'").arg(expectedWord).arg(token->word()), token); @@ -422,6 +422,7 @@ int WbTokenizer::tokenize(const QString &fileName, const QString &prefix) { mChar = readChar(); while (true) { QString word = readWord(); + // cppcheck-suppress constVariablePointer WbToken *token = new WbToken(word, mTokenLine, mTokenColumn); mVector.append(token); if (!token->isValid()) { @@ -455,6 +456,7 @@ int WbTokenizer::tokenizeString(const QString &string) { mChar = readChar(); while (true) { QString word = readWord(); + // cppcheck-suppress constVariablePointer WbToken *token = new WbToken(word, mTokenLine, mTokenColumn); mVector.append(token); if (!token->isValid()) { @@ -488,7 +490,7 @@ const QStringList WbTokenizer::tags() const { const QString WbTokenizer::templateLanguage() const { const QStringList lines = mInfo.split("\n"); - foreach (QString line, lines) { + foreach (const QString &line, lines) { if (line.startsWith("template language:") && line.toLower().contains("javascript")) { return QString("javascript"); } diff --git a/src/webots/vrml/WbVrmlNodeUtilities.cpp b/src/webots/vrml/WbVrmlNodeUtilities.cpp index 1348cd9a650..4eeedbe0c7a 100644 --- a/src/webots/vrml/WbVrmlNodeUtilities.cpp +++ b/src/webots/vrml/WbVrmlNodeUtilities.cpp @@ -27,7 +27,7 @@ namespace { bool checkForUseOrDefNode(const WbNode *node, const QString &useName, const QString &previousUseName, bool &useOverlap, bool &defOverlap, bool &abortSearch); - bool checkForUseOrDefNode(WbField *field, const QString &useName, const QString &previousUseName, bool &useOverlap, + bool checkForUseOrDefNode(const WbField *field, const QString &useName, const QString &previousUseName, bool &useOverlap, bool &defOverlap, bool &abortSearch) { WbValue *const value = field->value(); const WbMFNode *const mfnode = dynamic_cast(value); @@ -157,8 +157,8 @@ bool WbVrmlNodeUtilities::isFieldDescendant(const WbNode *node, const QString &f if (node == NULL) return false; - WbNode *n = node->parentNode(); - WbField *field = node->parentField(true); + const WbNode *n = node->parentNode(); + const WbField *field = node->parentField(true); while (n && !n->isWorldRoot() && field) { if (field->name() == fieldName) return true; @@ -251,7 +251,7 @@ const WbField *WbVrmlNodeUtilities::findClosestParameterInProto(const WbField *f WbNode *WbVrmlNodeUtilities::findRootProtoNode(WbNode *const node) { WbNode *n = node; do { - WbProtoModel *proto = n->proto(); + const WbProtoModel *proto = n->proto(); if (proto) return n; n = n->parentNode(); @@ -282,7 +282,7 @@ QList WbVrmlNodeUtilities::protoNodesInWorldFile(const WbNode *r return result; } -bool WbVrmlNodeUtilities::existsVisibleProtoNodeNamed(const QString &modelName, WbNode *root) { +bool WbVrmlNodeUtilities::existsVisibleProtoNodeNamed(const QString &modelName, const WbNode *root) { if (!root) return false; @@ -304,7 +304,7 @@ bool WbVrmlNodeUtilities::existsVisibleProtoNodeNamed(const QString &modelName, return false; } -WbNode *WbVrmlNodeUtilities::findUpperTemplateNeedingRegenerationFromField(WbField *modifiedField, WbNode *parentNode) { +WbNode *WbVrmlNodeUtilities::findUpperTemplateNeedingRegenerationFromField(const WbField *modifiedField, WbNode *parentNode) { if (parentNode == NULL || modifiedField == NULL) return NULL; @@ -314,11 +314,11 @@ WbNode *WbVrmlNodeUtilities::findUpperTemplateNeedingRegenerationFromField(WbFie return findUpperTemplateNeedingRegeneration(parentNode); } -WbNode *WbVrmlNodeUtilities::findUpperTemplateNeedingRegeneration(WbNode *modifiedNode) { +WbNode *WbVrmlNodeUtilities::findUpperTemplateNeedingRegeneration(const WbNode *modifiedNode) { if (modifiedNode == NULL) return NULL; - WbField *field = modifiedNode->parentField(); + const WbField *field = modifiedNode->parentField(); WbNode *node = modifiedNode->parentNode(); while (node && field && !node->isWorldRoot()) { if (node->isTemplate() && field->isTemplateRegenerator()) @@ -363,7 +363,7 @@ bool WbVrmlNodeUtilities::hasASubsequentUseOrDefNode(const WbNode *defNode, cons const WbNode *parentNode = node->parentNode(); while (parentNode) { - WbField *const parentField = node->parentField(); + const WbField *const parentField = node->parentField(); const WbMFNode *const mfnode = dynamic_cast(parentField->value()); if (mfnode) { const int index = mfnode->nodeIndex(node) + 1; @@ -423,7 +423,7 @@ bool WbVrmlNodeUtilities::hasAreferredDefNodeDescendant(const WbNode *node, cons return true; } - foreach (WbField *field, node->fieldsOrParameters()) { + foreach (const WbField *field, node->fieldsOrParameters()) { WbValue *value = field->value(); const WbSFNode *const sfnode = dynamic_cast(value); if (sfnode && sfnode->value()) { @@ -466,6 +466,7 @@ QList WbVrmlNodeUtilities::findUseNodeAncestors(WbNode *node) { if (node == NULL) return list; + // cppcheck-suppress constVariablePointer WbNode *n = node; while (n && !n->isWorldRoot()) { if (n->isUseNode()) @@ -476,7 +477,7 @@ QList WbVrmlNodeUtilities::findUseNodeAncestors(WbNode *node) { return list; } -QString WbVrmlNodeUtilities::exportNodeToString(WbNode *node) { +QString WbVrmlNodeUtilities::exportNodeToString(const WbNode *node) { QString nodeString; WbWriter writer(&nodeString, ".wbt"); node->write(writer); diff --git a/src/webots/vrml/WbVrmlNodeUtilities.hpp b/src/webots/vrml/WbVrmlNodeUtilities.hpp index 26671e1cf3f..b67090826a1 100644 --- a/src/webots/vrml/WbVrmlNodeUtilities.hpp +++ b/src/webots/vrml/WbVrmlNodeUtilities.hpp @@ -57,15 +57,15 @@ namespace WbVrmlNodeUtilities { // checks whether a node of specific model name exists in the node tree and returns true if it is visible // default fields that won't be written to the WBT file are skipped - bool existsVisibleProtoNodeNamed(const QString &modelName, WbNode *root); + bool existsVisibleProtoNodeNamed(const QString &modelName, const WbNode *root); // find the closest template ancestor in which the modified node is contained in template field // which requires a template instance regeneration - WbNode *findUpperTemplateNeedingRegeneration(WbNode *modifiedNode); + WbNode *findUpperTemplateNeedingRegeneration(const WbNode *modifiedNode); // find the closest template ancestor of given field in which the modified field is contained // in template field which requires a template instance regeneration - WbNode *findUpperTemplateNeedingRegenerationFromField(WbField *modifiedField, WbNode *parentNode); + WbNode *findUpperTemplateNeedingRegenerationFromField(const WbField *modifiedField, WbNode *parentNode); ////////////////////////////// // Non-permanent properties // @@ -86,7 +86,7 @@ namespace WbVrmlNodeUtilities { /////////// // Other // /////////// - QString exportNodeToString(WbNode *node); + QString exportNodeToString(const WbNode *node); bool transformBackwardCompatibility(WbTokenizer *tokenizer); } // namespace WbVrmlNodeUtilities diff --git a/src/webots/vrml/WbWriter.hpp b/src/webots/vrml/WbWriter.hpp index a18a273bd32..4738a787286 100644 --- a/src/webots/vrml/WbWriter.hpp +++ b/src/webots/vrml/WbWriter.hpp @@ -54,7 +54,7 @@ class WbWriter { void writeFieldStart(const QString &name, bool w3dQuote); void writeFieldEnd(bool w3dQuote); - WbVector3 jointOffset() const { return mJointOffset; } + const WbVector3 &jointOffset() const { return mJointOffset; } void setJointOffset(const WbVector3 &offset) { mJointOffset = offset; } // change current indentation @@ -73,7 +73,7 @@ class WbWriter { void trackDeclaration(const QString &protoName, const QString &protoUrl) { mTrackedDeclarations.append(std::pair(protoName, protoUrl)); }; - QList> declarations() const { return mTrackedDeclarations; }; + const QList> &declarations() const { return mTrackedDeclarations; }; QMap &indexedFaceSetDefMap() { return mIndexedFaceSetDefMap; } WbWriter &operator<<(const QString &s); diff --git a/src/webots/wren/WbSpotLightRepresentation.hpp b/src/webots/wren/WbSpotLightRepresentation.hpp index c546e78f3f3..e313f124a4d 100644 --- a/src/webots/wren/WbSpotLightRepresentation.hpp +++ b/src/webots/wren/WbSpotLightRepresentation.hpp @@ -31,7 +31,7 @@ class WbSpotLightRepresentation : public WbLightRepresentation { // Constructor and destructor WbSpotLightRepresentation(WrTransform *parent, const WbVector3 &position, float radius, float cutOffAngle, const WbVector3 &direction); - ~WbSpotLightRepresentation(); + ~WbSpotLightRepresentation() override; // Setters void setRadius(float radius) { diff --git a/src/webots/wren/WbTesselator.cpp b/src/webots/wren/WbTesselator.cpp index 9c64f80aa0e..802a68a49c2 100644 --- a/src/webots/wren/WbTesselator.cpp +++ b/src/webots/wren/WbTesselator.cpp @@ -77,8 +77,8 @@ static void tessEnd() { // the glu tesselator calls this function in the right order to populate the // index list static void tessVertexData(void *vertex, void *r) { - QList> *results = (QList> *)r; - TesselatorData *tesselatorData = static_cast(vertex); + QList> *results = static_cast> *>(r); + const TesselatorData *tesselatorData = static_cast(vertex); results->append(QVector() << tesselatorData->coordIndex << tesselatorData->normalIndex << tesselatorData->texIndex); } @@ -114,11 +114,11 @@ QString WbTesselator::tesselate(const QList> &indexes, const QList< GLUtesselator *tesselator = gluNewTess(); assert(tesselator); - gluTessCallback(tesselator, GLU_TESS_BEGIN, (GLU_function_pointer)&tessBegin); - gluTessCallback(tesselator, GLU_TESS_VERTEX_DATA, (GLU_function_pointer)&tessVertexData); - gluTessCallback(tesselator, GLU_TESS_END, (GLU_function_pointer)&tessEnd); - gluTessCallback(tesselator, GLU_TESS_EDGE_FLAG, (GLU_function_pointer)&tessEdgeFlag); - gluTessCallback(tesselator, GLU_TESS_ERROR, (GLU_function_pointer)&tessError); + gluTessCallback(tesselator, GLU_TESS_BEGIN, reinterpret_cast(&tessBegin)); + gluTessCallback(tesselator, GLU_TESS_VERTEX_DATA, reinterpret_cast(&tessVertexData)); + gluTessCallback(tesselator, GLU_TESS_END, reinterpret_cast(&tessEnd)); + gluTessCallback(tesselator, GLU_TESS_EDGE_FLAG, reinterpret_cast(&tessEdgeFlag)); + gluTessCallback(tesselator, GLU_TESS_ERROR, reinterpret_cast(&tessError)); gluTessProperty(tesselator, GLU_TESS_WINDING_RULE, GLU_TESS_WINDING_POSITIVE); gluTessBeginPolygon(tesselator, &results); gluTessBeginContour(tesselator); diff --git a/src/webots/wren/WbTranslateRotateManipulator.hpp b/src/webots/wren/WbTranslateRotateManipulator.hpp index 3e5edbf1a31..39d5b4cab01 100644 --- a/src/webots/wren/WbTranslateRotateManipulator.hpp +++ b/src/webots/wren/WbTranslateRotateManipulator.hpp @@ -35,7 +35,7 @@ class WbTranslateRotateManipulator : public WbWrenAbstractManipulator { public: WbTranslateRotateManipulator(bool isTranslationAvailable, bool isRotationAvailable); - virtual ~WbTranslateRotateManipulator(); + virtual ~WbTranslateRotateManipulator() override; // Setters void initializeHandlesEntities(); diff --git a/src/webots/wren/WbWrenAbstractResizeManipulator.hpp b/src/webots/wren/WbWrenAbstractResizeManipulator.hpp index 18eef0e3abe..7d01d758131 100644 --- a/src/webots/wren/WbWrenAbstractResizeManipulator.hpp +++ b/src/webots/wren/WbWrenAbstractResizeManipulator.hpp @@ -30,7 +30,7 @@ class WbWrenAbstractResizeManipulator : public WbWrenAbstractManipulator { public: enum ResizeConstraint { NO_CONSTRAINT, UNIFORM, X_EQUAL_Y }; - virtual ~WbWrenAbstractResizeManipulator(); + virtual ~WbWrenAbstractResizeManipulator() override; // Setters virtual void setResizeConstraint(ResizeConstraint constraint); diff --git a/src/webots/wren/WbWrenFullScreenOverlay.cpp b/src/webots/wren/WbWrenFullScreenOverlay.cpp index 3b3231f5e44..24393c147d3 100644 --- a/src/webots/wren/WbWrenFullScreenOverlay.cpp +++ b/src/webots/wren/WbWrenFullScreenOverlay.cpp @@ -134,7 +134,7 @@ void WbWrenFullScreenOverlay::setupTexture(const QString &text, int fontSize) { wr_texture_set_translucent(WR_TEXTURE(mTexture), false); wr_texture_setup(WR_TEXTURE(mTexture)); - float white[4] = {1.0f, 1.0f, 1.0f, 1.0f}; + const float white[4] = {1.0f, 1.0f, 1.0f, 1.0f}; wr_drawable_texture_set_color(mTexture, white); wr_drawable_texture_clear(mTexture); wr_drawable_texture_set_font(mTexture, font); diff --git a/src/webots/wren/WbWrenPicker.cpp b/src/webots/wren/WbWrenPicker.cpp index 3df93aad7a2..2b78ab90c75 100644 --- a/src/webots/wren/WbWrenPicker.cpp +++ b/src/webots/wren/WbWrenPicker.cpp @@ -142,7 +142,7 @@ bool WbWrenPicker::pick(int x, int y) { char *data = new char[4]; wr_frame_buffer_copy_pixel(mFrameBuffer, 0, x, y, data, true); - unsigned char *data2 = reinterpret_cast(data); + const unsigned char *data2 = reinterpret_cast(data); int id = (data2[0] << 24) | (data2[1] << 16) | (data2[2] << 8) | data2[3]; delete[] data; diff --git a/src/webots/wren/WbWrenTextureOverlay.cpp b/src/webots/wren/WbWrenTextureOverlay.cpp index 154f6b668d6..3130115d00c 100644 --- a/src/webots/wren/WbWrenTextureOverlay.cpp +++ b/src/webots/wren/WbWrenTextureOverlay.cpp @@ -294,7 +294,7 @@ void WbWrenTextureOverlay::copyDataToTexture(void *data, TextureType type, int x if (type == TEXTURE_TYPE_DEPTH) { int *processedData = new int[width * height]; - float *originalData = static_cast(data); + const float *originalData = static_cast(data); const float multiplier = 255.0f / mMaxRange; for (int i = 0; i < width * height; ++i) { unsigned char v = (unsigned char)(multiplier * originalData[i]); diff --git a/src/wren/Camera.hpp b/src/wren/Camera.hpp index 3ac5657e6e5..a93e043e57a 100644 --- a/src/wren/Camera.hpp +++ b/src/wren/Camera.hpp @@ -154,7 +154,7 @@ namespace wren { private: Camera(); - virtual ~Camera() {} + virtual ~Camera() override {} void updateView() const; void updateProjection() const; diff --git a/src/wren/CustomUniform.hpp b/src/wren/CustomUniform.hpp index c76fd443cc4..073de98c409 100644 --- a/src/wren/CustomUniform.hpp +++ b/src/wren/CustomUniform.hpp @@ -49,7 +49,7 @@ namespace wren { template class CustomUniform : public CustomUniformBase { public: CustomUniform(const std::string &name, const T &initialValue) : CustomUniformBase(name), mValue(initialValue) {} - virtual ~CustomUniform() {} + virtual ~CustomUniform() override {} void setValue(const char *value) override { mValue = *(reinterpret_cast(value)); } void uploadValue() const override { diff --git a/src/wren/DirectionalLight.hpp b/src/wren/DirectionalLight.hpp index 972d88a3c14..0b4c5748809 100644 --- a/src/wren/DirectionalLight.hpp +++ b/src/wren/DirectionalLight.hpp @@ -32,11 +32,10 @@ namespace wren { void setDirection(const glm::vec3 &direction); LightNode::Type type() override { return TYPE_DIRECTIONAL; } - void updateFromParent() override {} private: DirectionalLight(); - virtual ~DirectionalLight(); + virtual ~DirectionalLight() override; void recomputeAabb() const override { mAabb = gAabbInf; } diff --git a/src/wren/DrawableTexture.cpp b/src/wren/DrawableTexture.cpp index 49ee41d63b7..b094593cd22 100644 --- a/src/wren/DrawableTexture.cpp +++ b/src/wren/DrawableTexture.cpp @@ -275,7 +275,7 @@ void wr_drawable_texture_set_font(WrDrawableTexture *texture, WrFont *font) { reinterpret_cast(texture)->setFont(reinterpret_cast(font)); } -void wr_drawable_texture_set_color(WrDrawableTexture *texture, float *color) { +void wr_drawable_texture_set_color(WrDrawableTexture *texture, const float *color) { reinterpret_cast(texture)->setColor(color); } diff --git a/src/wren/DrawableTexture.hpp b/src/wren/DrawableTexture.hpp index 79d65b780f5..6aa83bf1617 100644 --- a/src/wren/DrawableTexture.hpp +++ b/src/wren/DrawableTexture.hpp @@ -28,7 +28,7 @@ namespace wren { static DrawableTexture *createDrawableTexture() { return new DrawableTexture(); } void setFont(Font *font) { mFont = font; } - void setColor(float *color) { mColor = toInt(color); } + void setColor(const float *color) { mColor = toInt(color); } void setAntialiasing(bool antialiasing) { mFontAntiAliasing = antialiasing; } void setUsePremultipliedAlpha(bool premultipliedAlpha) { mPremultipliedAlpha = premultipliedAlpha; } @@ -43,7 +43,7 @@ namespace wren { private: DrawableTexture(); - ~DrawableTexture(); + ~DrawableTexture() override; void updateDirtyRect(int x, int y); void resetDirtyRect() { diff --git a/src/wren/DynamicMesh.cpp b/src/wren/DynamicMesh.cpp index dd67d3cf403..25bada53a31 100644 --- a/src/wren/DynamicMesh.cpp +++ b/src/wren/DynamicMesh.cpp @@ -522,7 +522,7 @@ namespace wren { static void createOrCompleteEdge(size_t triangleIndex, unsigned int vertexIndex0, unsigned int vertexIndex1, std::unordered_map, Mesh::Edge> &edgeMap, - std::vector &triangles, std::vector &edges) { + const std::vector &triangles, std::vector &edges) { // Either add the edge to the edge map if it isn't present, or complete // an existing edge if it is already present in the edge map. auto itEdgeInverse = edgeMap.find(std::make_pair(vertexIndex1, vertexIndex0)); diff --git a/src/wren/DynamicMesh.hpp b/src/wren/DynamicMesh.hpp index b70a3806c9c..7f28aee135b 100644 --- a/src/wren/DynamicMesh.hpp +++ b/src/wren/DynamicMesh.hpp @@ -84,7 +84,7 @@ namespace wren { protected: DynamicMesh(bool hasNormals, bool hasTextureCoordinates, bool hasColorPerVertex); - virtual ~DynamicMesh(){}; + virtual ~DynamicMesh() override{}; private: void updateGl(); diff --git a/src/wren/FileImport.cpp b/src/wren/FileImport.cpp index 4acd4baf772..d851aa72da1 100644 --- a/src/wren/FileImport.cpp +++ b/src/wren/FileImport.cpp @@ -214,7 +214,7 @@ namespace wren { DynamicMesh *dynamicMesh = DynamicMesh::createDynamicMesh(mesh->HasNormals(), mesh->HasTextureCoords(0), false); aiMatrix4x4 transform; - aiNode *current = node->mParent; + const aiNode *current = node->mParent; while (current != scene->mRootNode && current != NULL) { transform = transform * node->mTransformation; current = current->mParent; @@ -282,7 +282,7 @@ namespace wren { // Bones hierarchy for (SkeletonBone *bone : bones) { - aiNode *node = scene->mRootNode->FindNode(bone->name()); + const aiNode *node = scene->mRootNode->FindNode(bone->name()); assert(node != NULL); aiNode *current = node->mParent; while (current != NULL) { diff --git a/src/wren/FrameBuffer.cpp b/src/wren/FrameBuffer.cpp index 45f9533a306..c402b36366f 100644 --- a/src/wren/FrameBuffer.cpp +++ b/src/wren/FrameBuffer.cpp @@ -113,7 +113,7 @@ namespace wren { setRequireAction(GlUser::GL_ACTION_PREPARE); } - void FrameBuffer::bind() { + void FrameBuffer::bind() const { glstate::bindFrameBuffer(mGlName); std::vector drawBuffers; @@ -125,13 +125,13 @@ namespace wren { glDrawBuffers(drawBuffers.size(), &drawBuffers[0]); } - void FrameBuffer::blitToScreen() { + void FrameBuffer::blitToScreen() const { glstate::bindDrawFrameBuffer(0); blit(0, true, false, false, 0, 0, mWidth, mHeight, 0, 0, mWidth, mHeight); } - void FrameBuffer::release() { + void FrameBuffer::release() const { glstate::releaseFrameBuffer(mGlName); } @@ -267,7 +267,7 @@ namespace wren { return mOutputTextures[mOutputDrawBuffers[index].mStorageIndex]->glFormatParams(); } - void FrameBuffer::swapTexture(TextureRtt *texture) { + void FrameBuffer::swapTexture(const TextureRtt *texture) { glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, GL_TEXTURE_2D, texture->glName(), 0); } diff --git a/src/wren/FrameBuffer.hpp b/src/wren/FrameBuffer.hpp index 6220a473bd3..8d551923dcf 100644 --- a/src/wren/FrameBuffer.hpp +++ b/src/wren/FrameBuffer.hpp @@ -51,7 +51,7 @@ namespace wren { // Encapsulate memory management static FrameBuffer *createFrameBuffer() { return new FrameBuffer(); } static void deleteFrameBuffer(FrameBuffer *frameBuffer); - static void swapTexture(TextureRtt *texture); + static void swapTexture(const TextureRtt *texture); void appendOutputTexture(TextureRtt *texture); void appendOutputTextureDisable(TextureRtt *texture); @@ -81,9 +81,9 @@ namespace wren { unsigned int glName() const { return mGlName; } void setup(); - void blitToScreen(); - void bind(); - void release(); + void blitToScreen() const; + void bind() const; + void release() const; void initiateCopyToPbo(); void copyContents(size_t index, void *data); @@ -97,7 +97,7 @@ namespace wren { private: FrameBuffer(); - ~FrameBuffer() {} + ~FrameBuffer() override {} const Texture::GlFormatParams &drawBufferFormat(size_t index) const; diff --git a/src/wren/LightNode.cpp b/src/wren/LightNode.cpp index f5852d4d380..435d49da433 100644 --- a/src/wren/LightNode.cpp +++ b/src/wren/LightNode.cpp @@ -47,7 +47,7 @@ namespace wren { // debug::printVec4(LightNode::cActiveLights.mAmbientLight, "ambient light"); glm::int32 lightCount = 0; - for (DirectionalLight *l : directionalLights) { + for (const DirectionalLight *l : directionalLights) { if (!l->parent() || l->parent()->isVisible()) { LightNode::cActiveLights.mDirectionalLights[lightCount].mColorAndIntensity = glm::vec4(l->color(), l->intensity()), LightNode::cActiveLights.mDirectionalLights[lightCount].mDirection = @@ -65,7 +65,7 @@ namespace wren { // DEBUG(lightCount << " active directional lights"); lightCount = 0; - for (PointLight *l : pointLights) { + for (const PointLight *l : pointLights) { if (!l->parent() || l->parent()->isVisible()) { LightNode::cActiveLights.mPointLights[lightCount].mColorAndIntensity = glm::vec4(l->color(), l->intensity()), LightNode::cActiveLights.mPointLights[lightCount].mPosition = camera->view() * glm::vec4(l->position(), 1.0); @@ -86,7 +86,7 @@ namespace wren { LightNode::cActiveLights.mLightCount[1] = lightCount; lightCount = 0; - for (SpotLight *l : spotLights) { + for (const SpotLight *l : spotLights) { if (!l->parent() || l->parent()->isVisible()) { LightNode::cActiveLights.mSpotLights[lightCount].mColorAndIntensity = glm::vec4(l->color(), l->intensity()), LightNode::cActiveLights.mSpotLights[lightCount].mPosition = camera->view() * glm::vec4(l->position(), 1.0f); diff --git a/src/wren/LightNode.hpp b/src/wren/LightNode.hpp index 39f18b8e322..b2afc36106e 100644 --- a/src/wren/LightNode.hpp +++ b/src/wren/LightNode.hpp @@ -69,7 +69,7 @@ namespace wren { protected: LightNode(); - virtual ~LightNode(); + virtual ~LightNode() override; static std::vector cActiveLightsCastingShadows; diff --git a/src/wren/Mesh.hpp b/src/wren/Mesh.hpp index f45a38398ee..03c3e3c9ceb 100644 --- a/src/wren/Mesh.hpp +++ b/src/wren/Mesh.hpp @@ -114,7 +114,7 @@ namespace wren { protected: Mesh() {} - virtual ~Mesh(){}; + virtual ~Mesh() override{}; std::vector mCoords; std::vector mNormals; diff --git a/src/wren/Overlay.cpp b/src/wren/Overlay.cpp index c6468b92da9..ac2a211fb61 100644 --- a/src/wren/Overlay.cpp +++ b/src/wren/Overlay.cpp @@ -159,7 +159,7 @@ namespace wren { cOverlays.erase(std::remove(cOverlays.begin(), cOverlays.end(), this), cOverlays.end()); } - void Overlay::prepareTexture(Texture *texture, int textureUnitIndex) { + void Overlay::prepareTexture(Texture *texture, int textureUnitIndex) const { if (!texture) return; diff --git a/src/wren/Overlay.hpp b/src/wren/Overlay.hpp index 2fff05d1ebe..12d28c42998 100644 --- a/src/wren/Overlay.hpp +++ b/src/wren/Overlay.hpp @@ -89,7 +89,7 @@ namespace wren { Overlay(); ~Overlay(); - void prepareTexture(Texture *texture, int textureUnitIndex); + void prepareTexture(Texture *texture, int textureUnitIndex) const; static ShaderProgram *cDefaultSizeProgram; static size_t cMaxOrder; diff --git a/src/wren/PbrMaterial.hpp b/src/wren/PbrMaterial.hpp index 08187971c24..f4f3dc0e83d 100644 --- a/src/wren/PbrMaterial.hpp +++ b/src/wren/PbrMaterial.hpp @@ -58,7 +58,7 @@ namespace wren { private: PbrMaterial(); - ~PbrMaterial(); + ~PbrMaterial() override; void init(); static std::unordered_map cCache; diff --git a/src/wren/PhongMaterial.hpp b/src/wren/PhongMaterial.hpp index 5d474d5a98d..2a377498fd6 100644 --- a/src/wren/PhongMaterial.hpp +++ b/src/wren/PhongMaterial.hpp @@ -57,7 +57,7 @@ namespace wren { private: PhongMaterial(); - ~PhongMaterial(); + ~PhongMaterial() override; void init(); static std::unordered_map cCache; diff --git a/src/wren/PointLight.hpp b/src/wren/PointLight.hpp index c32cbca28d4..8386cdc301d 100644 --- a/src/wren/PointLight.hpp +++ b/src/wren/PointLight.hpp @@ -30,7 +30,7 @@ namespace wren { private: PointLight(); - virtual ~PointLight(); + virtual ~PointLight() override; }; } // namespace wren diff --git a/src/wren/PositionalLight.hpp b/src/wren/PositionalLight.hpp index d943adcdb8a..25c34d5d33d 100644 --- a/src/wren/PositionalLight.hpp +++ b/src/wren/PositionalLight.hpp @@ -56,7 +56,7 @@ namespace wren { protected: PositionalLight(); - virtual ~PositionalLight() {} + virtual ~PositionalLight() override {} private: mutable bool mIsPositionDirty; diff --git a/src/wren/Renderable.cpp b/src/wren/Renderable.cpp index e424d493a39..47b93855c0d 100644 --- a/src/wren/Renderable.cpp +++ b/src/wren/Renderable.cpp @@ -343,10 +343,11 @@ void wr_renderable_set_z_sorted_rendering(WrRenderable *renderable, bool z_sorte WrMaterial *wr_renderable_get_material(WrRenderable *renderable, const char *name) { if (!name) { - wren::Material *defaultMaterial = reinterpret_cast(renderable)->defaultMaterial(); + const wren::Material *defaultMaterial = reinterpret_cast(renderable)->defaultMaterial(); return defaultMaterial->materialStructure(); } else { - wren::Material *optionalMaterial = reinterpret_cast(renderable)->optionalMaterial(std::string(name)); + const wren::Material *optionalMaterial = + reinterpret_cast(renderable)->optionalMaterial(std::string(name)); if (optionalMaterial) return optionalMaterial->materialStructure(); else diff --git a/src/wren/Renderable.hpp b/src/wren/Renderable.hpp index 18a974d8c83..f3b2da15d09 100644 --- a/src/wren/Renderable.hpp +++ b/src/wren/Renderable.hpp @@ -46,7 +46,7 @@ namespace wren { void setDefaultMaterial(Material *material) { mDefaultMaterial = material; } void setEffectiveMaterial(Material *material) { mEffectiveMaterial = material; } - void setOptionalMaterial(std::string name, Material *material) { mOptionalMaterials[name] = material; } + void setOptionalMaterial(const std::string &name, Material *material) { mOptionalMaterials[name] = material; } // To ensure a valid bounding sphere, only set a Mesh to a Renderable after having called Mesh::setup. void setMesh(Mesh *mesh); @@ -96,7 +96,7 @@ namespace wren { static const char *cUseMaterialName; Renderable(); - virtual ~Renderable(); + virtual ~Renderable() override; void setupAndRender(const ShaderProgram *program); void updateShadowVolumeCaster(); diff --git a/src/wren/Scene.cpp b/src/wren/Scene.cpp index 5733e1041fe..90791423099 100644 --- a/src/wren/Scene.cpp +++ b/src/wren/Scene.cpp @@ -236,7 +236,7 @@ namespace wren { renderToViewports({mMainViewport}, culling); } - void Scene::renderToViewports(std::vector viewports, bool culling) { + void Scene::renderToViewports(const std::vector &viewports, bool culling) { assert(glstate::isInitialized()); DEBUG("Notify frame listeners..."); @@ -585,10 +585,6 @@ namespace wren { return std::partition(first, last, [](const Renderable *r) -> bool { return !r->receiveShadows(); }); } - Scene::RenderQueueIterator Scene::partitionByZOrder(RenderQueueIterator first, RenderQueueIterator last) { - return std::partition(first, last, [](const Renderable *r) -> bool { return r->zSortedRendering(); }); - } - Scene::ShadowVolumeIterator Scene::partitionShadowsByVisibility(ShadowVolumeIterator first, ShadowVolumeIterator last, LightNode *light) { return std::partition(first, last, [this, &light](ShadowVolumeCaster *shadowVolume) -> bool { @@ -600,7 +596,7 @@ namespace wren { std::sort(first, last, [](const Renderable *a, const Renderable *b) -> bool { return a->sortingId() > b->sortingId(); }); } - void Scene::sortRenderQueueByDistance(RenderQueueIterator first, RenderQueueIterator last) { + void Scene::sortRenderQueueByDistance(RenderQueueIterator first, RenderQueueIterator last) const { for (auto it = first; it < last; ++it) (*it)->recomputeBoundingSphereInViewSpace(mCurrentViewport->camera()->view()); @@ -670,10 +666,10 @@ namespace wren { const primitive::Aabb &cameraAabb = camera->aabb(); glm::vec3 cameraToLightInv; if (light->type() != LightNode::TYPE_DIRECTIONAL) { - PositionalLight *positionalLight = static_cast(light); + const PositionalLight *positionalLight = static_cast(light); cameraToLightInv = 1.0f / glm::normalize(positionalLight->position() - camera->position()); } else { - DirectionalLight *directionalLight = static_cast(light); + const DirectionalLight *directionalLight = static_cast(light); cameraToLightInv = 1.0f / -directionalLight->direction(); } @@ -812,7 +808,7 @@ namespace wren { } } - void Scene::renderStencilFog(RenderQueueIterator first, RenderQueueIterator last) { + void Scene::renderStencilFog(RenderQueueIterator first, RenderQueueIterator last) const { glstate::setBlend(true); glstate::setBlendEquation(GL_FUNC_ADD); glstate::setBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); diff --git a/src/wren/Scene.hpp b/src/wren/Scene.hpp index 029ea598303..d865cbd9043 100644 --- a/src/wren/Scene.hpp +++ b/src/wren/Scene.hpp @@ -91,7 +91,7 @@ namespace wren { int computeNodeCount() const; static void printSceneTree(); void render(bool culling); - void renderToViewports(std::vector viewports, bool culling); + void renderToViewports(const std::vector &viewports, bool culling); void addFrameListener(void (*listener)()) { mListeners.push_back(listener); } void removeFrameListener(void (*listener)()); @@ -114,12 +114,11 @@ namespace wren { static RenderQueueIterator partitionByUseMaterial(RenderQueueIterator first, RenderQueueIterator last); static RenderQueueIterator partitionByStencilProgram(RenderQueueIterator first, RenderQueueIterator last); static RenderQueueIterator partitionByShadowReceiving(RenderQueueIterator first, RenderQueueIterator last); - static RenderQueueIterator partitionByZOrder(RenderQueueIterator first, RenderQueueIterator last); ShadowVolumeIterator partitionShadowsByVisibility(ShadowVolumeIterator first, ShadowVolumeIterator last, LightNode *light); static void sortRenderQueueByState(RenderQueueIterator first, RenderQueueIterator last); - void sortRenderQueueByDistance(RenderQueueIterator first, RenderQueueIterator last); + void sortRenderQueueByDistance(RenderQueueIterator first, RenderQueueIterator last) const; static void renderDefault(RenderQueueIterator first, RenderQueueIterator last, bool disableDepthTest = false); void renderStencilPerLight(LightNode *light, RenderQueueIterator first, RenderQueueIterator firstShadowReceiver, @@ -129,7 +128,7 @@ namespace wren { static void renderStencilAmbientEmissive(RenderQueueIterator first, RenderQueueIterator last); static void renderStencilDiffuseSpecular(RenderQueueIterator first, RenderQueueIterator last, LightNode *light, bool applyShadows = true); - void renderStencilFog(RenderQueueIterator first, RenderQueueIterator last); + void renderStencilFog(RenderQueueIterator first, RenderQueueIterator last) const; static void renderStencilWithoutProgram(RenderQueueIterator first, RenderQueueIterator last); static void renderTranslucent(RenderQueueIterator first, RenderQueueIterator last, bool disableDepthTest = false); diff --git a/src/wren/ShaderProgram.hpp b/src/wren/ShaderProgram.hpp index c60d7b84692..9b7da59bf69 100644 --- a/src/wren/ShaderProgram.hpp +++ b/src/wren/ShaderProgram.hpp @@ -83,7 +83,7 @@ namespace wren { static bool readFile(const std::string &path, std::string &contents); ShaderProgram(); - ~ShaderProgram(); + ~ShaderProgram() override; unsigned int compileShader(const std::string &path, unsigned int type); bool linkProgram(); diff --git a/src/wren/Skeleton.hpp b/src/wren/Skeleton.hpp index 6773bc490a0..e6b8d9bc287 100644 --- a/src/wren/Skeleton.hpp +++ b/src/wren/Skeleton.hpp @@ -52,7 +52,7 @@ namespace wren { private: Skeleton(){}; - virtual ~Skeleton(); + virtual ~Skeleton() override; std::vector mBones; std::vector mMeshes; diff --git a/src/wren/SkeletonBone.hpp b/src/wren/SkeletonBone.hpp index 18b388f23e8..55c922858d2 100644 --- a/src/wren/SkeletonBone.hpp +++ b/src/wren/SkeletonBone.hpp @@ -52,7 +52,7 @@ namespace wren { private: SkeletonBone(Skeleton *skeleton, const char *name); - virtual ~SkeletonBone() {} + virtual ~SkeletonBone() override {} std::string mName; std::unordered_map> mWeights; diff --git a/src/wren/SpotLight.hpp b/src/wren/SpotLight.hpp index 4f87df67ef2..67eb39da84e 100644 --- a/src/wren/SpotLight.hpp +++ b/src/wren/SpotLight.hpp @@ -66,7 +66,7 @@ namespace wren { private: SpotLight(); - virtual ~SpotLight(); + virtual ~SpotLight() override; mutable bool mIsDirectionDirty; mutable glm::vec3 mDirectionAbsolute; diff --git a/src/wren/StaticMesh.hpp b/src/wren/StaticMesh.hpp index 5bac679eed3..444758afa89 100644 --- a/src/wren/StaticMesh.hpp +++ b/src/wren/StaticMesh.hpp @@ -82,7 +82,7 @@ namespace wren { protected: StaticMesh(); - virtual ~StaticMesh() {} + virtual ~StaticMesh() override {} private: void computeTrianglesAndEdges(); diff --git a/src/wren/Texture.hpp b/src/wren/Texture.hpp index e727325ccad..8096c99f522 100644 --- a/src/wren/Texture.hpp +++ b/src/wren/Texture.hpp @@ -96,7 +96,7 @@ namespace wren { protected: Texture(); - virtual ~Texture(); + virtual ~Texture() override; virtual void setGlName(unsigned int glName) = 0; void cleanupGl() override; diff --git a/src/wren/Texture2d.hpp b/src/wren/Texture2d.hpp index 873d8b2a31b..af9ccf95de9 100644 --- a/src/wren/Texture2d.hpp +++ b/src/wren/Texture2d.hpp @@ -54,7 +54,7 @@ namespace wren { static std::unordered_map cCache; Texture2d(); - virtual ~Texture2d() {} + virtual ~Texture2d() override {} void setGlName(unsigned int glName) override { mCacheData->mGlName = glName; }; void prepareGl() override; diff --git a/src/wren/TextureCubeMap.hpp b/src/wren/TextureCubeMap.hpp index 393961d6a9f..8bc342f667d 100644 --- a/src/wren/TextureCubeMap.hpp +++ b/src/wren/TextureCubeMap.hpp @@ -41,7 +41,7 @@ namespace wren { private: TextureCubeMap(); - ~TextureCubeMap() {} + ~TextureCubeMap() override {} void prepareGl() override; diff --git a/src/wren/TextureCubeMapBaker.cpp b/src/wren/TextureCubeMapBaker.cpp index 07a670e85d2..cb54816a1b5 100644 --- a/src/wren/TextureCubeMapBaker.cpp +++ b/src/wren/TextureCubeMapBaker.cpp @@ -313,7 +313,7 @@ namespace wren { return prefilteredCube; } - TextureRtt *bakeBrdf(ShaderProgram *brdfShader, unsigned int size) { + TextureRtt *bakeBrdf(const ShaderProgram *brdfShader, unsigned int size) { unsigned int captureFBO = 0; unsigned int captureRBO = 0; glGenFramebuffers(1, &captureFBO); @@ -389,5 +389,5 @@ WrTextureCubeMap *wr_texture_cubemap_bake_specular_irradiance(WrTextureCubeMap * WrTextureRtt *wr_texture_cubemap_bake_brdf(WrShaderProgram *shader, unsigned int size) { return reinterpret_cast( - wren::texturecubemapbaker::bakeBrdf(reinterpret_cast(shader), size)); + wren::texturecubemapbaker::bakeBrdf(reinterpret_cast(shader), size)); } diff --git a/src/wren/TextureRtt.hpp b/src/wren/TextureRtt.hpp index d2611d89f8a..ac9e214fdde 100644 --- a/src/wren/TextureRtt.hpp +++ b/src/wren/TextureRtt.hpp @@ -36,7 +36,7 @@ namespace wren { protected: TextureRtt(); - virtual ~TextureRtt() {} + virtual ~TextureRtt() override {} unsigned int mGlName; bool mInitializeData; diff --git a/src/wren/Transform.cpp b/src/wren/Transform.cpp index 160f636bdfe..d572e089af8 100644 --- a/src/wren/Transform.cpp +++ b/src/wren/Transform.cpp @@ -49,7 +49,7 @@ namespace wren { int Transform::computeChildCount() const { int count = mChildren.size(); - for (Node *n : mChildren) + for (const Node *n : mChildren) count += n->computeChildCount(); return count; diff --git a/src/wren/Transform.hpp b/src/wren/Transform.hpp index ac8b41a4c83..1337e092eb2 100644 --- a/src/wren/Transform.hpp +++ b/src/wren/Transform.hpp @@ -45,14 +45,14 @@ namespace wren { int computeChildCount() const override; void setMatrixDirty() const override { TransformNode::setMatrixDirty(); - for (Node *n : mChildren) + for (const Node *n : mChildren) n->setMatrixDirty(); } protected: Transform(); explicit Transform(Transform *source); - virtual ~Transform(); + virtual ~Transform() override; private: void recomputeAabb() const override { @@ -71,7 +71,7 @@ namespace wren { if (mChildren.size()) { std::vector spheres; spheres.reserve(mChildren.size()); - for (Node *child : mChildren) + for (const Node *child : mChildren) spheres.push_back(child->boundingSphere()); mBoundingSphere = primitive::mergeBoundingSpheres(spheres); diff --git a/src/wren/TransformNode.hpp b/src/wren/TransformNode.hpp index 971b6bdb0a5..7810898c8fc 100644 --- a/src/wren/TransformNode.hpp +++ b/src/wren/TransformNode.hpp @@ -121,7 +121,7 @@ namespace wren { protected: TransformNode(); explicit TransformNode(TransformNode *source); - ~TransformNode() {} + virtual ~TransformNode() override {} private: // May be modified when getting position/scale/orientation/matrix, thus mutable diff --git a/src/wren/UniformBuffer.hpp b/src/wren/UniformBuffer.hpp index 674f4ec9e85..9a6143856b5 100644 --- a/src/wren/UniformBuffer.hpp +++ b/src/wren/UniformBuffer.hpp @@ -22,7 +22,7 @@ namespace wren { class UniformBuffer : public GlUser { public: UniformBuffer(unsigned int binding, int size); - ~UniformBuffer(); + ~UniformBuffer() override; unsigned int glName() const { return mGlName; } unsigned int binding() const { return mBinding; } diff --git a/tests/sources/test_cppcheck.py b/tests/sources/test_cppcheck.py index fac0943ec36..98882724393 100644 --- a/tests/sources/test_cppcheck.py +++ b/tests/sources/test_cppcheck.py @@ -148,6 +148,8 @@ def test_sources_with_cppcheck(self): command += ' --library=qt -j %s' % str(multiprocessing.cpu_count()) command += ' --inline-suppr --suppress=invalidPointerCast --suppress=useStlAlgorithm --suppress=uninitMemberVar' command += ' --suppress=noCopyConstructor --suppress=noOperatorEq --suppress=strdupCalled --suppress=unknownMacro' + command += ' --suppress=duplInheritedMember --suppress=constParameterCallback' + command += ' --check-level=exhaustive' if os.environ.get('CI') else ' --suppress=normalCheckLevelMaxBranches' # command += ' --xml ' # Uncomment this line to get more information on the errors command += ' --output-file=\"' + self.reportFilename + '\"' for include in includeDirs: @@ -191,6 +193,8 @@ def test_projects_with_cppcheck(self): command += self.platformOptions command += ' --library=qt --inline-suppr --suppress=invalidPointerCast --suppress=useStlAlgorithm -UKROS_COMPILATION' command += ' --suppress=strdupCalled --suppress=ctuOneDefinitionRuleViolation --suppress=unknownMacro' + command += ' --suppress=duplInheritedMember --suppress=constParameterCallback' + command += ' --check-level=exhaustive' if os.environ.get('CI') else ' --suppress=normalCheckLevelMaxBranches' # command += ' --xml' # Uncomment this line to get more information on the errors command += ' --std=c++03 --output-file=\"' + self.reportFilename + '\"' sources = self.add_source_files(sourceDirs, skippedDirs, skippedFiles)