gui_task_widget.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 #ifndef _GUI_TASK_WIDGET_HH_
18 #define _GUI_TASK_WIDGET_HH_
19 
20 #include <ros/ros.h>
21 #include <vrx_gazebo/Task.h>
22 #include <vrx_gazebo/Contact.h>
23 
24 #include <string>
25 #include <vector>
26 
27 #include <gazebo/common/Plugin.hh>
28 #include <gazebo/gui/GuiPlugin.hh>
29 #include <gazebo/transport/transport.hh>
30 #include "std_msgs/Float64.h"
31 #include "gazebo_msgs/LinkStates.h"
32 
33 namespace gazebo
34 {
35  class GUITaskWidget : public GUIPlugin
36  {
37  Q_OBJECT
38 
40  public: GUITaskWidget();
41 
43  public: ~GUITaskWidget();
44 
47  signals: void SetTaskInfo(QString _string);
48 
51  signals: void SetWindDirection(QPixmap _pixmap);
52 
55  signals: void SetContact(QPixmap _pixmap);
56 
59  protected: void OnTaskInfo(const vrx_gazebo::Task::ConstPtr &_msg);
60 
63  protected: void OnWindSpeed(const std_msgs::Float64::ConstPtr &_msg);
64 
67  protected: void OnWindDirection(const std_msgs::Float64::ConstPtr &_msg);
68 
71  protected: void OnLinkStates(const gazebo_msgs::LinkStates::ConstPtr &_msg);
72 
75  protected: void OnContact(const vrx_gazebo::Contact::ConstPtr &_msg);
76 
80  private: std::string FormatTime(unsigned int sec) const;
81 
83  private: std::unique_ptr<ros::NodeHandle> node;
84 
87 
90 
93 
96 
99 
102 
104  private: QPixmap windPixmap;
105 
107  private: QPainter windPainter;
108 
110  private: QPixmap contactPixmap;
111 
113  private: QPainter contactPainter;
114 
116  private: QPen pen;
117 
119  private: double windSpeed = 0;
120 
122  private: double wamvHeading = 0;
123  };
124 }
125 
126 #endif
QPen pen
general use pen
void OnWindSpeed(const std_msgs::Float64::ConstPtr &_msg)
Callback that received wind speed messages.
ros::Subscriber contactSub
Subscriber to contact messages.
~GUITaskWidget()
Destructor.
double windSpeed
last reported windspeed
void OnContact(const vrx_gazebo::Contact::ConstPtr &_msg)
Callback that receives Contact messages.
void OnLinkStates(const gazebo_msgs::LinkStates::ConstPtr &_msg)
Callback that receives link state messages.
ros::Subscriber taskSub
Subscriber to Task messages.
std::string FormatTime(unsigned int sec) const
Helper function to format time string.
void OnWindDirection(const std_msgs::Float64::ConstPtr &_msg)
Callback that received wind direction messages.
QPainter windPainter
Paiter for painting on the compass.
double wamvHeading
last reported wamvHeading(yaw)
void SetContact(QPixmap _pixmap)
A signal used to set the contact widget.
void SetTaskInfo(QString _string)
A signal used to set the task info line edit.
QPixmap windPixmap
Pixmap for the wind and wamv direction compass.
ros::Subscriber linkStateSub
Subscriber to link state messages.
void SetWindDirection(QPixmap _pixmap)
A signal used to set the wind and wamv direction.
ros::Subscriber windDirectionSub
Subscriber to wind direction messages.
GUITaskWidget()
Constructor.
void OnTaskInfo(const vrx_gazebo::Task::ConstPtr &_msg)
Callback that received task info messages.
QPainter contactPainter
painter for contact widget
std::unique_ptr< ros::NodeHandle > node
A ros NodeHandle.
QPixmap contactPixmap
pixmap for the contact widget
ros::Time contactTime
Last time contact occurred.
ros::Subscriber windSpeedSub
Subscriber to wind Speed messages.


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