Skip to content

Commit 79483ba

Browse files
committed
Drop Kinetic support
1 parent 367153e commit 79483ba

File tree

7 files changed

+0
-76
lines changed

7 files changed

+0
-76
lines changed

visualization/motion_planning_tasks/test/test_merge_models.cpp

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,6 @@ void modifySourceModel(QAbstractItemModel* src, T* proxy, const QModelIndex& src
6060
bool called = false;
6161
const char* new_value = "foo";
6262

63-
#if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0)
6463
auto con =
6564
proxy->connect(proxy, &T::dataChanged,
6665
[&called, &src_index, new_value](const QModelIndex& topLeft, const QModelIndex& bottomRight) {
@@ -73,14 +72,11 @@ void modifySourceModel(QAbstractItemModel* src, T* proxy, const QModelIndex& src
7372
EXPECT_STREQ(topLeft.data().toString().toLatin1().data(), new_value);
7473
called = true;
7574
});
76-
#endif
7775

7876
EXPECT_TRUE(src->setData(src_index, new_value));
7977

80-
#if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0)
8178
proxy->disconnect(con);
8279
EXPECT_TRUE(called);
83-
#endif
8480
}
8581

8682
TEST(TreeMergeModel, basics) {

visualization/motion_planning_tasks/utils/flat_merge_proxy_model.cpp

Lines changed: 0 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -226,13 +226,8 @@ class FlatMergeProxyModelPrivate
226226
void _q_sourceRowsMoved(const QModelIndex& sourceParent, int sourceStart, int sourceEnd,
227227
const QModelIndex& destParent, int dest);
228228

229-
#if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0)
230229
// NOLINTNEXTLINE(readability-identifier-naming)
231230
void _q_sourceDataChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight, const QVector<int>& roles);
232-
#else
233-
// NOLINTNEXTLINE(readability-identifier-naming)
234-
void _q_sourceDataChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); // NOLINT
235-
#endif
236231
};
237232

238233
FlatMergeProxyModel::FlatMergeProxyModel(QObject* parent) : QAbstractItemModel(parent) {
@@ -448,13 +443,8 @@ bool FlatMergeProxyModel::insertModel(QAbstractItemModel* model, int pos) {
448443
SLOT(_q_sourceRowsAboutToBeMoved(QModelIndex, int, int, QModelIndex, int)));
449444
connect(model, SIGNAL(rowsMoved(QModelIndex, int, int, QModelIndex, int)), this,
450445
SLOT(_q_sourceRowsMoved(QModelIndex, int, int, QModelIndex, int)));
451-
#if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0)
452446
connect(model, SIGNAL(dataChanged(QModelIndex, QModelIndex, QVector<int>)), this,
453447
SLOT(_q_sourceDataChanged(QModelIndex, QModelIndex, QVector<int>)));
454-
#else
455-
connect(model, SIGNAL(dataChanged(QModelIndex, QModelIndex)), this,
456-
SLOT(_q_sourceDataChanged(QModelIndex, QModelIndex)));
457-
#endif
458448

459449
return true;
460450
}
@@ -504,13 +494,8 @@ void FlatMergeProxyModel::onRemoveModel(QAbstractItemModel* model) {
504494
SLOT(_q_sourceRowsAboutToBeMoved(QModelIndex, int, int, QModelIndex, int)));
505495
disconnect(model, SIGNAL(rowsMoved(QModelIndex, int, int, QModelIndex, int)), this,
506496
SLOT(_q_sourceRowsMoved(QModelIndex, int, int, QModelIndex, int)));
507-
#if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0)
508497
disconnect(model, SIGNAL(dataChanged(QModelIndex, QModelIndex, QVector<int>)), this,
509498
SLOT(_q_sourceDataChanged(QModelIndex, QModelIndex, QVector<int>)));
510-
#else
511-
disconnect(model, SIGNAL(dataChanged(QModelIndex, QModelIndex)), this,
512-
SLOT(_q_sourceDataChanged(QModelIndex, QModelIndex)));
513-
#endif
514499
}
515500

516501
bool FlatMergeProxyModelPrivate::removeModel(std::vector<ModelData>::iterator it, bool call) {
@@ -587,18 +572,11 @@ void FlatMergeProxyModelPrivate::_q_sourceRowsRemoved(const QModelIndex& parent,
587572
q_ptr->endRemoveRows();
588573
}
589574

590-
#if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0)
591575
// NOLINTNEXTLINE(readability-identifier-naming)
592576
void FlatMergeProxyModelPrivate::_q_sourceDataChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight,
593577
const QVector<int>& roles) {
594578
q_ptr->dataChanged(mapFromSource(topLeft), mapFromSource(bottomRight), roles);
595579
}
596-
#else
597-
// NOLINTNEXTLINE(readability-identifier-naming)
598-
void FlatMergeProxyModelPrivate::_q_sourceDataChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight) {
599-
q_ptr->dataChanged(mapFromSource(topLeft), mapFromSource(bottomRight));
600-
}
601-
#endif
602580
} // namespace utils
603581
} // namespace moveit_rviz_plugin
604582

visualization/motion_planning_tasks/utils/flat_merge_proxy_model.h

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -110,12 +110,7 @@ public Q_SLOTS:
110110
Q_PRIVATE_SLOT(d_func(), void _q_sourceRowsRemoved(QModelIndex, int, int))
111111
Q_PRIVATE_SLOT(d_func(), void _q_sourceRowsAboutToBeMoved(QModelIndex, int, int, QModelIndex, int))
112112
Q_PRIVATE_SLOT(d_func(), void _q_sourceRowsMoved(QModelIndex, int, int, QModelIndex, int))
113-
114-
#if QT_VERSION >= 0x050000 // due to moc issue we need to use the hex number
115113
Q_PRIVATE_SLOT(d_func(), void _q_sourceDataChanged(QModelIndex, QModelIndex, QVector<int>))
116-
#else
117-
Q_PRIVATE_SLOT(d_func(), void _q_sourceDataChanged(QModelIndex, QModelIndex))
118-
#endif
119114
};
120115
} // namespace utils
121116
} // namespace moveit_rviz_plugin

visualization/motion_planning_tasks/utils/tree_merge_proxy_model.cpp

Lines changed: 0 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -211,13 +211,8 @@ class TreeMergeProxyModelPrivate
211211
void _q_sourceRowsMoved(const QModelIndex& sourceParent, int sourceStart, int sourceEnd,
212212
const QModelIndex& destParent, int dest);
213213

214-
#if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0)
215214
// NOLINTNEXTLINE(readability-identifier-naming)
216215
void _q_sourceDataChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight, const QVector<int>& roles);
217-
#else
218-
// NOLINTNEXTLINE(readability-identifier-naming)
219-
void _q_sourceDataChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight);
220-
#endif
221216
};
222217

223218
TreeMergeProxyModel::TreeMergeProxyModel(QObject* parent) : QAbstractItemModel(parent) {
@@ -421,13 +416,8 @@ bool TreeMergeProxyModel::insertModel(const QString& name, QAbstractItemModel* m
421416
SLOT(_q_sourceRowsAboutToBeMoved(QModelIndex, int, int, QModelIndex, int)));
422417
connect(model, SIGNAL(rowsMoved(QModelIndex, int, int, QModelIndex, int)), this,
423418
SLOT(_q_sourceRowsMoved(QModelIndex, int, int, QModelIndex, int)));
424-
#if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0)
425419
connect(model, SIGNAL(dataChanged(QModelIndex, QModelIndex, QVector<int>)), this,
426420
SLOT(_q_sourceDataChanged(QModelIndex, QModelIndex, QVector<int>)));
427-
#else
428-
connect(model, SIGNAL(dataChanged(QModelIndex, QModelIndex)), this,
429-
SLOT(_q_sourceDataChanged(QModelIndex, QModelIndex)));
430-
#endif
431421

432422
return true;
433423
}
@@ -482,13 +472,8 @@ void TreeMergeProxyModel::onRemoveModel(QAbstractItemModel* model) {
482472
SLOT(_q_sourceRowsAboutToBeMoved(QModelIndex, int, int, QModelIndex, int)));
483473
QObject::disconnect(model, SIGNAL(rowsMoved(QModelIndex, int, int, QModelIndex, int)), this,
484474
SLOT(_q_sourceRowsMoved(QModelIndex, int, int, QModelIndex, int)));
485-
#if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0)
486475
QObject::disconnect(model, SIGNAL(dataChanged(QModelIndex, QModelIndex, QVector<int>)), this,
487476
SLOT(_q_sourceDataChanged(QModelIndex, QModelIndex, QVector<int>)));
488-
#else
489-
QObject::disconnect(model, SIGNAL(dataChanged(QModelIndex, QModelIndex)), this,
490-
SLOT(_q_sourceDataChanged(QModelIndex, QModelIndex)));
491-
#endif
492477
}
493478

494479
bool TreeMergeProxyModelPrivate::removeModel(std::vector<ModelData>::iterator it, bool call) {
@@ -559,18 +544,11 @@ void TreeMergeProxyModelPrivate::_q_sourceRowsRemoved(const QModelIndex& parent,
559544
q_ptr->endRemoveRows();
560545
}
561546

562-
#if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0)
563547
// NOLINTNEXTLINE(readability-identifier-naming)
564548
void TreeMergeProxyModelPrivate::_q_sourceDataChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight,
565549
const QVector<int>& roles) {
566550
q_ptr->dataChanged(mapFromSource(topLeft), mapFromSource(bottomRight), roles);
567551
}
568-
#else
569-
// NOLINTNEXTLINE(readability-identifier-naming)
570-
void TreeMergeProxyModelPrivate::_q_sourceDataChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight) {
571-
q_ptr->dataChanged(mapFromSource(topLeft), mapFromSource(bottomRight));
572-
}
573-
#endif
574552
} // namespace utils
575553
} // namespace moveit_rviz_plugin
576554

visualization/motion_planning_tasks/utils/tree_merge_proxy_model.h

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -110,12 +110,7 @@ public Q_SLOTS:
110110
Q_PRIVATE_SLOT(d_func(), void _q_sourceRowsRemoved(QModelIndex, int, int))
111111
Q_PRIVATE_SLOT(d_func(), void _q_sourceRowsAboutToBeMoved(QModelIndex, int, int, QModelIndex, int))
112112
Q_PRIVATE_SLOT(d_func(), void _q_sourceRowsMoved(QModelIndex, int, int, QModelIndex, int))
113-
114-
#if QT_VERSION >= 0x050000 // due to moc issue we need to use the hex number
115113
Q_PRIVATE_SLOT(d_func(), void _q_sourceDataChanged(QModelIndex, QModelIndex, QVector<int>))
116-
#else
117-
Q_PRIVATE_SLOT(d_func(), void _q_sourceDataChanged(QModelIndex, QModelIndex))
118-
#endif
119114
};
120115
} // namespace utils
121116
} // namespace moveit_rviz_plugin

visualization/visualization_tools/CMakeLists.txt

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -2,11 +2,6 @@ set(MOVEIT_LIB_NAME moveit_task_visualization_tools)
22

33
set(PROJECT_INCLUDE ${CMAKE_CURRENT_SOURCE_DIR}/include/moveit/visualization_tools)
44

5-
# TODO: Remove when Kinetic support is dropped
6-
if(rviz_VERSION VERSION_LESS 1.13.1) # Does rviz supports TF2?
7-
add_definitions(-DRVIZ_TF1)
8-
endif()
9-
105
set(HEADERS
116
${PROJECT_INCLUDE}/display_solution.h
127
${PROJECT_INCLUDE}/marker_visualization.h

visualization/visualization_tools/src/marker_visualization.cpp

Lines changed: 0 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -7,9 +7,6 @@
77
#include <rviz/frame_manager.h>
88
#include <OgreSceneManager.h>
99
#include <OgreSceneNode.h>
10-
#ifndef RVIZ_TF1
11-
#include <tf/tf.h>
12-
#endif
1310
#include <tf2_msgs/TF2Error.h>
1411
#include <ros/console.h>
1512

@@ -71,23 +68,13 @@ bool MarkerVisualization::createMarkers(rviz::DisplayContext* context, Ogre::Sce
7168
Ogre::Vector3 pos = Ogre::Vector3::ZERO;
7269

7370
try {
74-
#ifdef RVIZ_TF1
75-
tf::TransformListener* tf = context->getFrameManager()->getTFClient();
76-
tf::StampedTransform tm;
77-
tf->lookupTransform(planning_frame_, fixed_frame, ros::Time(), tm);
78-
auto q = tm.getRotation();
79-
auto p = tm.getOrigin();
80-
quat = Ogre::Quaternion(q.w(), -q.x(), -q.y(), -q.z());
81-
pos = Ogre::Vector3(p.x(), p.y(), p.z());
82-
#else
8371
std::shared_ptr<tf2_ros::Buffer> tf = context->getFrameManager()->getTF2BufferPtr();
8472
geometry_msgs::TransformStamped tm;
8573
tm = tf->lookupTransform(planning_frame_, fixed_frame, ros::Time());
8674
auto q = tm.transform.rotation;
8775
auto p = tm.transform.translation;
8876
quat = Ogre::Quaternion(q.w, -q.x, -q.y, -q.z);
8977
pos = Ogre::Vector3(p.x, p.y, p.z);
90-
#endif
9178
} catch (const tf2::TransformException& e) {
9279
ROS_WARN_STREAM_NAMED("MarkerVisualization", e.what());
9380
return false;

0 commit comments

Comments
 (0)