Skip to content

Commit

Permalink
Merge fixes from 'melodic-devel' branch
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke committed Aug 1, 2022
2 parents fb8f306 + 5435574 commit d4b4930
Show file tree
Hide file tree
Showing 24 changed files with 100 additions and 65 deletions.
1 change: 1 addition & 0 deletions src/rviz/default_plugin/fluid_pressure_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ FluidPressureDisplay::FluidPressureDisplay() : point_cloud_common_(new PointClou

FluidPressureDisplay::~FluidPressureDisplay()
{
FluidPressureDisplay::unsubscribe();
delete point_cloud_common_;
}

Expand Down
1 change: 0 additions & 1 deletion src/rviz/default_plugin/grid_cells_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@
#include <OgreSceneNode.h>
#include <OgreSceneManager.h>
#include <OgreManualObject.h>
#include <OgreBillboardSet.h>

#include <rviz/frame_manager.h>
#include <rviz/ogre_helpers/arrow.h>
Expand Down
1 change: 1 addition & 0 deletions src/rviz/default_plugin/illuminance_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ IlluminanceDisplay::IlluminanceDisplay() : point_cloud_common_(new PointCloudCom

IlluminanceDisplay::~IlluminanceDisplay()
{
IlluminanceDisplay::unsubscribe();
delete point_cloud_common_;
}

Expand Down
1 change: 1 addition & 0 deletions src/rviz/default_plugin/laser_scan_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@ LaserScanDisplay::LaserScanDisplay()

LaserScanDisplay::~LaserScanDisplay()
{
LaserScanDisplay::unsubscribe();
delete point_cloud_common_;
delete projector_;
}
Expand Down
1 change: 0 additions & 1 deletion src/rviz/default_plugin/path_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,6 @@
#include <OgreSceneNode.h>
#include <OgreSceneManager.h>
#include <OgreManualObject.h>
#include <OgreBillboardSet.h>
#include <OgreMatrix4.h>

#include <rviz/display_context.h>
Expand Down
1 change: 1 addition & 0 deletions src/rviz/default_plugin/point_cloud2_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ PointCloud2Display::PointCloud2Display() : point_cloud_common_(new PointCloudCom

PointCloud2Display::~PointCloud2Display()
{
PointCloud2Display::unsubscribe();
delete point_cloud_common_;
}

Expand Down
3 changes: 3 additions & 0 deletions src/rviz/default_plugin/point_cloud_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -380,6 +380,9 @@ void PointCloudCommon::initialize(DisplayContext* context, Ogre::SceneNode* scen

PointCloudCommon::~PointCloudCommon()
{
// Ensure any threads holding the mutexes have finished
boost::recursive_mutex::scoped_lock lock1(transformers_mutex_);
boost::mutex::scoped_lock lock2(new_clouds_mutex_);
delete transformer_class_loader_;
}

Expand Down
1 change: 1 addition & 0 deletions src/rviz/default_plugin/point_cloud_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@ PointCloudDisplay::PointCloudDisplay() : point_cloud_common_(new PointCloudCommo

PointCloudDisplay::~PointCloudDisplay()
{
PointCloudDisplay::unsubscribe();
delete point_cloud_common_;
}

Expand Down
1 change: 0 additions & 1 deletion src/rviz/default_plugin/polygon_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,6 @@
#include <OgreSceneNode.h>
#include <OgreSceneManager.h>
#include <OgreManualObject.h>
#include <OgreBillboardSet.h>

#include <rviz/display_context.h>
#include <rviz/frame_manager.h>
Expand Down
1 change: 1 addition & 0 deletions src/rviz/default_plugin/relative_humidity_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ RelativeHumidityDisplay::RelativeHumidityDisplay() : point_cloud_common_(new Poi

RelativeHumidityDisplay::~RelativeHumidityDisplay()
{
RelativeHumidityDisplay::unsubscribe();
delete point_cloud_common_;
}

Expand Down
1 change: 1 addition & 0 deletions src/rviz/default_plugin/temperature_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ TemperatureDisplay::TemperatureDisplay() : point_cloud_common_(new PointCloudCom

TemperatureDisplay::~TemperatureDisplay()
{
TemperatureDisplay::unsubscribe();
delete point_cloud_common_;
}

Expand Down
2 changes: 1 addition & 1 deletion src/rviz/display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -284,7 +284,7 @@ void Display::setFixedFrame(const QString& fixed_frame)

void Display::emitTimeSignal(ros::Time time)
{
Q_EMIT(timeSignal(this, time));
Q_EMIT(timeSignal(time, QPrivateSignal()));
}

void Display::reset()
Expand Down
2 changes: 1 addition & 1 deletion src/rviz/display.h
Original file line number Diff line number Diff line change
Expand Up @@ -225,7 +225,7 @@ class RVIZ_EXPORT Display : public BoolProperty

Q_SIGNALS:

void timeSignal(rviz::Display* display, ros::Time time);
void timeSignal(ros::Time time, QPrivateSignal);

public Q_SLOTS:
/** @brief Enable or disable this Display.
Expand Down
1 change: 0 additions & 1 deletion src/rviz/ogre_helpers/point_cloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,6 @@
#include <OgreQuaternion.h>
#include <OgreManualObject.h>
#include <OgreMaterialManager.h>
#include <OgreBillboardSet.h>
#include <OgreBillboard.h>
#include <OgreTexture.h>
#include <OgreTextureManager.h>
Expand Down
6 changes: 3 additions & 3 deletions src/rviz/ogre_helpers/point_cloud.h
Original file line number Diff line number Diff line change
Expand Up @@ -96,9 +96,9 @@ typedef std::vector<PointCloudRenderablePtr> V_PointCloudRenderable;
* \class PointCloud
* \brief A visual representation of a set of points.
*
* Displays a set of points using any number of Ogre BillboardSets. PointCloud is optimized for sets of
* points that change
* rapidly, rather than for large clouds that never change.
* Displays a set of points using vertex and geometry shaders.
* PointCloud is optimized for sets of points that change rapidly,
* rather than for large clouds that never change.
*
* Most of the functions in PointCloud are not safe to call from any thread but the render thread.
* Exceptions are clear() and addPoints(), which
Expand Down
78 changes: 44 additions & 34 deletions src/rviz/properties/splitter_handle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,9 +49,7 @@ SplitterHandle::SplitterHandle(QTreeView* parent)

bool SplitterHandle::eventFilter(QObject* event_target, QEvent* event)
{
if (event_target == parent_ &&
(event->type() == QEvent::Resize || event->type() == QEvent::LayoutRequest ||
event->type() == QEvent::Show))
if (event_target == parent_ && event->type() == QEvent::Resize)
{
updateGeometry();
}
Expand All @@ -61,13 +59,14 @@ bool SplitterHandle::eventFilter(QObject* event_target, QEvent* event)
void SplitterHandle::updateGeometry()
{
int w = 7;
int new_column_width = int(first_column_size_ratio_ * parent_->contentsRect().width());
parent_->setColumnWidth(0, new_column_width);
parent_->setColumnWidth(1, parent_->viewport()->contentsRect().width() - new_column_width);

int new_x = new_column_width - w / 2 + parent_->columnViewportPosition(0);
if (new_x != x() || parent_->height() != height())
setGeometry(new_x, 0, w, parent_->height());
const auto& content = parent_->contentsRect();
int new_column_width = int(first_column_size_ratio_ * content.width());
parent_->header()->resizeSection(0, new_column_width); // fixed size for name column
parent_->header()->resizeSection(1, content.width() - new_column_width);

int new_x = content.x() + new_column_width - w / 2;
if (new_x != x() || content.height() != height())
setGeometry(new_x, content.y(), w, content.height());
}

void SplitterHandle::setRatio(float ratio)
Expand All @@ -81,49 +80,60 @@ float SplitterHandle::getRatio()
return first_column_size_ratio_;
}

void SplitterHandle::setDesiredWidth(int width)
{
const auto& content = parent_->contentsRect();
int new_column_width = qBound(parent_->header()->minimumSectionSize(), // minimum
width, // desired
content.width()); // maximum

if (new_column_width != parent_->header()->sectionSize(0))
{
first_column_size_ratio_ = new_column_width / (float)content.width();
updateGeometry();
}
}

void SplitterHandle::mousePressEvent(QMouseEvent* event)
{
if (event->button() == Qt::LeftButton)
{
// position of mouse press inside this QWidget
x_press_offset_ = event->x();
// position of mouse press relative to splitter line / the center of the widget
x_press_offset_ = event->x() - width() / 2;
}
}

void SplitterHandle::mouseMoveEvent(QMouseEvent* event)
{
int padding = 55;

if (event->buttons() & Qt::LeftButton)
{
QPoint pos_rel_parent = parent_->mapFromGlobal(event->globalPos());

int new_x = pos_rel_parent.x() - x_press_offset_ - parent_->columnViewportPosition(0);

if (new_x > parent_->width() - width() - padding)
{
new_x = parent_->width() - width() - padding;
}

if (new_x < padding)
{
new_x = padding;
}

if (new_x != x())
{
int new_column_width = new_x + width() / 2 - parent_->contentsRect().x();
first_column_size_ratio_ = new_column_width / (float)parent_->contentsRect().width();
updateGeometry();
}
setDesiredWidth(pos_rel_parent.x() - parent_->contentsRect().x() - x_press_offset_);
}
}

// adjust splitter position to optimally fit content
void SplitterHandle::mouseDoubleClickEvent(QMouseEvent* /*event*/)
{
int available_width = parent_->contentsRect().width();
int default_width = 0.5f * available_width;
// missing width to default
int col0 = static_cast<QAbstractItemView*>(parent_)->sizeHintForColumn(0) - default_width;
int col1 = static_cast<QAbstractItemView*>(parent_)->sizeHintForColumn(1) - default_width;

if (col0 <= 0 && col1 <= 0) // each column fits
setDesiredWidth(default_width);
else if (col0 + col1 <= 0) // both columns fit together, but require a non-default splitting
setDesiredWidth(default_width + col0 + 0.5f * std::abs(col0 + col1)); // uniformly split extra space
else
setDesiredWidth(default_width + col0 - 0.5f * (col0 + col1)); // uniformly cut missing space
}

void SplitterHandle::paintEvent(QPaintEvent* /*event*/)
{
QPainter painter(this);
painter.setPen(color_);
painter.drawLine(1 + width() / 2, 0, 1 + width() / 2, height());
painter.drawLine(width() / 2, 0, width() / 2, height());
}

} // end namespace rviz
4 changes: 4 additions & 0 deletions src/rviz/properties/splitter_handle.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,9 @@ class SplitterHandle : public QWidget
/** @brief Get the ratio of the parent's left column to the parent widget width. */
float getRatio();

/** @brief Set desired width of first column - subject to clamping */
void setDesiredWidth(int width);

/** @brief Catch resize events sent to parent to update splitter's
* geometry. Always returns false. */
bool eventFilter(QObject* event_target, QEvent* event) override;
Expand All @@ -70,6 +73,7 @@ class SplitterHandle : public QWidget
protected:
void mousePressEvent(QMouseEvent* event) override;
void mouseMoveEvent(QMouseEvent* event) override;
void mouseDoubleClickEvent(QMouseEvent* event) override;
void paintEvent(QPaintEvent* event) override;

private:
Expand Down
9 changes: 6 additions & 3 deletions src/rviz/time_panel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,8 +153,7 @@ void TimePanel::onDisplayAdded(Display* display)
}
else
{
connect(display, SIGNAL(timeSignal(rviz::Display*, ros::Time)), this,
SLOT(onTimeSignal(rviz::Display*, ros::Time)));
connect(display, SIGNAL(timeSignal(ros::Time)), this, SLOT(onTimeSignal(ros::Time)));
}
}

Expand All @@ -168,8 +167,12 @@ void TimePanel::onDisplayRemoved(Display* display)
}
}

void TimePanel::onTimeSignal(Display* display, ros::Time time)
void TimePanel::onTimeSignal(ros::Time time)
{
Display* display = qobject_cast<Display*>(sender());
if (!display)
return;

QString name = display->getName();
int index = sync_source_selector_->findData(QVariant((qulonglong)display));

Expand Down
2 changes: 1 addition & 1 deletion src/rviz/time_panel.h
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ protected Q_SLOTS:
void onDisplayAdded(rviz::Display* display);
void onDisplayRemoved(rviz::Display* display);

void onTimeSignal(rviz::Display* display, ros::Time time);
void onTimeSignal(ros::Time time);

void load(const Config& config) override;
void save(Config config) const override;
Expand Down
25 changes: 18 additions & 7 deletions src/rviz/visualization_frame.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1320,6 +1320,23 @@ QWidget* VisualizationFrame::getParentWindow()
return this;
}

void VisualizationFrame::onPanelDeleted(QObject* dock)
{
for (int i = 0; i < custom_panels_.size(); ++i)
{
if (custom_panels_[i].dock == dock)
{
auto& record = custom_panels_[i];
record.delete_action->deleteLater();
delete_view_menu_->removeAction(record.delete_action);
delete_view_menu_->setDisabled(delete_view_menu_->actions().isEmpty());
custom_panels_.removeAt(i);
setDisplayConfigModified();
return;
}
}
}

void VisualizationFrame::onDeletePanel()
{
// This should only be called as a SLOT from a QAction in the
Expand All @@ -1334,13 +1351,6 @@ void VisualizationFrame::onDeletePanel()
if (custom_panels_[i].delete_action == action)
{
delete custom_panels_[i].dock;
custom_panels_.removeAt(i);
setDisplayConfigModified();
action->deleteLater();
if (delete_view_menu_->actions().size() == 1 && delete_view_menu_->actions().first() == action)
{
delete_view_menu_->setEnabled(false);
}
return;
}
}
Expand Down Expand Up @@ -1393,6 +1403,7 @@ QDockWidget* VisualizationFrame::addPanelByName(const QString& name,
record.panel = panel;
record.name = name;
record.delete_action = delete_view_menu_->addAction(name, this, SLOT(onDeletePanel()));
connect(record.dock, &QObject::destroyed, this, &VisualizationFrame::onPanelDeleted);
custom_panels_.append(record);
delete_view_menu_->setEnabled(true);

Expand Down
1 change: 1 addition & 0 deletions src/rviz/visualization_frame.h
Original file line number Diff line number Diff line change
Expand Up @@ -269,6 +269,7 @@ protected Q_SLOTS:

void reset();

void onPanelDeleted(QObject* dock);
void onHelpDestroyed();

void hideLeftDock(bool hide);
Expand Down
4 changes: 2 additions & 2 deletions src/test/render_points_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@
#include <QApplication>
#include <QVBoxLayout>

#include <OGRE/OgreCamera.h>
#include <OGRE/OgreSceneNode.h>
#include <OgreCamera.h>
#include <OgreSceneNode.h>

using namespace rviz;

Expand Down
8 changes: 4 additions & 4 deletions src/test/render_points_test.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,10 +44,10 @@
#include <rviz/ogre_helpers/billboard_line.h>
#include <rviz/ogre_helpers/render_system.h>

#include <OGRE/OgreRoot.h>
#include <OGRE/OgreSceneManager.h>
#include <OGRE/OgreViewport.h>
#include <OGRE/OgreLight.h>
#include <OgreRoot.h>
#include <OgreSceneManager.h>
#include <OgreViewport.h>
#include <OgreLight.h>

#include <ros/time.h>
#endif
Expand Down
10 changes: 5 additions & 5 deletions src/test/two_render_widgets.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,11 +35,11 @@
#include <QVBoxLayout>
#include <QPushButton>

#include <OGRE/OgreCamera.h>
#include <OGRE/OgreEntity.h>
#include <OGRE/OgreRenderWindow.h>
#include <OGRE/OgreSceneNode.h>
#include <OGRE/OgreViewport.h>
#include <OgreCamera.h>
#include <OgreEntity.h>
#include <OgreRenderWindow.h>
#include <OgreSceneNode.h>
#include <OgreViewport.h>

using namespace rviz;

Expand Down

0 comments on commit d4b4930

Please sign in to comment.