Quad-SDK
Loading...
Searching...
No Matches
remote_heartbeat.h
1#ifndef REMOTE_HEARTBEAT_H
2#define REMOTE_HEARTBEAT_H
3
4#include <quad_msgs/LegCommandArray.h>
5#include <quad_utils/ros_utils.h>
6#include <ros/ros.h>
7
9
13 public:
19 RemoteHeartbeat(ros::NodeHandle nh);
20
24 void spin();
25
26 private:
31 void robotHeartbeatCallback(const std_msgs::Header::ConstPtr& msg);
32
34 ros::NodeHandle nh_;
35
37 ros::Subscriber robot_heartbeat_sub_;
38
40 ros::Publisher remote_heartbeat_pub_;
41
44
47
50};
51
52#endif // REMOTE_HEARTBEAT_H
A class for implementing a remote heartbeat.
Definition remote_heartbeat.h:12
void robotHeartbeatCallback(const std_msgs::Header::ConstPtr &msg)
Callback function to handle new robot heartbeat.
Definition remote_heartbeat.cpp:26
double update_rate_
Update rate for sending and receiving data.
Definition remote_heartbeat.h:43
ros::Subscriber robot_heartbeat_sub_
Subscriber for robot heartbeat messages.
Definition remote_heartbeat.h:37
double robot_latency_threshold_warn_
Latency threshold on robot messages for warnings (s)
Definition remote_heartbeat.h:46
void spin()
Calls ros spinOnce and pubs data at set frequency.
Definition remote_heartbeat.cpp:50
double robot_latency_threshold_error_
Latency threshold on robot messages for error (s)
Definition remote_heartbeat.h:49
ros::Publisher remote_heartbeat_pub_
ROS publisher for remote heartbeat messages.
Definition remote_heartbeat.h:40
ros::NodeHandle nh_
Nodehandle to pub to and sub from.
Definition remote_heartbeat.h:34