17 #ifndef _GUI_TASK_WIDGET_HH_ 18 #define _GUI_TASK_WIDGET_HH_ 21 #include <vrx_gazebo/Task.h> 22 #include <vrx_gazebo/Contact.h> 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" 59 protected:
void OnTaskInfo(
const vrx_gazebo::Task::ConstPtr &_msg);
63 protected:
void OnWindSpeed(
const std_msgs::Float64::ConstPtr &_msg);
67 protected:
void OnWindDirection(
const std_msgs::Float64::ConstPtr &_msg);
71 protected:
void OnLinkStates(
const gazebo_msgs::LinkStates::ConstPtr &_msg);
75 protected:
void OnContact(
const vrx_gazebo::Contact::ConstPtr &_msg);
80 private: std::string
FormatTime(
unsigned int sec)
const;
83 private: std::unique_ptr<ros::NodeHandle>
node;