-
Notifications
You must be signed in to change notification settings - Fork 158
Right_Click_Services #590
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
base: master
Are you sure you want to change the base?
Right_Click_Services #590
Changes from 20 commits
a980c7f
9827340
288da7f
1b66854
50d5b45
e208f2d
c4759ab
15f144b
937ce84
b6f31e2
fbe884a
01655b1
44445c8
94cd04b
66cc20c
aeb56b2
1411dd9
e0dce22
438f014
3b5510e
3e10717
14e3784
6e4414b
a2912c2
c3ef060
5b456f7
2e20f7c
d5e7bdd
8560299
55e88c4
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -31,8 +31,15 @@ | |
| #include <GL/glew.h> | ||
| #include <GL/gl.h> | ||
| #include <GL/glu.h> | ||
|
|
||
| #include <iostream> | ||
|
Contributor
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This include is duplicated. |
||
| #include <mapviz/map_canvas.h> | ||
| #include <QMenu> | ||
| #include <QAction> | ||
| #include "ros/ros.h" | ||
| #include <vector> | ||
| #include <string> | ||
| #include <sstream> | ||
| #include <iostream> | ||
|
|
||
| // C++ standard libraries | ||
| #include <cmath> | ||
|
|
@@ -90,6 +97,7 @@ MapCanvas::MapCanvas(QWidget* parent) : | |
| setFrameRate(50.0); | ||
| frame_rate_timer_.start(); | ||
| setFocusPolicy(Qt::StrongFocus); | ||
| this->setContextMenuPolicy(Qt::CustomContextMenu); | ||
| } | ||
|
|
||
| MapCanvas::~MapCanvas() | ||
|
|
@@ -319,13 +327,15 @@ void MapCanvas::Zoom(float factor) | |
|
|
||
| void MapCanvas::mousePressEvent(QMouseEvent* e) | ||
| { | ||
| mouse_x_ = e->x(); | ||
| mouse_y_ = e->y(); | ||
| mouse_previous_y_ = mouse_y_; | ||
| drag_x_ = 0; | ||
| drag_y_ = 0; | ||
| mouse_pressed_ = true; | ||
| mouse_button_ = e->button(); | ||
|
|
||
| mouse_x_ = e->x(); | ||
alex94263 marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| mouse_y_ = e->y(); | ||
| mouse_previous_y_ = mouse_y_; | ||
| drag_x_ = 0; | ||
| drag_y_ = 0; | ||
| mouse_pressed_ = true; | ||
| mouse_button_ = e->button(); | ||
|
|
||
| } | ||
|
|
||
| void MapCanvas::keyPressEvent(QKeyEvent* event) | ||
|
|
@@ -614,4 +624,34 @@ double MapCanvas::frameRate() const | |
| { | ||
| return 1000.0 / frame_rate_timer_.interval(); | ||
| } | ||
| } // namespace mapviz | ||
|
|
||
| std::string MapCanvas::showCustomContextMenu(const QPoint &pos,std::vector<std::string> result){ | ||
| QMenu contextMenu(this); | ||
| std::vector<QAction *> actions; | ||
|
|
||
| for(auto service : result){ | ||
|
||
| QAction * act= new QAction(service.c_str(),this); | ||
| actions.push_back(act); | ||
| } | ||
| for(auto action: actions){ | ||
| contextMenu.addAction(action); | ||
| } | ||
|
|
||
| QAction* selectedItem=contextMenu.exec(pos); | ||
| for(auto action: actions){ | ||
| action->deleteLater(); | ||
| } | ||
|
|
||
| if (selectedItem){ | ||
| ROS_INFO("make call to %s",selectedItem->text().toStdString().c_str()); | ||
| return selectedItem->text().toStdString().c_str(); | ||
| }else{ | ||
| ROS_ERROR("Service:'' doesn't exist"); | ||
|
||
| return ""; | ||
| } | ||
|
|
||
| } | ||
|
|
||
|
|
||
| } | ||
|
|
||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -26,7 +26,22 @@ set(DEPENDENCIES | |
| visualization_msgs | ||
| ) | ||
|
|
||
| find_package(catkin REQUIRED COMPONENTS ${DEPENDENCIES}) | ||
| find_package(catkin REQUIRED COMPONENTS ${DEPENDENCIES} | ||
| std_msgs | ||
| geometry_msgs | ||
| message_generation | ||
|
||
| ) | ||
|
|
||
| add_message_files(DIRECTORY msg | ||
| FILES | ||
| Location.msg | ||
| ) | ||
|
|
||
| add_service_files(FILES | ||
| AvailableServices.srv | ||
| GPSCommand.srv | ||
| ) | ||
| generate_messages(DEPENDENCIES std_msgs geometry_msgs) | ||
|
|
||
| ### QT ### | ||
| if("$ENV{ROS_DISTRO}" STRLESS "kinetic") | ||
|
|
@@ -101,6 +116,7 @@ set(UI_FILES | |
| ui/path_config.ui | ||
| ui/plan_route_config.ui | ||
| ui/point_click_publisher_config.ui | ||
| ui/right_click_services_config.ui | ||
|
Contributor
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Please keep the order of files in these lists alphabetized. |
||
| ui/pointcloud2_config.ui | ||
| ui/robot_image_config.ui | ||
| ui/route_config.ui | ||
|
|
@@ -127,6 +143,7 @@ set(SRC_FILES | |
| src/placeable_window_proxy.cpp | ||
| src/plan_route_plugin.cpp | ||
| src/point_click_publisher_plugin.cpp | ||
| src/right_click_services_plugin.cpp | ||
| src/pointcloud2_plugin.cpp | ||
| src/point_drawing_plugin.cpp | ||
| src/robot_image_plugin.cpp | ||
|
|
@@ -155,6 +172,7 @@ set(HEADER_FILES | |
| include/${PROJECT_NAME}/placeable_window_proxy.h | ||
| include/${PROJECT_NAME}/plan_route_plugin.h | ||
| include/${PROJECT_NAME}/point_click_publisher_plugin.h | ||
| include/${PROJECT_NAME}/right_click_services_plugin.h | ||
| include/${PROJECT_NAME}/pointcloud2_plugin.h | ||
| include/${PROJECT_NAME}/point_drawing_plugin.h | ||
| include/${PROJECT_NAME}/robot_image_plugin.h | ||
|
|
||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,82 @@ | ||
| // ***************************************************************************** | ||
| // handling right click event, calls service which will display a | ||
| // number of services that are available on that specific location | ||
| // | ||
| // ***************************************************************************** | ||
|
|
||
|
|
||
| #ifndef MAPVIZ_PLUGINS_right_click_services_H | ||
|
||
| #define MAPVIZ_PLUGINS_right_click_services_H | ||
|
|
||
| // Include mapviz_plugin.h first to ensure GL deps are included in the right order | ||
| #include <mapviz/mapviz_plugin.h> | ||
|
|
||
| #include <QGLWidget> | ||
| #include <QTimer> | ||
| #include <mapviz/map_canvas.h> | ||
| #include <QMouseEvent> | ||
| #include <mapviz_plugins/canvas_click_filter.h> | ||
|
|
||
| #include <ros/ros.h> | ||
|
|
||
| // QT autogenerated files | ||
| #include "ui_right_click_services_config.h" | ||
| #include "ui_topic_select.h" | ||
|
|
||
| /** | ||
| * This is a pretty straightforward plugin. It watches for user clicks on the | ||
| * canvas, then converts the coordinates into a specified frame and publishes | ||
| * them as PointStamped messages on a specified topic. | ||
| */ | ||
| namespace mapviz_plugins | ||
| { | ||
| class RightClickServicesPlugin : public mapviz::MapvizPlugin | ||
| { | ||
| Q_OBJECT; | ||
| public: | ||
|
|
||
| RightClickServicesPlugin(); | ||
| virtual ~RightClickServicesPlugin(); | ||
|
|
||
| bool Initialize(QGLWidget* canvas); | ||
| void Shutdown() {} | ||
|
|
||
| virtual void SetNode(const ros::NodeHandle& node); | ||
| virtual void PrintError(const std::string& message); | ||
| virtual void PrintInfo(const std::string& message); | ||
| virtual void PrintWarning(const std::string& message); | ||
|
|
||
| void Draw(double x, double y, double scale); | ||
|
|
||
| void Transform() {} | ||
|
|
||
| void LoadConfig(const YAML::Node& node, const std::string& path); | ||
| void SaveConfig(YAML::Emitter& emitter, const std::string& path); | ||
|
|
||
| QWidget* GetConfigWidget(QWidget* parent); | ||
|
|
||
|
|
||
| void serviceCall(std::string service); | ||
|
|
||
|
|
||
| protected Q_SLOTS: | ||
|
|
||
| void pointClicked(const QPointF& point, const Qt::MouseButton& button); | ||
| void topicChanged(const QString& topic); | ||
| void updateFrames(); | ||
|
|
||
|
|
||
| private: | ||
| void showContextMenu(const QPoint& pos, boost::shared_ptr<geometry_msgs::PointStamped> stamped); | ||
| Ui::right_click_services_config ui_; | ||
| QWidget* config_widget_; | ||
|
|
||
| CanvasClickFilter click_filter_; | ||
| mapviz::MapCanvas* canvas_; | ||
|
|
||
| QTimer frame_timer_; | ||
| ros::Publisher point_publisher_; | ||
| }; | ||
| } | ||
|
|
||
| #endif //MAPVIZ_PLUGINS_right_click_services_H | ||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,8 @@ | ||
| #Location | ||
|
||
| # Latitude (degrees). Positive is north of equator; negative is south. | ||
| float64 latitude | ||
| # Longitude [degrees]. Positive is east of prime meridian; negative is west. | ||
| float64 longitude | ||
| # Altitude [m]. Positive is above the WGS 84 ellipsoid | ||
| # (quiet NaN if no altitude is available). | ||
| float64 altitude | ||
Uh oh!
There was an error while loading. Please reload this page.