main.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2018 Amazon.com, Inc. or its affiliates. All Rights Reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License").
5  * You may not use this file except in compliance with the License.
6  * A copy of the License is located at
7  *
8  * http://aws.amazon.com/apache2.0
9  *
10  * or in the "license" file accompanying this file. This file is distributed
11  * on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either
12  * express or implied. See the License for the specific language governing
13  * permissions and limitations under the License.
14  */
15 
16 #include <aws/core/Aws.h>
17 #include <aws/core/utils/logging/LogMacros.h>
21 #include <ros/ros.h>
22 #include <rosgraph_msgs/Log.h>
23 #include <iostream>
24 #include <unordered_set>
25 #include <string>
26 
28 
29 constexpr char kNodeName[] = "cloudwatch_logger";
30 
31 int main(int argc, char ** argv)
32 {
33  Aws::SDKOptions options;
34  Aws::InitAPI(options);
35  Aws::Utils::Logging::InitializeAWSLogging(
36  Aws::MakeShared<Aws::Utils::Logging::AWSROSLogger>(kNodeName));
37  ros::init(argc, argv, kNodeName);
38  AWS_LOGSTREAM_INFO(__func__, "Starting " << kNodeName << "...");
39 
40  // required values
41  double publish_frequency;
42  std::string log_group;
43  std::string log_stream;
44  bool subscribe_to_rosout;
45  Aws::SDKOptions sdk_options;
47  Aws::CloudWatchLogs::CloudWatchOptions cloudwatch_options;
48 
49  ros::NodeHandle nh;
50 
51  std::shared_ptr<Aws::Client::ParameterReaderInterface> parameter_reader =
52  std::make_shared<Aws::Client::Ros1NodeParameterReader>();
53 
54  // checking configurations to set values or set to default values;
55  Aws::CloudWatchLogs::Utils::ReadPublishFrequency(parameter_reader, publish_frequency);
56  Aws::CloudWatchLogs::Utils::ReadLogGroup(parameter_reader, log_group);
57  Aws::CloudWatchLogs::Utils::ReadLogStream(parameter_reader, log_stream);
58  Aws::CloudWatchLogs::Utils::ReadSubscribeToRosout(parameter_reader, subscribe_to_rosout);
59  Aws::CloudWatchLogs::Utils::ReadMinLogVerbosity(parameter_reader, logger_options.min_log_severity);
61  Aws::CloudWatchLogs::Utils::ReadIgnoreNodesSet(parameter_reader, logger_options.ignore_nodes);
62  Aws::CloudWatchLogs::Utils::ReadCloudWatchOptions(parameter_reader, cloudwatch_options);
63 
64  // configure aws settings
65  Aws::Client::ClientConfigurationProvider client_config_provider(parameter_reader);
66  Aws::Client::ClientConfiguration config = client_config_provider.GetClientConfiguration();
67 
68  Aws::CloudWatchLogs::Utils::LogNode cloudwatch_logger(logger_options);
69  cloudwatch_logger.Initialize(log_group, log_stream, config, sdk_options, cloudwatch_options);
70 
73  &cloudwatch_logger);
74 
75  cloudwatch_logger.start();
76 
77  // callback function
78  boost::function<void(const rosgraph_msgs::Log::ConstPtr &)> callback;
79  callback = [&cloudwatch_logger](const rosgraph_msgs::Log::ConstPtr & log_msg) -> void {
80  cloudwatch_logger.RecordLogs(log_msg);
81  };
82 
83  // subscribe to additional topics, if any
84  std::vector<ros::Subscriber> subscriptions;
85  Aws::CloudWatchLogs::Utils::ReadSubscriberList(subscribe_to_rosout, parameter_reader, callback, nh, subscriptions);
86  AWS_LOGSTREAM_INFO(__func__, "Initialized " << kNodeName << ".");
87 
88  bool publish_when_size_reached = cloudwatch_options.uploader_options.batch_trigger_publish_size
90 
91  ros::Timer timer;
92  // Publish on a timer if we are not publishing on a size limit.
93  if (!publish_when_size_reached) {
94  timer =
95  nh.createTimer(ros::Duration(publish_frequency),
97  &cloudwatch_logger);
98  }
99 
100  ros::spin();
101 
102  AWS_LOGSTREAM_INFO(__func__, "Shutting down " << kNodeName << ".");
103  cloudwatch_logger.shutdown();
104  Aws::Utils::Logging::ShutdownAWSLogging();
105  ros::shutdown();
106  Aws::ShutdownAPI(options);
107 
108  return 0;
109 }
Aws::AwsError ReadIgnoreNodesSet(const std::shared_ptr< Aws::Client::ParameterReaderInterface > &parameter_reader, std::unordered_set< std::string > &ignore_nodes)
Aws::DataFlow::UploaderOptions uploader_options
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
int main(int argc, char **argv)
Definition: main.cpp:31
bool checkIfOnline(std_srvs::Trigger::Request &request, std_srvs::Trigger::Response &response)
Definition: log_node.cpp:54
Aws::AwsError ReadSubscribeToRosout(const std::shared_ptr< Aws::Client::ParameterReaderInterface > &parameter_reader, bool &subscribe_to_rosout)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Aws::AwsError ReadMinLogVerbosity(const std::shared_ptr< Aws::Client::ParameterReaderInterface > &parameter_reader, int8_t &min_log_verbosity)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
Aws::AwsError ReadPublishFrequency(const std::shared_ptr< Aws::Client::ParameterReaderInterface > &parameter_reader, double &publish_frequency)
Aws::AwsError ReadSubscriberList(bool subscribe_to_rosout, const std::shared_ptr< Aws::Client::ParameterReaderInterface > &parameter_reader, const boost::function< void(const rosgraph_msgs::Log::ConstPtr &)> &callback, ros::NodeHandle &nh, std::vector< ros::Subscriber > &subscriptions)
void TriggerLogPublisher(const ros::TimerEvent &)
Trigger the log manager to call its Service function to publish logs to cloudwatch periodically...
Definition: log_node.cpp:102
void RecordLogs(const rosgraph_msgs::Log::ConstPtr &log_msg)
Emits RecordLog using the log manager.
Definition: log_node.cpp:87
static constexpr UploaderOptions kDefaultUploaderOptions
std::unordered_set< std::string > ignore_nodes
Definition: log_node.h:47
Aws::AwsError ReadLogStream(const std::shared_ptr< Aws::Client::ParameterReaderInterface > &parameter_reader, std::string &log_stream)
Aws::AwsError ReadPublishTopicNames(const std::shared_ptr< Aws::Client::ParameterReaderInterface > &parameter_reader, bool &publish_topic_names)
ROSCPP_DECL void spin()
void Initialize(const std::string &log_group, const std::string &log_stream, const Aws::Client::ClientConfiguration &config, Aws::SDKOptions &sdk_options, const Aws::CloudWatchLogs::CloudWatchOptions &cloudwatch_options, const std::shared_ptr< LogServiceFactory > &log_service_factory=std::make_shared< LogServiceFactory >())
Reads creds, region, and SDK option to configure log manager.
Definition: log_node.cpp:46
Aws::AwsError ReadLogGroup(const std::shared_ptr< Aws::Client::ParameterReaderInterface > &parameter_reader, std::string &log_group)
ClientConfiguration GetClientConfiguration(const std::string &ros_version_override="")
void ReadCloudWatchOptions(const std::shared_ptr< Aws::Client::ParameterReaderInterface > &parameter_reader, Aws::CloudWatchLogs::CloudWatchOptions &cloudwatch_options)
ROSCPP_DECL void shutdown()
constexpr char kNodeName[]
Definition: main.cpp:29


cloudwatch_logger
Author(s): AWS RoboMaker
autogenerated on Mon Feb 28 2022 22:02:40