Skip to content

Commit

Permalink
Adding a service to set the image topic.
Browse files Browse the repository at this point in the history
  • Loading branch information
AndyZe committed Oct 9, 2018
1 parent 6d514fe commit 2f8d391
Show file tree
Hide file tree
Showing 5 changed files with 48 additions and 20 deletions.
20 changes: 16 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 2.8.3)

project(rqt_image_view)
# Load catkin and all dependencies required for this package
find_package(catkin REQUIRED COMPONENTS rqt_gui rqt_gui_cpp image_transport sensor_msgs geometry_msgs cv_bridge)
find_package(catkin REQUIRED COMPONENTS cv_bridge rqt_gui rqt_gui_cpp geometry_msgs image_transport message_generation sensor_msgs)

if("${qt_gui_cpp_USE_QT_MAJOR_VERSION} " STREQUAL "5 ")
find_package(Qt5Widgets REQUIRED)
Expand Down Expand Up @@ -33,12 +33,22 @@ if(NOT EXISTS "${CATKIN_DEVEL_PREFIX}/${CATKIN_GLOBAL_INCLUDE_DESTINATION}")
file(MAKE_DIRECTORY "${CATKIN_DEVEL_PREFIX}/${CATKIN_GLOBAL_INCLUDE_DESTINATION}")
endif()

add_service_files(DIRECTORY srv
FILES
SetImageTopic.srv
)

catkin_python_setup()

generate_messages(
DEPENDENCIES
)

catkin_package(
INCLUDE_DIRS ${rqt_image_view_INCLUDE_DIRECTORIES}
LIBRARIES ${PROJECT_NAME}
CATKIN_DEPENDS rqt_gui rqt_gui_cpp image_transport sensor_msgs cv_bridge geometry_msgs
CATKIN_DEPENDS rqt_gui rqt_gui_cpp image_transport sensor_msgs cv_bridge geometry_msgs message_runtime
)
catkin_python_setup()

if("${qt_gui_cpp_USE_QT_MAJOR_VERSION} " STREQUAL "5 ")
qt5_wrap_cpp(rqt_image_view_MOCS ${rqt_image_view_HDRS})
Expand Down Expand Up @@ -67,6 +77,8 @@ endif()
find_package(class_loader)
class_loader_hide_library_symbols(${PROJECT_NAME})

add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS})

install(FILES plugin.xml
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
Expand All @@ -83,4 +95,4 @@ catkin_install_python(PROGRAMS scripts/rqt_image_view

install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
)
)
8 changes: 7 additions & 1 deletion include/rqt_image_view/image_view.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,11 +37,12 @@

#include <ui_image_view.h>

#include <geometry_msgs/Point.h>
#include <image_transport/image_transport.h>
#include <ros/package.h>
#include <ros/macros.h>
#include "rqt_image_view/SetImageTopic.h"
#include <sensor_msgs/Image.h>
#include <geometry_msgs/Point.h>

#include <opencv2/core/core.hpp>

Expand Down Expand Up @@ -114,6 +115,9 @@ protected slots:

virtual void callbackImage(const sensor_msgs::Image::ConstPtr& msg);

bool changeImageService(rqt_image_view::SetImageTopic::Request &req,
rqt_image_view::SetImageTopic::Response &res);

virtual void invertPixels(int x, int y);

QList<int> getGridIndices(int size) const;
Expand Down Expand Up @@ -151,6 +155,8 @@ protected slots:
int num_gridlines_;

RotateState rotate_state_;

ros::ServiceServer change_topic_service_;
};

}
Expand Down
24 changes: 10 additions & 14 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<package>
<package format="2">
<name>rqt_image_view</name>
<version>0.4.13</version>
<description>rqt_image_view provides a GUI plugin for displaying images using image_transport.</description>
Expand All @@ -15,19 +15,15 @@

<buildtool_depend>catkin</buildtool_depend>

<build_depend>cv_bridge</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>image_transport</build_depend>
<build_depend>qtbase5-dev</build_depend>
<build_depend>rqt_gui</build_depend>
<build_depend>rqt_gui_cpp</build_depend>
<build_depend>sensor_msgs</build_depend>
<run_depend>cv_bridge</run_depend>
<run_depend>geometry_msgs</run_depend>
<run_depend>image_transport</run_depend>
<run_depend>rqt_gui</run_depend>
<run_depend>rqt_gui_cpp</run_depend>
<run_depend>sensor_msgs</run_depend>
<depend>cv_bridge</depend>
<depend>geometry_msgs</depend>
<depend>image_transport</depend>
<depend>message_generation</depend>
<depend>qtbase5-dev</depend>
<depend>rqt_gui</depend>
<depend>rqt_gui_cpp</depend>
<depend>sensor_msgs</depend>
<depend>message_runtime</depend>

<export>
<rqt_gui plugin="${prefix}/plugin.xml"/>
Expand Down
14 changes: 13 additions & 1 deletion src/rqt_image_view/image_view.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,12 +112,15 @@ void ImageView::initPlugin(qt_gui_cpp::PluginContext& context)
hide_toolbar_action_->setCheckable(true);
ui_.image_frame->addAction(hide_toolbar_action_);
connect(hide_toolbar_action_, SIGNAL(toggled(bool)), this, SLOT(onHideToolbarChanged(bool)));

change_topic_service_ = getNodeHandle().advertiseService("/rqt_image_view/change_image_topic", &ImageView::changeImageService, this);
}

void ImageView::shutdownPlugin()
{
subscriber_.shutdown();
pub_mouse_left_.shutdown();
change_topic_service_.shutdown();
}

void ImageView::saveSettings(qt_gui_cpp::Settings& plugin_settings, qt_gui_cpp::Settings& instance_settings) const
Expand Down Expand Up @@ -455,6 +458,15 @@ void ImageView::syncRotateLabel()
}
}

bool ImageView::changeImageService(rqt_image_view::SetImageTopic::Request &req,
rqt_image_view::SetImageTopic::Response &res)
{
selectTopic( QString::fromStdString(req.image_topic) );
updateTopicList();

return true;
}

void ImageView::invertPixels(int x, int y)
{
// Could do 255-conversion_mat_.at<cv::Vec3b>(cv::Point(x,y))[i], but that doesn't work well on gray
Expand Down Expand Up @@ -625,4 +637,4 @@ void ImageView::callbackImage(const sensor_msgs::Image::ConstPtr& msg)
}
}

PLUGINLIB_EXPORT_CLASS(rqt_image_view::ImageView, rqt_gui_cpp::Plugin)
PLUGINLIB_EXPORT_CLASS(rqt_image_view::ImageView, rqt_gui_cpp::Plugin)
2 changes: 2 additions & 0 deletions srv/SetImageTopic.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
string image_topic
---

0 comments on commit 2f8d391

Please sign in to comment.