in health_metric_collector/src/collector.cpp [47:88]
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
rclcpp::NodeOptions node_options;
node_options.allow_undeclared_parameters(true);
node_options.automatically_declare_parameters_from_overrides(true);
auto node = rclcpp::Node::make_shared(DEFAULT_NODE_NAME, std::string(), node_options);
auto param_reader = std::make_shared<Ros2NodeParameterReader>(node);
// get interval param
double interval = DEFAULT_INTERVAL_SEC;
param_reader->ReadParam(ParameterPath(INTERVAL_PARAM_NAME), interval);
// get robot id
std::string robot_id = DEFAULT_ROBOT_ID;
param_reader->ReadParam(ParameterPath(ROBOT_ID_DIMENSION), robot_id);
// advertise
AWS_LOG_INFO(__func__, "Starting Health Metric Collector Node...");
auto mg = std::make_shared<MetricManager>(node, METRICS_TOPIC_NAME, TOPIC_BUFFER_SIZE);
mg->AddDimension(ROBOT_ID_DIMENSION, robot_id);
mg->AddDimension(CATEGORY_DIMENSION, HEALTH_CATEGORY);
std::vector<std::shared_ptr<MetricCollectorInterface>> collectors;
auto cpu_collector = std::make_shared<CPUMetricCollector>(mg);
collectors.push_back(cpu_collector);
auto sys_collector = std::make_shared<SysInfoCollector>(mg);
collectors.push_back(sys_collector);
// start metrics collection
CollectAndPublish f(mg, collectors);
auto timer = node->create_wall_timer(1s, [&f]{f.Publish();});
rclcpp::spin(node);
AWS_LOG_INFO(__func__, "Shutting down Health Metric Collector Node...");
return 0;
}