Skip to content

Commit

Permalink
Change log level for lifecycle_publisher (#1715)
Browse files Browse the repository at this point in the history
* Change log level for lifecycle_publisher

De-activating a lifecycle publisher while the function that was invoking `publish` is still running floods the log of useless warning messages.
This requires to add a boolean check around the publish call, thus making useless the choice of a lifecycle publisher

Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com>

* change lifecycle publisher to log warning only once per transition

Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com>

* rework lifecycle publisher log mechanism to use an helper function

Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com>

* change doxygen format to use implicit brief

Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com>

Co-authored-by: Alberto Soragna <asoragna@irobot.com>
  • Loading branch information
alsora and Alberto Soragna authored Aug 19, 2021
1 parent d7764b4 commit 4fcd05d
Showing 1 changed file with 27 additions and 10 deletions.
37 changes: 27 additions & 10 deletions rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,7 @@ class LifecyclePublisher : public LifecyclePublisherInterface,
const rclcpp::PublisherOptionsWithAllocator<Alloc> & options)
: rclcpp::Publisher<MessageT, Alloc>(node_base, topic, qos, options),
enabled_(false),
should_log_(true),
logger_(rclcpp::get_logger("LifecyclePublisher"))
{
}
Expand All @@ -81,11 +82,7 @@ class LifecyclePublisher : public LifecyclePublisherInterface,
publish(std::unique_ptr<MessageT, MessageDeleter> msg)
{
if (!enabled_) {
RCLCPP_WARN(
logger_,
"Trying to publish message on the topic '%s', but the publisher is not activated",
this->get_topic_name());

log_publisher_not_enabled();
return;
}
rclcpp::Publisher<MessageT, Alloc>::publish(std::move(msg));
Expand All @@ -101,11 +98,7 @@ class LifecyclePublisher : public LifecyclePublisherInterface,
publish(const MessageT & msg)
{
if (!enabled_) {
RCLCPP_WARN(
logger_,
"Trying to publish message on the topic '%s', but the publisher is not activated",
this->get_topic_name());

log_publisher_not_enabled();
return;
}
rclcpp::Publisher<MessageT, Alloc>::publish(msg);
Expand All @@ -121,6 +114,7 @@ class LifecyclePublisher : public LifecyclePublisherInterface,
on_deactivate()
{
enabled_ = false;
should_log_ = true;
}

virtual bool
Expand All @@ -130,7 +124,30 @@ class LifecyclePublisher : public LifecyclePublisherInterface,
}

private:
/// LifecyclePublisher log helper function
/**
* Helper function that logs a message saying that publisher can't publish
* because it's not enabled.
*/
void log_publisher_not_enabled()
{
// Nothing to do if we are not meant to log
if (!should_log_) {
return;
}

// Log the message
RCLCPP_WARN(
logger_,
"Trying to publish message on the topic '%s', but the publisher is not activated",
this->get_topic_name());

// We stop logging until the flag gets enabled again
should_log_ = false;
}

bool enabled_ = false;
bool should_log_ = true;
rclcpp::Logger logger_;
};

Expand Down

0 comments on commit 4fcd05d

Please sign in to comment.