Signals | Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
gazebo::GUITaskWidget Class Reference

#include <gui_task_widget.hh>

Inheritance diagram for gazebo::GUITaskWidget:
Inheritance graph
[legend]

Signals

void SetContact (QPixmap _pixmap)
 A signal used to set the contact widget. More...
 
void SetTaskInfo (QString _string)
 A signal used to set the task info line edit. More...
 
void SetWindDirection (QPixmap _pixmap)
 A signal used to set the wind and wamv direction. More...
 

Public Member Functions

 GUITaskWidget ()
 Constructor. More...
 
 ~GUITaskWidget ()
 Destructor. More...
 

Protected Member Functions

void OnContact (const vrx_gazebo::Contact::ConstPtr &_msg)
 Callback that receives Contact messages. More...
 
void OnLinkStates (const gazebo_msgs::LinkStates::ConstPtr &_msg)
 Callback that receives link state messages. More...
 
void OnTaskInfo (const vrx_gazebo::Task::ConstPtr &_msg)
 Callback that received task info messages. More...
 
void OnWindDirection (const std_msgs::Float64::ConstPtr &_msg)
 Callback that received wind direction messages. More...
 
void OnWindSpeed (const std_msgs::Float64::ConstPtr &_msg)
 Callback that received wind speed messages. More...
 

Private Member Functions

std::string FormatTime (unsigned int sec) const
 Helper function to format time string. More...
 

Private Attributes

QPainter contactPainter
 painter for contact widget More...
 
QPixmap contactPixmap
 pixmap for the contact widget More...
 
ros::Subscriber contactSub
 Subscriber to contact messages. More...
 
ros::Time contactTime
 Last time contact occurred. More...
 
ros::Subscriber linkStateSub
 Subscriber to link state messages. More...
 
std::unique_ptr< ros::NodeHandlenode
 A ros NodeHandle. More...
 
QPen pen
 general use pen More...
 
ros::Subscriber taskSub
 Subscriber to Task messages. More...
 
double wamvHeading = 0
 last reported wamvHeading(yaw) More...
 
ros::Subscriber windDirectionSub
 Subscriber to wind direction messages. More...
 
QPainter windPainter
 Paiter for painting on the compass. More...
 
QPixmap windPixmap
 Pixmap for the wind and wamv direction compass. More...
 
double windSpeed = 0
 last reported windspeed More...
 
ros::Subscriber windSpeedSub
 Subscriber to wind Speed messages. More...
 

Detailed Description

Definition at line 35 of file gui_task_widget.hh.

Constructor & Destructor Documentation

GUITaskWidget::GUITaskWidget ( )

Constructor.

Definition at line 32 of file gui_task_widget.cc.

GUITaskWidget::~GUITaskWidget ( )

Destructor.

Definition at line 120 of file gui_task_widget.cc.

Member Function Documentation

std::string GUITaskWidget::FormatTime ( unsigned int  sec) const
private

Helper function to format time string.

Parameters
[in]_msgTime message.
Returns
Time formatted as a string.

Definition at line 241 of file gui_task_widget.cc.

void GUITaskWidget::OnContact ( const vrx_gazebo::Contact::ConstPtr &  _msg)
protected

Callback that receives Contact messages.

Parameters
[in]_msgwind direction info message that is received.

Definition at line 125 of file gui_task_widget.cc.

void GUITaskWidget::OnLinkStates ( const gazebo_msgs::LinkStates::ConstPtr &  _msg)
protected

Callback that receives link state messages.

Parameters
[in]_msgwind direction info message that is received.

Definition at line 145 of file gui_task_widget.cc.

void GUITaskWidget::OnTaskInfo ( const vrx_gazebo::Task::ConstPtr &  _msg)
protected

Callback that received task info messages.

Parameters
[in]_msgTask info message that is received.

Definition at line 216 of file gui_task_widget.cc.

void GUITaskWidget::OnWindDirection ( const std_msgs::Float64::ConstPtr &  _msg)
protected

Callback that received wind direction messages.

Parameters
[in]_msgwind direction info message that is received.

Definition at line 174 of file gui_task_widget.cc.

void GUITaskWidget::OnWindSpeed ( const std_msgs::Float64::ConstPtr &  _msg)
protected

Callback that received wind speed messages.

Parameters
[in]_msgwindspeed info message that is received.

Definition at line 209 of file gui_task_widget.cc.

void gazebo::GUITaskWidget::SetContact ( QPixmap  _pixmap)
signal

A signal used to set the contact widget.

Parameters
[in]_stringString representation of windspeed info.
void gazebo::GUITaskWidget::SetTaskInfo ( QString  _string)
signal

A signal used to set the task info line edit.

Parameters
[in]_stringString representation of task info.
void gazebo::GUITaskWidget::SetWindDirection ( QPixmap  _pixmap)
signal

A signal used to set the wind and wamv direction.

Parameters
[in]_stringString representation of windspeed info.

Member Data Documentation

QPainter gazebo::GUITaskWidget::contactPainter
private

painter for contact widget

Definition at line 113 of file gui_task_widget.hh.

QPixmap gazebo::GUITaskWidget::contactPixmap
private

pixmap for the contact widget

Definition at line 110 of file gui_task_widget.hh.

ros::Subscriber gazebo::GUITaskWidget::contactSub
private

Subscriber to contact messages.

Definition at line 98 of file gui_task_widget.hh.

ros::Time gazebo::GUITaskWidget::contactTime
private

Last time contact occurred.

Definition at line 101 of file gui_task_widget.hh.

ros::Subscriber gazebo::GUITaskWidget::linkStateSub
private

Subscriber to link state messages.

Definition at line 95 of file gui_task_widget.hh.

std::unique_ptr<ros::NodeHandle> gazebo::GUITaskWidget::node
private

A ros NodeHandle.

Definition at line 83 of file gui_task_widget.hh.

QPen gazebo::GUITaskWidget::pen
private

general use pen

Definition at line 116 of file gui_task_widget.hh.

ros::Subscriber gazebo::GUITaskWidget::taskSub
private

Subscriber to Task messages.

Definition at line 86 of file gui_task_widget.hh.

double gazebo::GUITaskWidget::wamvHeading = 0
private

last reported wamvHeading(yaw)

Definition at line 122 of file gui_task_widget.hh.

ros::Subscriber gazebo::GUITaskWidget::windDirectionSub
private

Subscriber to wind direction messages.

Definition at line 92 of file gui_task_widget.hh.

QPainter gazebo::GUITaskWidget::windPainter
private

Paiter for painting on the compass.

Definition at line 107 of file gui_task_widget.hh.

QPixmap gazebo::GUITaskWidget::windPixmap
private

Pixmap for the wind and wamv direction compass.

Definition at line 104 of file gui_task_widget.hh.

double gazebo::GUITaskWidget::windSpeed = 0
private

last reported windspeed

Definition at line 119 of file gui_task_widget.hh.

ros::Subscriber gazebo::GUITaskWidget::windSpeedSub
private

Subscriber to wind Speed messages.

Definition at line 89 of file gui_task_widget.hh.


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


vrx_gazebo
Author(s): Brian Bingham , Carlos Aguero
autogenerated on Thu May 7 2020 03:54:56