Skip to content

Commit 23d9e81

Browse files
ImageDisplay: publish mouse clicks (#1737)
Publish mouse clicks (or dragging) on <image_topic>/mouse_click Co-authored-by: Robert Haschke <[email protected]>
1 parent 2fd5e9d commit 23d9e81

File tree

5 files changed

+173
-0
lines changed

5 files changed

+173
-0
lines changed

src/rviz/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,7 @@ add_library(${PROJECT_NAME}
4040
help_panel.cpp
4141
image/ros_image_texture.cpp
4242
image/image_display_base.cpp
43+
image/mouse_click.cpp
4344
loading_dialog.cpp
4445
message_filter_display.h
4546
mesh_loader.cpp

src/rviz/default_plugin/image_display.cpp

+15
Original file line numberDiff line numberDiff line change
@@ -138,6 +138,8 @@ void ImageDisplay::onInitialize()
138138
render_panel_->getCamera()->setNearClipDistance(0.01f);
139139

140140
updateNormalizeOptions();
141+
142+
mouse_click_ = new MouseClick(render_panel_, update_nh_);
141143
}
142144

143145
ImageDisplay::~ImageDisplay()
@@ -153,13 +155,17 @@ ImageDisplay::~ImageDisplay()
153155
void ImageDisplay::onEnable()
154156
{
155157
ImageDisplayBase::subscribe();
158+
mouse_click_->enable();
159+
156160
render_panel_->getRenderWindow()->setActive(true);
157161
}
158162

159163
void ImageDisplay::onDisable()
160164
{
161165
render_panel_->getRenderWindow()->setActive(false);
162166
ImageDisplayBase::unsubscribe();
167+
mouse_click_->disable();
168+
163169
reset();
164170
}
165171

@@ -219,6 +225,8 @@ void ImageDisplay::update(float wall_dt, float ros_dt)
219225
}
220226

221227
render_panel_->getRenderWindow()->update();
228+
229+
mouse_click_->setDimensions(img_width, img_height, win_width, win_height);
222230
}
223231
catch (UnsupportedImageEncoding& e)
224232
{
@@ -249,6 +257,13 @@ void ImageDisplay::processMessage(const sensor_msgs::Image::ConstPtr& msg)
249257
texture_.addMessage(msg);
250258
}
251259

260+
void ImageDisplay::updateTopic()
261+
{
262+
ImageDisplayBase::updateTopic();
263+
mouse_click_->setImageTopic(topic_property_->getTopic());
264+
}
265+
266+
252267
} // namespace rviz
253268

254269
#include <pluginlib/class_list_macros.hpp>

src/rviz/default_plugin/image_display.h

+4
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@
3939

4040
#include "rviz/image/image_display_base.h"
4141
#include "rviz/image/ros_image_texture.h"
42+
#include "rviz/image/mouse_click.h"
4243
#include "rviz/render_panel.h"
4344

4445
#include "rviz/properties/bool_property.h"
@@ -81,6 +82,7 @@ public Q_SLOTS:
8182

8283
/* This is called by incomingMessage(). */
8384
void processMessage(const sensor_msgs::Image::ConstPtr& msg) override;
85+
void updateTopic() override;
8486

8587
Ogre::SceneManager* img_scene_manager_;
8688

@@ -98,6 +100,8 @@ public Q_SLOTS:
98100
FloatProperty* max_property_;
99101
IntProperty* median_buffer_size_property_;
100102
bool got_float_image_;
103+
104+
MouseClick* mouse_click_;
101105
};
102106

103107
} // namespace rviz

src/rviz/image/mouse_click.cpp

+97
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,97 @@
1+
#include "rviz/image/mouse_click.h"
2+
#include <QWidget>
3+
#include <ros/names.h>
4+
5+
6+
namespace rviz
7+
{
8+
MouseClick::MouseClick(QWidget* widget, const ros::NodeHandle& nh) : QObject(widget)
9+
{
10+
img_width_ = img_height_ = win_width_ = win_height_ = 0;
11+
node_handle_ = nh;
12+
topic_name_ok_ = false;
13+
}
14+
15+
void MouseClick::enable()
16+
{
17+
if (topic_name_ok_)
18+
{
19+
publisher_ = node_handle_.advertise<geometry_msgs::PointStamped>(topic_, 1);
20+
parent()->installEventFilter(this);
21+
}
22+
}
23+
24+
void MouseClick::disable()
25+
{
26+
parent()->removeEventFilter(this);
27+
publisher_.shutdown();
28+
}
29+
30+
bool MouseClick::eventFilter(QObject* obj, QEvent* event)
31+
{
32+
if (event->type() == QEvent::MouseButtonPress || event->type() == QEvent::MouseMove)
33+
{
34+
QMouseEvent* me = static_cast<QMouseEvent*>(event);
35+
QPointF windowPos = me->windowPos();
36+
bool left_button = me->buttons() == Qt::LeftButton;
37+
38+
if (left_button && img_width_ != 0 && img_height_ != 0 && win_width_ != 0 && win_height_ != 0)
39+
{
40+
float img_aspect = float(img_width_) / float(img_height_);
41+
float win_aspect = float(win_width_) / float(win_height_);
42+
43+
int pix_x = -1;
44+
int pix_y = -1;
45+
if (img_aspect > win_aspect) // Window is taller than the image: black bars over and under image.
46+
{
47+
pix_x = int(float(windowPos.x()) / float(win_width_) * float(img_width_));
48+
49+
int resized_img_height = int(float(win_width_) / float(img_width_) * float(img_height_));
50+
int bias = int((float(win_height_) - float(resized_img_height)) / 2.0);
51+
pix_y = (float(windowPos.y()) - bias) / float(resized_img_height) * float(img_height_);
52+
}
53+
else // Window wider than the image: black bars on the side.
54+
{
55+
pix_y = int(float(windowPos.y()) / float(win_height_) * float(img_height_));
56+
57+
int resized_img_width = int(float(win_height_) / float(img_height_) * float(img_width_));
58+
int bias = int((float(win_width_) - float(resized_img_width)) / 2.0);
59+
pix_x = (float(windowPos.x()) - bias) / float(resized_img_width) * float(img_width_);
60+
}
61+
62+
// Publish if clicked point is inside the image.
63+
if (pix_x >= 0 && pix_x < img_width_ && pix_y >= 0 && pix_y < img_height_)
64+
{
65+
geometry_msgs::PointStamped point_msg;
66+
point_msg.header.stamp = ros::Time::now();
67+
point_msg.point.x = pix_x;
68+
point_msg.point.y = pix_y;
69+
publisher_.publish(point_msg);
70+
}
71+
}
72+
}
73+
return QObject::eventFilter(obj, event);
74+
}
75+
76+
void MouseClick::setDimensions(int img_width, int img_height, int win_width, int win_height)
77+
{
78+
img_width_ = img_width;
79+
img_height_ = img_height;
80+
win_width_ = win_width;
81+
win_height_ = win_height;
82+
}
83+
84+
void MouseClick::setImageTopic(const QString& topic)
85+
{
86+
disable();
87+
88+
// Build the click full topic name based on the image topic
89+
topic_ = topic.toStdString().append("/mouse_click");
90+
91+
std::string error;
92+
topic_name_ok_ = ros::names::validate(topic_, error);
93+
94+
enable();
95+
}
96+
97+
} // namespace rviz

src/rviz/image/mouse_click.h

+56
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,56 @@
1+
#ifndef RVIZ_MOUSE_CLICK_H
2+
#define RVIZ_MOUSE_CLICK_H
3+
4+
#include <QObject>
5+
6+
#ifndef Q_MOC_RUN // See: https://bugreports.qt-project.org/browse/QTBUG-22829
7+
#include <iostream>
8+
#include <string>
9+
#include <boost/shared_ptr.hpp>
10+
11+
#include <QMouseEvent>
12+
13+
#include "ros/ros.h"
14+
#include "geometry_msgs/PointStamped.h"
15+
#include "std_msgs/String.h"
16+
17+
#include "rviz/rviz_export.h"
18+
#include "rviz/display.h"
19+
#endif
20+
21+
22+
namespace rviz
23+
{
24+
/** @brief Class for capturing mouse clicks.
25+
*
26+
* This class handles mouse clicking functionalities integrated into the ImageDisplay.
27+
* It uses a qt event filter to capture mouse clicks, handles image resizing and checks if the click was
28+
* inside or outside the image. It also scales the pixel coordinates to get them w.r.t. the image (not
29+
* the window) size. Mouse clicks image pixel coordinates are published as ros geometry_msgs
30+
* PointStamped. The z component is ignored. The topic name where the mouse clicks are published is
31+
* defined created after the subscribed image topic as: <image_topic>/mouse_click.
32+
*/
33+
34+
class RVIZ_EXPORT MouseClick : QObject
35+
{
36+
public:
37+
MouseClick(QWidget* widget, const ros::NodeHandle& nh);
38+
39+
void enable();
40+
void disable();
41+
42+
void setDimensions(int img_width, int img_height, int win_width, int win_height);
43+
void setImageTopic(const QString& topic);
44+
45+
private:
46+
virtual bool eventFilter(QObject* obj, QEvent* event);
47+
48+
int img_width_, img_height_, win_width_, win_height_; // To assess if the clicks are inside the image.
49+
ros::NodeHandle node_handle_;
50+
ros::Publisher publisher_;
51+
std::string topic_;
52+
bool topic_name_ok_;
53+
};
54+
55+
} // namespace rviz
56+
#endif

0 commit comments

Comments
 (0)