diff --git a/.github/workflows/rust-minimal.yml b/.github/workflows/rust-minimal.yml index 51b598b5a..5d2e6bce0 100644 --- a/.github/workflows/rust-minimal.yml +++ b/.github/workflows/rust-minimal.yml @@ -69,11 +69,10 @@ jobs: # Colcon can not be run in a venv which is required in Ubuntu Noble # Removing the externally managed file - - name: Install colcon-cargo and colcon-ros-cargo + - name: Install colcon-cargo run: | sudo rm -f /usr/lib/python3.12/EXTERNALLY-MANAGED sudo pip3 install git+https://github.com/colcon/colcon-cargo.git - sudo pip3 install git+https://github.com/colcon/colcon-ros-cargo.git - name: Check formatting of Rust packages run: | diff --git a/.github/workflows/rust-stable.yml b/.github/workflows/rust-stable.yml index ed67407f6..5119016fb 100644 --- a/.github/workflows/rust-stable.yml +++ b/.github/workflows/rust-stable.yml @@ -69,11 +69,10 @@ jobs: # Colcon can not be run in a venv which is required in Ubuntu Noble # Removing the externally managed file - - name: Install colcon-cargo and colcon-ros-cargo + - name: Install colcon-cargo run: | sudo rm -f /usr/lib/python3.12/EXTERNALLY-MANAGED sudo pip3 install git+https://github.com/colcon/colcon-cargo.git - sudo pip3 install git+https://github.com/colcon/colcon-ros-cargo.git - name: Check formatting of Rust packages run: | diff --git a/.github/workflows/rust-win.yml b/.github/workflows/rust-win.yml index 85ab6ccf0..cc1ce14ec 100644 --- a/.github/workflows/rust-win.yml +++ b/.github/workflows/rust-win.yml @@ -39,13 +39,12 @@ jobs: - name: Install ros2_rust prerequisites # prerequisites and fixes for windows build ros2_rust: # * Libclang has to be added (from the ros2_rust instructions) and the dll has to be renamed - # * colcon-ros-cargo and colcon-cargo have to be added as PyPI packages + # * colcon-cargo has to be added as a PyPI package run: | pixi add libclang --manifest-path C:\pixi_ws\pixi.toml $src = "C:\pixi_ws\.pixi\envs\default\Library\bin\libclang-13.dll" $dst = "C:\pixi_ws\.pixi\envs\default\Library\bin\libclang.dll" if (Test-Path $src) { Rename-Item -Path $src -NewName "libclang.dll" } - pixi add --pypi "colcon-ros-cargo@git+https://github.com/colcon/colcon-ros-cargo.git" --manifest-path C:\pixi_ws\pixi.toml pixi add --pypi "colcon-cargo@git+https://github.com/colcon/colcon-cargo.git" --manifest-path C:\pixi_ws\pixi.toml pixi upgrade colcon-core --manifest-path C:\pixi_ws\pixi.toml diff --git a/docs/writing-your-first-rclrs-node.md b/docs/writing-your-first-rclrs-node.md index 8dbd8d2fa..f8f1d4487 100644 --- a/docs/writing-your-first-rclrs-node.md +++ b/docs/writing-your-first-rclrs-node.md @@ -44,7 +44,7 @@ Instead, you can store the node as a regular member. Let's add a struct that con ```rust use std::sync::Arc; -use std_msgs::msg::String as StringMsg; +use rclrs::std_msgs::msg::String as StringMsg; struct RepublisherNode { node: Arc, @@ -111,7 +111,7 @@ So, to store the received data in the struct, the following things have to chang ```rust use std::sync::{Arc, Mutex}; // (1) -use std_msgs::msg::String as StringMsg; +use rclrs::std_msgs::msg::String as StringMsg; struct RepublisherNode { node: Arc, diff --git a/docs/writing_a_simple_publisher_and_subscriber.md b/docs/writing_a_simple_publisher_and_subscriber.md index 55e3a9284..1e2d32271 100644 --- a/docs/writing_a_simple_publisher_and_subscriber.md +++ b/docs/writing_a_simple_publisher_and_subscriber.md @@ -94,7 +94,7 @@ To construct a node, replace the code in your `main.rs` file with the following: /// methods to publish a simple "Hello World" message on a loop in separate threads. use rclrs::{create_node, Context, Node, Publisher, RclrsError, QOS_PROFILE_DEFAULT}; use std::{env, sync::Arc, thread, time::Duration}; -use std_msgs::msg::String as StringMsg; +use rclrs::std_msgs::msg::String as StringMsg; /// SimplePublisherNode struct contains node and publisher members. /// Used to initialize a ROS 2 node and publisher, and publish messages. struct SimplePublisherNode { @@ -138,7 +138,7 @@ handling, iteration, threading, ROS 2 communication, and string message publishi ```rust use rclrs::{create_node, Context, Node, Publisher, RclrsError, QOS_PROFILE_DEFAULT}; use std::{env, sync::Arc, thread, time::Duration}; -use std_msgs::msg::String as StringMsg; +use rclrs::std_msgs::msg::String as StringMsg; ``` * `use std::{sync::Arc, time::Duration, iter, thread};`: Imports specific features from the standard library: - `Arc` is for thread-safe shared ownership of data. @@ -149,7 +149,7 @@ use std_msgs::msg::String as StringMsg; - `RclrsError` for handling errors. - `QOS_PROFILE_DEFAULT` for default Quality of Service settings. - `Context, create_node, Node, Publisher` are for ROS 2 node creation and publishing. -* `use std_msgs::msg::String as StringMsg;`: Imports the `StringMsg` type for publishing string messages. +* `use rclrs::std_msgs::msg::String as StringMsg;`: Imports the `StringMsg` type for publishing string messages. #### `SimplePublisherNode` Next, this structure defines a `SimplePublisherNode` which holds references to a ROS 2 node and a publisher for string messages. @@ -291,7 +291,7 @@ use std::{ thread, time::Duration, }; -use std_msgs::msg::String as StringMsg; +use rclrs::std_msgs::msg::String as StringMsg; pub struct SimpleSubscriptionNode { node: Arc, _subscriber: Arc>, diff --git a/rclrs/Cargo.toml b/rclrs/Cargo.toml index dc2da0cdc..4bc4a9512 100644 --- a/rclrs/Cargo.toml +++ b/rclrs/Cargo.toml @@ -65,6 +65,9 @@ tokio = { version = "1", features = ["rt", "time", "macros"] } cfg-if = "1.0.0" rustflags = "0.1" +# Used to read Cargo.toml dependencies when re-exporting generated crates +cargo_toml = "0.14" + [features] default = [] dyn_msg = ["ament_rs", "libloading"] diff --git a/rclrs/build.rs b/rclrs/build.rs index 930940ff9..7ef6a04c9 100644 --- a/rclrs/build.rs +++ b/rclrs/build.rs @@ -1,4 +1,8 @@ -use std::{env, path::Path}; +use std::{env, fs, path::Path}; +use std::path::PathBuf; + +use cargo_toml::Manifest; + const AMENT_PREFIX_PATH: &str = "AMENT_PREFIX_PATH"; const ROS_DISTRO: &str = "ROS_DISTRO"; @@ -13,6 +17,19 @@ fn get_env_var_or_abort(env_var: &'static str) -> String { } } +fn marked_reexport(cargo_toml: String) -> bool { + cargo_toml.contains("[package.metadata.rclrs]") + && cargo_toml.contains("reexport = true") +} + +fn star_deps_to_use(manifest: &Manifest) -> String { + manifest.dependencies + .iter() + .filter(|(_, version)| version.req() == "*") + .map(|(name, _)| format!("use crate::{name};\n")) + .collect::() +} + fn main() { println!( "cargo:rustc-check-cfg=cfg(ros_distro, values(\"{}\"))", @@ -54,6 +71,91 @@ fn main() { println!("cargo:rustc-link-search=native={}", library_path.display()); } + // Re-export any generated interface crates that we find + let ament_prefix_paths = env!("AMENT_PREFIX_PATH", "AMENT_PREFIX_PATH environment variable not set - please source ROS 2 installation first."); + let export_crate_tomls = ament_prefix_paths + .split(':') + .map(PathBuf::from) + .flat_map(|base_path| { + // 1. Try to read share/ directory + fs::read_dir(base_path.join("share")).into_iter().flatten() + }) + .filter_map(|entry| entry.ok()) + .filter(|entry| entry.path().is_dir()) + .flat_map(|package_dir| { + // 2. Try to read /rust/ directory + fs::read_dir(package_dir.path().join("rust")) + .into_iter() + .flatten() + }) + .filter_map(|entry| entry.ok()) + .map(|entry| entry.path()) + .filter(|path| path.file_name() == Some(std::ffi::OsStr::new("Cargo.toml"))) + .filter(|path| { + fs::read_to_string(path) + .map(marked_reexport) + .unwrap_or(false) + }); + + let content: String = export_crate_tomls + .filter_map(|path| path.parent().map(|p| p.to_path_buf())) + .map(|package_dir| { + let package = package_dir + .parent() + .unwrap() + .file_name() + .unwrap() + .to_str() + .unwrap(); + + // Find all dependencies for this crate that have a `*` version requirement. + // We will assume that these are other exported dependencies that need symbols + // exposed in their module. + let dependencies: String = Manifest::from_path(package_dir.clone().join("Cargo.toml")) + .iter() + .map(star_deps_to_use) + .collect(); + + let internal_mods: String = fs::read_dir(package_dir.join("src")) + .into_iter() + .flatten() + .filter_map(|entry| entry.ok()) + .filter(|entry| entry.path().is_file()) + // Ignore lib.rs and any rmw.rs. lib.rs is only used if the crate is consumed + // independently, and rmw.rs files need their top level module + // (i.e. msg, srv, action) to exist to be re-exported. + .filter(|entry| { + let name = entry.file_name(); + name != "lib.rs" && name != "rmw.rs" + }) + // Wrap the inclusion of each file in a module matching the file stem + // so that the generated code can be imported like `rclrs::std_msgs::msgs::Bool` + .filter_map(|e| { + e.path() + .file_stem() + .and_then(|stem| stem.to_str()) + .map(|stem| { + let idiomatic_path = e.path().display().to_string(); + let sep = std::path::MAIN_SEPARATOR; + let rmw_path = idiomatic_path + .rsplit_once(std::path::MAIN_SEPARATOR) + .map(|(dir, _)| format!("{dir}{sep}{stem}{sep}rmw.rs")) + .unwrap_or_else(|| "rmw.rs".to_string()); + format!("pub mod {stem} {{ {dependencies} include!(\"{idiomatic_path}\"); pub mod rmw {{ {dependencies} include!(\"{rmw_path}\");}} }}") + }) + }) + .collect(); + + format!("pub mod {package} {{ {internal_mods} }}") + }) + .collect(); + + let out_dir = env::var("OUT_DIR").expect("OUT_DIR not set "); + let dest_path = PathBuf::from(out_dir).join("interfaces.rs"); + + // TODO I would like to run rustfmt on this generated code, similar to how bindgen does it + fs::write(dest_path, content.clone()).expect("Failed to write interfaces.rs"); + println!("cargo:rustc-link-lib=dylib=rcl"); println!("cargo:rustc-link-lib=dylib=rcl_action"); println!("cargo:rustc-link-lib=dylib=rcl_yaml_param_parser"); diff --git a/rclrs/src/action.rs b/rclrs/src/action.rs index 62b1543de..126f1ee75 100644 --- a/rclrs/src/action.rs +++ b/rclrs/src/action.rs @@ -9,7 +9,7 @@ pub use action_goal_receiver::*; pub(crate) mod action_server; pub use action_server::*; -use crate::{log_error, rcl_bindings::*, vendor::builtin_interfaces::msg::Time, DropGuard}; +use crate::{log_error, rcl_bindings::*, builtin_interfaces::msg::Time, DropGuard}; use std::fmt; #[cfg(feature = "serde")] @@ -256,7 +256,7 @@ fn empty_goal_status_array() -> DropGuard { #[cfg(test)] mod tests { use crate::{ - vendor::example_interfaces::action::{ + example_interfaces::action::{ Fibonacci, Fibonacci_Feedback, Fibonacci_Goal, Fibonacci_Result, }, *, diff --git a/rclrs/src/action/action_client.rs b/rclrs/src/action/action_client.rs index af02651d5..6156d47f4 100644 --- a/rclrs/src/action/action_client.rs +++ b/rclrs/src/action/action_client.rs @@ -2,7 +2,7 @@ use super::empty_goal_status_array; use crate::{ log_warn, rcl_bindings::*, - vendor::{action_msgs::srv::CancelGoal_Response, builtin_interfaces::msg::Time}, + {action_msgs::srv::CancelGoal_Response, builtin_interfaces::msg::Time}, CancelResponse, CancelResponseCode, DropGuard, GoalStatus, GoalStatusCode, GoalUuid, MultiCancelResponse, Node, NodeHandle, QoSProfile, RclPrimitive, RclPrimitiveHandle, RclPrimitiveKind, RclrsError, ReadyKind, TakeFailedAsNone, ToResult, Waitable, diff --git a/rclrs/src/action/action_client/goal_client.rs b/rclrs/src/action/action_client/goal_client.rs index 61d2773ff..d3cfade61 100644 --- a/rclrs/src/action/action_client/goal_client.rs +++ b/rclrs/src/action/action_client/goal_client.rs @@ -1,5 +1,5 @@ use crate::{ - vendor::builtin_interfaces::msg::Time, CancellationClient, FeedbackClient, GoalStatus, + builtin_interfaces::msg::Time, CancellationClient, FeedbackClient, GoalStatus, GoalStatusCode, ResultClient, StatusWatcher, }; use rosidl_runtime_rs::Action; @@ -96,7 +96,7 @@ impl GoalClient { /// /// ``` /// use rclrs::*; -/// use crate::rclrs::vendor::example_interfaces::action::Fibonacci; +/// use crate::rclrs::example_interfaces::action::Fibonacci; /// use futures::StreamExt; /// /// async fn process_goal_client_stream( diff --git a/rclrs/src/action/action_server.rs b/rclrs/src/action/action_server.rs index e75ea3079..2ca43b656 100644 --- a/rclrs/src/action/action_server.rs +++ b/rclrs/src/action/action_server.rs @@ -1,7 +1,7 @@ use super::empty_goal_status_array; use crate::{ action::GoalUuid, error::ToResult, rcl_bindings::*, - vendor::action_msgs::srv::CancelGoal_Response, ActionGoalReceiver, CancelResponseCode, + action_msgs::srv::CancelGoal_Response, ActionGoalReceiver, CancelResponseCode, DropGuard, GoalStatusCode, Node, NodeHandle, QoSProfile, RclPrimitive, RclPrimitiveHandle, RclPrimitiveKind, RclrsError, ReadyKind, TakeFailedAsNone, Waitable, WaitableLifecycle, ENTITY_LIFECYCLE_MUTEX, diff --git a/rclrs/src/action/action_server/cancellation_state.rs b/rclrs/src/action/action_server/cancellation_state.rs index 9dc166fbe..d60cb8e5d 100644 --- a/rclrs/src/action/action_server/cancellation_state.rs +++ b/rclrs/src/action/action_server/cancellation_state.rs @@ -2,7 +2,7 @@ use super::ActionServerHandle; use crate::{ log_error, rcl_bindings::*, - vendor::{ + { action_msgs::{msg::GoalInfo, srv::CancelGoal_Response}, unique_identifier_msgs::msg::UUID, }, diff --git a/rclrs/src/client.rs b/rclrs/src/client.rs index 461c53575..1fe5a30f1 100644 --- a/rclrs/src/client.rs +++ b/rclrs/src/client.rs @@ -159,7 +159,7 @@ where /// signatures and which returns a `()` (a.k.a. nothing). /// ``` /// # use rclrs::*; - /// # use crate::rclrs::vendor::test_msgs; + /// # use crate::rclrs::test_msgs; /// # let node = Context::default() /// # .create_basic_executor() /// # .create_node("test_node")?; @@ -187,7 +187,7 @@ where /// /// ``` /// # use rclrs::*; - /// # use crate::rclrs::vendor::test_msgs; + /// # use crate::rclrs::test_msgs; /// # use std::future::Future; /// # let node = Context::default() /// # .create_basic_executor() @@ -216,7 +216,7 @@ where /// /// ``` /// # use rclrs::*; - /// # use crate::rclrs::vendor::test_msgs; + /// # use crate::rclrs::test_msgs; /// # let node = Context::default() /// # .create_basic_executor() /// # .create_node("test_node")?; @@ -568,7 +568,7 @@ unsafe impl Send for rcl_client_t {} #[cfg(test)] mod tests { use super::*; - use crate::{test_helpers::*, vendor::test_msgs}; + use crate::{test_helpers::*, test_msgs}; #[test] fn traits() { diff --git a/rclrs/src/lib.rs b/rclrs/src/lib.rs index 408d52b3a..d48f832ea 100644 --- a/rclrs/src/lib.rs +++ b/rclrs/src/lib.rs @@ -32,7 +32,7 @@ //! //! ```no_run //! use rclrs::*; -//! # use crate::rclrs::vendor::example_interfaces; +//! # use crate::rclrs::example_interfaces; //! //! let context = Context::default_from_env()?; //! let mut executor = context.create_basic_executor(); @@ -59,7 +59,7 @@ //! # let context = Context::default_from_env()?; //! # let mut executor = context.create_basic_executor(); //! # let node = executor.create_node("example_node")?; -//! # use crate::rclrs::vendor::example_interfaces; +//! # use crate::rclrs::example_interfaces; //! # //! // This worker will manage the data for us. //! // The worker's data is called its payload. @@ -99,7 +99,7 @@ //! The following is a simple example of using a mandatory parameter: //! ```no_run //! use rclrs::*; -//! # use crate::rclrs::vendor::example_interfaces; +//! # use crate::rclrs::example_interfaces; //! use std::sync::Arc; //! //! let mut executor = Context::default_from_env()?.create_basic_executor(); @@ -129,7 +129,7 @@ //! //! ```no_run //! use rclrs::*; -//! # use crate::rclrs::vendor::example_interfaces; +//! # use crate::rclrs::example_interfaces; //! use std::time::Duration; //! //! let mut executor = Context::default_from_env()?.create_basic_executor(); @@ -196,7 +196,6 @@ mod subscription; mod time; mod time_source; mod timer; -pub mod vendor; mod wait_set; mod worker; @@ -205,6 +204,8 @@ mod test_helpers; mod rcl_bindings; +include!(concat!(env!("OUT_DIR"), "/interfaces.rs")); + #[cfg(feature = "dyn_msg")] pub mod dynamic_message; diff --git a/rclrs/src/node.rs b/rclrs/src/node.rs index abb69f977..7058c4b9d 100644 --- a/rclrs/src/node.rs +++ b/rclrs/src/node.rs @@ -248,7 +248,7 @@ impl NodeState { /// In some cases the payload type can be inferred by Rust: /// ``` /// # use rclrs::*; - /// # use crate::rclrs::vendor::example_interfaces; + /// # use crate::rclrs::example_interfaces; /// let executor = Context::default().create_basic_executor(); /// let node = executor.create_node("my_node").unwrap(); /// @@ -274,7 +274,7 @@ impl NodeState { /// /// ``` /// # use rclrs::*; - /// # use crate::rclrs::vendor::example_interfaces; + /// # use crate::rclrs::example_interfaces; /// # let executor = Context::default().create_basic_executor(); /// # let node = executor.create_node("my_node").unwrap(); /// let worker = node.create_worker::(String::new()); @@ -283,7 +283,7 @@ impl NodeState { /// The data given to the worker can be any custom data type: /// ``` /// # use rclrs::*; - /// # use crate::rclrs::vendor::example_interfaces; + /// # use crate::rclrs::example_interfaces; /// # let executor = Context::default().create_basic_executor(); /// # let node = executor.create_node("my_node").unwrap(); /// @@ -319,7 +319,7 @@ impl NodeState { /// # use rclrs::*; /// # let executor = Context::default().create_basic_executor(); /// # let node = executor.create_node("my_node").unwrap(); - /// # use crate::rclrs::vendor::test_msgs; + /// # use crate::rclrs::test_msgs; /// let client = node.create_client::( /// "my_service" /// ) @@ -333,7 +333,7 @@ impl NodeState { /// # use rclrs::*; /// # let executor = Context::default().create_basic_executor(); /// # let node = executor.create_node("my_node").unwrap(); - /// # use crate::rclrs::vendor::test_msgs; + /// # use crate::rclrs::test_msgs; /// let client = node.create_client::( /// "my_service" /// .keep_all() @@ -400,7 +400,7 @@ impl NodeState { /// # use rclrs::*; /// # let executor = Context::default().create_basic_executor(); /// # let node = executor.create_node("my_node").unwrap(); - /// # use crate::rclrs::vendor::test_msgs; + /// # use crate::rclrs::test_msgs; /// let publisher = node.create_publisher::( /// "my_topic" /// ) @@ -412,7 +412,7 @@ impl NodeState { /// /// ``` /// # use rclrs::*; - /// # use crate::rclrs::vendor::test_msgs; + /// # use crate::rclrs::test_msgs; /// # let executor = Context::default().create_basic_executor(); /// # let node = executor.create_node("my_node").unwrap(); /// let publisher = node.create_publisher::( @@ -459,7 +459,7 @@ impl NodeState { /// Pass in only the service name for the `options` argument to use all default service options: /// ``` /// # use rclrs::*; - /// # use crate::rclrs::vendor::test_msgs; + /// # use crate::rclrs::test_msgs; /// # let executor = Context::default().create_basic_executor(); /// # let node = executor.create_node("my_node").unwrap(); /// let service = node.create_service::( @@ -476,7 +476,7 @@ impl NodeState { /// /// ``` /// # use rclrs::*; - /// # use crate::rclrs::vendor::test_msgs; + /// # use crate::rclrs::test_msgs; /// # let executor = Context::default().create_basic_executor(); /// # let node = executor.create_node("my_node").unwrap(); /// let service = node.create_service::( @@ -515,7 +515,7 @@ impl NodeState { /// /// ``` /// # use rclrs::*; - /// # use crate::rclrs::vendor::example_interfaces; + /// # use crate::rclrs::example_interfaces; /// # let executor = Context::default().create_basic_executor(); /// # let node = executor.create_node("my_node").unwrap(); /// use std::sync::Mutex; @@ -541,7 +541,7 @@ impl NodeState { /// /// ``` /// # use rclrs::*; - /// # use crate::rclrs::vendor::example_interfaces; + /// # use crate::rclrs::example_interfaces; /// # let executor = Context::default().create_basic_executor(); /// # let node = executor.create_node("my_node").unwrap(); /// use std::sync::{Arc, Mutex}; @@ -635,7 +635,7 @@ impl NodeState { /// /// ``` /// # use rclrs::*; - /// # use crate::rclrs::vendor::example_interfaces; + /// # use crate::rclrs::example_interfaces; /// # let executor = Context::default().create_basic_executor(); /// # let node = executor.create_node("my_node")?; /// use std::sync::Arc; @@ -707,7 +707,7 @@ impl NodeState { /// Pass in only the topic name for the `options` argument to use all default subscription options: /// ``` /// # use rclrs::*; - /// # use crate::rclrs::vendor::test_msgs; + /// # use crate::rclrs::test_msgs; /// # let executor = Context::default().create_basic_executor(); /// # let node = executor.create_node("my_node").unwrap(); /// let subscription = node.create_subscription( @@ -723,7 +723,7 @@ impl NodeState { /// /// ``` /// # use rclrs::*; - /// # use crate::rclrs::vendor::test_msgs; + /// # use crate::rclrs::test_msgs; /// # let executor = Context::default().create_basic_executor(); /// # let node = executor.create_node("my_node").unwrap(); /// let subscription = node.create_subscription( @@ -766,7 +766,7 @@ impl NodeState { /// /// ``` /// # use rclrs::*; - /// # use crate::rclrs::vendor::example_interfaces; + /// # use crate::rclrs::example_interfaces; /// # let executor = Context::default().create_basic_executor(); /// # let node = executor.create_node("my_node").unwrap(); /// use std::sync::Mutex; @@ -789,7 +789,7 @@ impl NodeState { /// /// ``` /// # use rclrs::*; - /// # use crate::rclrs::vendor::example_interfaces; + /// # use crate::rclrs::example_interfaces; /// # let executor = Context::default().create_basic_executor(); /// # let node = executor.create_node("my_node").unwrap(); /// use std::sync::{Arc, Mutex}; @@ -890,7 +890,7 @@ impl NodeState { /// /// ``` /// # use rclrs::*; - /// # use crate::rclrs::vendor::example_interfaces; + /// # use crate::rclrs::example_interfaces; /// # let executor = Context::default().create_basic_executor(); /// # let node = executor.create_node("my_node").unwrap(); /// @@ -1370,7 +1370,7 @@ mod tests { #[test] fn test_topic_names_and_types() -> Result<(), RclrsError> { - use crate::vendor::test_msgs::msg; + use crate::test_msgs::msg; let graph = construct_test_graph("test_topics_graph")?; diff --git a/rclrs/src/parameter.rs b/rclrs/src/parameter.rs index fe9fa0918..00a3c39cc 100644 --- a/rclrs/src/parameter.rs +++ b/rclrs/src/parameter.rs @@ -8,7 +8,7 @@ pub use range::*; use service::*; pub use value::*; -use crate::vendor::rcl_interfaces::msg::rmw::{ParameterType, ParameterValue as RmwParameterValue}; +use crate::rcl_interfaces::msg::rmw::{ParameterType, ParameterValue as RmwParameterValue}; use crate::{ call_string_getter_with_rcl_node, rcl_bindings::*, Node, RclrsError, ENTITY_LIFECYCLE_MUTEX, diff --git a/rclrs/src/parameter/range.rs b/rclrs/src/parameter/range.rs index 6a46d2ff0..fe88ca4b3 100644 --- a/rclrs/src/parameter/range.rs +++ b/rclrs/src/parameter/range.rs @@ -1,5 +1,5 @@ use crate::{ - vendor::rcl_interfaces::msg::rmw::{FloatingPointRange, IntegerRange}, + rcl_interfaces::msg::rmw::{FloatingPointRange, IntegerRange}, DeclarationError, ParameterValue, ParameterVariant, }; use rosidl_runtime_rs::{seq, BoundedSequence}; diff --git a/rclrs/src/parameter/service.rs b/rclrs/src/parameter/service.rs index 5d1c25216..317759a75 100644 --- a/rclrs/src/parameter/service.rs +++ b/rclrs/src/parameter/service.rs @@ -3,7 +3,7 @@ use std::{ sync::{Arc, Mutex}, }; -use crate::vendor::rcl_interfaces::{msg::rmw::*, srv::rmw::*}; +use crate::rcl_interfaces::{msg::rmw::*, srv::rmw::*}; use rosidl_runtime_rs::Sequence; use super::ParameterMap; @@ -307,7 +307,7 @@ impl ParameterService { #[cfg(test)] mod tests { use crate::{ - vendor::rcl_interfaces::{ + rcl_interfaces::{ msg::rmw::{ Parameter as RmwParameter, ParameterType, ParameterValue as RmwParameterValue, }, diff --git a/rclrs/src/parameter/value.rs b/rclrs/src/parameter/value.rs index ff0c86c46..972f9c7dc 100644 --- a/rclrs/src/parameter/value.rs +++ b/rclrs/src/parameter/value.rs @@ -3,7 +3,7 @@ use std::{ffi::CStr, sync::Arc}; use crate::{ parameter::{ParameterRange, ParameterRanges}, rcl_bindings::*, - vendor::rcl_interfaces::msg::rmw::{ParameterType, ParameterValue as RmwParameterValue}, + rcl_interfaces::msg::rmw::{ParameterType, ParameterValue as RmwParameterValue}, ParameterValueError, }; diff --git a/rclrs/src/publisher.rs b/rclrs/src/publisher.rs index f5540957d..6e0a3b6ea 100644 --- a/rclrs/src/publisher.rs +++ b/rclrs/src/publisher.rs @@ -337,14 +337,14 @@ mod tests { #[test] fn traits() { - use crate::vendor::test_msgs; + use crate::test_msgs; assert_send::>(); assert_sync::>(); } #[test] fn test_publishers() -> Result<(), RclrsError> { - use crate::{vendor::test_msgs::msg, TopicEndpointInfo}; + use crate::{test_msgs::msg, TopicEndpointInfo}; let namespace = "/test_publishers_graph"; let graph = construct_test_graph(namespace)?; diff --git a/rclrs/src/publisher/loaned_message.rs b/rclrs/src/publisher/loaned_message.rs index 4a39d7001..135c6042a 100644 --- a/rclrs/src/publisher/loaned_message.rs +++ b/rclrs/src/publisher/loaned_message.rs @@ -98,7 +98,7 @@ mod tests { #[test] fn traits() { - use crate::{test_helpers::*, vendor::test_msgs}; + use crate::{test_helpers::*, test_msgs}; assert_send::>(); assert_sync::>(); diff --git a/rclrs/src/service.rs b/rclrs/src/service.rs index 596ef1f81..149f1a8c4 100644 --- a/rclrs/src/service.rs +++ b/rclrs/src/service.rs @@ -398,14 +398,14 @@ mod tests { #[test] fn traits() { - use crate::vendor::test_msgs; + use crate::test_msgs; assert_send::>(); assert_sync::>(); } #[test] fn test_services() -> Result<(), RclrsError> { - use crate::{vendor::test_msgs::srv, TopicNamesAndTypes}; + use crate::{test_msgs::srv, TopicNamesAndTypes}; let namespace = "/test_services_graph"; let graph = construct_test_graph(namespace)?; diff --git a/rclrs/src/subscription.rs b/rclrs/src/subscription.rs index 06d331eb8..971ad6336 100644 --- a/rclrs/src/subscription.rs +++ b/rclrs/src/subscription.rs @@ -416,7 +416,7 @@ impl Drop for SubscriptionHandle { #[cfg(test)] mod tests { use super::*; - use crate::{test_helpers::*, vendor::test_msgs::msg}; + use crate::{test_helpers::*, test_msgs::msg}; #[test] fn traits() { @@ -527,13 +527,15 @@ mod tests { #[test] fn test_delayed_subscription() { - use crate::{vendor::example_interfaces::msg::Empty, *}; + use crate::{example_interfaces::msg::Empty, *}; use futures::{ channel::{mpsc, oneshot}, StreamExt, }; use std::sync::atomic::{AtomicBool, Ordering}; + let _ = crate::rcl_interfaces::msg::IntegerRange; + let mut executor = Context::default().create_basic_executor(); let node = executor .create_node( diff --git a/rclrs/src/subscription/into_async_subscription_callback.rs b/rclrs/src/subscription/into_async_subscription_callback.rs index 334fc0a9a..e17e10cf3 100644 --- a/rclrs/src/subscription/into_async_subscription_callback.rs +++ b/rclrs/src/subscription/into_async_subscription_callback.rs @@ -103,7 +103,7 @@ where mod tests { use super::*; - type TestMessage = crate::vendor::test_msgs::msg::BoundedSequences; + type TestMessage = crate::test_msgs::msg::BoundedSequences; #[test] fn callback_conversion() { diff --git a/rclrs/src/subscription/into_node_subscription_callback.rs b/rclrs/src/subscription/into_node_subscription_callback.rs index 007ee137e..be86f8e3c 100644 --- a/rclrs/src/subscription/into_node_subscription_callback.rs +++ b/rclrs/src/subscription/into_node_subscription_callback.rs @@ -131,7 +131,7 @@ where mod tests { use super::*; - type TestMessage = crate::vendor::test_msgs::msg::BoundedSequences; + type TestMessage = crate::test_msgs::msg::BoundedSequences; #[test] fn callback_conversion() { diff --git a/rclrs/src/subscription/readonly_loaned_message.rs b/rclrs/src/subscription/readonly_loaned_message.rs index db891176e..121f34028 100644 --- a/rclrs/src/subscription/readonly_loaned_message.rs +++ b/rclrs/src/subscription/readonly_loaned_message.rs @@ -58,7 +58,7 @@ mod tests { #[test] fn traits() { - use crate::{test_helpers::*, vendor::test_msgs}; + use crate::{test_helpers::*, test_msgs}; assert_send::>(); assert_sync::>(); diff --git a/rclrs/src/time.rs b/rclrs/src/time.rs index 1b8250d74..358e07000 100644 --- a/rclrs/src/time.rs +++ b/rclrs/src/time.rs @@ -1,4 +1,4 @@ -use crate::{rcl_bindings::*, vendor::builtin_interfaces}; +use crate::{rcl_bindings::*, builtin_interfaces}; use std::{ num::TryFromIntError, ops::{Add, Sub}, diff --git a/rclrs/src/time_source.rs b/rclrs/src/time_source.rs index bb2c52fd8..fabf9b7a2 100644 --- a/rclrs/src/time_source.rs +++ b/rclrs/src/time_source.rs @@ -1,6 +1,6 @@ use crate::{ clock::{Clock, ClockSource, ClockType}, - vendor::rosgraph_msgs::msg::Clock as ClockMsg, + rosgraph_msgs::msg::Clock as ClockMsg, IntoPrimitiveOptions, Node, NodeState, QoSProfile, ReadOnlyParameter, Subscription, QOS_PROFILE_CLOCK, }; diff --git a/rclrs/src/vendor/action_msgs/mod.rs b/rclrs/src/vendor/action_msgs/mod.rs deleted file mode 100644 index f43deda46..000000000 --- a/rclrs/src/vendor/action_msgs/mod.rs +++ /dev/null @@ -1,7 +0,0 @@ -#![allow(non_camel_case_types)] -#![allow(clippy::derive_partial_eq_without_eq)] -#![allow(clippy::upper_case_acronyms)] - -pub mod msg; - -pub mod srv; diff --git a/rclrs/src/vendor/action_msgs/msg.rs b/rclrs/src/vendor/action_msgs/msg.rs deleted file mode 100644 index 32c7b7089..000000000 --- a/rclrs/src/vendor/action_msgs/msg.rs +++ /dev/null @@ -1,457 +0,0 @@ -pub mod rmw { - #[cfg(feature = "serde")] - use serde::{Deserialize, Serialize}; - - #[link(name = "action_msgs__rosidl_typesupport_c")] - extern "C" { - fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalInfo( - ) -> *const std::ffi::c_void; - } - - #[link(name = "action_msgs__rosidl_generator_c")] - extern "C" { - fn action_msgs__msg__GoalInfo__init(msg: *mut GoalInfo) -> bool; - fn action_msgs__msg__GoalInfo__Sequence__init( - seq: *mut rosidl_runtime_rs::Sequence, - size: usize, - ) -> bool; - fn action_msgs__msg__GoalInfo__Sequence__fini( - seq: *mut rosidl_runtime_rs::Sequence, - ); - fn action_msgs__msg__GoalInfo__Sequence__copy( - in_seq: &rosidl_runtime_rs::Sequence, - out_seq: *mut rosidl_runtime_rs::Sequence, - ) -> bool; - } - - // Corresponds to action_msgs__msg__GoalInfo - #[repr(C)] - #[cfg_attr(feature = "serde", derive(Deserialize, Serialize))] - #[derive(Clone, Debug, PartialEq, PartialOrd)] - pub struct GoalInfo { - pub goal_id: crate::vendor::unique_identifier_msgs::msg::rmw::UUID, - pub stamp: crate::vendor::builtin_interfaces::msg::rmw::Time, - } - - impl Default for GoalInfo { - fn default() -> Self { - unsafe { - let mut msg = std::mem::zeroed(); - if !action_msgs__msg__GoalInfo__init(&mut msg as *mut _) { - panic!("Call to action_msgs__msg__GoalInfo__init() failed"); - } - msg - } - } - } - - impl rosidl_runtime_rs::SequenceAlloc for GoalInfo { - fn sequence_init(seq: &mut rosidl_runtime_rs::Sequence, size: usize) -> bool { - // SAFETY: This is safe since the pointer is guaranteed to be valid/initialized. - unsafe { action_msgs__msg__GoalInfo__Sequence__init(seq as *mut _, size) } - } - fn sequence_fini(seq: &mut rosidl_runtime_rs::Sequence) { - // SAFETY: This is safe since the pointer is guaranteed to be valid/initialized. - unsafe { action_msgs__msg__GoalInfo__Sequence__fini(seq as *mut _) } - } - fn sequence_copy( - in_seq: &rosidl_runtime_rs::Sequence, - out_seq: &mut rosidl_runtime_rs::Sequence, - ) -> bool { - // SAFETY: This is safe since the pointer is guaranteed to be valid/initialized. - unsafe { action_msgs__msg__GoalInfo__Sequence__copy(in_seq, out_seq as *mut _) } - } - } - - impl rosidl_runtime_rs::Message for GoalInfo { - type RmwMsg = Self; - fn into_rmw_message( - msg_cow: std::borrow::Cow<'_, Self>, - ) -> std::borrow::Cow<'_, Self::RmwMsg> { - msg_cow - } - fn from_rmw_message(msg: Self::RmwMsg) -> Self { - msg - } - } - - impl rosidl_runtime_rs::RmwMessage for GoalInfo - where - Self: Sized, - { - const TYPE_NAME: &'static str = "action_msgs/msg/GoalInfo"; - fn get_type_support() -> *const std::ffi::c_void { - // SAFETY: No preconditions for this function. - unsafe { - rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalInfo() - } - } - } - - #[link(name = "action_msgs__rosidl_typesupport_c")] - extern "C" { - fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatus( - ) -> *const std::ffi::c_void; - } - - #[link(name = "action_msgs__rosidl_generator_c")] - extern "C" { - fn action_msgs__msg__GoalStatus__init(msg: *mut GoalStatus) -> bool; - fn action_msgs__msg__GoalStatus__Sequence__init( - seq: *mut rosidl_runtime_rs::Sequence, - size: usize, - ) -> bool; - fn action_msgs__msg__GoalStatus__Sequence__fini( - seq: *mut rosidl_runtime_rs::Sequence, - ); - fn action_msgs__msg__GoalStatus__Sequence__copy( - in_seq: &rosidl_runtime_rs::Sequence, - out_seq: *mut rosidl_runtime_rs::Sequence, - ) -> bool; - } - - // Corresponds to action_msgs__msg__GoalStatus - #[repr(C)] - #[cfg_attr(feature = "serde", derive(Deserialize, Serialize))] - #[derive(Clone, Debug, PartialEq, PartialOrd)] - pub struct GoalStatus { - pub goal_info: crate::vendor::action_msgs::msg::rmw::GoalInfo, - pub status: i8, - } - - impl GoalStatus { - /// Indicates status has not been properly set. - pub const STATUS_UNKNOWN: i8 = 0; - /// The goal has been accepted and is awaiting execution. - pub const STATUS_ACCEPTED: i8 = 1; - /// The goal is currently being executed by the action server. - pub const STATUS_EXECUTING: i8 = 2; - /// The client has requested that the goal be canceled and the action server has - /// accepted the cancel request. - pub const STATUS_CANCELING: i8 = 3; - /// The goal was achieved successfully by the action server. - pub const STATUS_SUCCEEDED: i8 = 4; - /// The goal was canceled after an external request from an action client. - pub const STATUS_CANCELED: i8 = 5; - /// The goal was terminated by the action server without an external request. - pub const STATUS_ABORTED: i8 = 6; - } - - impl Default for GoalStatus { - fn default() -> Self { - unsafe { - let mut msg = std::mem::zeroed(); - if !action_msgs__msg__GoalStatus__init(&mut msg as *mut _) { - panic!("Call to action_msgs__msg__GoalStatus__init() failed"); - } - msg - } - } - } - - impl rosidl_runtime_rs::SequenceAlloc for GoalStatus { - fn sequence_init(seq: &mut rosidl_runtime_rs::Sequence, size: usize) -> bool { - // SAFETY: This is safe since the pointer is guaranteed to be valid/initialized. - unsafe { action_msgs__msg__GoalStatus__Sequence__init(seq as *mut _, size) } - } - fn sequence_fini(seq: &mut rosidl_runtime_rs::Sequence) { - // SAFETY: This is safe since the pointer is guaranteed to be valid/initialized. - unsafe { action_msgs__msg__GoalStatus__Sequence__fini(seq as *mut _) } - } - fn sequence_copy( - in_seq: &rosidl_runtime_rs::Sequence, - out_seq: &mut rosidl_runtime_rs::Sequence, - ) -> bool { - // SAFETY: This is safe since the pointer is guaranteed to be valid/initialized. - unsafe { action_msgs__msg__GoalStatus__Sequence__copy(in_seq, out_seq as *mut _) } - } - } - - impl rosidl_runtime_rs::Message for GoalStatus { - type RmwMsg = Self; - fn into_rmw_message( - msg_cow: std::borrow::Cow<'_, Self>, - ) -> std::borrow::Cow<'_, Self::RmwMsg> { - msg_cow - } - fn from_rmw_message(msg: Self::RmwMsg) -> Self { - msg - } - } - - impl rosidl_runtime_rs::RmwMessage for GoalStatus - where - Self: Sized, - { - const TYPE_NAME: &'static str = "action_msgs/msg/GoalStatus"; - fn get_type_support() -> *const std::ffi::c_void { - // SAFETY: No preconditions for this function. - unsafe { - rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatus( - ) - } - } - } - - #[link(name = "action_msgs__rosidl_typesupport_c")] - extern "C" { - fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatusArray( - ) -> *const std::ffi::c_void; - } - - #[link(name = "action_msgs__rosidl_generator_c")] - extern "C" { - fn action_msgs__msg__GoalStatusArray__init(msg: *mut GoalStatusArray) -> bool; - fn action_msgs__msg__GoalStatusArray__Sequence__init( - seq: *mut rosidl_runtime_rs::Sequence, - size: usize, - ) -> bool; - fn action_msgs__msg__GoalStatusArray__Sequence__fini( - seq: *mut rosidl_runtime_rs::Sequence, - ); - fn action_msgs__msg__GoalStatusArray__Sequence__copy( - in_seq: &rosidl_runtime_rs::Sequence, - out_seq: *mut rosidl_runtime_rs::Sequence, - ) -> bool; - } - - // Corresponds to action_msgs__msg__GoalStatusArray - #[repr(C)] - #[cfg_attr(feature = "serde", derive(Deserialize, Serialize))] - #[derive(Clone, Debug, PartialEq, PartialOrd)] - pub struct GoalStatusArray { - pub status_list: - rosidl_runtime_rs::Sequence, - } - - impl Default for GoalStatusArray { - fn default() -> Self { - unsafe { - let mut msg = std::mem::zeroed(); - if !action_msgs__msg__GoalStatusArray__init(&mut msg as *mut _) { - panic!("Call to action_msgs__msg__GoalStatusArray__init() failed"); - } - msg - } - } - } - - impl rosidl_runtime_rs::SequenceAlloc for GoalStatusArray { - fn sequence_init(seq: &mut rosidl_runtime_rs::Sequence, size: usize) -> bool { - // SAFETY: This is safe since the pointer is guaranteed to be valid/initialized. - unsafe { action_msgs__msg__GoalStatusArray__Sequence__init(seq as *mut _, size) } - } - fn sequence_fini(seq: &mut rosidl_runtime_rs::Sequence) { - // SAFETY: This is safe since the pointer is guaranteed to be valid/initialized. - unsafe { action_msgs__msg__GoalStatusArray__Sequence__fini(seq as *mut _) } - } - fn sequence_copy( - in_seq: &rosidl_runtime_rs::Sequence, - out_seq: &mut rosidl_runtime_rs::Sequence, - ) -> bool { - // SAFETY: This is safe since the pointer is guaranteed to be valid/initialized. - unsafe { action_msgs__msg__GoalStatusArray__Sequence__copy(in_seq, out_seq as *mut _) } - } - } - - impl rosidl_runtime_rs::Message for GoalStatusArray { - type RmwMsg = Self; - fn into_rmw_message( - msg_cow: std::borrow::Cow<'_, Self>, - ) -> std::borrow::Cow<'_, Self::RmwMsg> { - msg_cow - } - fn from_rmw_message(msg: Self::RmwMsg) -> Self { - msg - } - } - - impl rosidl_runtime_rs::RmwMessage for GoalStatusArray - where - Self: Sized, - { - const TYPE_NAME: &'static str = "action_msgs/msg/GoalStatusArray"; - fn get_type_support() -> *const std::ffi::c_void { - // SAFETY: No preconditions for this function. - unsafe { - rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatusArray() - } - } - } -} // mod rmw - -#[cfg(feature = "serde")] -use serde::{Deserialize, Serialize}; - -#[cfg_attr(feature = "serde", derive(Deserialize, Serialize))] -#[derive(Clone, Debug, PartialEq, PartialOrd)] -pub struct GoalInfo { - pub goal_id: crate::vendor::unique_identifier_msgs::msg::UUID, - pub stamp: crate::vendor::builtin_interfaces::msg::Time, -} - -impl Default for GoalInfo { - fn default() -> Self { - ::from_rmw_message( - crate::vendor::action_msgs::msg::rmw::GoalInfo::default(), - ) - } -} - -impl rosidl_runtime_rs::Message for GoalInfo { - type RmwMsg = crate::vendor::action_msgs::msg::rmw::GoalInfo; - - fn into_rmw_message(msg_cow: std::borrow::Cow<'_, Self>) -> std::borrow::Cow<'_, Self::RmwMsg> { - match msg_cow { - std::borrow::Cow::Owned(msg) => std::borrow::Cow::Owned(Self::RmwMsg { - goal_id: crate::vendor::unique_identifier_msgs::msg::UUID::into_rmw_message( - std::borrow::Cow::Owned(msg.goal_id), - ) - .into_owned(), - stamp: crate::vendor::builtin_interfaces::msg::Time::into_rmw_message( - std::borrow::Cow::Owned(msg.stamp), - ) - .into_owned(), - }), - std::borrow::Cow::Borrowed(msg) => std::borrow::Cow::Owned(Self::RmwMsg { - goal_id: crate::vendor::unique_identifier_msgs::msg::UUID::into_rmw_message( - std::borrow::Cow::Borrowed(&msg.goal_id), - ) - .into_owned(), - stamp: crate::vendor::builtin_interfaces::msg::Time::into_rmw_message( - std::borrow::Cow::Borrowed(&msg.stamp), - ) - .into_owned(), - }), - } - } - - fn from_rmw_message(msg: Self::RmwMsg) -> Self { - Self { - goal_id: crate::vendor::unique_identifier_msgs::msg::UUID::from_rmw_message( - msg.goal_id, - ), - stamp: crate::vendor::builtin_interfaces::msg::Time::from_rmw_message(msg.stamp), - } - } -} - -#[cfg_attr(feature = "serde", derive(Deserialize, Serialize))] -#[derive(Clone, Debug, PartialEq, PartialOrd)] -pub struct GoalStatus { - pub goal_info: crate::vendor::action_msgs::msg::GoalInfo, - pub status: i8, -} - -impl GoalStatus { - /// Indicates status has not been properly set. - pub const STATUS_UNKNOWN: i8 = 0; - /// The goal has been accepted and is awaiting execution. - pub const STATUS_ACCEPTED: i8 = 1; - /// The goal is currently being executed by the action server. - pub const STATUS_EXECUTING: i8 = 2; - /// The client has requested that the goal be canceled and the action server has - /// accepted the cancel request. - pub const STATUS_CANCELING: i8 = 3; - /// The goal was achieved successfully by the action server. - pub const STATUS_SUCCEEDED: i8 = 4; - /// The goal was canceled after an external request from an action client. - pub const STATUS_CANCELED: i8 = 5; - /// The goal was terminated by the action server without an external request. - pub const STATUS_ABORTED: i8 = 6; -} - -impl Default for GoalStatus { - fn default() -> Self { - ::from_rmw_message( - crate::vendor::action_msgs::msg::rmw::GoalStatus::default(), - ) - } -} - -impl rosidl_runtime_rs::Message for GoalStatus { - type RmwMsg = crate::vendor::action_msgs::msg::rmw::GoalStatus; - - fn into_rmw_message(msg_cow: std::borrow::Cow<'_, Self>) -> std::borrow::Cow<'_, Self::RmwMsg> { - match msg_cow { - std::borrow::Cow::Owned(msg) => std::borrow::Cow::Owned(Self::RmwMsg { - goal_info: crate::vendor::action_msgs::msg::GoalInfo::into_rmw_message( - std::borrow::Cow::Owned(msg.goal_info), - ) - .into_owned(), - status: msg.status, - }), - std::borrow::Cow::Borrowed(msg) => std::borrow::Cow::Owned(Self::RmwMsg { - goal_info: crate::vendor::action_msgs::msg::GoalInfo::into_rmw_message( - std::borrow::Cow::Borrowed(&msg.goal_info), - ) - .into_owned(), - status: msg.status, - }), - } - } - - fn from_rmw_message(msg: Self::RmwMsg) -> Self { - Self { - goal_info: crate::vendor::action_msgs::msg::GoalInfo::from_rmw_message(msg.goal_info), - status: msg.status, - } - } -} - -#[cfg_attr(feature = "serde", derive(Deserialize, Serialize))] -#[derive(Clone, Debug, PartialEq, PartialOrd)] -pub struct GoalStatusArray { - pub status_list: Vec, -} - -impl Default for GoalStatusArray { - fn default() -> Self { - ::from_rmw_message( - crate::vendor::action_msgs::msg::rmw::GoalStatusArray::default(), - ) - } -} - -impl rosidl_runtime_rs::Message for GoalStatusArray { - type RmwMsg = crate::vendor::action_msgs::msg::rmw::GoalStatusArray; - - fn into_rmw_message(msg_cow: std::borrow::Cow<'_, Self>) -> std::borrow::Cow<'_, Self::RmwMsg> { - match msg_cow { - std::borrow::Cow::Owned(msg) => std::borrow::Cow::Owned(Self::RmwMsg { - status_list: msg - .status_list - .into_iter() - .map(|elem| { - crate::vendor::action_msgs::msg::GoalStatus::into_rmw_message( - std::borrow::Cow::Owned(elem), - ) - .into_owned() - }) - .collect(), - }), - std::borrow::Cow::Borrowed(msg) => std::borrow::Cow::Owned(Self::RmwMsg { - status_list: msg - .status_list - .iter() - .map(|elem| { - crate::vendor::action_msgs::msg::GoalStatus::into_rmw_message( - std::borrow::Cow::Borrowed(elem), - ) - .into_owned() - }) - .collect(), - }), - } - } - - fn from_rmw_message(msg: Self::RmwMsg) -> Self { - Self { - status_list: msg - .status_list - .into_iter() - .map(crate::vendor::action_msgs::msg::GoalStatus::from_rmw_message) - .collect(), - } - } -} diff --git a/rclrs/src/vendor/action_msgs/srv.rs b/rclrs/src/vendor/action_msgs/srv.rs deleted file mode 100644 index f4cf6fe53..000000000 --- a/rclrs/src/vendor/action_msgs/srv.rs +++ /dev/null @@ -1,375 +0,0 @@ -#[cfg(feature = "serde")] -use serde::{Deserialize, Serialize}; - -#[cfg_attr(feature = "serde", derive(Deserialize, Serialize))] -#[derive(Clone, Debug, PartialEq, PartialOrd)] -pub struct CancelGoal_Request { - pub goal_info: crate::vendor::action_msgs::msg::GoalInfo, -} - -impl Default for CancelGoal_Request { - fn default() -> Self { - ::from_rmw_message( - crate::vendor::action_msgs::srv::rmw::CancelGoal_Request::default(), - ) - } -} - -impl rosidl_runtime_rs::Message for CancelGoal_Request { - type RmwMsg = crate::vendor::action_msgs::srv::rmw::CancelGoal_Request; - - fn into_rmw_message(msg_cow: std::borrow::Cow<'_, Self>) -> std::borrow::Cow<'_, Self::RmwMsg> { - match msg_cow { - std::borrow::Cow::Owned(msg) => std::borrow::Cow::Owned(Self::RmwMsg { - goal_info: crate::vendor::action_msgs::msg::GoalInfo::into_rmw_message( - std::borrow::Cow::Owned(msg.goal_info), - ) - .into_owned(), - }), - std::borrow::Cow::Borrowed(msg) => std::borrow::Cow::Owned(Self::RmwMsg { - goal_info: crate::vendor::action_msgs::msg::GoalInfo::into_rmw_message( - std::borrow::Cow::Borrowed(&msg.goal_info), - ) - .into_owned(), - }), - } - } - - fn from_rmw_message(msg: Self::RmwMsg) -> Self { - Self { - goal_info: crate::vendor::action_msgs::msg::GoalInfo::from_rmw_message(msg.goal_info), - } - } -} - -#[cfg_attr(feature = "serde", derive(Deserialize, Serialize))] -#[derive(Clone, Debug, PartialEq, PartialOrd)] -pub struct CancelGoal_Response { - pub return_code: i8, - pub goals_canceling: Vec, -} - -impl CancelGoal_Response { - /// Indicates the request was accepted without any errors. - /// - /// One or more goals have transitioned to the CANCELING state. The - /// goals_canceling list is not empty. - pub const ERROR_NONE: i8 = 0; - /// Indicates the request was rejected. - /// - /// No goals have transitioned to the CANCELING state. The goals_canceling list is - /// empty. - pub const ERROR_REJECTED: i8 = 1; - /// Indicates the requested goal ID does not exist. - /// - /// No goals have transitioned to the CANCELING state. The goals_canceling list is - /// empty. - pub const ERROR_UNKNOWN_GOAL_ID: i8 = 2; - /// Indicates the goal is not cancelable because it is already in a terminal state. - /// - /// No goals have transitioned to the CANCELING state. The goals_canceling list is - /// empty. - pub const ERROR_GOAL_TERMINATED: i8 = 3; -} - -impl Default for CancelGoal_Response { - fn default() -> Self { - ::from_rmw_message( - crate::vendor::action_msgs::srv::rmw::CancelGoal_Response::default(), - ) - } -} - -impl rosidl_runtime_rs::Message for CancelGoal_Response { - type RmwMsg = crate::vendor::action_msgs::srv::rmw::CancelGoal_Response; - - fn into_rmw_message(msg_cow: std::borrow::Cow<'_, Self>) -> std::borrow::Cow<'_, Self::RmwMsg> { - match msg_cow { - std::borrow::Cow::Owned(msg) => std::borrow::Cow::Owned(Self::RmwMsg { - return_code: msg.return_code, - goals_canceling: msg - .goals_canceling - .into_iter() - .map(|elem| { - crate::vendor::action_msgs::msg::GoalInfo::into_rmw_message( - std::borrow::Cow::Owned(elem), - ) - .into_owned() - }) - .collect(), - }), - std::borrow::Cow::Borrowed(msg) => std::borrow::Cow::Owned(Self::RmwMsg { - return_code: msg.return_code, - goals_canceling: msg - .goals_canceling - .iter() - .map(|elem| { - crate::vendor::action_msgs::msg::GoalInfo::into_rmw_message( - std::borrow::Cow::Borrowed(elem), - ) - .into_owned() - }) - .collect(), - }), - } - } - - fn from_rmw_message(msg: Self::RmwMsg) -> Self { - Self { - return_code: msg.return_code, - goals_canceling: msg - .goals_canceling - .into_iter() - .map(crate::vendor::action_msgs::msg::GoalInfo::from_rmw_message) - .collect(), - } - } -} - -#[link(name = "action_msgs__rosidl_typesupport_c")] -extern "C" { - fn rosidl_typesupport_c__get_service_type_support_handle__action_msgs__srv__CancelGoal( - ) -> *const std::ffi::c_void; -} - -// Corresponds to action_msgs__srv__CancelGoal -pub struct CancelGoal; - -impl rosidl_runtime_rs::Service for CancelGoal { - type Request = crate::vendor::action_msgs::srv::CancelGoal_Request; - type Response = crate::vendor::action_msgs::srv::CancelGoal_Response; - - fn get_type_support() -> *const std::ffi::c_void { - // SAFETY: No preconditions for this function. - unsafe { - rosidl_typesupport_c__get_service_type_support_handle__action_msgs__srv__CancelGoal() - } - } -} - -pub mod rmw { - - #[cfg(feature = "serde")] - use serde::{Deserialize, Serialize}; - - #[link(name = "action_msgs__rosidl_typesupport_c")] - extern "C" { - fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Request( - ) -> *const std::ffi::c_void; - } - - #[link(name = "action_msgs__rosidl_generator_c")] - extern "C" { - fn action_msgs__srv__CancelGoal_Request__init(msg: *mut CancelGoal_Request) -> bool; - fn action_msgs__srv__CancelGoal_Request__Sequence__init( - seq: *mut rosidl_runtime_rs::Sequence, - size: usize, - ) -> bool; - fn action_msgs__srv__CancelGoal_Request__Sequence__fini( - seq: *mut rosidl_runtime_rs::Sequence, - ); - fn action_msgs__srv__CancelGoal_Request__Sequence__copy( - in_seq: &rosidl_runtime_rs::Sequence, - out_seq: *mut rosidl_runtime_rs::Sequence, - ) -> bool; - } - - // Corresponds to action_msgs__srv__CancelGoal_Request - #[repr(C)] - #[cfg_attr(feature = "serde", derive(Deserialize, Serialize))] - #[derive(Clone, Debug, PartialEq, PartialOrd)] - pub struct CancelGoal_Request { - pub goal_info: crate::vendor::action_msgs::msg::rmw::GoalInfo, - } - - impl Default for CancelGoal_Request { - fn default() -> Self { - unsafe { - let mut msg = std::mem::zeroed(); - if !action_msgs__srv__CancelGoal_Request__init(&mut msg as *mut _) { - panic!("Call to action_msgs__srv__CancelGoal_Request__init() failed"); - } - msg - } - } - } - - impl rosidl_runtime_rs::SequenceAlloc for CancelGoal_Request { - fn sequence_init(seq: &mut rosidl_runtime_rs::Sequence, size: usize) -> bool { - // SAFETY: This is safe since the pointer is guaranteed to be valid/initialized. - unsafe { action_msgs__srv__CancelGoal_Request__Sequence__init(seq as *mut _, size) } - } - fn sequence_fini(seq: &mut rosidl_runtime_rs::Sequence) { - // SAFETY: This is safe since the pointer is guaranteed to be valid/initialized. - unsafe { action_msgs__srv__CancelGoal_Request__Sequence__fini(seq as *mut _) } - } - fn sequence_copy( - in_seq: &rosidl_runtime_rs::Sequence, - out_seq: &mut rosidl_runtime_rs::Sequence, - ) -> bool { - // SAFETY: This is safe since the pointer is guaranteed to be valid/initialized. - unsafe { - action_msgs__srv__CancelGoal_Request__Sequence__copy(in_seq, out_seq as *mut _) - } - } - } - - impl rosidl_runtime_rs::Message for CancelGoal_Request { - type RmwMsg = Self; - fn into_rmw_message( - msg_cow: std::borrow::Cow<'_, Self>, - ) -> std::borrow::Cow<'_, Self::RmwMsg> { - msg_cow - } - fn from_rmw_message(msg: Self::RmwMsg) -> Self { - msg - } - } - - impl rosidl_runtime_rs::RmwMessage for CancelGoal_Request - where - Self: Sized, - { - const TYPE_NAME: &'static str = "action_msgs/srv/CancelGoal_Request"; - fn get_type_support() -> *const std::ffi::c_void { - // SAFETY: No preconditions for this function. - unsafe { - rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Request() - } - } - } - - #[link(name = "action_msgs__rosidl_typesupport_c")] - extern "C" { - fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Response( - ) -> *const std::ffi::c_void; - } - - #[link(name = "action_msgs__rosidl_generator_c")] - extern "C" { - fn action_msgs__srv__CancelGoal_Response__init(msg: *mut CancelGoal_Response) -> bool; - fn action_msgs__srv__CancelGoal_Response__Sequence__init( - seq: *mut rosidl_runtime_rs::Sequence, - size: usize, - ) -> bool; - fn action_msgs__srv__CancelGoal_Response__Sequence__fini( - seq: *mut rosidl_runtime_rs::Sequence, - ); - fn action_msgs__srv__CancelGoal_Response__Sequence__copy( - in_seq: &rosidl_runtime_rs::Sequence, - out_seq: *mut rosidl_runtime_rs::Sequence, - ) -> bool; - } - - // Corresponds to action_msgs__srv__CancelGoal_Response - #[repr(C)] - #[cfg_attr(feature = "serde", derive(Deserialize, Serialize))] - #[derive(Clone, Debug, PartialEq, PartialOrd)] - pub struct CancelGoal_Response { - pub return_code: i8, - pub goals_canceling: - rosidl_runtime_rs::Sequence, - } - - impl CancelGoal_Response { - /// Indicates the request was accepted without any errors. - /// - /// One or more goals have transitioned to the CANCELING state. The - /// goals_canceling list is not empty. - pub const ERROR_NONE: i8 = 0; - /// Indicates the request was rejected. - /// - /// No goals have transitioned to the CANCELING state. The goals_canceling list is - /// empty. - pub const ERROR_REJECTED: i8 = 1; - /// Indicates the requested goal ID does not exist. - /// - /// No goals have transitioned to the CANCELING state. The goals_canceling list is - /// empty. - pub const ERROR_UNKNOWN_GOAL_ID: i8 = 2; - /// Indicates the goal is not cancelable because it is already in a terminal state. - /// - /// No goals have transitioned to the CANCELING state. The goals_canceling list is - /// empty. - pub const ERROR_GOAL_TERMINATED: i8 = 3; - } - - impl Default for CancelGoal_Response { - fn default() -> Self { - unsafe { - let mut msg = std::mem::zeroed(); - if !action_msgs__srv__CancelGoal_Response__init(&mut msg as *mut _) { - panic!("Call to action_msgs__srv__CancelGoal_Response__init() failed"); - } - msg - } - } - } - - impl rosidl_runtime_rs::SequenceAlloc for CancelGoal_Response { - fn sequence_init(seq: &mut rosidl_runtime_rs::Sequence, size: usize) -> bool { - // SAFETY: This is safe since the pointer is guaranteed to be valid/initialized. - unsafe { action_msgs__srv__CancelGoal_Response__Sequence__init(seq as *mut _, size) } - } - fn sequence_fini(seq: &mut rosidl_runtime_rs::Sequence) { - // SAFETY: This is safe since the pointer is guaranteed to be valid/initialized. - unsafe { action_msgs__srv__CancelGoal_Response__Sequence__fini(seq as *mut _) } - } - fn sequence_copy( - in_seq: &rosidl_runtime_rs::Sequence, - out_seq: &mut rosidl_runtime_rs::Sequence, - ) -> bool { - // SAFETY: This is safe since the pointer is guaranteed to be valid/initialized. - unsafe { - action_msgs__srv__CancelGoal_Response__Sequence__copy(in_seq, out_seq as *mut _) - } - } - } - - impl rosidl_runtime_rs::Message for CancelGoal_Response { - type RmwMsg = Self; - fn into_rmw_message( - msg_cow: std::borrow::Cow<'_, Self>, - ) -> std::borrow::Cow<'_, Self::RmwMsg> { - msg_cow - } - fn from_rmw_message(msg: Self::RmwMsg) -> Self { - msg - } - } - - impl rosidl_runtime_rs::RmwMessage for CancelGoal_Response - where - Self: Sized, - { - const TYPE_NAME: &'static str = "action_msgs/srv/CancelGoal_Response"; - fn get_type_support() -> *const std::ffi::c_void { - // SAFETY: No preconditions for this function. - unsafe { - rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Response() - } - } - } - - #[link(name = "action_msgs__rosidl_typesupport_c")] - extern "C" { - fn rosidl_typesupport_c__get_service_type_support_handle__action_msgs__srv__CancelGoal( - ) -> *const std::ffi::c_void; - } - - // Corresponds to action_msgs__srv__CancelGoal - pub struct CancelGoal; - - impl rosidl_runtime_rs::Service for CancelGoal { - type Request = crate::vendor::action_msgs::srv::rmw::CancelGoal_Request; - type Response = crate::vendor::action_msgs::srv::rmw::CancelGoal_Response; - - fn get_type_support() -> *const std::ffi::c_void { - // SAFETY: No preconditions for this function. - unsafe { - rosidl_typesupport_c__get_service_type_support_handle__action_msgs__srv__CancelGoal( - ) - } - } - } -} // mod rmw diff --git a/rclrs/src/vendor/builtin_interfaces/mod.rs b/rclrs/src/vendor/builtin_interfaces/mod.rs deleted file mode 100644 index 4c61d56a1..000000000 --- a/rclrs/src/vendor/builtin_interfaces/mod.rs +++ /dev/null @@ -1,5 +0,0 @@ -#![allow(non_camel_case_types)] -#![allow(clippy::derive_partial_eq_without_eq)] -#![allow(clippy::upper_case_acronyms)] - -pub mod msg; diff --git a/rclrs/src/vendor/builtin_interfaces/msg.rs b/rclrs/src/vendor/builtin_interfaces/msg.rs deleted file mode 100644 index fd2ec47cd..000000000 --- a/rclrs/src/vendor/builtin_interfaces/msg.rs +++ /dev/null @@ -1,258 +0,0 @@ -pub mod rmw { - #[cfg(feature = "serde")] - use serde::{Deserialize, Serialize}; - - #[link(name = "builtin_interfaces__rosidl_typesupport_c")] - extern "C" { - fn rosidl_typesupport_c__get_message_type_support_handle__builtin_interfaces__msg__Duration( - ) -> *const std::ffi::c_void; - } - - #[link(name = "builtin_interfaces__rosidl_generator_c")] - extern "C" { - fn builtin_interfaces__msg__Duration__init(msg: *mut Duration) -> bool; - fn builtin_interfaces__msg__Duration__Sequence__init( - seq: *mut rosidl_runtime_rs::Sequence, - size: usize, - ) -> bool; - fn builtin_interfaces__msg__Duration__Sequence__fini( - seq: *mut rosidl_runtime_rs::Sequence, - ); - fn builtin_interfaces__msg__Duration__Sequence__copy( - in_seq: &rosidl_runtime_rs::Sequence, - out_seq: *mut rosidl_runtime_rs::Sequence, - ) -> bool; - } - - // Corresponds to builtin_interfaces__msg__Duration - #[repr(C)] - #[cfg_attr(feature = "serde", derive(Deserialize, Serialize))] - #[derive(Clone, Debug, PartialEq, PartialOrd)] - pub struct Duration { - pub sec: i32, - pub nanosec: u32, - } - - impl Default for Duration { - fn default() -> Self { - unsafe { - let mut msg = std::mem::zeroed(); - if !builtin_interfaces__msg__Duration__init(&mut msg as *mut _) { - panic!("Call to builtin_interfaces__msg__Duration__init() failed"); - } - msg - } - } - } - - impl rosidl_runtime_rs::SequenceAlloc for Duration { - fn sequence_init(seq: &mut rosidl_runtime_rs::Sequence, size: usize) -> bool { - // SAFETY: This is safe since the pointer is guaranteed to be valid/initialized. - unsafe { builtin_interfaces__msg__Duration__Sequence__init(seq as *mut _, size) } - } - fn sequence_fini(seq: &mut rosidl_runtime_rs::Sequence) { - // SAFETY: This is safe since the pointer is guaranteed to be valid/initialized. - unsafe { builtin_interfaces__msg__Duration__Sequence__fini(seq as *mut _) } - } - fn sequence_copy( - in_seq: &rosidl_runtime_rs::Sequence, - out_seq: &mut rosidl_runtime_rs::Sequence, - ) -> bool { - // SAFETY: This is safe since the pointer is guaranteed to be valid/initialized. - unsafe { builtin_interfaces__msg__Duration__Sequence__copy(in_seq, out_seq as *mut _) } - } - } - - impl rosidl_runtime_rs::Message for Duration { - type RmwMsg = Self; - fn into_rmw_message( - msg_cow: std::borrow::Cow<'_, Self>, - ) -> std::borrow::Cow<'_, Self::RmwMsg> { - msg_cow - } - fn from_rmw_message(msg: Self::RmwMsg) -> Self { - msg - } - } - - impl rosidl_runtime_rs::RmwMessage for Duration - where - Self: Sized, - { - const TYPE_NAME: &'static str = "builtin_interfaces/msg/Duration"; - fn get_type_support() -> *const std::ffi::c_void { - // SAFETY: No preconditions for this function. - unsafe { - rosidl_typesupport_c__get_message_type_support_handle__builtin_interfaces__msg__Duration() - } - } - } - - #[link(name = "builtin_interfaces__rosidl_typesupport_c")] - extern "C" { - fn rosidl_typesupport_c__get_message_type_support_handle__builtin_interfaces__msg__Time( - ) -> *const std::ffi::c_void; - } - - #[link(name = "builtin_interfaces__rosidl_generator_c")] - extern "C" { - fn builtin_interfaces__msg__Time__init(msg: *mut Time) -> bool; - fn builtin_interfaces__msg__Time__Sequence__init( - seq: *mut rosidl_runtime_rs::Sequence