Skip to content

Commit d9cff55

Browse files
committed
Fix more -Wold-style-cast warnings
1 parent bd3a7d1 commit d9cff55

File tree

6 files changed

+15
-15
lines changed

6 files changed

+15
-15
lines changed

.github/workflows/ci.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ jobs:
3030
CLANG_TIDY: true
3131
TARGET_CMAKE_ARGS: >-
3232
-DCMAKE_BUILD_TYPE=Release
33-
-DCMAKE_CXX_FLAGS="-Werror -Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls"
33+
-DCMAKE_CXX_FLAGS="-Werror -Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wold-style-cast"
3434
- IMAGE: noetic-source
3535
NAME: asan
3636
DOCKER_RUN_OPTS: >-

core/src/stages/modify_planning_scene.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -98,8 +98,8 @@ void ModifyPlanningScene::attachObjects(planning_scene::PlanningScene& scene,
9898
bool attach = pair.second.second;
9999
if (invert)
100100
attach = !attach;
101-
obj.object.operation =
102-
attach ? (int8_t)moveit_msgs::CollisionObject::ADD : (int8_t)moveit_msgs::CollisionObject::REMOVE;
101+
obj.object.operation = attach ? static_cast<int8_t>(moveit_msgs::CollisionObject::ADD) :
102+
static_cast<int8_t>(moveit_msgs::CollisionObject::REMOVE);
103103
for (const std::string& name : pair.second.first) {
104104
obj.object.id = name;
105105
scene.processAttachedCollisionObjectMsg(obj);

visualization/motion_planning_tasks/src/local_task_model.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -101,7 +101,7 @@ QModelIndex LocalTaskModel::index(int row, int column, const QModelIndex& parent
101101

102102
Q_ASSERT(dynamic_cast<ContainerBase*>(node(parent)));
103103
ContainerBase* p = static_cast<ContainerBase*>(node(parent));
104-
if (!p || row < 0 || (size_t)row >= p->numChildren())
104+
if (!p || row < 0 || static_cast<size_t>(row) >= p->numChildren())
105105
return QModelIndex();
106106

107107
Node* child = nullptr;
@@ -151,7 +151,7 @@ QVariant LocalTaskModel::data(const QModelIndex& index, int role) const {
151151
case 0:
152152
return QString::fromStdString(n->name());
153153
case 1:
154-
return (uint)n->solutions().size();
154+
return static_cast<uint>(n->solutions().size());
155155
case 2:
156156
return 0;
157157
}
@@ -182,7 +182,7 @@ bool LocalTaskModel::removeRows(int row, int count, const QModelIndex& parent) {
182182

183183
Q_ASSERT(dynamic_cast<ContainerBase*>(node(parent)));
184184
ContainerBase* c = static_cast<ContainerBase*>(node(parent));
185-
if (row < 0 || (size_t)row + count > c->numChildren())
185+
if (row < 0 || static_cast<size_t>(row + count) > c->numChildren())
186186
return false;
187187

188188
beginRemoveRows(parent, row, row + count - 1);

visualization/motion_planning_tasks/src/remote_task_model.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -155,7 +155,7 @@ RemoteTaskModel::Node* RemoteTaskModel::node(const QModelIndex& index) const {
155155

156156
// internal pointer refers to parent node
157157
Node* parent = static_cast<Node*>(index.internalPointer());
158-
Q_ASSERT(index.row() >= 0 && (size_t)index.row() < parent->children_.size());
158+
Q_ASSERT(index.row() >= 0 && static_cast<size_t>(index.row()) < parent->children_.size());
159159
return parent->children_.at(index.row()).get();
160160
}
161161

@@ -209,7 +209,7 @@ QModelIndex RemoteTaskModel::index(int row, int column, const QModelIndex& paren
209209
return QModelIndex();
210210

211211
Node* p = node(parent);
212-
if (!p || row < 0 || (size_t)row >= p->children_.size())
212+
if (!p || row < 0 || static_cast<size_t>(row) >= p->children_.size())
213213
return QModelIndex();
214214

215215
p->children_[row]->node_flags_ |= WAS_VISITED;

visualization/motion_planning_tasks/utils/tree_merge_proxy_model.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -269,7 +269,7 @@ QModelIndex TreeMergeProxyModel::index(int row, int column, const QModelIndex& p
269269
return QModelIndex();
270270

271271
if (!parent.isValid()) { // top-level / group items
272-
if ((size_t)row >= d_ptr->data_.size())
272+
if (static_cast<size_t>(row) >= d_ptr->data_.size())
273273
return QModelIndex();
274274

275275
// for group items, internal pointer refers to this model
@@ -397,11 +397,11 @@ bool TreeMergeProxyModel::insertModel(const QString& name, QAbstractItemModel* m
397397
return false; // model can only inserted once
398398

399399
// limit pos to range [0, modelCount()]
400-
if (pos > 0 && pos > (int)modelCount())
400+
if (pos > 0 && pos > static_cast<int>(modelCount()))
401401
pos = modelCount();
402402
if (pos < 0)
403403
pos = modelCount() + std::max<int>(pos + 1, -modelCount());
404-
Q_ASSERT(pos >= 0 && pos <= (int)modelCount());
404+
Q_ASSERT(pos >= 0 && pos <= static_cast<int>(modelCount()));
405405
auto it = d_ptr->data_.begin();
406406
std::advance(it, pos);
407407

@@ -460,9 +460,9 @@ bool TreeMergeProxyModel::removeModel(int pos) {
460460
pos = modelCount() + pos + 1;
461461
if (pos < 0)
462462
return false;
463-
if (pos >= (int)modelCount())
463+
if (pos >= static_cast<int>(modelCount()))
464464
return false;
465-
Q_ASSERT(pos >= 0 && pos < (int)modelCount());
465+
Q_ASSERT(pos >= 0 && pos < static_cast<int>(modelCount()));
466466
auto it = d_ptr->data_.begin();
467467
std::advance(it, pos);
468468

visualization/visualization_tools/src/task_solution_visualization.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -246,7 +246,7 @@ void TaskSolutionVisualization::clearTrail() {
246246
void TaskSolutionVisualization::changedLoopDisplay() {
247247
// restart animation if current_state_ is at end and looping got activated
248248
if (displaying_solution_ && loop_display_property_->getBool() && slider_panel_ && slider_panel_->isVisible() &&
249-
current_state_ + 1 >= (int)displaying_solution_->getWayPointCount()) {
249+
current_state_ + 1 >= static_cast<int>(displaying_solution_->getWayPointCount())) {
250250
current_state_ = -1;
251251
slider_panel_->pauseButton(false);
252252
}
@@ -471,7 +471,7 @@ void TaskSolutionVisualization::renderWayPoint(size_t index, int previous_index)
471471
auto idx_pair = displaying_solution_->indexPair(index);
472472
scene = displaying_solution_->scene(idx_pair);
473473

474-
if (previous_index < 0 || previous_index >= (int)waypoint_count ||
474+
if (previous_index < 0 || previous_index >= static_cast<int>(waypoint_count) ||
475475
displaying_solution_->indexPair(previous_index).first != idx_pair.first) {
476476
// switch to new stage: show new planning scene
477477
renderPlanningScene(scene);

0 commit comments

Comments
 (0)