mouse_click.h
Go to the documentation of this file.
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 {
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.
51  std::string topic_;
53 };
54 
55 } // namespace rviz
56 #endif
ros::Publisher
ros.h
rviz::MouseClick::win_width_
int win_width_
Definition: mouse_click.h:48
rviz::MouseClick::node_handle_
ros::NodeHandle node_handle_
Definition: mouse_click.h:49
rviz::MouseClick::publisher_
ros::Publisher publisher_
Definition: mouse_click.h:50
rviz
Definition: add_display_dialog.cpp:54
display.h
rviz::MouseClick::topic_name_ok_
bool topic_name_ok_
Definition: mouse_click.h:52
rviz::MouseClick
Class for capturing mouse clicks.
Definition: mouse_click.h:34
ros::NodeHandle
rviz::MouseClick::topic_
std::string topic_
Definition: mouse_click.h:51


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