Skip to content

Commit

Permalink
Address review from @dirk-thomas
Browse files Browse the repository at this point in the history
  • Loading branch information
AndyZe authored and Andy Zelenak committed Apr 13, 2019
1 parent 94dba83 commit bd82bb7
Show file tree
Hide file tree
Showing 4 changed files with 6 additions and 6 deletions.
1 change: 0 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,6 @@ add_service_files(DIRECTORY srv
catkin_python_setup()

generate_messages(
DEPENDENCIES
)

catkin_package(
Expand Down
2 changes: 1 addition & 1 deletion include/rqt_image_view/image_view.h
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
7 changes: 4 additions & 3 deletions src/rqt_image_view/image_view.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down Expand Up @@ -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) );
Expand Down Expand Up @@ -673,4 +674,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: 1 addition & 1 deletion srv/SetImageTopic.srv
Original file line number Diff line number Diff line change
@@ -1,2 +1,2 @@
string image_topic
---
---

0 comments on commit bd82bb7

Please sign in to comment.