Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Depth image display options 2 #42

Merged
merged 7 commits into from
Sep 6, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion .github/workflows/build_and_test_rolling.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

name: Build and Test (rolling)

# Controls when the action will run.
# Controls when the action will run.
on:
# Triggers the workflow on push
push:
Expand All @@ -26,9 +26,11 @@ jobs:

# Steps represent a sequence of tasks that will be executed as part of the job
steps:
- uses: actions/checkout@v2
- uses: ros-tooling/setup-ros@v0.3
with:
use-ros2-testing: true
- uses: ros-tooling/action-ros-ci@v0.2
with:
target-ros2-distro: rolling
vcs-repo-file-url: dependencies.repos
9 changes: 9 additions & 0 deletions dependencies.repos
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
repositories:
vision_opencv:
type: git
url: https://github.com/ros-perception/vision_opencv.git
version: ros2
ros_image_to_qimage:
type: git
url: https://github.com/ros-sports/ros_image_to_qimage.git
version: rolling
240 changes: 178 additions & 62 deletions rqt_image_overlay/resource/configuration_dialog.ui
Original file line number Diff line number Diff line change
@@ -1,66 +1,182 @@
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>ConfigurationDialog</class>
<widget class="QDialog" name="configuration_dialog">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="windowTitle">
<string>Image Overlay configuration</string>
</property>
<layout class="QVBoxLayout" name="window_layout">
<item>
<layout class="QFormLayout" name="input_layout">
<item row="0" column="0">
<widget class="QLabel" name="windowLabel">
<property name="text">
<string>Waiting &amp;window (sec)</string>
</property>
<property name="toolTip">
<string>Time to wait before composing an image. If overlay messages arrive much later than the image, increase this value.</string>
</property>
<property name="buddy">
<cstring>window</cstring>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QDoubleSpinBox" name="window">
<property name="decimals">
<number>3</number>
</property>
</widget>
</item>
</layout>
</item>
<item>
<widget class="QDialogButtonBox" name="dialog_button_box">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="standardButtons">
<set>QDialogButtonBox::Cancel|QDialogButtonBox::Ok</set>
</property>
</widget>
</item>
<class>ConfigurationDialog</class>
<widget class="QDialog" name="configuration_dialog">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>307</width>
<height>228</height>
</rect>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="windowTitle">
<string>Image Overlay configuration</string>
</property>
<layout class="QVBoxLayout" name="window_layout">
<item>
<layout class="QFormLayout" name="input_layout">
<item row="0" column="0">
<widget class="QLabel" name="windowLabel">
<property name="toolTip">
<string>Time to wait before composing an image. If overlay messages arrive much later than the image, increase this value.</string>
</property>
<property name="text">
<string>Waiting &amp;window (sec)</string>
</property>
<property name="buddy">
<cstring>window_spin_box</cstring>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QDoubleSpinBox" name="window_spin_box">
<property name="decimals">
<number>3</number>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="dynamic_scaling_label">
<property name="text">
<string>Dynamic Scaling</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="minimum_value_label">
<property name="text">
<string>Minimum Value</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="maximum_value_label">
<property name="text">
<string>Maximum Value</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QDoubleSpinBox" name="minimum_value_spin_box">
<property name="decimals">
<number>4</number>
</property>
<property name="minimum">
<double>-10000000.000000000000000</double>
</property>
<property name="maximum">
<double>10000000.000000000000000</double>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QCheckBox" name="dynamic_scaling_check_box">
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QDoubleSpinBox" name="maximum_value_spin_box">
<property name="decimals">
<number>4</number>
</property>
<property name="minimum">
<double>-10000000.000000000000000</double>
</property>
<property name="maximum">
<double>10000000.000000000000000</double>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="colormap_label">
<property name="text">
<string>Colormap</string>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QSpinBox" name="colormap_spin_box">
<property name="minimum">
<number>-1</number>
</property>
<property name="value">
<number>-1</number>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QLabel" name="bg_label_label">
<property name="text">
<string>Background Label</string>
</property>
</widget>
</item>
<item row="5" column="1">
<widget class="QSpinBox" name="bg_label_spin_box">
<property name="minimum">
<number>-1</number>
</property>
<property name="value">
<number>-1</number>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections>
<connection>
<sender>dialog_button_box</sender>
<signal>accepted()</signal>
<receiver>configuration_dialog</receiver>
<slot>accept()</slot>
</connection>
<connection>
<sender>dialog_button_box</sender>
<signal>rejected()</signal>
<receiver>configuration_dialog</receiver>
<slot>reject()</slot>
</connection>
</connections>
</item>
<item>
<widget class="QDialogButtonBox" name="dialog_button_box">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="standardButtons">
<set>QDialogButtonBox::Cancel|QDialogButtonBox::Ok</set>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections>
<connection>
<sender>dialog_button_box</sender>
<signal>accepted()</signal>
<receiver>configuration_dialog</receiver>
<slot>accept()</slot>
<hints>
<hint type="sourcelabel">
<x>20</x>
<y>20</y>
</hint>
<hint type="destinationlabel">
<x>20</x>
<y>20</y>
</hint>
</hints>
</connection>
<connection>
<sender>dialog_button_box</sender>
<signal>rejected()</signal>
<receiver>configuration_dialog</receiver>
<slot>reject()</slot>
<hints>
<hint type="sourcelabel">
<x>20</x>
<y>20</y>
</hint>
<hint type="destinationlabel">
<x>20</x>
<y>20</y>
</hint>
</hints>
</connection>
</connections>
</ui>
53 changes: 51 additions & 2 deletions rqt_image_overlay/src/image_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include "image_manager.hpp"
#include "list_image_topics.hpp"
#include "image_transport/image_transport.hpp"
#include "qt_gui_cpp/settings.h"
#include "ros_image_to_qimage/ros_image_to_qimage.hpp"

namespace rqt_image_overlay
Expand All @@ -26,6 +27,10 @@ namespace rqt_image_overlay
ImageManager::ImageManager(const std::shared_ptr<rclcpp::Node> & node)
: node(node)
{
// Set initial cvtColorForDisplayOptions_ (setting max_image_value to 10.0 by default to match
// behavior from rqt_image_view)
cvtColorForDisplayOptions_ = std::make_shared<cv_bridge::CvtColorForDisplayOptions>();
cvtColorForDisplayOptions_->max_image_value = 10.0;
}

void ImageManager::callbackImage(const sensor_msgs::msg::Image::ConstSharedPtr & msg)
Expand All @@ -49,7 +54,7 @@ void ImageManager::onTopicChanged(int index)
std::bind(&ImageManager::callbackImage, this, std::placeholders::_1),
imageTopic.transport, rmw_qos_profile_sensor_data);
qDebug(
"ImageView::onTopicChanged() to topic '%s' with transport '%s'",
"ImageManager::onTopicChanged() to topic '%s' with transport '%s'",
imageTopic.topic.c_str(), imageTopic.transport.c_str());
} catch (image_transport::TransportLoadException & e) {
qWarning("(ImageManager) Loading image transport plugin failed");
Expand All @@ -74,6 +79,31 @@ void ImageManager::updateImageTopicList()
endResetModel();
}

void ImageManager::saveSettings(qt_gui_cpp::Settings & settings) const
{
QMap<QString, QVariant> map;
auto options = getCvtColorForDisplayOptions();
map.insert("do_dynamic_scaling", options.do_dynamic_scaling);
map.insert("min_image_value", options.min_image_value);
map.insert("max_image_value", options.max_image_value);
map.insert("colormap", options.colormap);
map.insert("bg_label", options.bg_label);
settings.setValue("cvtColorForDisplayOptions", QVariant(map));
}

void ImageManager::restoreSettings(const qt_gui_cpp::Settings & settings)
{
if (settings.contains("cvtColorForDisplayOptions")) {
QMap<QString, QVariant> map = settings.value("cvtColorForDisplayOptions").toMap();
auto cvtColorForDisplayOptions = std::make_shared<cv_bridge::CvtColorForDisplayOptions>();
cvtColorForDisplayOptions->do_dynamic_scaling = map.value("do_dynamic_scaling").toBool();
cvtColorForDisplayOptions->min_image_value = map.value("min_image_value").toDouble();
cvtColorForDisplayOptions->max_image_value = map.value("max_image_value").toDouble();
cvtColorForDisplayOptions->colormap = map.value("colormap").toInt();
cvtColorForDisplayOptions->bg_label = map.value("bg_label").toInt();
std::atomic_store(&cvtColorForDisplayOptions_, cvtColorForDisplayOptions);
}
}

int ImageManager::rowCount(const QModelIndex &) const
{
Expand All @@ -99,7 +129,8 @@ std::tuple<std::shared_ptr<QImage>, rclcpp::Time> ImageManager::getClosestImageA
{
auto closestTime = msgStorage.getClosestTime(targetTimeReceived);
auto msg = msgStorage.getMsg(closestTime);
auto image = std::make_shared<QImage>(ros_image_to_qimage::Convert(*msg));
auto image = std::make_shared<QImage>(
ros_image_to_qimage::Convert(*msg, getCvtColorForDisplayOptions()));
return std::make_tuple(image, rclcpp::Time{msg->header.stamp});
}

Expand All @@ -125,4 +156,22 @@ void ImageManager::addImageTopicExplicitly(ImageTopic imageTopic)
endResetModel();
}

void ImageManager::setCvtColorForDisplayOptions(
const cv_bridge::CvtColorForDisplayOptions & options)
{
auto cvtColorForDisplayOptions = std::make_shared<cv_bridge::CvtColorForDisplayOptions>();
cvtColorForDisplayOptions->do_dynamic_scaling = options.do_dynamic_scaling;
cvtColorForDisplayOptions->min_image_value = options.min_image_value;
cvtColorForDisplayOptions->max_image_value = options.max_image_value;
cvtColorForDisplayOptions->colormap = options.colormap;
cvtColorForDisplayOptions->bg_label = options.bg_label;
std::atomic_store(&cvtColorForDisplayOptions_, cvtColorForDisplayOptions);
}

cv_bridge::CvtColorForDisplayOptions ImageManager::getCvtColorForDisplayOptions() const
{
auto cvtColorForDisplayOptions = std::atomic_load(&cvtColorForDisplayOptions_);
return *cvtColorForDisplayOptions;
}

} // namespace rqt_image_overlay
Loading