Skip to content

Commit

Permalink
(#1737) Trying to implement rhaschke's comments.
Browse files Browse the repository at this point in the history
  • Loading branch information
miguelriemoliveira committed Aug 10, 2022
1 parent 6197411 commit 0135a80
Show file tree
Hide file tree
Showing 4 changed files with 25 additions and 24 deletions.
15 changes: 8 additions & 7 deletions src/rviz/default_plugin/image_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,6 @@ ImageDisplay::ImageDisplay() : ImageDisplayBase(), texture_()

got_float_image_ = false;

mouse_click = new MouseClick();
}

void ImageDisplay::onInitialize()
Expand Down Expand Up @@ -133,7 +132,9 @@ void ImageDisplay::onInitialize()

updateNormalizeOptions();

mouse_click->onInitialize(render_panel_);

mouse_click_.reset(new MouseClick(render_panel_, update_nh_));
mouse_click_->onInitialize();
}

ImageDisplay::~ImageDisplay()
Expand All @@ -149,7 +150,7 @@ ImageDisplay::~ImageDisplay()
void ImageDisplay::onEnable()
{
ImageDisplayBase::subscribe();
mouse_click->publish();
mouse_click_->publish();

render_panel_->getRenderWindow()->setActive(true);
}
Expand All @@ -158,7 +159,7 @@ void ImageDisplay::onDisable()
{
render_panel_->getRenderWindow()->setActive(false);
ImageDisplayBase::unsubscribe();
mouse_click->unpublish();
mouse_click_->unpublish();

reset();
}
Expand Down Expand Up @@ -220,7 +221,7 @@ void ImageDisplay::update(float wall_dt, float ros_dt)

render_panel_->getRenderWindow()->update();

mouse_click->setDimensions(img_width, img_height, win_width, win_height);
mouse_click_->setDimensions(img_width, img_height, win_width, win_height);
}
catch (UnsupportedImageEncoding& e)
{
Expand Down Expand Up @@ -254,13 +255,13 @@ void ImageDisplay::processMessage(const sensor_msgs::Image::ConstPtr& msg)
void ImageDisplay::setTopic(const QString& topic, const QString& datatype)
{
ImageDisplayBase::setTopic(topic, datatype);
mouse_click->setTopic(topic);
mouse_click_->setTopic(topic);
}

void ImageDisplay::updateTopic()
{
ImageDisplayBase::updateTopic();
mouse_click->updateTopic(topic_property_->getTopic());
mouse_click_->updateTopic(topic_property_->getTopic());
}


Expand Down
2 changes: 1 addition & 1 deletion src/rviz/default_plugin/image_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ public Q_SLOTS:
IntProperty* median_buffer_size_property_;
bool got_float_image_;

MouseClick* mouse_click_;
boost::shared_ptr<MouseClick> mouse_click_;
};

} // namespace rviz
Expand Down
27 changes: 13 additions & 14 deletions src/rviz/image/mouse_click.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,31 +6,30 @@
namespace rviz
{

MouseClick::MouseClick() : QObject()
MouseClick::MouseClick(QObject* parent, const ros::NodeHandle& nh) : QObject(parent)
{
node_handle_.reset(new ros::NodeHandle());
*node_handle_ = nh;
has_dimensions_ = false;
is_topic_name_ok_ = false;
setParent(parent);
parent->installEventFilter(this);
}

MouseClick::~MouseClick()
{
}


void MouseClick::onInitialize(QObject* parent)
void MouseClick::onInitialize()
{
setParent(parent);
parent->installEventFilter(this);

has_dimensions_ = false;
is_topic_name_ok_ = false;
node_handle_.reset(new ros::NodeHandle());
}

void MouseClick::publish()
{
if (is_topic_name_ok_)
{
publisher_.reset(
new ros::Publisher(node_handle_->advertise<geometry_msgs::PointStamped>(topic_, 1000)));
new ros::Publisher(node_handle_->advertise<geometry_msgs::PointStamped>(topic_, 1)));
}
}

Expand Down Expand Up @@ -82,10 +81,10 @@ bool MouseClick::eventFilter(QObject* obj, QEvent* event)
if (pix_x >= 0 && pix_x < img_width_ && pix_y >= 0 && pix_y < img_height_)
{
geometry_msgs::PointStamped point_msg;
point_msgs.header.stamp = ros::Time::now();
point_msgs.point.x = pix_x;
point_msgs.point.y = pix_y;
publisher_->publish(point_msgs);
point_msg.header.stamp = ros::Time::now();
point_msg.point.x = pix_x;
point_msg.point.y = pix_y;
publisher_->publish(point_msg);
}
}
}
Expand Down
5 changes: 3 additions & 2 deletions src/rviz/image/mouse_click.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include "std_msgs/String.h"

#include "rviz/rviz_export.h"
#include "rviz/display.h"
#endif


Expand All @@ -33,10 +34,10 @@ namespace rviz
class RVIZ_EXPORT MouseClick : QObject
{
public:
MouseClick();
MouseClick(QObject* parent, const ros::NodeHandle& nh);
~MouseClick();

void onInitialize(QObject* parent);
void onInitialize();

/** @brief ROS topic management. */
void publish();
Expand Down

0 comments on commit 0135a80

Please sign in to comment.