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

Adaptions for use within Team Spatzenhirn #1

Open
wants to merge 5 commits into
base: foxy-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 3 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
3 changes: 3 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
build
install
log
119 changes: 61 additions & 58 deletions include/rqt_image_view/image_view.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,121 +37,124 @@

#include <ui_image_view.h>

#include <image_transport/image_transport.hpp>
#include <image_transport/subscriber.hpp>

#include <sensor_msgs/msg/image.hpp>
#include <geometry_msgs/msg/point.hpp>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/image.hpp>

#include <opencv2/core/core.hpp>

#include <QAction>
#include <QImage>
#include <QList>
#include <QString>
#include <QSet>
#include <QSize>
#include <QString>
#include <QWidget>

#include <vector>

namespace rqt_image_view {

class ImageView
: public rqt_gui_cpp::Plugin
{
class ImageView : public rqt_gui_cpp::Plugin {

Q_OBJECT

Q_OBJECT
public:
ImageView();

public:
virtual void initPlugin(qt_gui_cpp::PluginContext &context);

ImageView();
virtual void shutdownPlugin();

virtual void initPlugin(qt_gui_cpp::PluginContext& context);
virtual void saveSettings(qt_gui_cpp::Settings &plugin_settings,
qt_gui_cpp::Settings &instance_settings) const;

virtual void shutdownPlugin();
virtual void restoreSettings(const qt_gui_cpp::Settings &plugin_settings,
const qt_gui_cpp::Settings &instance_settings);

virtual void saveSettings(qt_gui_cpp::Settings& plugin_settings, qt_gui_cpp::Settings& instance_settings) const;

virtual void restoreSettings(const qt_gui_cpp::Settings& plugin_settings, const qt_gui_cpp::Settings& instance_settings);
protected:
virtual QSet <QString> getTopics(const QSet <QString> &message_types);

protected slots:
virtual void selectTopic(const QString &topic);

virtual void updateTopicList();
protected slots:

protected:
virtual void updateTopicList();

virtual QSet<QString> getTopics(const QSet<QString>& message_types, const QSet<QString>& message_sub_types, const QList<QString>& transports);
virtual void onTopicChanged(int index);

virtual void selectTopic(const QString& topic);
virtual void onZoom1(bool checked);

protected slots:
virtual void onDynamicRange(bool checked);

virtual void onTopicChanged(int index);
virtual void saveImage();

virtual void onZoom1(bool checked);
virtual void updateNumGridlines();

virtual void onDynamicRange(bool checked);
virtual void onMousePublish(bool checked);

virtual void saveImage();
virtual void onMouseLeft(int x, int y);

virtual void updateNumGridlines();
virtual void onPubTopicChanged();

virtual void onMousePublish(bool checked);
virtual void onHideToolbarChanged(bool hide);

virtual void onMouseLeft(int x, int y);
virtual void onRotateLeft();

virtual void onPubTopicChanged();
virtual void onRotateRight();

virtual void onHideToolbarChanged(bool hide);
virtual void onVisibilityChanged(bool visible);

virtual void onRotateLeft();
virtual void onRotateRight();
virtual void subscribe();

protected:
virtual void unsubscribe();

virtual void callbackImage(const sensor_msgs::msg::Image::ConstSharedPtr& msg);
protected:
virtual void
callbackImage(sensor_msgs::msg::Image::ConstSharedPtr msg);

virtual void invertPixels(int x, int y);
virtual void invertPixels(int x, int y);

QList<int> getGridIndices(int size) const;
QList<int> getGridIndices(int size) const;

virtual void overlayGrid();
virtual void overlayGrid();

Ui::ImageViewWidget ui_;
Ui::ImageViewWidget ui_;

QWidget* widget_;
QWidget *widget_;

image_transport::Subscriber subscriber_;
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr subscriber_;

cv::Mat conversion_mat_;
cv::Mat conversion_mat_;

private:
private:
enum RotateState {
ROTATE_0 = 0,
ROTATE_90 = 1,
ROTATE_180 = 2,
ROTATE_270 = 3,

enum RotateState {
ROTATE_0 = 0,
ROTATE_90 = 1,
ROTATE_180 = 2,
ROTATE_270 = 3,
ROTATE_STATE_COUNT
};

ROTATE_STATE_COUNT
};
void syncRotateLabel();

void syncRotateLabel();
QString arg_topic_name;

QString arg_topic_name;
rclcpp::Publisher<geometry_msgs::msg::Point>::SharedPtr pub_mouse_left_;

rclcpp::Publisher<geometry_msgs::msg::Point>::SharedPtr pub_mouse_left_;
bool pub_topic_custom_;

bool pub_topic_custom_;
QAction *hide_toolbar_action_;

QAction* hide_toolbar_action_;
int num_gridlines_;

int num_gridlines_;
RotateState rotate_state_;

RotateState rotate_state_;
};
std::string cur_topic_name_;
};

}
} // namespace rqt_image_view

#endif // rqt_image_view__ImageView_H
75 changes: 36 additions & 39 deletions include/rqt_image_view/ratio_layouted_frame.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,71 +45,68 @@
namespace rqt_image_view {

/**
* RatioLayoutedFrame is a layout containing a single frame with a fixed aspect ratio.
* The default aspect ratio is 4:3.
* RatioLayoutedFrame is a layout containing a single frame with a fixed aspect
* ratio. The default aspect ratio is 4:3.
*/
class RatioLayoutedFrame
: public QFrame
{
class RatioLayoutedFrame : public QFrame {

Q_OBJECT
Q_OBJECT

public:
public:
RatioLayoutedFrame(QWidget *parent, Qt::WindowFlags flags = 0);

RatioLayoutedFrame(QWidget* parent, Qt::WindowFlags flags = 0);
virtual ~RatioLayoutedFrame();

virtual ~RatioLayoutedFrame();
const QImage &getImage() const;

const QImage& getImage() const;
QImage getImageCopy() const;

QImage getImageCopy() const;
void setImage(const QImage &image);

void setImage(const QImage& image);
QRect getAspectRatioCorrectPaintArea();

QRect getAspectRatioCorrectPaintArea();
void resizeToFitAspectRatio();

void resizeToFitAspectRatio();
void setOuterLayout(QHBoxLayout *outer_layout);

void setOuterLayout(QHBoxLayout* outer_layout);
void setInnerFrameMinimumSize(const QSize &size);

void setInnerFrameMinimumSize(const QSize& size);
void setInnerFrameMaximumSize(const QSize &size);

void setInnerFrameMaximumSize(const QSize& size);
void setInnerFrameFixedSize(const QSize &size);

void setInnerFrameFixedSize(const QSize& size);
signals:

signals:
void delayed_update();

void delayed_update();
void mouseLeft(int x, int y);

void mouseLeft(int x, int y);
protected
slots:

protected slots:
void onSmoothImageChanged(bool
checked);

void onSmoothImageChanged(bool checked);
protected:
void setAspectRatio(unsigned short width, unsigned short height);

protected:
void paintEvent(QPaintEvent *event);

void setAspectRatio(unsigned short width, unsigned short height);
private:
static int greatestCommonDivisor(int a, int b);

void paintEvent(QPaintEvent* event);
void mousePressEvent(QMouseEvent *mouseEvent);

private:
QHBoxLayout *outer_layout_;

static int greatestCommonDivisor(int a, int b);
QSize aspect_ratio_;

void mousePressEvent(QMouseEvent * mouseEvent);
QImage qimage_;
mutable QMutex qimage_mutex_;

QHBoxLayout* outer_layout_;
bool smoothImage_;
};

QSize aspect_ratio_;

QImage qimage_;
mutable QMutex qimage_mutex_;

bool smoothImage_;
};

}
} // namespace rqt_image_view

#endif // rqt_image_view__RatioLayoutedFrame_H
Loading