#include <gui_task_widget.hh>
|
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...
|
|
Definition at line 35 of file gui_task_widget.hh.
GUITaskWidget::GUITaskWidget |
( |
| ) |
|
GUITaskWidget::~GUITaskWidget |
( |
| ) |
|
std::string GUITaskWidget::FormatTime |
( |
unsigned int |
sec | ) |
const |
|
private |
Helper function to format time string.
- Parameters
-
- 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] | _msg | wind 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] | _msg | wind 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] | _msg | Task 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] | _msg | wind 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] | _msg | windspeed 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] | _string | String representation of windspeed info. |
void gazebo::GUITaskWidget::SetTaskInfo |
( |
QString |
_string | ) |
|
|
signal |
A signal used to set the task info line edit.
- Parameters
-
[in] | _string | String representation of task info. |
void gazebo::GUITaskWidget::SetWindDirection |
( |
QPixmap |
_pixmap | ) |
|
|
signal |
A signal used to set the wind and wamv direction.
- Parameters
-
[in] | _string | String representation of windspeed info. |
QPainter gazebo::GUITaskWidget::contactPainter |
|
private |
QPixmap gazebo::GUITaskWidget::contactPixmap |
|
private |
QPen gazebo::GUITaskWidget::pen |
|
private |
double gazebo::GUITaskWidget::wamvHeading = 0 |
|
private |
QPainter gazebo::GUITaskWidget::windPainter |
|
private |
QPixmap gazebo::GUITaskWidget::windPixmap |
|
private |
double gazebo::GUITaskWidget::windSpeed = 0 |
|
private |
The documentation for this class was generated from the following files: