src
ros_interface.h
Go to the documentation of this file.
1
// Provides a ROS interface for controlling rosmon
2
// Author: Max Schwarz <max.schwarz@uni-bonn.de>
3
4
#ifndef ROS_INTERFACE_H
5
#define ROS_INTERFACE_H
6
7
#include "
monitor/monitor.h
"
8
#include "
diagnostics_publisher.h
"
9
10
#include <
ros/node_handle.h
>
11
12
#include <rosmon_msgs/StartStop.h>
13
14
namespace
rosmon
15
{
16
17
class
ROSInterface
18
{
19
public
:
20
ROSInterface
(
monitor::Monitor
* monitor,
bool
enableDiagnostics=
false
,
21
const
std::string& diagnosticsPrefix={}
22
);
23
24
void
shutdown
();
25
private
:
26
void
update
();
27
bool
handleStartStop
(rosmon_msgs::StartStopRequest& req, rosmon_msgs::StartStopResponse& resp);
28
29
monitor::Monitor
*
m_monitor
;
30
31
ros::NodeHandle
m_nh
;
32
33
ros::WallTimer
m_updateTimer
;
34
35
ros::Publisher
m_pub_state
;
36
37
ros::ServiceServer
m_srv_startStop
;
38
39
bool
m_diagnosticsEnabled
;
40
std::unique_ptr<DiagnosticsPublisher>
m_diagnosticsPublisher
;
41
};
42
43
}
44
45
#endif
46
rosmon::ROSInterface::m_nh
ros::NodeHandle m_nh
Definition:
ros_interface.h:31
node_handle.h
rosmon
Definition:
diagnostics_publisher.cpp:34
ros::Publisher
monitor.h
rosmon::ROSInterface
Definition:
ros_interface.h:17
ros::WallTimer
rosmon::ROSInterface::m_srv_startStop
ros::ServiceServer m_srv_startStop
Definition:
ros_interface.h:37
rosmon::ROSInterface::ROSInterface
ROSInterface(monitor::Monitor *monitor, bool enableDiagnostics=false, const std::string &diagnosticsPrefix={})
Definition:
ros_interface.cpp:14
ros::ServiceServer
rosmon::ROSInterface::m_diagnosticsPublisher
std::unique_ptr< DiagnosticsPublisher > m_diagnosticsPublisher
Definition:
ros_interface.h:40
rosmon::monitor::Monitor
Definition:
monitor.h:24
rosmon::ROSInterface::shutdown
void shutdown()
Definition:
ros_interface.cpp:159
rosmon::ROSInterface::m_monitor
monitor::Monitor * m_monitor
Definition:
ros_interface.h:29
rosmon::ROSInterface::m_updateTimer
ros::WallTimer m_updateTimer
Definition:
ros_interface.h:33
diagnostics_publisher.h
rosmon::ROSInterface::m_pub_state
ros::Publisher m_pub_state
Definition:
ros_interface.h:35
rosmon::ROSInterface::update
void update()
Definition:
ros_interface.cpp:30
rosmon::ROSInterface::m_diagnosticsEnabled
bool m_diagnosticsEnabled
Definition:
ros_interface.h:39
ros::NodeHandle
rosmon::ROSInterface::handleStartStop
bool handleStartStop(rosmon_msgs::StartStopRequest &req, rosmon_msgs::StartStopResponse &resp)
Definition:
ros_interface.cpp:76
rosmon_core
Author(s): Max Schwarz
autogenerated on Wed Feb 21 2024 04:01:14