/* * Copyright 2018 Amazon.com, Inc. or its affiliates. All Rights Reserved. * * Licensed under the Apache License, Version 2.0 (the "License"). * You may not use this file except in compliance with the License. * A copy of the License is located at * * http://aws.amazon.com/apache2.0 * * or in the "license" file accompanying this file. This file is distributed * on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either * express or implied. See the License for the specific language governing * permissions and limitations under the License. */ #include #include #include #include #include #include #include #include #include #include #include using namespace Aws::Client; using namespace std::chrono_literals; using namespace ros_monitoring_msgs::msg; #define DEFAULT_INTERVAL_SEC 5 #define TOPIC_BUFFER_SIZE 1000 #define INTERVAL_PARAM_NAME "interval" #define ROBOT_ID_DIMENSION "robot_id" #define CATEGORY_DIMENSION "category" #define HEALTH_CATEGORY "RobotHealth" #define DEFAULT_ROBOT_ID "Default_Robot" #define DEFAULT_NODE_NAME "health_metric_collector" #define METRICS_TOPIC_NAME "metrics" 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(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(node, METRICS_TOPIC_NAME, TOPIC_BUFFER_SIZE); mg->AddDimension(ROBOT_ID_DIMENSION, robot_id); mg->AddDimension(CATEGORY_DIMENSION, HEALTH_CATEGORY); std::vector> collectors; auto cpu_collector = std::make_shared(mg); collectors.push_back(cpu_collector); auto sys_collector = std::make_shared(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; }