mouse_click.cpp
Go to the documentation of this file.
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 {
11  node_handle_ = nh;
12  topic_name_ok_ = false;
13 }
14 
16 {
17  if (topic_name_ok_)
18  {
19  publisher_ = node_handle_.advertise<geometry_msgs::PointStamped>(topic_, 1);
20  parent()->installEventFilter(this);
21  }
22 }
23 
25 {
26  parent()->removeEventFilter(this);
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;
93 
94  enable();
95 }
96 
97 } // namespace rviz
rviz::MouseClick::setImageTopic
void setImageTopic(const QString &topic)
Definition: mouse_click.cpp:84
rviz::MouseClick::eventFilter
virtual bool eventFilter(QObject *obj, QEvent *event)
Definition: mouse_click.cpp:30
rviz::MouseClick::win_height_
int win_height_
Definition: mouse_click.h:48
rviz::MouseClick::win_width_
int win_width_
Definition: mouse_click.h:48
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
rviz::MouseClick::disable
void disable()
Definition: mouse_click.cpp:24
ros::names::validate
ROSCPP_DECL bool validate(const std::string &name, std::string &error)
rviz::MouseClick::node_handle_
ros::NodeHandle node_handle_
Definition: mouse_click.h:49
rviz::MouseClick::publisher_
ros::Publisher publisher_
Definition: mouse_click.h:50
ros::Publisher::shutdown
void shutdown()
rviz
Definition: add_display_dialog.cpp:54
rviz::MouseClick::img_height_
int img_height_
Definition: mouse_click.h:48
rviz::MouseClick::enable
void enable()
Definition: mouse_click.cpp:15
mouse_click.h
rviz::MouseClick::topic_name_ok_
bool topic_name_ok_
Definition: mouse_click.h:52
names.h
rviz::MouseClick::setDimensions
void setDimensions(int img_width, int img_height, int win_width, int win_height)
Definition: mouse_click.cpp:76
rviz::MouseClick::MouseClick
MouseClick(QWidget *widget, const ros::NodeHandle &nh)
Definition: mouse_click.cpp:8
rviz::MouseClick::img_width_
int img_width_
Definition: mouse_click.h:48
ros::NodeHandle
rviz::MouseClick::topic_
std::string topic_
Definition: mouse_click.h:51
ros::Time::now
static Time now()


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Sat Jun 1 2024 02:31:53