16 #include <aws/core/utils/logging/LogMacros.h>    24 #include <ros_monitoring_msgs/MetricList.h>    32 #define DEFAULT_INTERVAL_SEC 5    33 #define TOPIC_BUFFER_SIZE 1000    34 #define INTERVAL_PARAM_NAME "interval"    35 #define ROBOT_ID_DIMENSION "robot_id"    36 #define CATEGORY_DIMENSION "category"    37 #define HEALTH_CATEGORY "RobotHealth"    38 #define DEFAULT_ROBOT_ID "Default_Robot"    39 #define DEFAULT_NODE_NAME "health_metric_collector"    40 #define INTERVAL_PARAM_NAME "interval"    41 #define METRICS_TOPIC_NAME "metrics"    44 int main(
int argc, 
char ** argv)
    48   auto param_reader = std::make_shared<Ros1NodeParameterReader>();
    62   AWS_LOG_INFO(__func__, 
"Starting Health Metric Collector Node...");
    67   std::vector<MetricCollectorInterface *> collectors;
    69   collectors.push_back(&cpu_collector);
    72   collectors.push_back(&sys_collector);
    80   AWS_LOG_INFO(__func__, 
"Shutting down Health Metric Collector Node...");
 #define ROBOT_ID_DIMENSION
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define DEFAULT_NODE_NAME
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const 
#define TOPIC_BUFFER_SIZE
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual void AddDimension(const std::string &name, const std::string &value) overridefinal
add global dimension (applies to all metrics). 
#define INTERVAL_PARAM_NAME
collects metrics from sysinfo. 
#define DEFAULT_INTERVAL_SEC
activates collectors and then publishes metrics. 
int main(int argc, char **argv)
Create, aggregate and publish metrics to ros topic. 
#define CATEGORY_DIMENSION
#define METRICS_TOPIC_NAME