Skip to content

Commit

Permalink
clean up render window resize logic
Browse files Browse the repository at this point in the history
  • Loading branch information
flynneva committed Jul 6, 2021
1 parent cd1da34 commit c3c1e98
Show file tree
Hide file tree
Showing 4 changed files with 24 additions and 32 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -259,12 +259,8 @@ void PointCloudCommon::updateStyle()
void PointCloudCommon::updateBillboardSize()
{
auto mode = static_cast<rviz_rendering::PointCloud::RenderMode>(style_property_->getOptionInt());
float size;
if (mode == rviz_rendering::PointCloud::RM_POINTS) {
size = point_pixel_size_property_->getFloat();
} else {
size = point_world_size_property_->getFloat();
}
float size = getSizeForRenderMode(mode);

for (auto & cloud_info : cloud_infos_) {
cloud_info->cloud_->setDimensions(size, size, size);
cloud_info->selection_handler_->setBoxSize(getSelectionBoxSize());
Expand Down Expand Up @@ -718,7 +714,7 @@ void PointCloudCommon::onDisable()
float PointCloudCommon::getSelectionBoxSize()
{
return style_property_->getOptionInt() != rviz_rendering::PointCloud::RM_POINTS ?
point_world_size_property_->getFloat() : 0.004f;
point_world_size_property_->getFloat() : point_pixel_size_property_->getFloat();
}

} // namespace rviz_default_plugins
3 changes: 3 additions & 0 deletions rviz_rendering/include/rviz_rendering/render_window.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,6 +142,9 @@ public slots:
void
exposeEvent(QExposeEvent * expose_event) override;

void
resizeEvent(QResizeEvent * resize_event) override;

bool
event(QEvent * event) override;

Expand Down
22 changes: 8 additions & 14 deletions rviz_rendering/src/rviz_rendering/ogre_render_window_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -231,14 +231,14 @@ RenderWindowImpl::initialize()
}

if (ogre_camera_) {
ogre_camera_->setAspectRatio(
Ogre::Real(parent_->width()) / Ogre::Real(parent_->height()));
ogre_camera_->setAutoAspectRatio(true);

ogre_viewport_ = ogre_render_window_->addViewport(ogre_camera_);
auto bg_color = Ogre::ColourValue(0.937254902f, 0.921568627f, 0.905882353f); // Qt background
ogre_viewport_->setBackgroundColour(bg_color);

ogre_camera_->setAspectRatio(
Ogre::Real(ogre_render_window_->getWidth()) / Ogre::Real(ogre_render_window_->getHeight()));
ogre_camera_->setAutoAspectRatio(true);

Ogre::TextureManager::getSingleton().setDefaultNumMipmaps(5);
Ogre::ResourceGroupManager::getSingleton().initialiseAllResourceGroups();
}
Expand All @@ -260,13 +260,8 @@ RenderWindowImpl::resize(size_t width, size_t height)
{
if (ogre_render_window_) {
this->setCameraAspectRatio();
ogre_render_window_->resize(
static_cast<unsigned int>(width), // NOLINT
static_cast<unsigned int>(height) // NOLINT
);
ogre_render_window_->windowMovedOrResized();
}
this->renderLater();
}

#if 0
Expand Down Expand Up @@ -477,16 +472,15 @@ void RenderWindowImpl::setBackgroundColor(Ogre::ColourValue background_color)

void RenderWindowImpl::setCameraAspectRatio()
{
// auto width = parent_->width();
auto width = parent_->width() ? parent_->width() : 100;
// auto height = parent_->height();
auto height = parent_->height() ? parent_->height() : 100;
auto width = parent_->width();
// auto width = ogre_render_window_->getWidth() ? ogre_render_window_->getWidth() : 100;
auto height = parent_->height();
// auto height = ogre_render_window_->getHeight() ? ogre_render_window_->getHeight() : 100;
if (ogre_camera_) {
ogre_camera_->setAspectRatio(Ogre::Real(width) / Ogre::Real(height));
// if (right_ogre_camera_) {
// right_ogre_camera_->setAspectRatio(Ogre::Real(width()) / Ogre::Real(height()));
// }

if (ogre_camera_->getProjectionType() == Ogre::PT_ORTHOGRAPHIC) {
Ogre::Matrix4 proj = buildScaledOrthoMatrix(
-width / ortho_scale_ / 2, width / ortho_scale_ / 2,
Expand Down
21 changes: 10 additions & 11 deletions rviz_rendering/src/rviz_rendering/render_window.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,8 +119,10 @@ RenderWindow::setupSceneAfterInit(setupSceneCallback setup_scene_callback)

void RenderWindow::windowMovedOrResized()
{
// It seems that the 'width' and 'height' parameters of the resize() method don't play a role here
impl_->resize(0, 0);
if (this->isExposed()) {
impl_->resize(this->width(), this->height());
this->renderNow();
}
}

void
Expand Down Expand Up @@ -152,18 +154,18 @@ ToString(const EnumType & enumValue)
return QString("%1::%2").arg(enumName).arg(static_cast<int>(enumValue));
}

void RenderWindow::resizeEvent(QResizeEvent * resize_event)
{
windowMovedOrResized();
}

bool
RenderWindow::event(QEvent * event)
{
// qDebug() <<
// "[" << QTime::currentTime().toString("HH:mm:ss:zzz") << "]:" <<
// "event->type() ==" << ToString(event->type());
switch (event->type()) {
case QEvent::Resize:
if (this->isExposed()) {
impl_->resize(this->width(), this->height());
}
return QWindow::event(event);
case QEvent::UpdateRequest:
this->renderNow();
return true;
Expand Down Expand Up @@ -192,10 +194,7 @@ RenderWindow::exposeEvent(QExposeEvent * expose_event)
{
Q_UNUSED(expose_event);

if (this->isExposed()) {
impl_->resize(this->width(), this->height());
this->renderNow();
}
windowMovedOrResized();
}

// bool
Expand Down

0 comments on commit c3c1e98

Please sign in to comment.