Public Member Functions | Private Member Functions | Private Attributes | List of all members
rviz::MouseClick Class Reference

Class for capturing mouse clicks. More...

#include <mouse_click.h>

Inheritance diagram for rviz::MouseClick:
Inheritance graph
[legend]

Public Member Functions

void disable ()
 
void enable ()
 
 MouseClick (QWidget *widget, const ros::NodeHandle &nh)
 
void setDimensions (int img_width, int img_height, int win_width, int win_height)
 
void setImageTopic (const QString &topic)
 

Private Member Functions

virtual bool eventFilter (QObject *obj, QEvent *event)
 

Private Attributes

int img_height_
 
int img_width_
 
ros::NodeHandle node_handle_
 
ros::Publisher publisher_
 
std::string topic_
 
bool topic_name_ok_
 
int win_height_
 
int win_width_
 

Detailed Description

Class for capturing mouse clicks.

This class handles mouse clicking functionalities integrated into the ImageDisplay. It uses a qt event filter to capture mouse clicks, handles image resizing and checks if the click was inside or outside the image. It also scales the pixel coordinates to get them w.r.t. the image (not the window) size. Mouse clicks image pixel coordinates are published as ros geometry_msgs PointStamped. The z component is ignored. The topic name where the mouse clicks are published is defined created after the subscribed image topic as: <image_topic>/mouse_click.

Definition at line 34 of file mouse_click.h.

Constructor & Destructor Documentation

◆ MouseClick()

rviz::MouseClick::MouseClick ( QWidget *  widget,
const ros::NodeHandle nh 
)

Definition at line 8 of file mouse_click.cpp.

Member Function Documentation

◆ disable()

void rviz::MouseClick::disable ( )

Definition at line 24 of file mouse_click.cpp.

◆ enable()

void rviz::MouseClick::enable ( )

Definition at line 15 of file mouse_click.cpp.

◆ eventFilter()

bool rviz::MouseClick::eventFilter ( QObject *  obj,
QEvent *  event 
)
privatevirtual

Definition at line 30 of file mouse_click.cpp.

◆ setDimensions()

void rviz::MouseClick::setDimensions ( int  img_width,
int  img_height,
int  win_width,
int  win_height 
)

Definition at line 76 of file mouse_click.cpp.

◆ setImageTopic()

void rviz::MouseClick::setImageTopic ( const QString &  topic)

Definition at line 84 of file mouse_click.cpp.

Member Data Documentation

◆ img_height_

int rviz::MouseClick::img_height_
private

Definition at line 48 of file mouse_click.h.

◆ img_width_

int rviz::MouseClick::img_width_
private

Definition at line 48 of file mouse_click.h.

◆ node_handle_

ros::NodeHandle rviz::MouseClick::node_handle_
private

Definition at line 49 of file mouse_click.h.

◆ publisher_

ros::Publisher rviz::MouseClick::publisher_
private

Definition at line 50 of file mouse_click.h.

◆ topic_

std::string rviz::MouseClick::topic_
private

Definition at line 51 of file mouse_click.h.

◆ topic_name_ok_

bool rviz::MouseClick::topic_name_ok_
private

Definition at line 52 of file mouse_click.h.

◆ win_height_

int rviz::MouseClick::win_height_
private

Definition at line 48 of file mouse_click.h.

◆ win_width_

int rviz::MouseClick::win_width_
private

Definition at line 48 of file mouse_click.h.


The documentation for this class was generated from the following files:


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Thu May 16 2024 02:30:50