Skip to content
This repository has been archived by the owner on Jun 10, 2021. It is now read-only.

Add launch file to launch system CPU and Memory collector nodes #63

Merged
merged 4 commits into from Jan 11, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
27 changes: 27 additions & 0 deletions system_metrics_collector/CMakeLists.txt
Expand Up @@ -54,6 +54,14 @@ add_executable(main src/system_metrics_collector/main.cpp)
target_link_libraries(main system_metrics_collector)
ament_target_dependencies(main)

add_executable(linux_cpu_collector src/system_metrics_collector/linux_cpu_collector.cpp)
target_link_libraries(linux_cpu_collector system_metrics_collector)
ament_target_dependencies(linux_cpu_collector)

add_executable(linux_memory_collector src/system_metrics_collector/linux_memory_collector.cpp)
target_link_libraries(linux_memory_collector system_metrics_collector)
ament_target_dependencies(linux_memory_collector)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
find_package(ament_cmake_gtest REQUIRED)
Expand Down Expand Up @@ -114,12 +122,31 @@ if(BUILD_TESTING)
lib/${PROJECT_NAME})
endif()

# Install launch files
install(DIRECTORY
launch
DESTINATION share/${PROJECT_NAME}/
)

# Install entry points
install(TARGETS
main
DESTINATION
lib/${PROJECT_NAME}
)

install(TARGETS
linux_cpu_collector
DESTINATION
lib/${PROJECT_NAME}
)

install(TARGETS
linux_memory_collector
DESTINATION
lib/${PROJECT_NAME}
)

install(TARGETS ${PROJECT_NAME}
DESTINATION lib
)
Expand Down
35 changes: 35 additions & 0 deletions system_metrics_collector/launch/system_cpu_and_memory.launch.py
@@ -0,0 +1,35 @@
# Copyright 2020 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.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License 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.

"""Launch system CPU and system memory metrics collector nodes."""


from launch import LaunchDescription
from launch_ros.actions import Node


def generate_launch_description():
"""Run system CPU and memory collector nodes using launch."""
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

nit: I feel this is redundant given the toplevel docstring + the fact that all launch files have this function syntax. But we can keep it

ld = LaunchDescription([
Node(
package='system_metrics_collector',
node_executable='linux_cpu_collector',
output='screen'),
Node(
package='system_metrics_collector',
node_executable='linux_memory_collector',
output='screen'
),
])
return ld
@@ -0,0 +1,34 @@
// Copyright 2020 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.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License 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.

#ifndef SYSTEM_METRICS_COLLECTOR__CONSTANTS_HPP_
#define SYSTEM_METRICS_COLLECTOR__CONSTANTS_HPP_

#include <chrono>

namespace system_metrics_collector
{

namespace collector_node_constants
{

constexpr const char kStatisticsTopicName[] = "system_metrics";
constexpr const std::chrono::seconds kDefaultCollectPeriod{1};
constexpr const std::chrono::minutes kDefaultPublishPeriod{1};

} // namespace collector_node_constants

} // namespace system_metrics_collector

#endif // SYSTEM_METRICS_COLLECTOR__CONSTANTS_HPP_
@@ -0,0 +1,47 @@
// Copyright 2020 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.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License 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 <memory>

#include "rclcpp/rclcpp.hpp"
#include "rcutils/logging_macros.h"

#include "../../src/system_metrics_collector/constants.hpp"
#include "../../src/system_metrics_collector/linux_cpu_measurement_node.hpp"
piraka9011 marked this conversation as resolved.
Show resolved Hide resolved

/**
* An entry point that starts the linux system CPU metric collector node.
*/

prajakta-gokhale marked this conversation as resolved.
Show resolved Hide resolved
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);

const auto cpu_node = std::make_shared<system_metrics_collector::LinuxCpuMeasurementNode>(
"linuxCpuCollector",
system_metrics_collector::collector_node_constants::kDefaultCollectPeriod,
system_metrics_collector::collector_node_constants::kStatisticsTopicName,
system_metrics_collector::collector_node_constants::kDefaultPublishPeriod);

rclcpp::executors::MultiThreadedExecutor ex;
cpu_node->Start();

ex.add_node(cpu_node);
ex.spin();

rclcpp::shutdown();
cpu_node->Stop();
return 0;
}
@@ -0,0 +1,46 @@
// Copyright 2020 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.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License 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 <memory>

#include "rclcpp/rclcpp.hpp"
#include "rcutils/logging_macros.h"

#include "../../src/system_metrics_collector/constants.hpp"
#include "../../src/system_metrics_collector/linux_memory_measurement_node.hpp"

/**
* An entry point that starts the linux system memory metric collector node.
*/

prajakta-gokhale marked this conversation as resolved.
Show resolved Hide resolved
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);

const auto mem_node = std::make_shared<system_metrics_collector::LinuxMemoryMeasurementNode>(
"linuxMemoryCollector",
system_metrics_collector::collector_node_constants::kDefaultCollectPeriod,
system_metrics_collector::collector_node_constants::kStatisticsTopicName,
system_metrics_collector::collector_node_constants::kDefaultPublishPeriod);

rclcpp::executors::MultiThreadedExecutor ex;
mem_node->Start();

ex.add_node(mem_node);
ex.spin();

rclcpp::shutdown();
mem_node->Stop();
return 0;
}