A class for implementing a remote heartbeat.
More...
#include <remote_heartbeat.h>
|
void | robotHeartbeatCallback (const std_msgs::Header::ConstPtr &msg) |
| Callback function to handle new robot heartbeat.
|
|
|
ros::NodeHandle | nh_ |
| Nodehandle to pub to and sub from.
|
|
ros::Subscriber | robot_heartbeat_sub_ |
| Subscriber for robot heartbeat messages.
|
|
ros::Publisher | remote_heartbeat_pub_ |
| ROS publisher for remote heartbeat messages.
|
|
double | update_rate_ |
| Update rate for sending and receiving data.
|
|
double | robot_latency_threshold_warn_ |
| Latency threshold on robot messages for warnings (s)
|
|
double | robot_latency_threshold_error_ |
| Latency threshold on robot messages for error (s)
|
|
A class for implementing a remote heartbeat.
RemoteHeartbeat publishes stamped messages at a fixed rate as a heartbeat
◆ RemoteHeartbeat()
RemoteHeartbeat::RemoteHeartbeat |
( |
ros::NodeHandle |
nh | ) |
|
Constructor for RemoteHeartbeat Class.
- Parameters
-
[in] | nh | ROS NodeHandle to publish and subscribe from |
- Returns
- Constructed object of type RemoteHeartbeat
◆ robotHeartbeatCallback()
void RemoteHeartbeat::robotHeartbeatCallback |
( |
const std_msgs::Header::ConstPtr & |
msg | ) |
|
|
private |
Callback function to handle new robot heartbeat.
- Parameters
-
[in] | msg | header containing robot heartbeat |
The documentation for this class was generated from the following files: