ed
gui_plugin.h
Go to the documentation of this file.
1 #ifndef ED_GUI_PLUGIN_H_
2 #define ED_GUI_PLUGIN_H_
3 
4 #include <ed/plugin.h>
5 
6 #include <ed/types.h>
7 
8 // Communication
9 #include <ros/callback_queue.h>
10 #include <ros/service_server.h>
11 #include <ros/publisher.h>
12 
13 // Configuration
15 
16 // Services
17 #include <ed_msgs/GetMeasurements.h>
18 #include <ed_msgs/SetLabel.h>
19 #include <ed_msgs/RaiseEvent.h>
20 #include <ed_msgs/GetGUICommand.h>
21 
22 // Map drawing
24 
25 #include <ed/event_clock.h>
26 
27 #include <map>
28 
29 class GUIPlugin : public ed::Plugin
30 {
31 
32 public:
33 
34  GUIPlugin();
35 
36  virtual ~GUIPlugin();
37 
39 
40  void initialize();
41 
42  void process(const ed::WorldModel& world, ed::UpdateRequest& req);
43 
45 
47 
48 
49  // Map drawing
50 
52 
54 
55  cv::Mat map_image_;
56 
57  // Communication
58 
59  ros::CallbackQueue cb_queue_;
60 
61  ros::ServiceServer srv_get_measurements_;
62 
63  ros::ServiceServer srv_set_label_;
64 
65  ros::ServiceServer srv_raise_event_;
66 
67  ros::ServiceServer srv_get_command_;
68 
69  ros::Publisher pub_image_map_;
70 
71  bool srvGetMeasurements(ed_msgs::GetMeasurements::Request& req, ed_msgs::GetMeasurements::Response& res);
72 
73  bool srvSetLabel(ed_msgs::SetLabel::Request& req, ed_msgs::SetLabel::Response& res);
74 
75  bool srvRaiseEvent(ed_msgs::RaiseEvent::Request& req, ed_msgs::RaiseEvent::Response& res);
76 
77  bool srvGetCommand(ed_msgs::GetGUICommand::Request& req, ed_msgs::GetGUICommand::Response& res);
78 
79 
80  void handleRequests();
81 
82  void publishMapImage();
83 
84  // Click
85 
86  cv::Point2i p_click_;
87 
88  ros::Time t_last_click_;
89 
90  // COMMAND
91 
93 
95 
97 
98  ros::Time t_command_;
99 
100  // SELECTION
101 
103 
104 
105  // HELPER FUNCTIONS
106 
107  ed::UUID getEntityFromClick(const cv::Point2i& p) const;
108 
109  cv::Point2i coordinateToPixel(const geo::Vector3& p) const;
110 
111  cv::Point2i coordinateToPixel(double x, double y, double z) const
112  {
113  return coordinateToPixel(geo::Vector3(x, y, z));
114  }
115 
116  cv::Point2i coordinateToPixel(const pcl::PointXYZ& p) const
117  {
118  return coordinateToPixel(p.x, p.y, p.z);
119  }
120 
121 };
122 
123 #endif
GUIPlugin::trigger_map_publish_
ed::EventClock trigger_map_publish_
Definition: gui_plugin.h:44
GUIPlugin::srvGetCommand
bool srvGetCommand(ed_msgs::GetGUICommand::Request &req, ed_msgs::GetGUICommand::Response &res)
Definition: gui_plugin.cpp:657
GUIPlugin::srv_raise_event_
ros::ServiceServer srv_raise_event_
Definition: gui_plugin.h:65
ed::Plugin
Definition: plugin.h:28
GUIPlugin::initialize
void initialize()
Definition: gui_plugin.cpp:247
ed::WorldModel
Definition: world_model.h:21
ed::UpdateRequest
Definition: update_request.h:24
GUIPlugin::t_last_click_
ros::Time t_last_click_
Definition: gui_plugin.h:88
std::string
DepthCamera.h
types.h
GUIPlugin::srv_set_label_
ros::ServiceServer srv_set_label_
Definition: gui_plugin.h:63
GUIPlugin::srvGetMeasurements
bool srvGetMeasurements(ed_msgs::GetMeasurements::Request &req, ed_msgs::GetMeasurements::Response &res)
Definition: gui_plugin.cpp:456
GUIPlugin::srvRaiseEvent
bool srvRaiseEvent(ed_msgs::RaiseEvent::Request &req, ed_msgs::RaiseEvent::Response &res)
Definition: gui_plugin.cpp:557
GUIPlugin::p_click_
cv::Point2i p_click_
Definition: gui_plugin.h:86
plugin.h
GUIPlugin::selected_id_
ed::UUID selected_id_
Definition: gui_plugin.h:102
geo::Transform3T
GUIPlugin::configure
void configure(tue::Configuration config)
Definition: gui_plugin.cpp:168
GUIPlugin::srv_get_measurements_
ros::ServiceServer srv_get_measurements_
Definition: gui_plugin.h:61
tue::config::ReaderWriter
ed::EventClock
Definition: event_clock.h:9
GUIPlugin::map_image_
cv::Mat map_image_
Definition: gui_plugin.h:55
GUIPlugin::srv_get_command_
ros::ServiceServer srv_get_command_
Definition: gui_plugin.h:67
event_clock.h
GUIPlugin::GUIPlugin
GUIPlugin()
Definition: gui_plugin.cpp:153
GUIPlugin::projector_
geo::DepthCamera projector_
Definition: gui_plugin.h:51
GUIPlugin::publishMapImage
void publishMapImage()
Definition: gui_plugin.cpp:297
ed::UUID
Definition: uuid.h:10
GUIPlugin::projector_pose_
geo::Pose3D projector_pose_
Definition: gui_plugin.h:53
GUIPlugin::~GUIPlugin
virtual ~GUIPlugin()
Definition: gui_plugin.cpp:162
geo::Vector3
map
GUIPlugin::command_params_
std::map< std::string, std::string > command_params_
Definition: gui_plugin.h:96
GUIPlugin
Definition: gui_plugin.h:29
GUIPlugin::process
void process(const ed::WorldModel &world, ed::UpdateRequest &req)
Definition: gui_plugin.cpp:253
configuration.h
GUIPlugin::world_model_
const ed::WorldModel * world_model_
Definition: gui_plugin.h:46
GUIPlugin::cb_queue_
ros::CallbackQueue cb_queue_
Definition: gui_plugin.h:59
GUIPlugin::srvSetLabel
bool srvSetLabel(ed_msgs::SetLabel::Request &req, ed_msgs::SetLabel::Response &res)
Definition: gui_plugin.cpp:494
GUIPlugin::command_
std::string command_
Definition: gui_plugin.h:92
GUIPlugin::coordinateToPixel
cv::Point2i coordinateToPixel(const pcl::PointXYZ &p) const
Definition: gui_plugin.h:116
geo::DepthCamera
GUIPlugin::command_id_
std::string command_id_
Definition: gui_plugin.h:94
GUIPlugin::handleRequests
void handleRequests()
Definition: gui_plugin.cpp:448
GUIPlugin::coordinateToPixel
cv::Point2i coordinateToPixel(double x, double y, double z) const
Definition: gui_plugin.h:111
GUIPlugin::pub_image_map_
ros::Publisher pub_image_map_
Definition: gui_plugin.h:69
GUIPlugin::getEntityFromClick
ed::UUID getEntityFromClick(const cv::Point2i &p) const
Definition: gui_plugin.cpp:271
GUIPlugin::t_command_
ros::Time t_command_
Definition: gui_plugin.h:98
GUIPlugin::coordinateToPixel
cv::Point2i coordinateToPixel(const geo::Vector3 &p) const
Definition: gui_plugin.cpp:264
config
tue::config::ReaderWriter config