diff --git a/Cargo.toml b/Cargo.toml index aac37d3..a6632ff 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -5,7 +5,7 @@ version = "0.5.3" authors = ["Martin Dahl "] description = "Easy to use, runtime-agnostic, async rust bindings for ROS2." license = "MIT OR Apache-2.0" -edition = "2018" +edition = "2021" readme = "README.md" homepage = "https://github.com/sequenceplanner/r2r" repository = "https://github.com/sequenceplanner/r2r" @@ -15,22 +15,22 @@ documentation = "https://sequenceplanner.github.io/r2r/" doctest = false [dependencies] -serde = { version = "1.0.123", features = ["derive"] } -serde_json = "1.0.62" -thiserror = "1.0" +serde = { version = "1.0.133", features = ["derive"] } +serde_json = "1.0.74" +thiserror = "1.0.30" lazy_static = "1.4.0" r2r_common = { path = "r2r_common", version = "0.2.0" } r2r_rcl = { path = "r2r_rcl", version = "0.2.0" } r2r_msg_gen = { path = "r2r_msg_gen", version = "0.2.1" } r2r_actions = { path = "r2r_actions", version = "0.2.0" } -uuid = { version = "0.8", features = ["serde", "v4"] } -retain_mut = "0.1.3" -futures = "0.3.15" +uuid = { version = "0.8.2", features = ["serde", "v4"] } +retain_mut = "0.1.5" +futures = "0.3.19" [dev-dependencies] -serde_json = "1.0.62" -futures = "0.3.15" -tokio = { version = "1", features = ["full"] } +serde_json = "1.0.74" +futures = "0.3.19" +tokio = { version = "1.15.0", features = ["full"] } rand = "0.8.4" [build-dependencies] diff --git a/examples/publishers.rs b/examples/publishers.rs index 0803a47..1af8540 100644 --- a/examples/publishers.rs +++ b/examples/publishers.rs @@ -1,12 +1,13 @@ use r2r::builtin_interfaces::msg::Duration; use r2r::std_msgs::msg::Int32; use r2r::trajectory_msgs::msg::*; +use r2r::QosProfile; fn main() -> Result<(), Box> { let ctx = r2r::Context::create()?; let mut node = r2r::Node::create(ctx, "testnode", "")?; - let publisher = node.create_publisher::("/jtp")?; - let publisher2 = node.create_publisher::("/native_count")?; + let publisher = node.create_publisher::("/jtp", QosProfile::default())?; + let publisher2 = node.create_publisher::("/native_count", QosProfile::default())?; // run for 10 seconds let mut count = 0; diff --git a/examples/rostopic_echo.rs b/examples/rostopic_echo.rs index ae73d89..a57039b 100644 --- a/examples/rostopic_echo.rs +++ b/examples/rostopic_echo.rs @@ -2,6 +2,7 @@ use futures::executor::LocalPool; use futures::future; use futures::stream::StreamExt; use futures::task::LocalSpawnExt; +use r2r::QosProfile; use std::collections::HashMap; use std::env; @@ -42,9 +43,9 @@ fn main() -> Result<(), Box> { // create echo topic let echo = &format!("{}_echo", topic); - let echo_pub = node.create_publisher_untyped(echo, type_name)?; + let echo_pub = node.create_publisher_untyped(echo, type_name, QosProfile::default())?; - let sub = node.subscribe_untyped(topic, type_name)?; + let sub = node.subscribe_untyped(topic, type_name, QosProfile::default())?; spawner.spawn_local(async move { sub.for_each(|msg| { match msg { diff --git a/examples/subscriber.rs b/examples/subscriber.rs index a186996..cab2109 100644 --- a/examples/subscriber.rs +++ b/examples/subscriber.rs @@ -2,12 +2,14 @@ use futures::executor::LocalPool; use futures::future; use futures::stream::StreamExt; use futures::task::LocalSpawnExt; +use r2r::QosProfile; fn main() -> Result<(), Box> { let ctx = r2r::Context::create()?; let mut node = r2r::Node::create(ctx, "testnode", "")?; - let mut sub = node.subscribe::("/topic")?; - let p = node.create_publisher::("/topic2")?; + let mut sub = node.subscribe::("/topic", QosProfile::default())?; + let p = + node.create_publisher::("/topic2", QosProfile::default())?; let mut pool = LocalPool::new(); let spawner = pool.spawner(); @@ -32,7 +34,7 @@ fn main() -> Result<(), Box> { })?; // for sub2 we just print the data - let sub2 = node.subscribe_untyped("/topic2", "std_msgs/msg/String")?; + let sub2 = node.subscribe_untyped("/topic2", "std_msgs/msg/String", QosProfile::default())?; spawner.spawn_local(async move { sub2.for_each(|msg| { println!("topic2: new msg: {}", msg.expect("deserialization error")); diff --git a/examples/tokio.rs b/examples/tokio.rs index b9cf5e7..80a2923 100644 --- a/examples/tokio.rs +++ b/examples/tokio.rs @@ -1,5 +1,6 @@ use futures::future; use futures::stream::StreamExt; +use r2r::QosProfile; use std::sync::{Arc, Mutex}; use tokio::task; @@ -13,8 +14,9 @@ struct SharedState { async fn main() -> Result<(), Box> { let ctx = r2r::Context::create()?; let mut node = r2r::Node::create(ctx, "testnode", "")?; - let mut sub = node.subscribe::("/topic")?; - let p = node.create_publisher::("/topic2")?; + let mut sub = node.subscribe::("/topic", QosProfile::default())?; + let p = + node.create_publisher::("/topic2", QosProfile::default())?; let state = Arc::new(Mutex::new(SharedState::default())); // task that every other time forwards message to topic2 @@ -41,7 +43,7 @@ async fn main() -> Result<(), Box> { }); // for sub2 we just print the data - let sub2 = node.subscribe::("/topic2")?; + let sub2 = node.subscribe::("/topic2", QosProfile::default())?; task::spawn(async move { sub2.for_each(|msg| { println!("topic2: new msg: {}", msg.data); diff --git a/examples/tokio_examples.rs b/examples/tokio_examples.rs index 9b1b8a8..9ed84f9 100644 --- a/examples/tokio_examples.rs +++ b/examples/tokio_examples.rs @@ -3,6 +3,7 @@ use std::sync::{Arc, Mutex}; use futures::future; use futures::stream::StreamExt; +use r2r::QosProfile; use tokio::task; #[tokio::main] @@ -42,7 +43,7 @@ async fn subscriber(arc_node: Arc>) -> Result<(), r2r::Error> { let sub = arc_node .lock() .unwrap() - .subscribe::("/topic")?; + .subscribe::("/topic", QosProfile::default())?; sub.for_each(|msg| { println!("topic: new msg: {}", msg.data); future::ready(()) @@ -56,7 +57,8 @@ async fn publisher(arc_node: Arc>) -> Result<(), r2r::Error> { // Limiting the scope when locking the arc let mut node = arc_node.lock().unwrap(); let timer = node.create_wall_timer(std::time::Duration::from_secs(2))?; - let publisher = node.create_publisher::("/topic")?; + let publisher = + node.create_publisher::("/topic", QosProfile::default())?; (timer, publisher) }; for _ in 1..10 { diff --git a/examples/tokio_publisher.rs b/examples/tokio_publisher.rs index ea4171c..0d67032 100644 --- a/examples/tokio_publisher.rs +++ b/examples/tokio_publisher.rs @@ -1,3 +1,5 @@ +use r2r::QosProfile; + #[tokio::main] async fn main() -> Result<(), Box> { let ctx = r2r::Context::create()?; @@ -5,7 +7,8 @@ async fn main() -> Result<(), Box> { let duration = std::time::Duration::from_millis(2500); let mut timer = node.create_wall_timer(duration)?; - let publisher = node.create_publisher::("/topic")?; + let publisher = + node.create_publisher::("/topic", QosProfile::default())?; let handle = tokio::task::spawn_blocking(move || loop { node.spin_once(std::time::Duration::from_millis(100)); diff --git a/r2r_actions/Cargo.toml b/r2r_actions/Cargo.toml index ab458dd..7229ae7 100644 --- a/r2r_actions/Cargo.toml +++ b/r2r_actions/Cargo.toml @@ -4,7 +4,7 @@ version = "0.2.0" authors = ["Martin Dahl "] description = "Internal dependency to the r2r crate." license = "MIT OR Apache-2.0" -edition = "2018" +edition = "2021" readme = "README.md" homepage = "https://github.com/sequenceplanner/r2r" repository = "https://github.com/sequenceplanner/r2r" @@ -15,6 +15,6 @@ r2r_rcl = { path = "../r2r_rcl", version = "0.2.0" } r2r_msg_gen = { path = "../r2r_msg_gen", version = "0.2.0" } [build-dependencies] -bindgen = "0.57.0" -itertools = "0.10.0" +bindgen = "0.59.2" +itertools = "0.10.3" r2r_common = { path = "../r2r_common", version = "0.2.0" } diff --git a/r2r_actions/build.rs b/r2r_actions/build.rs index 5057865..2acc46f 100644 --- a/r2r_actions/build.rs +++ b/r2r_actions/build.rs @@ -1,4 +1,4 @@ -use bindgen; + use itertools::Itertools; use std::env; use std::path::{Path, PathBuf}; @@ -12,10 +12,10 @@ fn main() { non_exhaustive: false, }); - if let Some(cmake_includes) = env::var("CMAKE_INCLUDE_DIRS").ok() { + if let Ok(cmake_includes) = env::var("CMAKE_INCLUDE_DIRS") { // we are running from cmake, do special thing. - let mut includes = cmake_includes.split(":").collect::>(); - includes.sort(); + let mut includes = cmake_includes.split(':').collect::>(); + includes.sort_unstable(); includes.dedup(); for x in &includes { @@ -25,8 +25,8 @@ fn main() { } env::var("CMAKE_LIBRARIES") - .unwrap_or(String::new()) - .split(":") + .unwrap_or_default() + .split(':') .into_iter() .filter(|s| s.contains(".so") || s.contains(".dylib")) .flat_map(|l| Path::new(l).parent().and_then(|p| p.to_str())) @@ -42,7 +42,7 @@ fn main() { let ament_prefix_var_name = "AMENT_PREFIX_PATH"; let ament_prefix_var = env::var(ament_prefix_var_name).expect("Source your ROS!"); - for ament_prefix_path in ament_prefix_var.split(":") { + for ament_prefix_path in ament_prefix_var.split(':') { builder = builder.clang_arg(format!("-I{}/include", ament_prefix_path)); println!( "added include search dir: {}", @@ -58,26 +58,26 @@ fn main() { .no_debug("_OSUnaligned.*") .derive_partialeq(true) .derive_copy(true) - // whitelist a few specific things that we need. - .whitelist_recursively(false) - .whitelist_type("rcl_action_client_t") + // allowlist a few specific things that we need. + .allowlist_recursively(false) + .allowlist_type("rcl_action_client_t") .opaque_type("rcl_action_client_t") - .whitelist_type("rcl_action_server_t") + .allowlist_type("rcl_action_server_t") .opaque_type("rcl_action_server_t") - .whitelist_type("rcl_action_goal_info_t") - .whitelist_type("rcl_action_goal_handle_t") + .allowlist_type("rcl_action_goal_info_t") + .allowlist_type("rcl_action_goal_handle_t") .opaque_type("rcl_action_goal_handle_t") - .whitelist_type("rcl_action_cancel_request_t") - .whitelist_type("rcl_action_cancel_response_t") - .whitelist_type("rcl_action_goal_event_t") - .whitelist_type("rcl_action_goal_state_t") + .allowlist_type("rcl_action_cancel_request_t") + .allowlist_type("rcl_action_cancel_response_t") + .allowlist_type("rcl_action_goal_event_t") + .allowlist_type("rcl_action_goal_state_t") .opaque_type("rcl_action_goal_state_t") - .whitelist_type("rcl_action_goal_status_array_t") + .allowlist_type("rcl_action_goal_status_array_t") .opaque_type("rcl_action_goal_status_array_t") - .whitelist_function("rcl_action_.*") - .whitelist_type("rcl_action_client_options_t") - .whitelist_type("rcl_action_server_options_t") - .whitelist_var("RCL_RET_ACTION_.*") + .allowlist_function("rcl_action_.*") + .allowlist_type("rcl_action_client_options_t") + .allowlist_type("rcl_action_server_options_t") + .allowlist_var("RCL_RET_ACTION_.*") .generate_comments(false) .generate() .expect("Unable to generate bindings"); diff --git a/r2r_common/Cargo.toml b/r2r_common/Cargo.toml index dc76744..e5531de 100644 --- a/r2r_common/Cargo.toml +++ b/r2r_common/Cargo.toml @@ -4,7 +4,7 @@ version = "0.2.0" authors = ["Martin Dahl "] description = "Minimal ros2 bindings." license = "Apache-2.0/MIT" -edition = "2018" +edition = "2021" readme = "README.md" homepage = "https://github.com/sequenceplanner/r2r" repository = "https://github.com/sequenceplanner/r2r" diff --git a/r2r_common/src/lib.rs b/r2r_common/src/lib.rs index 9e12e0a..825fc58 100644 --- a/r2r_common/src/lib.rs +++ b/r2r_common/src/lib.rs @@ -94,7 +94,7 @@ pub fn get_ros_msgs(paths: &[&Path]) -> Vec { pub fn parse_msgs(msgs: &Vec) -> Vec { let v: Vec> = msgs .iter() - .map(|l| l.split("/").into_iter().take(3).collect()) + .map(|l| l.split('/').into_iter().take(3).collect()) .collect(); let v: Vec<_> = v .iter() @@ -133,7 +133,7 @@ mod tests { use super::*; #[test] - fn test_parse_msgs() -> () { + fn test_parse_msgs() { let msgs = " std_msgs/msg/Bool x/y @@ -150,7 +150,7 @@ std_msgs/msg/String } #[test] - fn test_as_map() -> () { + fn test_as_map() { let msgs = " std_msgs/msg/Bool x/y diff --git a/r2r_msg_gen/Cargo.toml b/r2r_msg_gen/Cargo.toml index 1c476c3..1b8d97d 100644 --- a/r2r_msg_gen/Cargo.toml +++ b/r2r_msg_gen/Cargo.toml @@ -4,7 +4,7 @@ version = "0.2.1" authors = ["Martin Dahl "] description = "Internal dependency to the r2r crate." license = "MIT OR Apache-2.0" -edition = "2018" +edition = "2021" readme = "README.md" homepage = "https://github.com/sequenceplanner/r2r" repository = "https://github.com/sequenceplanner/r2r" @@ -16,7 +16,7 @@ r2r_rcl = { path = "../r2r_rcl", version = "0.2.0" } r2r_common = { path = "../r2r_common", version = "0.2.0" } [build-dependencies] -bindgen = "0.57.0" +bindgen = "0.59.2" r2r_rcl = { path = "../r2r_rcl", version = "0.2.0" } r2r_common = { path = "../r2r_common", version = "0.2.0" } -heck = "0.3.2" +heck = "0.4.0" diff --git a/r2r_msg_gen/build.rs b/r2r_msg_gen/build.rs index e0aed5e..1f4b8b4 100644 --- a/r2r_msg_gen/build.rs +++ b/r2r_msg_gen/build.rs @@ -1,5 +1,6 @@ -use bindgen; -use r2r_common; + +use heck::ToSnakeCase; + use std::env; use std::fs::File; use std::io::Write; @@ -10,16 +11,16 @@ fn main() { let mut builder = bindgen::Builder::default(); - let msg_list = if let Some(cmake_includes) = env::var("CMAKE_INCLUDE_DIRS").ok() { + let msg_list = if let Ok(cmake_includes) = env::var("CMAKE_INCLUDE_DIRS") { let packages = cmake_includes - .split(":") + .split(':') .flat_map(|i| Path::new(i).parent()) .collect::>(); - for p in cmake_includes.split(":") { + for p in cmake_includes.split(':') { builder = builder.clang_arg(format!("-I{}", p)); } - let deps = env::var("CMAKE_IDL_PACKAGES").unwrap_or(String::default()); - let deps = deps.split(":").collect::>(); + let deps = env::var("CMAKE_IDL_PACKAGES").unwrap_or_default(); + let deps = deps.split(':').collect::>(); let msgs = r2r_common::get_ros_msgs(&packages); r2r_common::parse_msgs(&msgs) .into_iter() @@ -27,12 +28,12 @@ fn main() { .collect::>() } else { let ament_prefix_var = env::var("AMENT_PREFIX_PATH").expect("Source your ROS!"); - for p in ament_prefix_var.split(":") { + for p in ament_prefix_var.split(':') { builder = builder.clang_arg(format!("-I{}/include", p)); } let paths = ament_prefix_var - .split(":") - .map(|i| Path::new(i)) + .split(':') + .map(Path::new) .collect::>(); let msgs = r2r_common::get_ros_msgs(&paths); @@ -63,7 +64,6 @@ fn main() { for msg in msg_list { // filename is certainly CamelCase -> snake_case. convert - use heck::SnakeCase; let include_filename = msg.name.to_snake_case(); includes.push_str(&format!( @@ -119,30 +119,30 @@ fn main() { .header(msg_includes_fn.to_str().unwrap()) .derive_copy(false) // blacklist types that are handled by rcl bindings - .blacklist_type("rosidl_message_type_support_t") - .blacklist_type("rosidl_service_type_support_t") - .blacklist_type("rosidl_action_type_support_t") - .blacklist_type("rosidl_runtime_c__String") - .blacklist_type("rosidl_runtime_c__String__Sequence") - .blacklist_type("rosidl_runtime_c__U16String") - .blacklist_type("rosidl_runtime_c__U16String__Sequence") - .blacklist_type("rosidl_runtime_c__float32__Sequence") - .blacklist_type("rosidl_runtime_c__float__Sequence") - .blacklist_type("rosidl_runtime_c__float64__Sequence") - .blacklist_type("rosidl_runtime_c__double__Sequence") - .blacklist_type("rosidl_runtime_c__long_double__Sequence") - .blacklist_type("rosidl_runtime_c__char__Sequence") - .blacklist_type("rosidl_runtime_c__wchar__Sequence") - .blacklist_type("rosidl_runtime_c__boolean__Sequence") - .blacklist_type("rosidl_runtime_c__octet__Sequence") - .blacklist_type("rosidl_runtime_c__uint8__Sequence") - .blacklist_type("rosidl_runtime_c__int8__Sequence") - .blacklist_type("rosidl_runtime_c__uint16__Sequence") - .blacklist_type("rosidl_runtime_c__int16__Sequence") - .blacklist_type("rosidl_runtime_c__uint32__Sequence") - .blacklist_type("rosidl_runtime_c__int32__Sequence") - .blacklist_type("rosidl_runtime_c__uint64__Sequence") - .blacklist_type("rosidl_runtime_c__int64__Sequence") + .blocklist_type("rosidl_message_type_support_t") + .blocklist_type("rosidl_service_type_support_t") + .blocklist_type("rosidl_action_type_support_t") + .blocklist_type("rosidl_runtime_c__String") + .blocklist_type("rosidl_runtime_c__String__Sequence") + .blocklist_type("rosidl_runtime_c__U16String") + .blocklist_type("rosidl_runtime_c__U16String__Sequence") + .blocklist_type("rosidl_runtime_c__float32__Sequence") + .blocklist_type("rosidl_runtime_c__float__Sequence") + .blocklist_type("rosidl_runtime_c__float64__Sequence") + .blocklist_type("rosidl_runtime_c__double__Sequence") + .blocklist_type("rosidl_runtime_c__long_double__Sequence") + .blocklist_type("rosidl_runtime_c__char__Sequence") + .blocklist_type("rosidl_runtime_c__wchar__Sequence") + .blocklist_type("rosidl_runtime_c__boolean__Sequence") + .blocklist_type("rosidl_runtime_c__octet__Sequence") + .blocklist_type("rosidl_runtime_c__uint8__Sequence") + .blocklist_type("rosidl_runtime_c__int8__Sequence") + .blocklist_type("rosidl_runtime_c__uint16__Sequence") + .blocklist_type("rosidl_runtime_c__int16__Sequence") + .blocklist_type("rosidl_runtime_c__uint32__Sequence") + .blocklist_type("rosidl_runtime_c__int32__Sequence") + .blocklist_type("rosidl_runtime_c__uint64__Sequence") + .blocklist_type("rosidl_runtime_c__int64__Sequence") .size_t_is_usize(true) .no_debug("_OSUnaligned.*") .generate_comments(false) diff --git a/r2r_msg_gen/src/lib.rs b/r2r_msg_gen/src/lib.rs index 6fe395a..58d5abc 100644 --- a/r2r_msg_gen/src/lib.rs +++ b/r2r_msg_gen/src/lib.rs @@ -207,7 +207,7 @@ pub fn generate_rust_msg(module_: &str, prefix_: &str, name_: &str) -> String { let key = format!("{}__{}__{}", module_, prefix_, name_); let ptr = INTROSPECTION_FNS .get(key.as_str()) - .expect(&format!("code generation error: {}", key)); + .unwrap_or_else(|| panic!("code generation error: {}", key)); let ptr = *ptr as *const i32 as *const rosidl_message_type_support_t; unsafe { let (module, prefix, mut name, c_struct, members) = introspection(ptr); @@ -221,7 +221,7 @@ pub fn generate_rust_msg(module_: &str, prefix_: &str, name_: &str) -> String { // same for actions with _Goal, _Result, _Feedback // TODO: refactor... // handle special case of ActionName_ServiceName_Response - let nn = name.splitn(3, "_").collect::>(); + let nn = name.splitn(3, '_').collect::>(); if let [_mod_name, _srv_name, msg_name] = &nn[..] { name = msg_name.to_string(); } else if let [_mod_name, msg_name] = &nn[..] { diff --git a/r2r_rcl/Cargo.toml b/r2r_rcl/Cargo.toml index 937c94a..feaa5da 100644 --- a/r2r_rcl/Cargo.toml +++ b/r2r_rcl/Cargo.toml @@ -4,17 +4,17 @@ version = "0.2.0" authors = ["Martin Dahl "] description = "Internal dependency to the r2r crate." license = "MIT OR Apache-2.0" -edition = "2018" +edition = "2021" readme = "README.md" homepage = "https://github.com/sequenceplanner/r2r" repository = "https://github.com/sequenceplanner/r2r" documentation = "https://sequenceplanner.github.io/r2r/" [dependencies] -paste = "1.0.4" -widestring = "0.4.3" +paste = "1.0.6" +widestring = "0.5.1" [build-dependencies] -bindgen = "0.57.0" -itertools = "0.10.0" +bindgen = "0.59.2" +itertools = "0.10.3" r2r_common = { path = "../r2r_common", version = "0.2.0" } diff --git a/r2r_rcl/build.rs b/r2r_rcl/build.rs index 6b3bd88..5aa2b5d 100644 --- a/r2r_rcl/build.rs +++ b/r2r_rcl/build.rs @@ -1,7 +1,7 @@ extern crate bindgen; use itertools::Itertools; -use r2r_common; + use std::env; use std::path::{Path, PathBuf}; @@ -16,10 +16,10 @@ fn main() { non_exhaustive: false, }); - if let Some(cmake_includes) = env::var("CMAKE_INCLUDE_DIRS").ok() { + if let Ok(cmake_includes) = env::var("CMAKE_INCLUDE_DIRS") { // we are running from cmake, do special thing. - let mut includes = cmake_includes.split(":").collect::>(); - includes.sort(); + let mut includes = cmake_includes.split(':').collect::>(); + includes.sort_unstable(); includes.dedup(); for x in &includes { @@ -28,9 +28,8 @@ fn main() { builder = builder.clang_arg(clang_arg); } - env::var("CMAKE_LIBRARIES") - .unwrap_or(String::new()) - .split(":") + env::var("CMAKE_LIBRARIES").unwrap_or_default() + .split(':') .into_iter() .filter(|s| s.contains(".so") || s.contains(".dylib")) .flat_map(|l| Path::new(l).parent().and_then(|p| p.to_str())) @@ -46,7 +45,7 @@ fn main() { let ament_prefix_var_name = "AMENT_PREFIX_PATH"; let ament_prefix_var = env::var(ament_prefix_var_name).expect("Source your ROS!"); - for ament_prefix_path in ament_prefix_var.split(":") { + for ament_prefix_path in ament_prefix_var.split(':') { builder = builder.clang_arg(format!("-I{}/include", ament_prefix_path)); println!( "added include search dir: {}", diff --git a/r2r_rcl/src/lib.rs b/r2r_rcl/src/lib.rs index 72d9c9d..649a43c 100644 --- a/r2r_rcl/src/lib.rs +++ b/r2r_rcl/src/lib.rs @@ -22,7 +22,7 @@ impl rosidl_runtime_c__String { s.to_str().unwrap_or("") } - pub fn assign(&mut self, other: &str) -> () { + pub fn assign(&mut self, other: &str) { let q = CString::new(other).unwrap(); unsafe { rosidl_runtime_c__String__assign(self as *mut _, q.as_ptr()); @@ -40,7 +40,7 @@ impl rosidl_runtime_c__U16String { s.to_string_lossy() } - pub fn assign(&mut self, other: &str) -> () { + pub fn assign(&mut self, other: &str) { let wstr = U16String::from_str(other); let to_send_ptr = wstr.as_ptr() as *const uint_least16_t; unsafe { @@ -59,7 +59,7 @@ impl rosidl_runtime_c__U16String__Sequence { } let strs = unsafe { std::slice::from_raw_parts_mut(self.data, values.len()) }; for (target, source) in strs.iter_mut().zip(values) { - target.assign(&source); + target.assign(source); } } @@ -83,7 +83,7 @@ impl rosidl_runtime_c__String__Sequence { } let strs = unsafe { std::slice::from_raw_parts_mut(self.data, values.len()) }; for (target, source) in strs.iter_mut().zip(values) { - target.assign(&source); + target.assign(source); } } diff --git a/tests/threads.rs b/tests/threads.rs index 0bf21fa..f99debd 100644 --- a/tests/threads.rs +++ b/tests/threads.rs @@ -1,6 +1,8 @@ use std::thread; use std::time::Duration; +use r2r::QosProfile; + #[test] // Let's create and drop a lot of node and publishers for a while to see that we can cope. fn doesnt_crash() -> Result<(), Box> { @@ -21,7 +23,10 @@ fn doesnt_crash() -> Result<(), Box> { // each with 10 publishers for _j in 0..10 { let p = node - .create_publisher::(&format!("/r2r{}", i)) + .create_publisher::( + &format!("/r2r{}", i), + QosProfile::default(), + ) .unwrap(); let to_send = r2r::std_msgs::msg::String { data: format!("[node{}]: {}", i, c), diff --git a/tests/tokio_testing.rs b/tests/tokio_testing.rs index 66d349d..036ccae 100644 --- a/tests/tokio_testing.rs +++ b/tests/tokio_testing.rs @@ -1,4 +1,5 @@ use futures::stream::StreamExt; +use r2r::QosProfile; use std::sync::{Arc, Mutex}; use tokio::task; @@ -7,10 +8,14 @@ use tokio::task; async fn tokio_testing() -> Result<(), Box> { let ctx = r2r::Context::create()?; let mut node = r2r::Node::create(ctx, "testnode", "")?; - let mut s_the_no = node.subscribe::("/the_no")?; - let mut s_new_no = node.subscribe::("/new_no")?; - let p_the_no = node.create_publisher::("/the_no")?; - let p_new_no = node.create_publisher::("/new_no")?; + let mut s_the_no = + node.subscribe::("/the_no", QosProfile::default())?; + let mut s_new_no = + node.subscribe::("/new_no", QosProfile::default())?; + let p_the_no = + node.create_publisher::("/the_no", QosProfile::default())?; + let p_new_no = + node.create_publisher::("/new_no", QosProfile::default())?; let state = Arc::new(Mutex::new(0)); task::spawn(async move {