Skip to content
4 changes: 4 additions & 0 deletions .github/workflows/tests_sources_with_latest_cppcheck.yml
Original file line number Diff line number Diff line change
@@ -1,6 +1,10 @@
name: Test Sources with Latest Cppcheck

on:
pull_request:
types: [opened, synchronize, reopened, labeled, unlabeled]
branches-ignore:
- 'released'
schedule:
- cron: '0 22 * * *'

Expand Down
4 changes: 2 additions & 2 deletions projects/robots/gctronic/e-puck/controllers/e-puck/e-puck.c
Original file line number Diff line number Diff line change
Expand Up @@ -46,8 +46,8 @@ int main(int argc, char *argv[]) {
int i, j;
double speed[2];
double sensors_value[8];
double braitenberg_coefficients[8][2] = {{0.942, -0.22}, {0.63, -0.1}, {0.5, -0.06}, {-0.06, -0.06},
{-0.06, -0.06}, {-0.06, 0.5}, {-0.19, 0.63}, {-0.13, 0.942}};
const double braitenberg_coefficients[8][2] = {{0.942, -0.22}, {0.63, -0.1}, {0.5, -0.06}, {-0.06, -0.06},
{-0.06, -0.06}, {-0.06, 0.5}, {-0.19, 0.63}, {-0.13, 0.942}};
int time_step;
int camera_time_step;
/* initialize Webots */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ int main(int argc, char *argv[]) {
int i, j;
double speed[2] = {0, 0};
double sensors_value[8];
double braitenberg_coefficients[8][2] = {{10, 8}, {7, -1.5}, {5, -1}, {-1, -1}, {-1, -1}, {-1, -1}, {-1, 5}, {-1.5, 7}};
const double braitenberg_coefficients[8][2] = {{10, 8}, {7, -1.5}, {5, -1}, {-1, -1}, {-1, -1}, {-1, -1}, {-1, 5}, {-1.5, 7}};

/* initialize Webots */
wb_robot_init();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -207,8 +207,6 @@ void KeyboardInterface::startListenKeyboard() {
void KeyboardInterface::setKeyPressed(int key) {
if (mKeyPressed[key] == VALIDATED)
mKeyPressed[key] = VALIDATED_STILL_PRESSED;
else if (mKeyPressed[key] == VALIDATED_STILL_PRESSED)
mKeyPressed[key] = VALIDATED_STILL_PRESSED;
else
mKeyPressed[key] = PRESSED;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,6 @@ static struct Sequence *read_sequence(char color, char number) {
sequence->next = new_sequence;
sequence = new_sequence;
sequence->next = new_sequence;
sequence = new_sequence;
sequence->time = time;
sequence->action = (char *)malloc(strlen(action) + 1);
strcpy(sequence->action, action);
Expand Down
4 changes: 2 additions & 2 deletions projects/samples/demos/controllers/moon/moon.c
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,8 @@ int main() {
double speed[2];
double sensor_value[16];
double kUnit = 8.24;
double matrix[2][16] = {{3, -18, -15, -15, -5, -5, 4, 4, 6, 6, 4, 4, 4, 4, 3, -18},
{-18, 3, 4, 4, 4, 4, 6, 6, 4, 4, -5, -5, -15, -15, -18, 3}};
const double matrix[2][16] = {{3, -18, -15, -15, -5, -5, 4, 4, 6, 6, 4, 4, 4, 4, 3, -18},
{-18, 3, 4, 4, 4, 4, 6, 6, 4, 4, -5, -5, -15, -15, -18, 3}};

wb_robot_init();
robot_name = wb_robot_get_name();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ int main(void) {
char name[] = "ds0";
double speed[2];
double sensor_value[NB_SENSORS];
double matrix[2][NB_SENSORS] = {{11, 12, 8, -2, -3, -5, -7, -9}, {-9, -8, -5, -1, -2, 6, 12, 11}};
const double matrix[2][NB_SENSORS] = {{11, 12, 8, -2, -3, -5, -7, -9}, {-9, -8, -5, -1, -2, 6, 12, 11}};

wb_robot_init();

Expand Down
2 changes: 1 addition & 1 deletion projects/samples/devices/controllers/lidar/lidar.c
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ int main(int argc, char **argv) {
wb_motor_set_velocity(right_motor, 0.0);

// set empirical coefficients for collision avoidance
double coefficients[2][2] = {{12.0, -6.0}, {-10.0, 8.0}};
const double coefficients[2][2] = {{12.0, -6.0}, {-10.0, 8.0}};
double base_speed = 6.0;

// init speed values
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ int main(int argc, char **argv) {
// init distance sensors
WbDeviceTag us[2];
double us_values[2];
double coefficients[2][2] = {{6.0, -3.0}, {-5.0, 4.0}};
const double coefficients[2][2] = {{6.0, -3.0}, {-5.0, 4.0}};
us[LEFT] = wb_robot_get_device("us0");
us[RIGHT] = wb_robot_get_device("us1");
for (i = 0; i < 2; i++)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,8 +58,9 @@ int main(int argc, char **argv) {
bool left_obstacle = ps_values[5] > 80.0 || ps_values[6] > 80.0 || ps_values[7] > 80.0;

// initialize motor speeds at 50% of MAX_SPEED.
double left_speed = 0.5 * MAX_SPEED;
double right_speed = 0.5 * MAX_SPEED;
double speed = 0.5 * MAX_SPEED;
double left_speed = speed;
double right_speed = speed;

// modify speeds according to obstacles
if (left_obstacle) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ AddStateDialog::AddStateDialog(Motion *motion, QWidget *parent) : QDialog(parent
populateListWidget();

QWidget *buttonsWidget = new QWidget(this);
QPushButton *cancelButton = new QPushButton(tr("Cancel"), buttonsWidget);
const QPushButton *cancelButton = new QPushButton(tr("Cancel"), buttonsWidget);
QPushButton *okButton = new QPushButton(tr("Ok"), buttonsWidget);
QHBoxLayout *hBoxLayout = new QHBoxLayout(buttonsWidget);
hBoxLayout->addStretch();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ Pose::Pose(const Pose &other) : mName(other.mName), mTime(other.mTime), mIsValid
int size = other.mStates.size();
mStates.reserve(size);
foreach (const MotorTargetState *item, other.mStates) {
MotorTargetState *state = new MotorTargetState(*item);
const MotorTargetState *state = new MotorTargetState(*item);
mStates.append(state);
connect(state, SIGNAL(updated()), this, SLOT(propagateStateUpdate()));
connect(state, SIGNAL(validChanged()), this, SLOT(updateIsValid()));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ PoseEditor::PoseEditor(Pose *pose, Pose *previousPose, Pose *nextPose, bool fixe
formLayout->addRow(tr("&Milliseconds:"), mMilliSecondsSpinBox);

QWidget *buttonsWidget = new QWidget(this);
QPushButton *cancelButton = new QPushButton(tr("Cancel"), buttonsWidget);
const QPushButton *cancelButton = new QPushButton(tr("Cancel"), buttonsWidget);
QPushButton *okButton = new QPushButton(tr("Ok"), buttonsWidget);
QHBoxLayout *hBoxLayout = new QHBoxLayout(buttonsWidget);
hBoxLayout->addStretch();
Expand Down
2 changes: 1 addition & 1 deletion src/controller/c/g_image.c
Original file line number Diff line number Diff line change
Expand Up @@ -224,7 +224,7 @@ struct ImageData {
unsigned long *target_data_size;
};

void g_image_save_to_jpeg_buffer_callback(void *context, void *data, int size) {
void g_image_save_to_jpeg_buffer_callback(void *context, const void *data, int size) {
if (!*(((struct ImageData *)context)->target_data))
*(((struct ImageData *)context)->target_data) = (unsigned char *)malloc(size);
else
Expand Down
6 changes: 3 additions & 3 deletions src/controller/c/supervisor.c
Original file line number Diff line number Diff line change
Expand Up @@ -1814,7 +1814,7 @@ static WbNodeRef node_get_from_id(int id, const char *function) {

WbNodeRef result = find_node_by_id(id);
if (!result) {
WbNodeRef node_list_before = node_list;
WbNodeRef *const node_list_before = node_list;
node_id = id;
wb_robot_flush_unlocked(function);
if (node_list != node_list_before)
Expand Down Expand Up @@ -2313,7 +2313,7 @@ WbFieldRef wb_supervisor_node_get_field_by_index(WbNodeRef node, int index) {
WbFieldRef result = find_field_by_id(node->id, index, false);
if (!result) {
// otherwise: need to talk to Webots
WbFieldRef field_list_before = field_list;
WbFieldRef *const field_list_before = field_list;
requested_field_index = index;
node_ref = node->id;
wb_robot_flush_unlocked(__FUNCTION__);
Expand Down Expand Up @@ -2349,7 +2349,7 @@ WbFieldRef wb_supervisor_node_get_proto_field_by_index(WbNodeRef node, int index
WbFieldRef result = find_field_by_id(node->id, index, true);
if (!result) {
// otherwise: need to talk to Webots
WbFieldRef field_list_before = field_list;
WbFieldRef *const field_list_before = field_list;
requested_field_index = index;
node_ref = node->id;
allow_search_in_proto = true;
Expand Down
2 changes: 1 addition & 1 deletion src/webots/app/WbApplication.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ WbApplication::~WbApplication() {
}

void WbApplication::setup() {
WbNodeOperations *nodeOperations = WbNodeOperations::instance();
const WbNodeOperations *nodeOperations = WbNodeOperations::instance();

// create and connect WbAnimationRecorder
WbAnimationRecorder *recorder = WbAnimationRecorder::instance();
Expand Down
8 changes: 4 additions & 4 deletions src/webots/control/WbControlledWorld.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ WbControlledWorld::WbControlledWorld(WbTokenizer *tokenizer) :
return;

mNeedToYield = false;
foreach (WbRobot *const robot, robots())
foreach (const WbRobot *const robot, robots())
connect(robot, &WbRobot::startControllerRequest, this, &WbControlledWorld::startController);
}

Expand Down Expand Up @@ -76,7 +76,7 @@ void WbControlledWorld::setUpControllerForNewRobot(WbRobot *robot) {
connect(robot, &WbRobot::controllerChanged, this, &WbControlledWorld::updateCurrentRobotController, Qt::UniqueConnection);
}

void WbControlledWorld::startController(WbRobot *robot) {
void WbControlledWorld::startController(const WbRobot *robot) {
if (robot->controllerName() == "<none>") {
connect(robot, &WbRobot::controllerChanged, this, &WbControlledWorld::updateCurrentRobotController, Qt::UniqueConnection);
return;
Expand Down Expand Up @@ -145,7 +145,7 @@ void WbControlledWorld::retryStepLater() {
emit stepBlocked(true);
}
// call the step() function again when a WbController received some data from the libController
foreach (WbController *const controller, mControllers)
foreach (const WbController *const controller, mControllers)
connect(controller, &WbController::requestReceived, this, &WbControlledWorld::step, Qt::UniqueConnection);
}

Expand Down Expand Up @@ -195,7 +195,7 @@ void WbControlledWorld::checkIfReadRequestCompleted() {

void WbControlledWorld::step() {
if (mFirstStep && !mRetryEnabled) {
foreach (WbRobot *const robot, robots()) {
foreach (const WbRobot *const robot, robots()) {
if (!robot->isControllerStarted())
startController(robot);
}
Expand Down
2 changes: 1 addition & 1 deletion src/webots/control/WbControlledWorld.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class WbControlledWorld : public WbSimulationWorld {
explicit WbControlledWorld(WbTokenizer *tokenizer = NULL);
virtual ~WbControlledWorld() override;

void startController(WbRobot *robot);
void startController(const WbRobot *robot);
void externConnection(WbController *controller, bool connect);
QStringList activeControllersNames() const;
bool needToWait(bool *waitForExternControllerStart = NULL);
Expand Down
2 changes: 1 addition & 1 deletion src/webots/control/WbController.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class WbController : public QObject {
// constructor & destructor
// name: controller name as in Robot.controller, e.g. "<generic>"
// arguments: controller arguments as in Robot.controllerArgs
explicit WbController(WbRobot *robot);
explicit WbController(const WbRobot *robot);
virtual ~WbController();

// start the controller
Expand Down
2 changes: 1 addition & 1 deletion src/webots/core/WbGuiRefreshOracle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ void WbGuiRefreshOracle::cleanup() {
WbGuiRefreshOracle::WbGuiRefreshOracle() : mCanRefreshNow(true) {
qAddPostRoutine(WbGuiRefreshOracle::cleanup);

WbSimulationState *state = WbSimulationState::instance();
const WbSimulationState *state = WbSimulationState::instance();
connect(state, &WbSimulationState::modeChanged, this, &WbGuiRefreshOracle::updateFlags);
connect(state, &WbSimulationState::controllerReadRequestsCompleted, this, &WbGuiRefreshOracle::updateFlags);
connect(&mGlobalRefreshTimer, &QTimer::timeout, this, &WbGuiRefreshOracle::updateFlags);
Expand Down
2 changes: 1 addition & 1 deletion src/webots/core/WbTelemetry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ void WbTelemetry::sendRequest(const QString &operation) {
data.append("&build=");
data.append(QString::number(UNIX_TIMESTAMP).toUtf8());
request.setHeader(QNetworkRequest::ContentTypeHeader, "application/x-www-form-urlencoded");
QNetworkReply *reply = WbNetwork::instance()->networkAccessManager()->post(request, data);
const QNetworkReply *reply = WbNetwork::instance()->networkAccessManager()->post(request, data);
if (id == 0) {
QEventLoop loop;
QTimer timer;
Expand Down
2 changes: 1 addition & 1 deletion src/webots/core/WbWebotsUpdateManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ void WbWebotsUpdateManager::cleanup() {
void WbWebotsUpdateManager::sendRequest() {
QNetworkRequest request;
request.setUrl(QUrl("https://api.github.com/repos/cyberbotics/webots/releases/latest"));
QNetworkReply *reply = WbNetwork::instance()->networkAccessManager()->get(request);
const QNetworkReply *reply = WbNetwork::instance()->networkAccessManager()->get(request);
connect(reply, &QNetworkReply::finished, this, &WbWebotsUpdateManager::downloadReplyFinished, Qt::UniqueConnection);
}

Expand Down
2 changes: 1 addition & 1 deletion src/webots/engine/WbAnimationRecorder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -272,7 +272,7 @@ void WbAnimationRecorder::populateCommands() {
}
}

foreach (WbAnimationCommand *command, mCommands) {
foreach (const WbAnimationCommand *command, mCommands) {
connect(command, &WbAnimationCommand::changed, this, &WbAnimationRecorder::addChangedCommandToList);
// support node deletions
connect(command->node(), &WbNode::destroyed, this, &WbAnimationRecorder::updateCommandsAfterNodeDeletion);
Expand Down
4 changes: 2 additions & 2 deletions src/webots/engine/WbSimulationWorld.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -226,7 +226,7 @@ void WbSimulationWorld::step() {
dImmersionOutlineDestroy(mImmersionGeoms.at(i).outline);
mImmersionGeoms.clear();

foreach (WbRobot *const robot, robots()) {
foreach (const WbRobot *const robot, robots()) {
if (robots().contains(robot)) // the 'processImmediateMessages' of another robot may have removed/regenerated this robot
robot->processImmediateMessages();
}
Expand Down Expand Up @@ -400,7 +400,7 @@ void WbSimulationWorld::reset(bool restartControllers) {
dImmersionLinkGroupEmpty(mCluster->immersionLinkGroup());
WbSoundEngine::stopAllSources();
if (restartControllers) {
foreach (WbRobot *const robot, robots()) {
foreach (const WbRobot *const robot, robots()) {
if (robot->isControllerStarted())
robot->restartController();
}
Expand Down
2 changes: 1 addition & 1 deletion src/webots/gui/WbGuidedTour.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ WbGuidedTour::WbGuidedTour(QWidget *parent) :
mNextButton = new QPushButton(tr("Next"), this);
mNextButton->setDefault(true);
mNextButton->setAutoDefault(true);
QPushButton *closeButton = new QPushButton(tr("Close"), this);
const QPushButton *closeButton = new QPushButton(tr("Close"), this);

connect(closeButton, &QPushButton::pressed, this, &WbGuidedTour::close);
connect(mPrevButton, &QPushButton::pressed, this, &WbGuidedTour::prev);
Expand Down
6 changes: 3 additions & 3 deletions src/webots/gui/WbMainWindow.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -196,7 +196,7 @@ WbMainWindow::WbMainWindow(bool minimizedOnStart, WbTcpServer *tcpServer, QWidge
connect(mAnimationRecordingTimer, &QTimer::timeout, this, &WbMainWindow::toggleAnimationIcon);
toggleAnimationAction(false);

WbAnimationRecorder *recorder = WbAnimationRecorder::instance();
const WbAnimationRecorder *recorder = WbAnimationRecorder::instance();
connect(recorder, &WbAnimationRecorder::initalizedFromStreamingServer, this, &WbMainWindow::disableAnimationAction);
connect(recorder, &WbAnimationRecorder::cleanedUpFromStreamingServer, this, &WbMainWindow::enableAnimationAction);
connect(recorder, &WbAnimationRecorder::requestOpenUrl, this,
Expand Down Expand Up @@ -1160,7 +1160,7 @@ void WbMainWindow::savePerspective(bool reloading, bool saveToFile, bool isSaveE
perspective->setConsolesSettings(settingsList);

// save rendering devices perspective
const QList<WbRenderingDevice *> renderingDevices = WbRenderingDevice::renderingDevices();
const QList<WbRenderingDevice *> &renderingDevices = WbRenderingDevice::renderingDevices();
foreach (const WbRenderingDevice *device, renderingDevices) {
if (device->overlay() != NULL)
perspective->setRenderingDevicePerspective(device->computeShortUniqueName(), device->perspective());
Expand Down Expand Up @@ -1249,7 +1249,7 @@ void WbMainWindow::restorePerspective(bool reloading, bool firstLoad, bool loadi

void WbMainWindow::restoreRenderingDevicesPerspective() {
const WbPerspective *perspective = WbWorld::instance()->perspective();
const QList<WbRenderingDevice *> devices = WbRenderingDevice::renderingDevices();
const QList<WbRenderingDevice *> &devices = WbRenderingDevice::renderingDevices();
for (int i = 0; i < devices.size(); ++i) {
WbRenderingDevice *device = devices[i];
QStringList devicePerspective = perspective->renderingDevicePerspective(device->computeShortUniqueName());
Expand Down
2 changes: 1 addition & 1 deletion src/webots/gui/WbNewProjectWizard.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,7 @@ QWizardPage *WbNewProjectWizard::createDirectoryPage() {
page->setTitle(tr("Directory selection"));
page->setSubTitle(tr("Please choose a directory for your new project:"));
mDirEdit = new WbLineEdit(page);
QPushButton *chooseButton = new QPushButton(tr("Choose"), page);
const QPushButton *chooseButton = new QPushButton(tr("Choose"), page);
connect(chooseButton, &QPushButton::pressed, this, &WbNewProjectWizard::chooseDirectory);
QHBoxLayout *layout = new QHBoxLayout(page);
layout->addWidget(mDirEdit);
Expand Down
2 changes: 1 addition & 1 deletion src/webots/gui/WbNewVersionDialog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ WbNewVersionDialog::WbNewVersionDialog() {
vBoxLayout->addWidget(telemetryBox);

// main button
QPushButton *startButton = new QPushButton(tr("Start Webots with the selected theme."));
const QPushButton *startButton = new QPushButton(tr("Start Webots with the selected theme."));
vBoxLayout->addWidget(startButton);

setLayout(vBoxLayout);
Expand Down
4 changes: 2 additions & 2 deletions src/webots/gui/WbView3D.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1582,7 +1582,7 @@ void WbView3D::mousePressEvent(QMouseEvent *event) {

// Overlays come first - special case for overlay resize and close (resize has priority)
bool displayOverlayClicked = false;
WbWrenTextureOverlay *overlay = NULL;
const WbWrenTextureOverlay *overlay = nullptr;
if (!mDragOverlay) {
WbRenderingDevice *renderingDevice = WbRenderingDevice::fromMousePosition(position.x(), position.y());
if (renderingDevice) {
Expand Down Expand Up @@ -1813,7 +1813,7 @@ void WbView3D::mouseMoveEvent(QMouseEvent *event) {
// Drag overlay even if modifier keys are pressed
WbRenderingDevice *const renderingDevice = WbRenderingDevice::fromMousePosition(position.x(), position.y());
if (renderingDevice) {
WbWrenTextureOverlay *const overlay = renderingDevice->overlay();
const WbWrenTextureOverlay *const overlay = renderingDevice->overlay();
if (overlay) {
overlay->putOnTop();
if (overlay->isInsideResizeArea(position.x(), position.y()))
Expand Down
2 changes: 1 addition & 1 deletion src/webots/gui/WbWebotsUpdateDialog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
WbWebotsUpdateDialog::WbWebotsUpdateDialog(bool displayCheckBox, QWidget *parent) : QDialog(parent) {
setWindowTitle(tr("Check for updates"));

QDialogButtonBox *buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok, Qt::Horizontal, this);
const QDialogButtonBox *buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok, Qt::Horizontal, this);
connect(buttonBox, &QDialogButtonBox::accepted, this, &WbWebotsUpdateDialog::accept);

mLabel = new QLabel(tr("Check for updates..."), this);
Expand Down
5 changes: 3 additions & 2 deletions src/webots/nodes/WbBaseNode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -285,15 +285,16 @@ bool WbBaseNode::isUrdfRootLink() const {
}

void WbBaseNode::exportUrdfJoint(WbWriter &writer) const {
if (!parentNode() || dynamic_cast<WbBasicJoint *>(parentNode()))
if (dynamic_cast<WbBasicJoint *>(parentNode()))
return;

WbVector3 translation;
WbVector3 eulerRotation;
const WbNode *const upperLinkRoot = findUrdfLinkRoot();
assert(upperLinkRoot);

if (dynamic_cast<const WbPose *>(this) && dynamic_cast<const WbPose *>(upperLinkRoot)) {
const WbPose *pose = dynamic_cast<const WbPose *>(this);
if (pose && dynamic_cast<const WbPose *>(upperLinkRoot)) {
const WbPose *const upperLinkRootPose = static_cast<const WbPose *>(this);
translation = upperLinkRootPose->translationFrom(upperLinkRoot);
eulerRotation = urdfRotation(upperLinkRootPose->rotationMatrixFrom(upperLinkRoot));
Expand Down
2 changes: 1 addition & 1 deletion src/webots/nodes/WbBasicJoint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,7 +129,7 @@ void WbBasicJoint::postFinalize() {
}
connect(mParameters, &WbSFNode::changed, this, &WbBasicJoint::updateParameters);

WbSolid *const s = solidEndPoint();
const WbSolid *const s = solidEndPoint();
if (s) {
connect(s, &WbSolid::positionChangedArtificially, this, &WbBasicJoint::updateEndPointPosition);
updateEndPointPosition();
Expand Down
Loading
Loading