Skip to content

advanced_logging example #460

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 9 additions & 0 deletions examples/advanced_logging/Cargo.toml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
[package]
name = "advanced_logging"
version = "0.1.0"
edition = "2021"

[dependencies]
rclrs = "*"
std_msgs = "*"
anyhow = { version = "1", features = ["backtrace"] }
19 changes: 19 additions & 0 deletions examples/advanced_logging/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
<?xml version="1.0"?>
<?xml-model
href="http://download.ros.org/schema/package_format3.xsd"
schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>examples_rclrs_advanced_logging</name>
<version>0.1.0</version>
<description>Package containing an advanced example of the logging mechanism in rclrs.</description>
<maintainer email="[email protected]">Antoine Van Malleghem</maintainer>
<license>Apache License 2.0</license>

<depend>rclrs</depend>
<depend>rosidl_runtime_rs</depend>
<depend>std_msgs</depend>

<export>
<build_type>ament_cargo</build_type>
</export>
</package>
40 changes: 40 additions & 0 deletions examples/advanced_logging/src/main.rs
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
use anyhow::{Error, Result};
use rclrs::*;
use std::time::Duration;

fn main() -> Result<(), Error> {
let context = Context::default_from_env()?;
let executor = context.create_basic_executor();

let node = executor.create_node("advanced_logger")?;

let publisher = node.create_publisher::<std_msgs::msg::String>("topic", QOS_PROFILE_DEFAULT)?;

let mut message = std_msgs::msg::String::default();

let mut publish_count: u32 = 1;

while context.ok() {
message.data = format!("Hello, world! {}", publish_count);
// log_fatal!(&node.name(), "Simple message from {}", node.name());
log!(
node.info().skip_first(),
"Publish every message but the first one: [{}]",
message.data
);
log!(
node.warn().throttle(Duration::from_millis(3000)),
"Publish with 3s throttling: [{}]",
message.data
);
log!(
node.error().only_if(publish_count % 10 == 0),
"Publishing every 10 messages: [{}]",
message.data
);
publisher.publish(&message)?;
publish_count += 1;
std::thread::sleep(std::time::Duration::from_millis(500));
}
Ok(())
}