Skip to content

Commit

Permalink
revert warning fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
CoolSpy3 committed Jul 11, 2024
1 parent 9d653d9 commit 5836abb
Show file tree
Hide file tree
Showing 51 changed files with 78 additions and 87 deletions.
2 changes: 1 addition & 1 deletion projects/default/controllers/ros/RosSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#include "RosSensor.hpp"

RosSensor::RosSensor(const std::string &deviceName, Device *device, Ros *ros, bool enableDefaultServices) :
RosSensor::RosSensor(std::string deviceName, Device *device, Ros *ros, bool enableDefaultServices) :
RosDevice(device, ros, enableDefaultServices),
mFrameIdPrefix("") {
std::string fixedDeviceName = Ros::fixedNameString(deviceName);
Expand Down
2 changes: 1 addition & 1 deletion projects/default/controllers/ros/RosSensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ class RosSensor : public RosDevice {
bool enableSensor(int timestep);

protected:
RosSensor(const std::string &deviceName, Device *device, Ros *ros, bool enableDefaultServices = true);
RosSensor(std::string deviceName, Device *device, Ros *ros, bool enableDefaultServices = true);

virtual ros::Publisher createPublisher() = 0;
virtual void publishValue(ros::Publisher publisher) = 0;
Expand Down
1 change: 0 additions & 1 deletion projects/default/libraries/vehicle/c/driver/src/driver.c
Original file line number Diff line number Diff line change
Expand Up @@ -448,7 +448,6 @@ 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);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 = reinterpret_cast<const unsigned char *>(&(data()[currentPos]));
const unsigned char *rawImage = (const unsigned char *)&(data()[currentPos]);

Camera *camera = DeviceManager::instance()->camera();
camera->resetSensorRequested();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ bool Communication::initialize(const string &ip) {
cleanup();
return false;
}
rc = connect(mFd, reinterpret_cast<struct sockaddr *>(&address), sizeof(struct sockaddr));
rc = connect(mFd, (struct sockaddr *)&address, sizeof(struct sockaddr));
if (rc == -1) {
fprintf(stderr, "Cannot connect to the server\n");
cleanup();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,6 @@ int Wrapper::robotStep(int step) {
break;
if (command == 1 && got_camera_image)
break;
// cppcheck-suppress knownConditionTrueFalse
if (command == 0 && header == 3)
break;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -230,7 +230,7 @@ void BotStudioWindow::openStateMachine() {
if (dialog.exec())
fileNames = dialog.selectedFiles();

if (!fileNames.isEmpty()) {
if (fileNames.size() > 0 && !fileNames.isEmpty()) {
mFile->setFileName(fileNames[0]);
loadStateMachine();
updateToolBars();
Expand Down Expand Up @@ -295,7 +295,7 @@ void BotStudioWindow::saveAsStateMachine() {
if (dialog.exec())
fileNames = dialog.selectedFiles();

if (!fileNames.isEmpty())
if (fileNames.size() > 0 && !fileNames.isEmpty())
mFile->setFileName(fileNames[0]);

saveStateMachine();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ class State : public AutomatonObject {
void removeTransition(Transition *t);
void removeTransitionAt(int i);
void removeAllTransitions();
const QList<Transition *> &transitions() const { return mTransition; }
QList<Transition *> transitions() const { return mTransition; }

void fromString(const QString &string);
void fromStringVersion3(const QString &string); // backward compatibility code
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -158,7 +158,6 @@ 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();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -187,7 +187,7 @@ void RobotisOp2MotionManager::playPage(int id, bool sync) {
} else {
InitMotionAsync();
mPage = new Action::PAGE;
if (!(mAction->LoadPage(id, static_cast<Action::PAGE *>(mPage))))
if (!(mAction->LoadPage(id, (Action::PAGE *)mPage)))
cerr << "Cannot load the page" << endl;
}
#endif
Expand Down Expand Up @@ -278,21 +278,21 @@ void RobotisOp2MotionManager::step(int duration) {
} else if (mWait > 0)
mWait--;
else {
if (mStepnum < static_cast<Action::PAGE *>(mPage)->header.stepnum) {
if (mStepnum < ((Action::PAGE *)mPage)->header.stepnum) {
for (int k = 0; k < DMM_NMOTORS; k++)
mTargetPositions[k] = valueToPosition(static_cast<Action::PAGE *>(mPage)->step[mStepnum].position[k + 1]);
mStepNumberToAchieveTarget = (8 * static_cast<Action::PAGE *>(mPage)->step[mStepnum].time) / mBasicTimeStep;
mTargetPositions[k] = valueToPosition(((Action::PAGE *)mPage)->step[mStepnum].position[k + 1]);
mStepNumberToAchieveTarget = (8 * ((Action::PAGE *)mPage)->step[mStepnum].time) / mBasicTimeStep;
if (mStepNumberToAchieveTarget == 0)
mStepNumberToAchieveTarget = 1;
mWait = (8 * static_cast<Action::PAGE *>(mPage)->step[mStepnum].pause) / mBasicTimeStep + 0.5;
mWait = (8 * ((Action::PAGE *)mPage)->step[mStepnum].pause) / mBasicTimeStep + 0.5;
mStepnum++;
step(duration);
} else if (mRepeat < (static_cast<Action::PAGE *>(mPage)->header.repeat)) {
} else if (mRepeat < (((Action::PAGE *)mPage)->header.repeat)) {
mRepeat++;
mStepnum = 0;
step(duration);
} else if (static_cast<Action::PAGE *>(mPage)->header.next != 0)
playPage(static_cast<Action::PAGE *>(mPage)->header.next, true);
} else if (((Action::PAGE *)mPage)->header.next != 0)
playPage(((Action::PAGE *)mPage)->header.next, true);
else
mMotionPlaying = false;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -202,7 +202,6 @@ 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;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -176,7 +176,6 @@ 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;

Expand Down
3 changes: 2 additions & 1 deletion src/controller/c/supervisor.c
Original file line number Diff line number Diff line change
Expand Up @@ -2100,7 +2100,8 @@ 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 index < node->contact_points[descendants].n ? node->contact_points[descendants].points[index].point :
return (node->contact_points[descendants].points && 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

node->contact_points[descendants].timestamp = t;
Expand Down
2 changes: 1 addition & 1 deletion src/webots/app/WbPerspective.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -295,7 +295,7 @@ bool WbPerspective::save() const {
return true;
}

void WbPerspective::setSimulationViewState(const QList<QByteArray> &state) {
void WbPerspective::setSimulationViewState(QList<QByteArray> state) {
assert(state.size() == 2);
mSimulationViewState = state[0];
mSceneTreeState = state[1];
Expand Down
6 changes: 3 additions & 3 deletions src/webots/app/WbPerspective.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ class WbPerspective {
bool centralWidgetVisible() const { return mCentralWidgetVisible; }

// splitter state of the simulation view
void setSimulationViewState(const QList<QByteArray> &state);
void setSimulationViewState(QList<QByteArray> state);
QList<QByteArray> simulationViewState() const;

// index of the selected tab in the text editor
Expand All @@ -73,7 +73,7 @@ class WbPerspective {

// list of opened files in the text editor
void setFilesList(const QStringList &list) { mFilesList = list; }
const QStringList &filesList() const { return mFilesList; }
QStringList filesList() const { return mFilesList; }

void setRobotWindowNodeNames(const QStringList &robotWindowNodeNames) { mRobotWindowNodeNames = robotWindowNodeNames; }
const QStringList &enabledRobotWindowNodeNames() const { return mRobotWindowNodeNames; }
Expand Down Expand Up @@ -104,7 +104,7 @@ class WbPerspective {
void setUserInteractionDisabled(WbAction::WbActionKind action, bool disabled) {
mDisabledUserInteractionsMap[action] = disabled;
}
const QMap<WbAction::WbActionKind, bool> &disabledUserInteractionsMap() const { return mDisabledUserInteractionsMap; }
QMap<WbAction::WbActionKind, bool> disabledUserInteractionsMap() const { return mDisabledUserInteractionsMap; }
bool isUserInteractionDisabled(WbAction::WbActionKind action) const {
return mDisabledUserInteractionsMap.value(action, false);
}
Expand Down
4 changes: 2 additions & 2 deletions src/webots/control/WbControlledWorld.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,8 @@ class WbControlledWorld : public WbSimulationWorld {

void step() override;

const QList<WbController *> &controllers() const { return mControllers; }
const QList<WbController *> &disconnectedExternControllers() const { return mDisconnectedExternControllers; }
QList<WbController *> controllers() const { return mControllers; }
QList<WbController *> disconnectedExternControllers() const { return mDisconnectedExternControllers; }

public slots:
void deleteController(WbController *controller);
Expand Down
3 changes: 1 addition & 2 deletions src/webots/core/WbFileUtil.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ bool WbFileUtil::copyAndReplaceString(const QString &sourcePath, const QString &
}

bool WbFileUtil::copyAndReplaceString(const QString &sourcePath, const QString &destinationPath,
const QList<std::pair<QString, QString>> &values) {
QList<std::pair<QString, QString>> values) {
QFile sourceFile(sourcePath);
if (!sourceFile.open(QIODevice::ReadOnly | QIODevice::Text)) {
return false;
Expand Down Expand Up @@ -110,7 +110,6 @@ int WbFileUtil::copyDir(const QString &sourcePath, const QString &destPath, bool
if (recurse) {
QStringList dirs = sourceDir.entryList(QDir::AllDirs | QDir::NoDotAndDotDot);
foreach (QString dir, dirs) {
// cppcheck-suppress variableScope
QString srcName = sourcePath + "/" + dir;
QString destName = destPath + "/" + dir;
if (!QDir(destName).exists() || merge)
Expand Down
2 changes: 1 addition & 1 deletion src/webots/core/WbFileUtil.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
const QList<std::pair<QString, QString>> &values);
QList<std::pair<QString, QString>> values);
bool copyAndReplaceString(const QString &sourcePath, const QString &destinationPath, const QString &before,
const QString &after);

Expand Down
2 changes: 1 addition & 1 deletion src/webots/core/WbPosixMemoryMappedFile.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
7 changes: 5 additions & 2 deletions src/webots/editor/WbBuildEditor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -508,8 +508,11 @@ void WbBuildEditor::jumpToError(QString fileName, int line, int column) {
if (currentBuffer() && QDir::isRelativePath(fileName))
fileName = compileDir().absoluteFilePath(fileName);

if (openFile(fileName) && line != -1)
currentBuffer()->markError(line, column);
if (openFile(fileName)) {
WbTextBuffer *buffer = currentBuffer();
if (line != -1)
buffer->markError(line, column);
}
}

void WbBuildEditor::unmarkError() {
Expand Down
4 changes: 2 additions & 2 deletions src/webots/editor/WbTextFind.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
6 changes: 3 additions & 3 deletions src/webots/gui/WbConsole.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
2 changes: 1 addition & 1 deletion src/webots/gui/WbRenderingDeviceWindow.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -167,7 +167,7 @@ WbRenderingDeviceWindow::~WbRenderingDeviceWindow() {
return;
QOpenGLFunctions_3_3_Core *f = QOpenGLVersionFunctionsFactory::get<QOpenGLFunctions_3_3_Core>(mContext);
f->glDeleteVertexArrays(1, &mVaoId);
f->glDeleteBuffers(2, reinterpret_cast<GLuint *>(&mVboId));
f->glDeleteBuffers(2, (GLuint *)&mVboId);
mContext->doneCurrent();
delete mVboId;
}
Expand Down
2 changes: 1 addition & 1 deletion src/webots/gui/WbRobotWindow.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
6 changes: 2 additions & 4 deletions src/webots/nodes/WbCamera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,18 +72,16 @@ class WbRecognizedObject : public WbObjectDetection {
virtual ~WbRecognizedObject() {}

int id() const { return mId; }
const QString &model() const { return mModel; }
// cppcheck-suppress returnByReference
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<WbRgb> &colors() const { return mColors; }
const QList<WbRgb> 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; }
// cppcheck-suppress passedByValue
void addColor(WbRgb colors) { mColors.append(colors); }
void clearColors() { mColors.clear(); }

Expand Down
4 changes: 2 additions & 2 deletions src/webots/nodes/WbCone.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 (t1 > 0.0 && z1 >= -halfH && z1 <= halfH)
if (mSide->value() && t1 > 0.0 && z1 >= -halfH && z1 <= halfH)
d = t1;
else if (t2 > 0.0 && z2 >= -halfH && z2 <= halfH)
else if (mSide->value() && t2 > 0.0 && z2 >= -halfH && z2 <= halfH)
d = t2;
}
}
Expand Down
1 change: 0 additions & 1 deletion src/webots/nodes/WbCylinder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -388,7 +388,6 @@ bool WbCylinder::pickUVCoordinate(WbVector2 &uv, const WbRay &ray, int textureCo
if (collisionDistance < 0)
return false;

// cppcheck-suppress variableScope
double h = scaledHeight();
double r = scaledRadius();

Expand Down
1 change: 0 additions & 1 deletion src/webots/nodes/WbDisplay.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -536,7 +536,6 @@ 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) {
Expand Down
2 changes: 1 addition & 1 deletion src/webots/nodes/WbRenderingDevice.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ class WbRenderingDevice : public WbSolidDevice {

// static functions
static WbRenderingDevice *fromMousePosition(int x, int y);
static const QList<WbRenderingDevice *> &renderingDevices() { return cRenderingDevices; }
static QList<WbRenderingDevice *> renderingDevices() { return cRenderingDevices; }

enum TextureRole { BACKGROUND_TEXTURE = 0, MAIN_TEXTURE, MASK_TEXTURE, FOREGROUND_TEXTURE };

Expand Down
2 changes: 1 addition & 1 deletion src/webots/nodes/WbRobot.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
const QList<WbRenderingDevice *> &renderingDevices() { return mRenderingDevices; }
QList<WbRenderingDevice *> renderingDevices() { return mRenderingDevices; }

// update sensors in case of no answer needs to be written at this step
virtual void updateSensors();
Expand Down
2 changes: 1 addition & 1 deletion src/webots/nodes/WbViewpoint.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ class WbViewpoint : public WbBaseNode {
void updateOrthographicViewHeight();

void setNodesVisibility(QList<const WbBaseNode *> nodes, bool visible);
const QList<const WbBaseNode *> &getInvisibleNodes() const { return mInvisibleNodes; }
QList<const WbBaseNode *> getInvisibleNodes() const { return mInvisibleNodes; }
void enableNodeVisibility(bool enabled);

// Ray picking based on current projection mode
Expand Down
4 changes: 2 additions & 2 deletions src/webots/nodes/utils/WbDictionary.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -296,6 +296,8 @@ 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
Expand All @@ -304,8 +306,6 @@ 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--;
Expand Down
2 changes: 1 addition & 1 deletion src/webots/nodes/utils/WbDisplayFont.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class WbDisplayFont {

unsigned int verticalSpace() const;
unsigned int fontSize() const { return mFontSize; }
const QString &error() const { return mError; }
QString error() const { return mError; }

private:
void loadFace(FT_Face *face, const QString &filename, unsigned int size);
Expand Down
Loading

0 comments on commit 5836abb

Please sign in to comment.