RVIZ panel for displaying KVH sensor status. More...
#include <kvh_geo_fog_3d_status_panel.hpp>

Public Member Functions | |
| void | DiagnosticsCallback (const diagnostic_msgs::DiagnosticArray::ConstPtr &) |
| Function to receive diagnostics information and calculate statuses. More... | |
| QHBoxLayout * | StatusIndicatorFactory (bool, std::string, std::string) |
| Create mappings from our diagnostics strings to painters. More... | |
| StatusPanel (QWidget *parent=0) | |
| Constructor for our RVIZ panel. More... | |
Public Member Functions inherited from rviz::Panel | |
| virtual QString | getClassId () const |
| virtual QString | getDescription () const |
| virtual QString | getName () const |
| void | initialize (VisualizationManager *manager) |
| virtual void | load (const Config &config) |
| virtual void | onInitialize () |
| Panel (QWidget *parent=0) | |
| virtual void | save (Config config) const |
| virtual void | setClassId (const QString &class_id) |
| virtual void | setDescription (const QString &description) |
| virtual void | setName (const QString &name) |
| virtual | ~Panel () |
Protected Attributes | |
| ros::Subscriber | diag_sub_ |
| ROS subscriber for diagnostics information. More... | |
| ros::NodeHandle | nh_ |
| Our ROS nodehandle object. More... | |
| std::unordered_map< std::string, StatusPainter * > | painter_map_ |
| Holds our key/value set of diagnostics message strings to painter objects. More... | |
Protected Attributes inherited from rviz::Panel | |
| VisualizationManager * | vis_manager_ |
Additional Inherited Members | |
Signals inherited from rviz::Panel | |
| void | configChanged () |
RVIZ panel for displaying KVH sensor status.
Definition at line 50 of file kvh_geo_fog_3d_status_panel.hpp.
| kvh::StatusPanel::StatusPanel | ( | QWidget * | parent = 0 | ) |
Constructor for our RVIZ panel.
| parent | [in] Our QWidget parent to which we belong. |
Sets up our widget with layouts and titles. Also subscribes to our ROS callback for diagnostics messages.
Definition at line 57 of file kvh_geo_fog_3d_status_panel.cpp.
| void kvh::StatusPanel::DiagnosticsCallback | ( | const diagnostic_msgs::DiagnosticArray::ConstPtr & | _diagArray | ) |
Function to receive diagnostics information and calculate statuses.
| _diagArray | The diagnostics message to operate on |
Does the work of parsing out diagnostics information and filling in our map.
Definition at line 209 of file kvh_geo_fog_3d_status_panel.cpp.
| QHBoxLayout * kvh::StatusPanel::StatusIndicatorFactory | ( | bool | _enabled, |
| std::string | _label, | ||
| std::string | _map_key | ||
| ) |
Create mappings from our diagnostics strings to painters.
| _enabled | [in] If we're showing this status |
| _label | [in] The label of this status section |
| _map_key | [in] The string to use as the key into the map of painters |
Definition at line 187 of file kvh_geo_fog_3d_status_panel.cpp.
|
protected |
ROS subscriber for diagnostics information.
Definition at line 61 of file kvh_geo_fog_3d_status_panel.hpp.
|
protected |
Our ROS nodehandle object.
Definition at line 59 of file kvh_geo_fog_3d_status_panel.hpp.
|
protected |
Holds our key/value set of diagnostics message strings to painter objects.
Definition at line 60 of file kvh_geo_fog_3d_status_panel.hpp.