From bd82bb7c1b756bb150d623170c19754b42ba526b Mon Sep 17 00:00:00 2001 From: AndyZe Date: Wed, 20 Mar 2019 15:17:54 -0500 Subject: [PATCH] Address review from @dirk-thomas --- CMakeLists.txt | 1 - include/rqt_image_view/image_view.h | 2 +- src/rqt_image_view/image_view.cpp | 7 ++++--- srv/SetImageTopic.srv | 2 +- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index c40ff2e..f8d6cb3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -45,7 +45,6 @@ add_service_files(DIRECTORY srv catkin_python_setup() generate_messages( - DEPENDENCIES ) catkin_package( diff --git a/include/rqt_image_view/image_view.h b/include/rqt_image_view/image_view.h index 69d02e4..fb0075b 100644 --- a/include/rqt_image_view/image_view.h +++ b/include/rqt_image_view/image_view.h @@ -117,7 +117,7 @@ protected slots: virtual void callbackImage(const sensor_msgs::Image::ConstPtr& msg); - bool changeImageService(rqt_image_view::SetImageTopic::Request &req, + bool setImageService(rqt_image_view::SetImageTopic::Request &req, rqt_image_view::SetImageTopic::Response &res); virtual void invertPixels(int x, int y); diff --git a/src/rqt_image_view/image_view.cpp b/src/rqt_image_view/image_view.cpp index 6909ad5..27c2e01 100644 --- a/src/rqt_image_view/image_view.cpp +++ b/src/rqt_image_view/image_view.cpp @@ -115,7 +115,8 @@ 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( getNodeHandle().getNamespace() + std::to_string(context.serialNumber()) + "/change_image_topic", &ImageView::changeImageService, this); + change_topic_service_ = getNodeHandle().advertiseService( + getNodeHandle().getNamespace() + std::to_string(context.serialNumber()) + "/set_image_topic", &ImageView::setImageService, this); } void ImageView::shutdownPlugin() @@ -485,7 +486,7 @@ void ImageView::syncRotateLabel() } } -bool ImageView::changeImageService(rqt_image_view::SetImageTopic::Request &req, +bool ImageView::setImageService(rqt_image_view::SetImageTopic::Request &req, rqt_image_view::SetImageTopic::Response &res) { selectTopic( QString::fromStdString(req.image_topic) ); @@ -673,4 +674,4 @@ void ImageView::callbackImage(const sensor_msgs::Image::ConstPtr& msg) } } -PLUGINLIB_EXPORT_CLASS(rqt_image_view::ImageView, rqt_gui_cpp::Plugin) \ No newline at end of file +PLUGINLIB_EXPORT_CLASS(rqt_image_view::ImageView, rqt_gui_cpp::Plugin) diff --git a/srv/SetImageTopic.srv b/srv/SetImageTopic.srv index 0045faa..c205b1f 100644 --- a/srv/SetImageTopic.srv +++ b/srv/SetImageTopic.srv @@ -1,2 +1,2 @@ string image_topic ---- \ No newline at end of file +---