ed
|
#include <gui_plugin.h>
Public Member Functions | |
void | configure (tue::Configuration config) |
cv::Point2i | coordinateToPixel (const geo::Vector3 &p) const |
cv::Point2i | coordinateToPixel (const pcl::PointXYZ &p) const |
cv::Point2i | coordinateToPixel (double x, double y, double z) const |
ed::UUID | getEntityFromClick (const cv::Point2i &p) const |
GUIPlugin () | |
void | handleRequests () |
void | initialize () |
void | process (const ed::WorldModel &world, ed::UpdateRequest &req) |
void | publishMapImage () |
bool | srvGetCommand (ed_msgs::GetGUICommand::Request &req, ed_msgs::GetGUICommand::Response &res) |
bool | srvGetMeasurements (ed_msgs::GetMeasurements::Request &req, ed_msgs::GetMeasurements::Response &res) |
bool | srvRaiseEvent (ed_msgs::RaiseEvent::Request &req, ed_msgs::RaiseEvent::Response &res) |
bool | srvSetLabel (ed_msgs::SetLabel::Request &req, ed_msgs::SetLabel::Response &res) |
virtual | ~GUIPlugin () |
![]() | |
virtual void | initialize (InitData &) |
const std::string & | name () const |
virtual void | process (const PluginInput &, UpdateRequest &) |
virtual | ~Plugin () |
Public Attributes | |
ros::CallbackQueue | cb_queue_ |
std::string | command_ |
std::string | command_id_ |
std::map< std::string, std::string > | command_params_ |
cv::Mat | map_image_ |
cv::Point2i | p_click_ |
geo::DepthCamera | projector_ |
geo::Pose3D | projector_pose_ |
ros::Publisher | pub_image_map_ |
ed::UUID | selected_id_ |
ros::ServiceServer | srv_get_command_ |
ros::ServiceServer | srv_get_measurements_ |
ros::ServiceServer | srv_raise_event_ |
ros::ServiceServer | srv_set_label_ |
ros::Time | t_command_ |
ros::Time | t_last_click_ |
ed::EventClock | trigger_map_publish_ |
const ed::WorldModel * | world_model_ |
Additional Inherited Members | |
![]() | |
TFBufferConstPtr | tf_buffer_ |
Definition at line 29 of file gui_plugin.h.
GUIPlugin::GUIPlugin | ( | ) |
Definition at line 153 of file gui_plugin.cpp.
|
virtual |
Definition at line 162 of file gui_plugin.cpp.
|
virtual |
Reimplemented from ed::Plugin.
Definition at line 168 of file gui_plugin.cpp.
cv::Point2i GUIPlugin::coordinateToPixel | ( | const geo::Vector3 & | p | ) | const |
Definition at line 264 of file gui_plugin.cpp.
|
inline |
Definition at line 116 of file gui_plugin.h.
|
inline |
Definition at line 111 of file gui_plugin.h.
ed::UUID GUIPlugin::getEntityFromClick | ( | const cv::Point2i & | p | ) | const |
Definition at line 271 of file gui_plugin.cpp.
void GUIPlugin::handleRequests | ( | ) |
Definition at line 448 of file gui_plugin.cpp.
|
virtual |
Reimplemented from ed::Plugin.
Definition at line 247 of file gui_plugin.cpp.
|
virtual |
Reimplemented from ed::Plugin.
Definition at line 253 of file gui_plugin.cpp.
void GUIPlugin::publishMapImage | ( | ) |
Definition at line 297 of file gui_plugin.cpp.
bool GUIPlugin::srvGetCommand | ( | ed_msgs::GetGUICommand::Request & | req, |
ed_msgs::GetGUICommand::Response & | res | ||
) |
Definition at line 657 of file gui_plugin.cpp.
bool GUIPlugin::srvGetMeasurements | ( | ed_msgs::GetMeasurements::Request & | req, |
ed_msgs::GetMeasurements::Response & | res | ||
) |
Definition at line 456 of file gui_plugin.cpp.
bool GUIPlugin::srvRaiseEvent | ( | ed_msgs::RaiseEvent::Request & | req, |
ed_msgs::RaiseEvent::Response & | res | ||
) |
Definition at line 557 of file gui_plugin.cpp.
bool GUIPlugin::srvSetLabel | ( | ed_msgs::SetLabel::Request & | req, |
ed_msgs::SetLabel::Response & | res | ||
) |
Definition at line 494 of file gui_plugin.cpp.
ros::CallbackQueue GUIPlugin::cb_queue_ |
Definition at line 59 of file gui_plugin.h.
std::string GUIPlugin::command_ |
Definition at line 92 of file gui_plugin.h.
std::string GUIPlugin::command_id_ |
Definition at line 94 of file gui_plugin.h.
std::map<std::string, std::string> GUIPlugin::command_params_ |
Definition at line 96 of file gui_plugin.h.
cv::Mat GUIPlugin::map_image_ |
Definition at line 55 of file gui_plugin.h.
cv::Point2i GUIPlugin::p_click_ |
Definition at line 86 of file gui_plugin.h.
geo::DepthCamera GUIPlugin::projector_ |
Definition at line 51 of file gui_plugin.h.
geo::Pose3D GUIPlugin::projector_pose_ |
Definition at line 53 of file gui_plugin.h.
ros::Publisher GUIPlugin::pub_image_map_ |
Definition at line 69 of file gui_plugin.h.
ed::UUID GUIPlugin::selected_id_ |
Definition at line 102 of file gui_plugin.h.
ros::ServiceServer GUIPlugin::srv_get_command_ |
Definition at line 67 of file gui_plugin.h.
ros::ServiceServer GUIPlugin::srv_get_measurements_ |
Definition at line 61 of file gui_plugin.h.
ros::ServiceServer GUIPlugin::srv_raise_event_ |
Definition at line 65 of file gui_plugin.h.
ros::ServiceServer GUIPlugin::srv_set_label_ |
Definition at line 63 of file gui_plugin.h.
ros::Time GUIPlugin::t_command_ |
Definition at line 98 of file gui_plugin.h.
ros::Time GUIPlugin::t_last_click_ |
Definition at line 88 of file gui_plugin.h.
ed::EventClock GUIPlugin::trigger_map_publish_ |
Definition at line 44 of file gui_plugin.h.
const ed::WorldModel* GUIPlugin::world_model_ |
Definition at line 46 of file gui_plugin.h.