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

Use rclcpp::NodeOptions during node construction #73

Merged
merged 8 commits into from Jan 17, 2020
Merged
Show file tree
Hide file tree
Changes from 7 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
Expand Up @@ -24,8 +24,13 @@ namespace collector_node_constants
{

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

constexpr const char kCollectPeriodParam[] = "measurement_period";
constexpr const std::chrono::milliseconds kDefaultCollectPeriod{1000}; // 1 second

Choose a reason for hiding this comment

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

Why is this still in milliseconds when the delay is now 1 second?

Copy link
Member Author

Choose a reason for hiding this comment

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

I need to get the count() in milliseconds at some point.


constexpr const char kPublishPeriodParam[] = "publish_period";
constexpr const std::chrono::milliseconds kDefaultPublishPeriod{60000}; // 1 minute


} // namespace collector_node_constants

Expand Down
Expand Up @@ -29,11 +29,8 @@ 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);
const auto cpu_node =
std::make_shared<system_metrics_collector::LinuxCpuMeasurementNode>("linuxCpuCollector");

rclcpp::executors::MultiThreadedExecutor ex;
cpu_node->Start();
Expand Down
Expand Up @@ -38,11 +38,10 @@ namespace system_metrics_collector

LinuxCpuMeasurementNode::LinuxCpuMeasurementNode(
const std::string & name,
const std::chrono::milliseconds measurement_period,
const std::string & topic,
const std::chrono::milliseconds publish_period)
: PeriodicMeasurementNode(name, measurement_period, topic, publish_period)
{}
const rclcpp::NodeOptions & options)
: PeriodicMeasurementNode{name, options}
{
}

bool LinuxCpuMeasurementNode::SetupStart()
{
Expand Down
Expand Up @@ -34,18 +34,17 @@ class LinuxCpuMeasurementNode : public system_metrics_collector::PeriodicMeasure
{
public:
/**
* Construct a LinuxCpuMeasurementNode
* Construct a LinuxCpuMeasurementNode.
* The following parameters may be set via the rclcpp::NodeOptions:
* `measurement_period`: the period of this node, used to read measurements
* `publish_period`: the period at which metrics are published. 0 ms means don't publish
mm318 marked this conversation as resolved.
Show resolved Hide resolved
mm318 marked this conversation as resolved.
Show resolved Hide resolved
*
* @param name the name of this node
* @param measurement_period the period of this node, used to read measurements
* @param topic the topic name used for publishing
* @param publish_period the period at which metrics are published. 0 ms means don't publish
* @param options the options (arguments, parameters, etc.) for this node
*/
LinuxCpuMeasurementNode(
const std::string & name,
const std::chrono::milliseconds measurement_period,
const std::string & topic,
const std::chrono::milliseconds publish_period);
const rclcpp::NodeOptions & options = rclcpp::NodeOptions{});

virtual ~LinuxCpuMeasurementNode() = default;

Expand Down
Expand Up @@ -28,11 +28,9 @@ 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);
const auto mem_node =
std::make_shared<system_metrics_collector::LinuxMemoryMeasurementNode>(
"linuxMemoryCollector");

rclcpp::executors::MultiThreadedExecutor ex;
mem_node->Start();
Expand Down
Expand Up @@ -38,10 +38,8 @@ namespace system_metrics_collector

LinuxMemoryMeasurementNode::LinuxMemoryMeasurementNode(
const std::string & name,
const std::chrono::milliseconds measurement_period,
const std::string & topic,
const std::chrono::milliseconds publish_period)
: PeriodicMeasurementNode(name, measurement_period, topic, publish_period)
const rclcpp::NodeOptions & options)
: PeriodicMeasurementNode{name, options}
{
}

Expand Down
Expand Up @@ -32,17 +32,16 @@ class LinuxMemoryMeasurementNode : public system_metrics_collector::PeriodicMeas
public:
/**
* Construct a LinuxMemoryMeasurementNode
* The following parameters may be set via the rclcpp::NodeOptions:
* `measurement_period`: the period of this node, used to read measurements
* `publish_period`: the period at which metrics are published
*
* @param name the name of this node
* @param measurement_period the period of this node, used to read measurements
* @param topic the topic name used for publishing
* @param publish_period the period at which metrics are published. 0 ms means don't publish
* @param options the options (arguments, parameters, etc.) for this node
*/
LinuxMemoryMeasurementNode(
const std::string & name,
const std::chrono::milliseconds measurement_period,
const std::string & topic,
const std::chrono::milliseconds publish_period);
const rclcpp::NodeOptions & options = rclcpp::NodeOptions{});

virtual ~LinuxMemoryMeasurementNode() = default;

Expand Down
Expand Up @@ -41,11 +41,9 @@ namespace system_metrics_collector

LinuxProcessCpuMeasurementNode::LinuxProcessCpuMeasurementNode(
const std::string & name,
const std::chrono::milliseconds measurement_period,
const std::string & topic,
const std::chrono::milliseconds publish_period)
: PeriodicMeasurementNode(name, measurement_period, topic, publish_period),
metric_name_(std::to_string(GetPid()) + kMetricName)
const rclcpp::NodeOptions & options)
: PeriodicMeasurementNode{name, options},
metric_name_{std::to_string(GetPid()) + kMetricName}
{
}

Expand Down
Expand Up @@ -39,17 +39,16 @@ class LinuxProcessCpuMeasurementNode : public PeriodicMeasurementNode
public:
/**
* Constructs a LinuxProcessCpuMeasurementNode.
* The following parameters may be set via the rclcpp::NodeOptions:
* `measurement_period`: the period of this node, used to read measurements
* `publish_period`: the period at which metrics are published
*
* @param name the name of this node
* @param measurement_period the period of this node, used to read measurements
* @param topic the topic name used for publishing
* @param publish_period the period at which metrics are published.
* @param options the options (arguments, parameters, etc.) for this node
*/
LinuxProcessCpuMeasurementNode(
const std::string & name,
const std::chrono::milliseconds measurement_period,
const std::string & topic,
const std::chrono::milliseconds publish_period);
const rclcpp::NodeOptions & options = rclcpp::NodeOptions{});

protected:
/**
Expand Down
Expand Up @@ -52,12 +52,10 @@ namespace system_metrics_collector

LinuxProcessMemoryMeasurementNode::LinuxProcessMemoryMeasurementNode(
const std::string & name,
const std::chrono::milliseconds measurement_period,
const std::string & topic,
const std::chrono::milliseconds publish_period)
: PeriodicMeasurementNode(name, measurement_period, topic, publish_period),
pid_(std::to_string(GetPid())),
file_to_read_(kProc + std::to_string(GetPid()) + kStatm)
const rclcpp::NodeOptions & options)
: PeriodicMeasurementNode{name, options},
pid_{std::to_string(GetPid())},
file_to_read_{kProc + std::to_string(GetPid()) + kStatm}
{
}

Expand Down
Expand Up @@ -46,17 +46,16 @@ class LinuxProcessMemoryMeasurementNode : public PeriodicMeasurementNode
public:
/**
* Construct a LinuxProcessMemoryMeasurementNode
* The following parameters may be set via the rclcpp::NodeOptions:
* `measurement_period`: the period of this node, used to read measurements
* `publish_period`: the period at which metrics are published
*
* @param name the name of this node
* @param measurement_period the period of this node, used to read measurements
* @param topic the topic name used for publishing
* @param publish_period the period at which metrics are published.
* @param options the options (arguments, parameters, etc.) for this node
*/
LinuxProcessMemoryMeasurementNode(
const std::string & name,
const std::chrono::milliseconds measurement_period,
const std::string & topic,
const std::chrono::milliseconds publish_period);
const rclcpp::NodeOptions & options = rclcpp::NodeOptions{});

protected:
/**
Expand Down
32 changes: 7 additions & 25 deletions system_metrics_collector/src/system_metrics_collector/main.cpp
Expand Up @@ -27,12 +27,6 @@
#include "../../src/system_metrics_collector/linux_process_cpu_measurement_node.hpp"
#include "../../src/system_metrics_collector/linux_process_memory_measurement_node.hpp"

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

void set_node_to_debug(
const system_metrics_collector::PeriodicMeasurementNode * node,
Expand All @@ -57,31 +51,19 @@ int main(int argc, char ** argv)
rclcpp::init(argc, argv);

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

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

const auto mem_node =
std::make_shared<system_metrics_collector::LinuxMemoryMeasurementNode>("linuxMemoryCollector");

const auto process_cpu_node =
std::make_shared<system_metrics_collector::LinuxProcessCpuMeasurementNode>(
"linuxProcessCpuCollector",
kDefaultCollectPeriod,
kStatisticsTopicName,
kDefaultPublishPeriod);
"linuxProcessCpuCollector");

const auto process_mem_node =
std::make_shared<system_metrics_collector::LinuxProcessMemoryMeasurementNode>(
"linuxProcessMemoryCollector",
kDefaultCollectPeriod,
kStatisticsTopicName,
kDefaultPublishPeriod);
"linuxProcessMemoryCollector");

rclcpp::executors::MultiThreadedExecutor ex;
cpu_node->Start();
Expand Down
Expand Up @@ -16,9 +16,11 @@
#include "periodic_measurement_node.hpp"

#include <chrono>
#include <limits>
#include <stdexcept>
#include <string>

#include "constants.hpp"
#include "rclcpp/rclcpp.hpp"

using metrics_statistics_msgs::msg::MetricsMessage;
Expand All @@ -28,31 +30,36 @@ namespace system_metrics_collector

PeriodicMeasurementNode::PeriodicMeasurementNode(
const std::string & name,
const std::chrono::milliseconds measurement_period,
const std::string & publishing_topic,
const std::chrono::milliseconds publish_period)
: Node(name),
measurement_period_(measurement_period),
publishing_topic_(publishing_topic),
measurement_timer_(nullptr),
publish_timer_(nullptr),
publish_period_(publish_period)
const rclcpp::NodeOptions & options)
: Node{name, options}
{
// rclcpp::Node throws if name is empty

if (measurement_period <= std::chrono::milliseconds{0}) {
throw std::invalid_argument{"measurement_period cannot be negative"};
}
rcl_interfaces::msg::IntegerRange positive_range;
positive_range.from_value = 1;
positive_range.to_value =
std::numeric_limits<decltype(rcl_interfaces::msg::IntegerRange::to_value)>::max();
positive_range.step = 1;

if (publishing_topic.empty()) {
throw std::invalid_argument{"publishing_topic cannot be empty"};
}
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.read_only = true;
descriptor.integer_range.push_back(positive_range);
mm318 marked this conversation as resolved.
Show resolved Hide resolved

if (publish_period <= std::chrono::milliseconds{0}) {
throw std::invalid_argument{"publish_period cannot be negative"};
}
// rclcpp::Node throws if name is empty

if (publish_period <= measurement_period) {
descriptor.description = "The period in milliseconds between each measurement";
auto measurement_period = declare_parameter(
collector_node_constants::kCollectPeriodParam,
collector_node_constants::kDefaultCollectPeriod.count(),
descriptor);
measurement_period_ = std::chrono::milliseconds{measurement_period};

descriptor.description = "The period in milliseconds between each published MetricsMessage";
auto publish_period = declare_parameter(
collector_node_constants::kPublishPeriodParam,
collector_node_constants::kDefaultPublishPeriod.count(),
descriptor);
publish_period_ = std::chrono::milliseconds{publish_period};

if (publish_period_ <= measurement_period_) {
throw std::invalid_argument{
"publish_period cannot be less than or equal to the measurement_period"};
}
Expand All @@ -68,7 +75,8 @@ bool PeriodicMeasurementNode::SetupStart()
measurement_period_, [this]() {this->PerformPeriodicMeasurement();});

if (publisher_ == nullptr) {
publisher_ = create_publisher<MetricsMessage>(publishing_topic_, 10 /*history_depth*/);
publisher_ = create_publisher<MetricsMessage>(collector_node_constants::kStatisticsTopicName,
Copy link
Contributor

Choose a reason for hiding this comment

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

Oh I see what you're doing now. Why aren't we keeping the member? This PR is actually removing functionality where we could pull the publishing topic out of NodeOptions. The work required seems minimal and I don't see why we can't do it, as a read only parameter, here.

Copy link
Member Author

Choose a reason for hiding this comment

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

This PR is actually removing functionality where we could pull the publishing topic out of NodeOptions.

I was going to do that, too, but this is what @thomas-moulard suggested under on the same rationale as the node name.

Copy link
Contributor

Choose a reason for hiding this comment

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

I took @thomas-moulard 's comment to mean we don't need to set and test a custom topic name in test. I'm going to follow up with him as we've discussed allowing a user to configure the topic name.

Copy link
Member Author

@mm318 mm318 Jan 16, 2020

Choose a reason for hiding this comment

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

This was discussed in the team chatroom. Topic name will be configured via remapping (--ros-args --remap system_metrics:=custom_topic_name).

Copy link
Contributor

Choose a reason for hiding this comment

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

--ros-args --remap

Got it, found this explanation: https://index.ros.org/doc/ros2/Tutorials/Node-arguments/#example

10 /*history_depth*/);
}

RCLCPP_DEBUG(this->get_logger(), "SetupStart: creating publish_timer_");
Expand Down Expand Up @@ -104,7 +112,7 @@ std::string PeriodicMeasurementNode::GetStatusString() const
std::stringstream ss;
ss << "name=" << get_name() <<
", measurement_period=" << std::to_string(measurement_period_.count()) << "ms" <<
", publishing_topic=" << publishing_topic_ <<
", publishing_topic=" << (publisher_ ? publisher_->get_topic_name() : "") <<
", publish_period=" << std::to_string(publish_period_.count()) + "ms" <<
", " << Collector::GetStatusString();
return ss.str();
Expand Down
Expand Up @@ -38,19 +38,15 @@ class PeriodicMeasurementNode : public system_metrics_collector::Collector,
public:
/**
* Construct a PeriodicMeasurementNode.
* The following parameters may be set via the rclcpp::NodeOptions:
* `measurement_period`: the period of this node, used to read measurements
* `publish_period`: the period at which metrics are published
*
* @param name the name of this node. This must be non-empty.
* @param topic the topic for publishing data. This must be non-empty.
* @param measurement_period. This must be non-negative and strictly less than publish_period.
* @param publish_period the window of active measurements. This must be non-negative and
* strictly greater than measurement_period.
* @param options the options (arguments, parameters, etc.) for this node
* @throws std::invalid_argument for any invalid input
*/
PeriodicMeasurementNode(
const std::string & name,
const std::chrono::milliseconds measurement_period,
const std::string & publishing_topic, // todo @dbbonnie think about a default topic
const std::chrono::milliseconds publish_period);
PeriodicMeasurementNode(const std::string & name, const rclcpp::NodeOptions & options);
Copy link
Contributor

Choose a reason for hiding this comment

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

Doc string update

Copy link
Member Author

Choose a reason for hiding this comment

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

Done.


virtual ~PeriodicMeasurementNode() = default;

Expand Down Expand Up @@ -105,18 +101,14 @@ class PeriodicMeasurementNode : public system_metrics_collector::Collector,
*/
void PublishStatisticMessage() override;

/**
* Topic used for publishing
*/
const std::string publishing_topic_;
/**
* The period used to take a single measurement
*/
const std::chrono::milliseconds measurement_period_;
std::chrono::milliseconds measurement_period_;
/**
* The period used to publish measurement data
*/
const std::chrono::milliseconds publish_period_;
std::chrono::milliseconds publish_period_;
Copy link
Contributor

Choose a reason for hiding this comment

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

Is this used anymore?

Copy link
Member Author

Choose a reason for hiding this comment

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

The value is coming from the parameters and stored here. Is your idea that the parameters values should be read at Start() and not stored, so that each Stop()->Start() cycle might have updated/different parameter values?

Copy link
Contributor

Choose a reason for hiding this comment

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

Sorry, this is the wrong line. I meant for line 107 (std::string publishing_topic_;). Mainly because there is a change with the status string that does not used publishing_topic_.

Copy link
Member Author

Choose a reason for hiding this comment

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

Okay, I removed the publishing_topic_ member variable.


rclcpp::TimerBase::SharedPtr measurement_timer_;
rclcpp::TimerBase::SharedPtr publish_timer_;
Expand Down