Git Product home page Git Product logo

Comments (14)

tylerjw avatar tylerjw commented on August 20, 2024 1

Thank you for looking into that warning message. I'm also confused by it, and it seems to have gone away with my latest changes based on the pattern above. I was probably doing something wrong before and creating multiple nodes with the same name somehow.

These changes led me to find another fun issue: ros2/rcutils#434

from rclcpp.

jrutgeer avatar jrutgeer commented on August 20, 2024

What about this:

void some_unrelated_function()
{
  RCLCPP_INFO(rclcpp::get_logger("node_name"), "Dut Node log"); // --> goes to /rosout
  RCLCPP_INFO(rclcpp::get_logger("node_name").get_child("some_child"), "Child log"); // --> goes to /rosout
}



int main(int argc, char** argv)
{
  rclcpp::init(argc, argv);
  rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("node_name");
 
  some_unrelated_function();

}

As long as the node named "node_name" exists, its logger can be accessed anywhere through its name.

from rclcpp.

tylerjw avatar tylerjw commented on August 20, 2024

@jrutgeer the problem with that approach is I have many functions and types in the MoveIt libraries that are used in many different nodes, including ones that do not exist in the MoveIt repo itself.

from rclcpp.

jrutgeer avatar jrutgeer commented on August 20, 2024

@tylerjw

What I mean is the following:

The mapping between logger names and /rosout publishers is stored in one hashmap per process.

This means that if there are two nodes, named A and B, and node B has following code:

RCLCPP_INFO(rclcpp::get_logger("A"), "Some log message");

Then this will also be published through the /rosout publisher of node A, even though you are in node B.

And you don't have to be inside a node. Any function (e.g. not at all related to a node) can call

RCLCPP_INFO(rclcpp::get_logger("A"), "Some log message");

And this will still output to /rosout using the publisher of node A.

I think the only thing that is necessary is that:

  • rclcpp::init() is called,
  • Some node with a known name is present in that process for as long as you are publishing.

from rclcpp.

tylerjw avatar tylerjw commented on August 20, 2024

Similar to what you are suggesting, I considered creating a node with the name moveit_{random number} in each process. Then each namespace (child logger) would be based on this. The problem is then I loose the information of which process the log came from in the rosout topic.

To continue your example let me rename A and B to moveit_34 and move_group for a more concrete example.

The move_group node creates a RobotTrajectory type, which uses my get_logger function to create a child logger named moveit_34.robot_trajectory.

Separately I have another process with another node moveit_task_constructor that also creates a RobotTrajectory which then calls my logger function and that creates moveit_12 and moveit_12.robot_trajectory loggers.

When reading the logs I now know I have two different processes logging from within robot_trajectory but I do not know which one is which. This also presents new challenges around creating tooling that will call set_logger_level for specific sub-loggers to configure them to be at different log levels. I don't know before running the process what the root log node name will be because it has a random number associated with it to avoid collisions. And after I've started the process I'm unsure how I would figure out from what process came what node names so I can associate the generic moveit node with the named one.

Am I misunderstanding what you are suggesting I should do?

from rclcpp.

jrutgeer avatar jrutgeer commented on August 20, 2024

What if you'd:

  • Give the root node in each process always the same default name (e.g. "moveit_rosout"),
  • The first process uses:
    get_logger("moveit_rosout").get_child("move_group").get_child("RobotTrajectory")
  • The second process uses:
    get_logger("moveit_rosout").get_child("moveit_task_constructor").get_child("RobotTrajectory")

EDIT: you will indeed not be able to set the loglevel through a service if they all have the same name.

from rclcpp.

tylerjw avatar tylerjw commented on August 20, 2024

EDIT: you will indeed not be able to set the loglevel through a service if they all have the same name.

I hadn't thought of that but I do think I need a unique root node name for the service to work. I also need to spin whatever node starts with the service for setting log levels. I'm not sure if you can set log levels for loggers under a different root name in a process.

from rclcpp.

tylerjw avatar tylerjw commented on August 20, 2024

Here is my prototype of your pattern. It does publish to /rosout (most of the time, I don't think it consistently flushes publish events, If I add a sleep at the end it always works):

#include <string>
#include <memory>
#include <thread>
#include <unordered_map>
#include <rclcpp/rclcpp.hpp>
#include <fmt/format.h>
#include <rsl/random.hpp>

rclcpp::Logger& get_root_logger() {
  static auto moveit_node = std::make_shared<rclcpp::Node>(fmt::format("____moveit_{}", rsl::rng()()));
  static auto logger = moveit_node->get_logger();
  return logger;
}

void set_node_logger_name(std::string const& name) {
  static auto node = std::make_shared<rclcpp::Node>(fmt::format("{}_rosout", name));
  get_root_logger() = node->get_logger();
}

rclcpp::Logger get_logger(std::string const& name) {
  return get_root_logger().get_child(name);
}

int main(int argc, char** argv)
{
  rclcpp::init(argc, argv);
  rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("dut_node");
  set_node_logger_name(node->get_name());

  RCLCPP_ERROR(get_logger("child1"), "A");
  RCLCPP_ERROR(get_logger("child2"), "A");
  RCLCPP_ERROR(get_logger("child3"), "A");
  RCLCPP_ERROR(get_logger("child4"), "A");

  RCLCPP_ERROR(get_logger("child1"), "B");
  RCLCPP_ERROR(get_logger("child2"), "B");
  RCLCPP_ERROR(get_logger("child3"), "B");
  RCLCPP_ERROR(get_logger("child4"), "B");

  std::this_thread::sleep_for(std::chrono::seconds(1));
}

The idea here is that the function that returns the reference would be hidden in one translation unit for my logger utility.

from rclcpp.

jrutgeer avatar jrutgeer commented on August 20, 2024

Wrt. the code:

  • What is the "dut_node" for?
  • Other than that: looks good to me.

Wrt: the loglevel service:

  • Similar to the /rosout hashmap, there is one loglevel hashmap per process (linking names to loglevels). So if you know the name of one node per process (that provides the set_loglevel_service), then you can set loglevels for all loggers in that process (by their name) through that node's service.

  • Do realize that this is, as of yet, still an open issue. I am not so fond of using the set_loglevel_service because of that. It can lead to sporadic crashes.

from rclcpp.

tylerjw avatar tylerjw commented on August 20, 2024

Do realize that ros2/ros2#1355 (comment) is, as of yet, still an open issue. I am not so fond of using the set_loglevel_service because of that. It can lead to sporadic crashes.

I did not realize this. I was intending to try to re-create the file-based configuration of log levels we had in ROS 1. Is there any other ways you know of setting the log level per namespace except through the service?

from rclcpp.

tylerjw avatar tylerjw commented on August 20, 2024

What is the "dut_node" for?

dut stands for device under test. I have a python integration launch test that runs this and observes /rosout using rclpy.

from rclcpp.

tylerjw avatar tylerjw commented on August 20, 2024

To be clear, the reason the above prototype works is the node used for publishing has static lifetime.

from rclcpp.

tylerjw avatar tylerjw commented on August 20, 2024

I noticed on more thing. Each process creating a moveit node is going to cause a bunch of warnings about name collisions. To fix that, I updated the prototype to do something slightly different. I am now creating the node in the set_node_logger_name function.

I am also creating a node I expect to be a throw away and never used in the get_root_logger function in case someone tries to call get_logger function without calling set_node_logger_name as calls to get_child on a non-node logger greets the user with an exception.

from rclcpp.

jrutgeer avatar jrutgeer commented on August 20, 2024

Each process creating a moveit node is going to cause a bunch of warnings about name collisions.

Are you referring to this warning message?

If so, I don't understand it:

That code is in rcl_logging_rosout_init_publisher_for_node(), which afaik is called only from the node_base constructor.
Even in your original code, shared_ptr to the node is static so it should be initialized only once?

So why would you get that warning, and why does it make a difference if the node is instantiated in get_root_logger() vs set_node_logger_name()?


Is there any other ways you know of setting the log level per namespace except through the service?

As command line arguments, e.g.:

ros2 run package node --ros-args --log-level DEBUG --log-level rcl:=INFO 

from rclcpp.

Related Issues (20)

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.