diff --git a/.github/workflows/rust.yml b/.github/workflows/rust-minimal.yml similarity index 94% rename from .github/workflows/rust.yml rename to .github/workflows/rust-minimal.yml index 3fd48dba0..9b1a5bb49 100644 --- a/.github/workflows/rust.yml +++ b/.github/workflows/rust-minimal.yml @@ -1,4 +1,4 @@ -name: Rust +name: Rust Minimal on: push: @@ -6,7 +6,10 @@ on: pull_request: branches: [ main ] schedule: - - cron: '0 0 * * *' + # Run the CI at 02:22 UTC every Tuesday + # We pick an arbitrary time outside of most of the world's work hours + # to minimize the likelihood of running alongside a heavy workload. + - cron: '22 2 * * 2' env: CARGO_TERM_COLOR: always @@ -51,7 +54,7 @@ jobs: use-ros2-testing: ${{ matrix.ros_distribution == 'rolling' }} - name: Setup Rust - uses: dtolnay/rust-toolchain@1.74.0 + uses: dtolnay/rust-toolchain@1.75 with: components: clippy, rustfmt diff --git a/.github/workflows/rust-stable.yml b/.github/workflows/rust-stable.yml new file mode 100644 index 000000000..6dc395496 --- /dev/null +++ b/.github/workflows/rust-stable.yml @@ -0,0 +1,130 @@ +name: Rust Stable + +on: + push: + branches: [ main ] + pull_request: + branches: [ main ] + schedule: + # Run the CI at 02:22 UTC every Tuesday + # We pick an arbitrary time outside of most of the world's work hours + # to minimize the likelihood of running alongside a heavy workload. + - cron: '22 2 * * 2' + +env: + CARGO_TERM_COLOR: always + +jobs: + build: + strategy: + matrix: + ros_distribution: + - humble + - iron + - rolling + include: + # Humble Hawksbill (May 2022 - May 2027) + - docker_image: rostooling/setup-ros-docker:ubuntu-jammy-ros-humble-ros-base-latest + ros_distribution: humble + ros_version: 2 + # Iron Irwini (May 2023 - November 2024) + - docker_image: rostooling/setup-ros-docker:ubuntu-jammy-ros-iron-ros-base-latest + ros_distribution: iron + ros_version: 2 + # Rolling Ridley (June 2020 - Present) + - docker_image: rostooling/setup-ros-docker:ubuntu-jammy-ros-rolling-ros-base-latest + ros_distribution: rolling + ros_version: 2 + runs-on: ubuntu-latest + continue-on-error: ${{ matrix.ros_distribution == 'rolling' }} + container: + image: ${{ matrix.docker_image }} + steps: + - uses: actions/checkout@v4 + + - name: Search packages in this repository + id: list_packages + run: | + echo ::set-output name=package_list::$(colcon list --names-only) + + - name: Setup ROS environment + uses: ros-tooling/setup-ros@v0.7 + with: + required-ros-distributions: ${{ matrix.ros_distribution }} + use-ros2-testing: ${{ matrix.ros_distribution == 'rolling' }} + + - name: Setup Rust + uses: dtolnay/rust-toolchain@stable + with: + components: clippy, rustfmt + + - name: Install colcon-cargo and colcon-ros-cargo + run: | + 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: | + for path in $(colcon list | awk '$3 == "(ament_cargo)" { print $2 }'); do + cd $path + rustup toolchain install nightly + cargo +nightly fmt -- --check + cd - + done + + - name: Install cargo-ament-build + run: | + cargo install --debug cargo-ament-build + + - name: Build and test + id: build + uses: ros-tooling/action-ros-ci@v0.3 + with: + package-name: ${{ steps.list_packages.outputs.package_list }} + target-ros2-distro: ${{ matrix.ros_distribution }} + vcs-repo-file-url: ros2_rust_${{ matrix.ros_distribution }}.repos + + - name: Run clippy on Rust packages + run: | + cd ${{ steps.build.outputs.ros-workspace-directory-name }} + . /opt/ros/${{ matrix.ros_distribution }}/setup.sh + for path in $(colcon list | awk '$3 == "(ament_cargo)" { print $2 }'); do + cd $path + echo "Running clippy in $path" + # Run clippy for all features except generate_docs (needed for docs.rs) + if [ "$(basename $path)" = "rclrs" ]; then + cargo clippy --all-targets -F default,dyn_msg -- -D warnings + else + cargo clippy --all-targets --all-features -- -D warnings + fi + cd - + done + + - name: Run cargo test on Rust packages + run: | + cd ${{ steps.build.outputs.ros-workspace-directory-name }} + . install/setup.sh + for path in $(colcon list | awk '$3 == "(ament_cargo)" && $1 != "examples_rclrs_minimal_pub_sub" && $1 != "examples_rclrs_minimal_client_service" && $1 != "rust_pubsub" { print $2 }'); do + cd $path + echo "Running cargo test in $path" + # Run cargo test for all features except generate_docs (needed for docs.rs) + if [ "$(basename $path)" = "rclrs" ]; then + cargo test -F default,dyn_msg + elif [ "$(basename $path)" = "rosidl_runtime_rs" ]; then + cargo test -F default + else + cargo test --all-features + fi + cd - + done + + - name: Rustdoc check + run: | + cd ${{ steps.build.outputs.ros-workspace-directory-name }} + . /opt/ros/${{ matrix.ros_distribution }}/setup.sh + for path in $(colcon list | awk '$3 == "(ament_cargo)" && $1 != "examples_rclrs_minimal_pub_sub" && $1 != "examples_rclrs_minimal_client_service" && $1 != "rust_pubsub" { print $2 }'); do + cd $path + echo "Running rustdoc check in $path" + cargo rustdoc -- -D warnings + cd - + done diff --git a/rclrs/Cargo.toml b/rclrs/Cargo.toml index f489ea3f0..fe17cc990 100644 --- a/rclrs/Cargo.toml +++ b/rclrs/Cargo.toml @@ -6,7 +6,7 @@ authors = ["Esteve Fernandez ", "Nikolai Morin (), } - // If we have a throttle interval then check if we're inside or outside + // If we have a throttle duration then check if we're inside or outside // of that interval. - let interval = params.get_interval(); - if interval > std::time::Duration::ZERO { + let throttle = params.get_throttle(); + if throttle > std::time::Duration::ZERO { static LAST_LOG_TIME: OnceLock> = OnceLock::new(); let last_log_time = LAST_LOG_TIME.get_or_init(|| { Mutex::new(std::time::SystemTime::now()) @@ -136,11 +136,10 @@ macro_rules! log { if !first_time { let now = std::time::SystemTime::now(); let mut previous = last_log_time.lock().unwrap(); - if now >= *previous + interval { + if now >= *previous + throttle { *previous = now; } else { - // We are still inside the throttle interval, so just exit - // here. + // We are still inside the throttle interval, so just exit here. return; } } @@ -209,7 +208,16 @@ macro_rules! log_unconditional { // Only allocate a CString for the function name once per call to this macro. static FUNCTION_NAME: OnceLock = OnceLock::new(); let function_name = FUNCTION_NAME.get_or_init(|| { - CString::new($crate::function!()).unwrap_or( + // This call to function! is nested within two layers of closures, + // so we need to strip away those suffixes or else users will be + // misled. If we ever restructure these macros or if Rust changes + // the way it names closures, this implementation detail may need to + // change. + let function_name = $crate::function!() + .strip_suffix("::{{closure}}::{{closure}}") + .unwrap(); + + CString::new(function_name).unwrap_or( CString::new("").unwrap() ) }); @@ -278,21 +286,60 @@ pub unsafe fn impl_log( file_name: file.as_ptr(), line_number: line as usize, }; - static FORMAT_CSTR: OnceLock = OnceLock::new(); - let format_cstr = FORMAT_CSTR.get_or_init(|| CString::new("%s").unwrap()); + + static FORMAT_STRING: OnceLock = OnceLock::new(); + let format_string = FORMAT_STRING.get_or_init(|| CString::new("%s").unwrap()); let severity = severity.as_native(); let _lifecycle = ENTITY_LIFECYCLE_MUTEX.lock().unwrap(); - // SAFETY: Global variables are protected via ENTITY_LIFECYCLE_MUTEX, no other preconditions are required - unsafe { - rcutils_log( - &location, - severity as i32, - logger_name.as_ptr(), - format_cstr.as_ptr(), - message.as_ptr(), - ); + + #[cfg(test)] + { + // If we are compiling for testing purposes, when the default log + // output handler is being used we need to use the format_string, + // but when our custom log output handler is being used we need to + // pass the raw message string so that it can be viewed by the + // custom log output handler, allowing us to use it for test assertions. + if log_handler::is_using_custom_handler() { + // We are using the custom log handler that is only used during + // logging tests, so pass the raw message as the format string. + unsafe { + // SAFETY: The global mutex is locked as _lifecycle + rcutils_log( + &location, + severity as i32, + logger_name.as_ptr(), + message.as_ptr(), + ); + } + } else { + // We are using the normal log handler so call rcutils_log the normal way. + unsafe { + // SAFETY: The global mutex is locked as _lifecycle + rcutils_log( + &location, + severity as i32, + logger_name.as_ptr(), + format_string.as_ptr(), + message.as_ptr(), + ); + } + } + } + + #[cfg(not(test))] + { + unsafe { + // SAFETY: The global mutex is locked as _lifecycle + rcutils_log( + &location, + severity as i32, + logger_name.as_ptr(), + format_string.as_ptr(), + message.as_ptr(), + ); + } } }; @@ -380,25 +427,121 @@ macro_rules! function { #[cfg(test)] mod tests { - use crate::{test_helpers::*, *}; + use crate::{log_handler::*, test_helpers::*, *}; + use std::sync::Mutex; #[test] fn test_logging_macros() -> Result<(), RclrsError> { + // This test ensures that strings which are being sent to the logger are + // being sanitized correctly. Rust generally and our logging macro in + // particular do not use C-style formatting strings, but rcutils expects + // to receive C-style formatting strings alongside variadic arguments + // that describe how to fill in the formatting. + // + // If we pass the final string into rcutils as the format with no + // variadic arguments, then it may trigger a crash or undefined behavior + // if the message happens to contain any % symbols. In particular %n + // will trigger a crash when no variadic arguments are given because it + // attempts to write to a buffer. If no buffer is given, a seg fault + // happens. + log!("please do not crash", "%n"); + let graph = construct_test_graph("test_logging_macros")?; + + let log_collection: Arc>>> = Arc::new(Mutex::new(Vec::new())); + let inner_log_collection = log_collection.clone(); + + log_handler::set_logging_output_handler(move |log_entry: log_handler::LogEntry| { + inner_log_collection + .lock() + .unwrap() + .push(log_entry.into_owned()); + }) + .unwrap(); + + let last_logger_name = || { + log_collection + .lock() + .unwrap() + .last() + .unwrap() + .logger_name + .clone() + }; + + let last_message = || { + log_collection + .lock() + .unwrap() + .last() + .unwrap() + .message + .clone() + }; + + let last_location = || { + log_collection + .lock() + .unwrap() + .last() + .unwrap() + .location + .clone() + }; + + let last_severity = || log_collection.lock().unwrap().last().unwrap().severity; + + let count_message = |message: &str| { + let mut count = 0; + for log in log_collection.lock().unwrap().iter() { + if log.message == message { + count += 1; + } + } + count + }; + let node = graph.node1; log!(&*node, "Logging with node dereference"); + assert_eq!(last_logger_name(), node.logger().name()); + assert_eq!(last_message(), "Logging with node dereference"); + assert_eq!(last_severity(), LogSeverity::Info); + assert_eq!( + last_location().function_name, + "rclrs::logging::tests::test_logging_macros", + ); for _ in 0..10 { log!(node.once(), "Logging once"); } + assert_eq!(count_message("Logging once"), 1); + assert_eq!(last_severity(), LogSeverity::Info); log!(node.logger(), "Logging with node logger"); + assert_eq!(last_message(), "Logging with node logger"); + assert_eq!(last_severity(), LogSeverity::Info); + log!(node.debug(), "Debug from node"); + // The default severity level is Info so we should not see the last message + assert_ne!(last_message(), "Debug from node"); + assert_ne!(last_severity(), LogSeverity::Debug); + log!(node.info(), "Info from node"); + assert_eq!(last_message(), "Info from node"); + assert_eq!(last_severity(), LogSeverity::Info); + log!(node.warn(), "Warn from node"); + assert_eq!(last_message(), "Warn from node"); + assert_eq!(last_severity(), LogSeverity::Warn); + log!(node.error(), "Error from node"); + assert_eq!(last_message(), "Error from node"); + assert_eq!(last_severity(), LogSeverity::Error); + log!(node.fatal(), "Fatal from node"); + assert_eq!(last_message(), "Fatal from node"); + assert_eq!(last_severity(), LogSeverity::Fatal); log_debug!(node.logger(), "log_debug macro"); log_info!(node.logger(), "log_info macro"); @@ -412,26 +555,44 @@ mod tests { for i in 0..3 { log!(node.warn().skip_first(), "Formatted warning #{}", i); } + assert_eq!(count_message("Formatted warning #0"), 0); + assert_eq!(count_message("Formatted warning #1"), 1); + assert_eq!(count_message("Formatted warning #2"), 1); node.logger().set_level(LogSeverity::Debug).unwrap(); log_debug!(node.logger(), "This debug message appears"); + assert_eq!(last_message(), "This debug message appears"); + assert_eq!(last_severity(), LogSeverity::Debug); + node.logger().set_level(LogSeverity::Info).unwrap(); - log_debug!(node.logger(), "This debug message does not"); + log_debug!(node.logger(), "This debug message does not appear"); + assert_ne!(last_message(), "This debug message does not appear"); log!("custom logger name", "message for custom logger"); + assert_eq!(last_logger_name(), "custom logger name"); + assert_eq!(last_message(), "message for custom logger"); + for _ in 0..3 { log!( - "custom logger name".once(), - "one-time message for custom logger" + "custom logger name once".once(), + "one-time message for custom logger", ); } + assert_eq!(last_logger_name(), "custom logger name once"); + assert_eq!(last_severity(), LogSeverity::Info); + assert_eq!(count_message("one-time message for custom logger"), 1); for _ in 0..3 { log!( - "custom logger name".error().skip_first(), + "custom logger name skip".error().skip_first(), "error for custom logger", ); } + assert_eq!(last_logger_name(), "custom logger name skip"); + assert_eq!(last_severity(), LogSeverity::Error); + assert_eq!(count_message("error for custom logger"), 2); + + reset_logging_output_handler(); Ok(()) } diff --git a/rclrs/src/logging/log_params.rs b/rclrs/src/logging/log_params.rs index d8cbc8995..79197cd98 100644 --- a/rclrs/src/logging/log_params.rs +++ b/rclrs/src/logging/log_params.rs @@ -10,13 +10,12 @@ pub struct LogParams<'a> { severity: LogSeverity, /// Specify when a log message should be published (See[`LoggingOccurrence`] above) occurs: LogOccurrence, - /// Specify the publication interval of the message. A value of ZERO (0) indicates that the - /// message should be published every time, otherwise, the message will only be published once - /// the specified interval has elapsed. - /// This field is typically used to limit the output from high-frequency messages, e.g. instead - /// of publishing a log message every 10 milliseconds, the `publish_interval` can be configured - /// such that the message is published every 10 seconds. - interval: Duration, + /// Specify a publication throttling interval for the message. A value of ZERO (0) indicates that the + /// message should not be throttled. Otherwise, the message will only be published once the specified + /// interval has elapsed. This field is typically used to limit the output from high-frequency messages, + /// e.g. if `log!(logger.throttle(Duration::from_secs(1)), "message");` is called every 10ms, it will + /// nevertheless only be published once per second. + throttle: Duration, /// The log message will only published if the specified expression evaluates to true only_if: bool, } @@ -28,7 +27,7 @@ impl<'a> LogParams<'a> { logger_name, severity: Default::default(), occurs: Default::default(), - interval: Duration::new(0, 0), + throttle: Duration::new(0, 0), only_if: true, } } @@ -48,9 +47,9 @@ impl<'a> LogParams<'a> { self.occurs } - /// Get the interval - pub fn get_interval(&self) -> Duration { - self.interval + /// Get the throttle interval duration + pub fn get_throttle(&self) -> Duration { + self.throttle } /// Get the arbitrary filter set by the user @@ -88,14 +87,14 @@ pub trait ToLogParams<'a>: Sized { params } - /// Set an interval during which this log will not publish. A value of zero - /// will never block the message from being published, and this is the + /// Set a throttling interval during which this log will not publish. A value + /// of zero will never block the message from being published, and this is the /// default behavior. /// /// A negative duration is not valid, but will be treated as a zero duration. - fn interval(self, interval: Duration) -> LogParams<'a> { + fn throttle(self, throttle: Duration) -> LogParams<'a> { let mut params = self.to_log_params(); - params.interval = interval; + params.throttle = throttle; params } @@ -103,7 +102,7 @@ pub trait ToLogParams<'a>: Sized { /// this function. /// /// Other factors may prevent the log from being published if a `true` is - /// passed in, such as `ToLogParams::interval` or `ToLogParams::once` + /// passed in, such as `ToLogParams::throttle` or `ToLogParams::once` /// filtering the log. fn only_if(self, only_if: bool) -> LogParams<'a> { let mut params = self.to_log_params(); @@ -162,8 +161,13 @@ pub enum LoggerName<'a> { } /// Logging severity. +// +// TODO(@mxgrey): Consider whether this is redundant with RCUTILS_LOG_SEVERITY. +// Perhaps we can customize the output of bindgen to automatically change the name +// of RCUTILS_LOG_SEVERITY to just LogSeverity so it's more idiomatic and then +// export it from the rclrs module. #[doc(hidden)] -#[derive(Debug, Clone, Copy)] +#[derive(Debug, Clone, Copy, PartialEq, Eq, PartialOrd, Ord, Hash)] pub enum LogSeverity { /// Use the severity level of the parent logger (or the root logger if the /// current logger has no parent) @@ -199,6 +203,22 @@ impl LogSeverity { LogSeverity::Fatal => RCUTILS_LOG_SEVERITY_FATAL, } } + + /// This is only used by the log output handler during testing, so it will + /// not be compiled when testing is not configured + #[cfg(test)] + pub(crate) fn from_native(native: i32) -> Self { + use crate::rcl_bindings::rcl_log_severity_t::*; + match native { + _ if native == RCUTILS_LOG_SEVERITY_UNSET as i32 => LogSeverity::Unset, + _ if native == RCUTILS_LOG_SEVERITY_DEBUG as i32 => LogSeverity::Debug, + _ if native == RCUTILS_LOG_SEVERITY_INFO as i32 => LogSeverity::Info, + _ if native == RCUTILS_LOG_SEVERITY_WARN as i32 => LogSeverity::Warn, + _ if native == RCUTILS_LOG_SEVERITY_ERROR as i32 => LogSeverity::Error, + _ if native == RCUTILS_LOG_SEVERITY_FATAL as i32 => LogSeverity::Fatal, + _ => panic!("Invalid native severity received: {}", native), + } + } } impl Default for LogSeverity { diff --git a/rclrs/src/logging/logging_configuration.rs b/rclrs/src/logging/logging_configuration.rs index 2f7014273..1012608ec 100644 --- a/rclrs/src/logging/logging_configuration.rs +++ b/rclrs/src/logging/logging_configuration.rs @@ -1,12 +1,6 @@ use std::sync::{Arc, Mutex, OnceLock, Weak}; -use crate::{ - rcl_bindings::{ - rcl_arguments_t, rcl_context_t, rcl_logging_configure, rcl_logging_fini, - rcutils_get_default_allocator, - }, - RclrsError, ToResult, ENTITY_LIFECYCLE_MUTEX, -}; +use crate::{rcl_bindings::*, RclrsError, ToResult, ENTITY_LIFECYCLE_MUTEX}; struct LoggingConfiguration { lifecycle: Mutex>, @@ -55,3 +49,203 @@ impl Drop for LoggingLifecycle { } } } + +#[cfg(test)] +pub(crate) mod log_handler { + //! This module provides a way to customize how log output is handled. For + //! now we are not making this a private API and are only using it for tests + //! in rclrs. We can consider making it public in the future, but we should + //! put more consideration into the API before doing so, and more crucially + //! we need to figure out a way to process C-style formatting strings with + //! a [`va_list`] from inside of Rust, which seems to be very messy. + + use std::{ + borrow::Cow, + ffi::CStr, + sync::{ + atomic::{AtomicBool, Ordering}, + OnceLock, + }, + }; + + use crate::{rcl_bindings::*, LogSeverity, ENTITY_LIFECYCLE_MUTEX}; + + /// Global variable that allows a custom log handler to be set. This log + /// handler will be applied throughout the entire application and cannot be + /// replaced with a different custom log handler. If you want to be able to + /// change the log handler over the lifetime of your application, you should + /// design your own custom handler with an Arc> inside that allows + /// its own behavior to be modified. + static LOGGING_OUTPUT_HANDLER: OnceLock = OnceLock::new(); + + /// Alias for an arbitrary log handler that is compatible with raw rcl types + pub(crate) type RawLogHandler = Box< + dyn Fn( + *const rcutils_log_location_t, // location + std::os::raw::c_int, // severity + *const std::os::raw::c_char, // logger name + rcutils_time_point_value_t, // timestamp + *const std::os::raw::c_char, // format + *mut va_list, // formatting arguments + ) + + 'static + + Send + + Sync, + >; + + /// This is an idiomatic representation of all the information for a log entry + #[derive(Clone)] + pub(crate) struct LogEntry<'a> { + pub(crate) location: LogLocation<'a>, + pub(crate) severity: LogSeverity, + pub(crate) logger_name: Cow<'a, str>, + pub(crate) timestamp: i64, + pub(crate) message: Cow<'a, str>, + } + + impl<'a> LogEntry<'a> { + /// Change the entry from something borrowed into something owned + pub(crate) fn into_owned(self) -> LogEntry<'static> { + LogEntry { + location: self.location.into_owned(), + severity: self.severity, + logger_name: Cow::Owned(self.logger_name.into_owned()), + timestamp: self.timestamp, + message: Cow::Owned(self.message.into_owned()), + } + } + } + + /// Rust-idiomatic representation of the location of a log + #[derive(Debug, Clone)] + pub(crate) struct LogLocation<'a> { + pub function_name: Cow<'a, str>, + pub file_name: Cow<'a, str>, + pub line_number: usize, + } + + impl<'a> LogLocation<'a> { + pub(crate) fn into_owned(self) -> LogLocation<'static> { + LogLocation { + function_name: Cow::Owned(self.function_name.into_owned()), + file_name: Cow::Owned(self.file_name.into_owned()), + line_number: self.line_number, + } + } + } + + #[derive(Debug)] + pub(crate) struct OutputHandlerAlreadySet; + + static USING_CUSTOM_HANDLER: OnceLock = OnceLock::new(); + + /// Set an idiomatic log hander + pub(crate) fn set_logging_output_handler( + handler: impl Fn(LogEntry) + 'static + Send + Sync, + ) -> Result<(), OutputHandlerAlreadySet> { + let raw_handler = Box::new( + move |raw_location: *const rcutils_log_location_t, + raw_severity: std::os::raw::c_int, + raw_logger_name: *const std::os::raw::c_char, + raw_timestamp: rcutils_time_point_value_t, + raw_format: *const std::os::raw::c_char, + // NOTE: In the rclrs logging test we are choosing to format + // the full message in advance when using the custom handler, + // so the format field always contains the finished formatted + // message. Therefore we can just ignore the raw formatting + // arguments. + _raw_formatting_arguments: *mut va_list| { + unsafe { + // NOTE: We use .unwrap() extensively inside this function because + // it only gets used during tests. We should reconsider this if + // we ever make this public. + let location = LogLocation { + function_name: Cow::Borrowed( + CStr::from_ptr((*raw_location).function_name) + .to_str() + .unwrap(), + ), + file_name: Cow::Borrowed( + CStr::from_ptr((*raw_location).file_name).to_str().unwrap(), + ), + line_number: (*raw_location).line_number, + }; + let severity = LogSeverity::from_native(raw_severity); + let logger_name = + Cow::Borrowed(CStr::from_ptr(raw_logger_name).to_str().unwrap()); + let timestamp: i64 = raw_timestamp; + let message = Cow::Borrowed(CStr::from_ptr(raw_format).to_str().unwrap()); + handler(LogEntry { + location, + severity, + logger_name, + timestamp, + message, + }); + } + }, + ); + + set_raw_logging_output_handler(raw_handler) + } + + /// Set the logging output handler directly + pub(crate) fn set_raw_logging_output_handler( + handler: RawLogHandler, + ) -> Result<(), OutputHandlerAlreadySet> { + LOGGING_OUTPUT_HANDLER + .set(handler) + .map_err(|_| OutputHandlerAlreadySet)?; + let _lifecycle = ENTITY_LIFECYCLE_MUTEX.lock().unwrap(); + unsafe { + // SAFETY: + // - We have locked the global mutex + rcutils_logging_set_output_handler(Some(rclrs_logging_output_handler)); + } + + USING_CUSTOM_HANDLER + .get_or_init(|| AtomicBool::new(false)) + .store(true, Ordering::Release); + Ok(()) + } + + pub(crate) fn is_using_custom_handler() -> bool { + USING_CUSTOM_HANDLER + .get_or_init(|| AtomicBool::new(false)) + .load(Ordering::Acquire) + } + + /// This function exists so that we can give a raw function pointer to + /// rcutils_logging_set_output_handler, which is needed by its API. + extern "C" fn rclrs_logging_output_handler( + location: *const rcutils_log_location_t, + severity: std::os::raw::c_int, + logger_name: *const std::os::raw::c_char, + timestamp: rcutils_time_point_value_t, + message: *const std::os::raw::c_char, + logging_output: *mut va_list, + ) { + let handler = LOGGING_OUTPUT_HANDLER.get().unwrap(); + (*handler)( + location, + severity, + logger_name, + timestamp, + message, + logging_output, + ); + } + + /// Reset the logging output handler to the default one + pub(crate) fn reset_logging_output_handler() { + let _lifecycle = ENTITY_LIFECYCLE_MUTEX.lock().unwrap(); + unsafe { + // SAFETY: The global mutex is locked. No other precondition is + // required. + rcutils_logging_set_output_handler(Some(rcl_logging_multiple_output_handler)); + } + USING_CUSTOM_HANDLER + .get_or_init(|| AtomicBool::new(false)) + .store(false, Ordering::Release); + } +} diff --git a/rclrs/src/parameter.rs b/rclrs/src/parameter.rs index c7740a2d5..3c49993b3 100644 --- a/rclrs/src/parameter.rs +++ b/rclrs/src/parameter.rs @@ -27,18 +27,18 @@ use std::{ // Among the most relevant ones: // // * Parameter declaration returns an object which will be the main accessor to the parameter, -// providing getters and, except for read only parameters, setters. Object destruction will -// undeclare the parameter. +// providing getters and, except for read only parameters, setters. Object destruction will +// undeclare the parameter. // * Declaration uses a builder pattern to specify ranges, description, human readable constraints -// instead of an ParameterDescriptor argument. +// instead of an ParameterDescriptor argument. // * Parameters properties of read only and dynamic are embedded in their type rather than being a -// boolean parameter. +// boolean parameter. // * There are no runtime exceptions for common cases such as undeclared parameter, already -// declared, or uninitialized. +// declared, or uninitialized. // * There is no "parameter not set" type, users can instead decide to have a `Mandatory` parameter -// that must always have a value or `Optional` parameter that can be unset. +// that must always have a value or `Optional` parameter that can be unset. // * Explicit API for access to undeclared parameters by having a -// `node.use_undeclared_parameters()` API that allows access to all parameters. +// `node.use_undeclared_parameters()` API that allows access to all parameters. #[derive(Clone, Debug)] struct ParameterOptionsStorage { @@ -703,9 +703,9 @@ impl<'a> Parameters<'a> { /// Returns: /// * `Ok(())` if setting was successful. /// * [`Err(DeclarationError::TypeMismatch)`] if the type of the requested value is different - /// from the parameter's type. + /// from the parameter's type. /// * [`Err(DeclarationError::OutOfRange)`] if the requested value is out of the parameter's - /// range. + /// range. /// * [`Err(DeclarationError::ReadOnly)`] if the parameter is read only. pub fn set( &self, diff --git a/rclrs/src/parameter/range.rs b/rclrs/src/parameter/range.rs index 96f66d6e3..6a46d2ff0 100644 --- a/rclrs/src/parameter/range.rs +++ b/rclrs/src/parameter/range.rs @@ -32,7 +32,7 @@ impl From<()> for ParameterRanges { /// Usually only one of these ranges will be applied, but all have to be stored since: /// /// * A dynamic parameter can change its type at runtime, in which case a different range could be -/// applied. +/// applied. /// * Introspection through service calls requires all the ranges to be reported to the user. #[derive(Clone, Debug, Default)] pub struct ParameterRanges { diff --git a/rclrs/src/subscription.rs b/rclrs/src/subscription.rs index 36c241d19..fbd518c21 100644 --- a/rclrs/src/subscription.rs +++ b/rclrs/src/subscription.rs @@ -272,9 +272,7 @@ where } fn execute(&self) -> Result<(), RclrsError> { - // Immediately evaluated closure, to handle SubscriptionTakeFailed - // outside this match - match (|| { + let evaluate = || { match &mut *self.callback.lock().unwrap() { AnySubscriptionCallback::Regular(cb) => { let (msg, _) = self.take()?; @@ -302,7 +300,11 @@ where } } Ok(()) - })() { + }; + + // Immediately evaluated closure, to handle SubscriptionTakeFailed + // outside this match + match evaluate() { Err(RclrsError::RclError { code: RclReturnCode::SubscriptionTakeFailed, .. diff --git a/rclrs/src/subscription/message_info.rs b/rclrs/src/subscription/message_info.rs index 010bf28ec..1adecd3ec 100644 --- a/rclrs/src/subscription/message_info.rs +++ b/rclrs/src/subscription/message_info.rs @@ -4,26 +4,28 @@ use crate::rcl_bindings::*; /// An identifier for a publisher in the local context. /// -/// To quote the `rmw` documentation: +/// To quote the [`rmw` documentation][1]: /// /// > The identifier uniquely identifies the publisher for the local context, but -/// it will not necessarily be the same identifier given in other contexts or processes -/// for the same publisher. -/// Therefore the identifier will uniquely identify the publisher within your application -/// but may disagree about the identifier for that publisher when compared to another -/// application. -/// Even with this limitation, when combined with the publisher sequence number it can -/// uniquely identify a message within your local context. -/// Publisher GIDs generated by the RMW implementation could collide at some point, in which -/// case it is not possible to distinguish which publisher sent the message. -/// The details of how GIDs are generated are RMW implementation dependent. -/// +/// > it will not necessarily be the same identifier given in other contexts or processes +/// > for the same publisher. +/// > Therefore the identifier will uniquely identify the publisher within your application +/// > but may disagree about the identifier for that publisher when compared to another +/// > application. +/// > Even with this limitation, when combined with the publisher sequence number it can +/// > uniquely identify a message within your local context. +/// > Publisher GIDs generated by the RMW implementation could collide at some point, in which +/// > case it is not possible to distinguish which publisher sent the message. +/// > The details of how GIDs are generated are RMW implementation dependent. +/// > /// > It is possible the the RMW implementation needs to reuse a publisher GID, -/// due to running out of unique identifiers or some other constraint, in which case -/// the RMW implementation may document what happens in that case, but that -/// behavior is not defined here. -/// However, this should be avoided, if at all possible, by the RMW implementation, -/// and should be unlikely to happen in practice. +/// > due to running out of unique identifiers or some other constraint, in which case +/// > the RMW implementation may document what happens in that case, but that +/// > behavior is not defined here. +/// > However, this should be avoided, if at all possible, by the RMW implementation, +/// > and should be unlikely to happen in practice. +/// +/// [1]: https://docs.ros.org/en/rolling/p/rmw/generated/structrmw__message__info__s.html#_CPPv4N18rmw_message_info_s13publisher_gidE #[derive(Clone, Debug, PartialEq, Eq)] pub struct PublisherGid { /// Bytes identifying a publisher in the RMW implementation. diff --git a/rclrs/src/vendor/action_msgs/mod.rs b/rclrs/src/vendor/action_msgs/mod.rs new file mode 100644 index 000000000..f43deda46 --- /dev/null +++ b/rclrs/src/vendor/action_msgs/mod.rs @@ -0,0 +1,7 @@ +#![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 new file mode 100644 index 000000000..32c7b7089 --- /dev/null +++ b/rclrs/src/vendor/action_msgs/msg.rs @@ -0,0 +1,457 @@ +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 new file mode 100644 index 000000000..f4cf6fe53 --- /dev/null +++ b/rclrs/src/vendor/action_msgs/srv.rs @@ -0,0 +1,375 @@ +#[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 index a6365b3b8..4c61d56a1 100644 --- a/rclrs/src/vendor/builtin_interfaces/mod.rs +++ b/rclrs/src/vendor/builtin_interfaces/mod.rs @@ -1,3 +1,5 @@ #![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 index 371803171..fd2ec47cd 100644 --- a/rclrs/src/vendor/builtin_interfaces/msg.rs +++ b/rclrs/src/vendor/builtin_interfaces/msg.rs @@ -5,7 +5,7 @@ pub mod rmw { #[link(name = "builtin_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__builtin_interfaces__msg__Duration( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "builtin_interfaces__rosidl_generator_c")] @@ -80,7 +80,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "builtin_interfaces/msg/Duration"; - fn get_type_support() -> *const std::os::raw::c_void { + 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() @@ -91,7 +91,7 @@ pub mod rmw { #[link(name = "builtin_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__builtin_interfaces__msg__Time( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "builtin_interfaces__rosidl_generator_c")] @@ -166,7 +166,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "builtin_interfaces/msg/Time"; - fn get_type_support() -> *const std::os::raw::c_void { + 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__Time( diff --git a/rclrs/src/vendor/mod.rs b/rclrs/src/vendor/mod.rs index fe87087b1..df638ee7f 100644 --- a/rclrs/src/vendor/mod.rs +++ b/rclrs/src/vendor/mod.rs @@ -1,7 +1,8 @@ //! Created by vendor_interfaces.py #![allow(dead_code)] -#![allow(clippy::derive_partial_eq_without_eq)] +pub mod action_msgs; pub mod builtin_interfaces; pub mod rcl_interfaces; pub mod rosgraph_msgs; +pub mod unique_identifier_msgs; diff --git a/rclrs/src/vendor/rcl_interfaces/mod.rs b/rclrs/src/vendor/rcl_interfaces/mod.rs index ff96b59a9..f43deda46 100644 --- a/rclrs/src/vendor/rcl_interfaces/mod.rs +++ b/rclrs/src/vendor/rcl_interfaces/mod.rs @@ -1,4 +1,6 @@ #![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/rcl_interfaces/msg.rs b/rclrs/src/vendor/rcl_interfaces/msg.rs index 39c029ae1..7f6dbcc58 100644 --- a/rclrs/src/vendor/rcl_interfaces/msg.rs +++ b/rclrs/src/vendor/rcl_interfaces/msg.rs @@ -5,7 +5,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__FloatingPointRange( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -83,7 +83,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/msg/FloatingPointRange"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__FloatingPointRange() @@ -94,7 +94,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__IntegerRange( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -170,7 +170,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/msg/IntegerRange"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__IntegerRange() @@ -181,7 +181,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__ListParametersResult( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -260,7 +260,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/msg/ListParametersResult"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__ListParametersResult() @@ -271,7 +271,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__Log( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -364,7 +364,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/msg/Log"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__Log() @@ -375,7 +375,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__ParameterDescriptor( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -464,7 +464,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/msg/ParameterDescriptor"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__ParameterDescriptor() @@ -475,7 +475,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__ParameterEventDescriptors( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -566,7 +566,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/msg/ParameterEventDescriptors"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__ParameterEventDescriptors() @@ -577,7 +577,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__ParameterEvent( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -660,7 +660,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/msg/ParameterEvent"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__ParameterEvent() @@ -671,7 +671,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__Parameter( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -746,7 +746,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/msg/Parameter"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__Parameter() @@ -757,7 +757,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__ParameterType( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -845,7 +845,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/msg/ParameterType"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__ParameterType() @@ -856,7 +856,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__ParameterValue( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -941,7 +941,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/msg/ParameterValue"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__ParameterValue() @@ -952,7 +952,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__SetParametersResult( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -1029,7 +1029,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/msg/SetParametersResult"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__SetParametersResult() diff --git a/rclrs/src/vendor/rcl_interfaces/srv.rs b/rclrs/src/vendor/rcl_interfaces/srv.rs index 221d7eac1..3f43398a1 100644 --- a/rclrs/src/vendor/rcl_interfaces/srv.rs +++ b/rclrs/src/vendor/rcl_interfaces/srv.rs @@ -582,7 +582,7 @@ impl rosidl_runtime_rs::Message for SetParameters_Response { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__DescribeParameters( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } // Corresponds to rcl_interfaces__srv__DescribeParameters @@ -592,7 +592,7 @@ impl rosidl_runtime_rs::Service for DescribeParameters { type Request = crate::vendor::rcl_interfaces::srv::DescribeParameters_Request; type Response = crate::vendor::rcl_interfaces::srv::DescribeParameters_Response; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__DescribeParameters() @@ -603,7 +603,7 @@ impl rosidl_runtime_rs::Service for DescribeParameters { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__GetParameters( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } // Corresponds to rcl_interfaces__srv__GetParameters @@ -613,7 +613,7 @@ impl rosidl_runtime_rs::Service for GetParameters { type Request = crate::vendor::rcl_interfaces::srv::GetParameters_Request; type Response = crate::vendor::rcl_interfaces::srv::GetParameters_Response; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__GetParameters() @@ -624,7 +624,7 @@ impl rosidl_runtime_rs::Service for GetParameters { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__GetParameterTypes( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } // Corresponds to rcl_interfaces__srv__GetParameterTypes @@ -634,7 +634,7 @@ impl rosidl_runtime_rs::Service for GetParameterTypes { type Request = crate::vendor::rcl_interfaces::srv::GetParameterTypes_Request; type Response = crate::vendor::rcl_interfaces::srv::GetParameterTypes_Response; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__GetParameterTypes() @@ -645,7 +645,7 @@ impl rosidl_runtime_rs::Service for GetParameterTypes { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__ListParameters( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } // Corresponds to rcl_interfaces__srv__ListParameters @@ -655,7 +655,7 @@ impl rosidl_runtime_rs::Service for ListParameters { type Request = crate::vendor::rcl_interfaces::srv::ListParameters_Request; type Response = crate::vendor::rcl_interfaces::srv::ListParameters_Response; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__ListParameters() @@ -666,7 +666,7 @@ impl rosidl_runtime_rs::Service for ListParameters { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__SetParametersAtomically( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } // Corresponds to rcl_interfaces__srv__SetParametersAtomically @@ -676,7 +676,7 @@ impl rosidl_runtime_rs::Service for SetParametersAtomically { type Request = crate::vendor::rcl_interfaces::srv::SetParametersAtomically_Request; type Response = crate::vendor::rcl_interfaces::srv::SetParametersAtomically_Response; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__SetParametersAtomically() @@ -687,7 +687,7 @@ impl rosidl_runtime_rs::Service for SetParametersAtomically { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__SetParameters( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } // Corresponds to rcl_interfaces__srv__SetParameters @@ -697,7 +697,7 @@ impl rosidl_runtime_rs::Service for SetParameters { type Request = crate::vendor::rcl_interfaces::srv::SetParameters_Request; type Response = crate::vendor::rcl_interfaces::srv::SetParameters_Response; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__SetParameters() @@ -706,13 +706,14 @@ impl rosidl_runtime_rs::Service for SetParameters { } pub mod rmw { + #[cfg(feature = "serde")] use serde::{Deserialize, Serialize}; #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__DescribeParameters_Request( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -799,7 +800,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/srv/DescribeParameters_Request"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__DescribeParameters_Request() @@ -810,7 +811,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__DescribeParameters_Response( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -902,7 +903,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/srv/DescribeParameters_Response"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__DescribeParameters_Response() @@ -913,7 +914,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__GetParameters_Request( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -996,7 +997,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/srv/GetParameters_Request"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__GetParameters_Request() @@ -1007,7 +1008,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__GetParameters_Response( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -1091,7 +1092,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/srv/GetParameters_Response"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__GetParameters_Response() @@ -1102,7 +1103,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__GetParameterTypes_Request( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -1185,7 +1186,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/srv/GetParameterTypes_Request"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__GetParameterTypes_Request() @@ -1196,7 +1197,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__GetParameterTypes_Response( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -1283,7 +1284,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/srv/GetParameterTypes_Response"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__GetParameterTypes_Response() @@ -1294,7 +1295,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__ListParameters_Request( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -1382,7 +1383,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/srv/ListParameters_Request"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__ListParameters_Request() @@ -1393,7 +1394,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__ListParameters_Response( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -1476,7 +1477,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/srv/ListParameters_Response"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__ListParameters_Response() @@ -1487,7 +1488,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__SetParametersAtomically_Request( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -1576,7 +1577,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/srv/SetParametersAtomically_Request"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__SetParametersAtomically_Request() @@ -1587,7 +1588,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__SetParametersAtomically_Response( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -1676,7 +1677,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/srv/SetParametersAtomically_Response"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__SetParametersAtomically_Response() @@ -1687,7 +1688,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__SetParameters_Request( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -1771,7 +1772,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/srv/SetParameters_Request"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__SetParameters_Request() @@ -1782,7 +1783,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__SetParameters_Response( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rcl_interfaces__rosidl_generator_c")] @@ -1867,7 +1868,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rcl_interfaces/srv/SetParameters_Response"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__srv__SetParameters_Response() @@ -1878,7 +1879,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__DescribeParameters( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } // Corresponds to rcl_interfaces__srv__DescribeParameters @@ -1888,7 +1889,7 @@ pub mod rmw { type Request = crate::vendor::rcl_interfaces::srv::rmw::DescribeParameters_Request; type Response = crate::vendor::rcl_interfaces::srv::rmw::DescribeParameters_Response; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__DescribeParameters() @@ -1899,7 +1900,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__GetParameters( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } // Corresponds to rcl_interfaces__srv__GetParameters @@ -1909,7 +1910,7 @@ pub mod rmw { type Request = crate::vendor::rcl_interfaces::srv::rmw::GetParameters_Request; type Response = crate::vendor::rcl_interfaces::srv::rmw::GetParameters_Response; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__GetParameters() @@ -1920,7 +1921,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__GetParameterTypes( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } // Corresponds to rcl_interfaces__srv__GetParameterTypes @@ -1930,7 +1931,7 @@ pub mod rmw { type Request = crate::vendor::rcl_interfaces::srv::rmw::GetParameterTypes_Request; type Response = crate::vendor::rcl_interfaces::srv::rmw::GetParameterTypes_Response; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__GetParameterTypes() @@ -1941,7 +1942,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__ListParameters( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } // Corresponds to rcl_interfaces__srv__ListParameters @@ -1951,7 +1952,7 @@ pub mod rmw { type Request = crate::vendor::rcl_interfaces::srv::rmw::ListParameters_Request; type Response = crate::vendor::rcl_interfaces::srv::rmw::ListParameters_Response; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__ListParameters() @@ -1962,7 +1963,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__SetParametersAtomically( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } // Corresponds to rcl_interfaces__srv__SetParametersAtomically @@ -1972,7 +1973,7 @@ pub mod rmw { type Request = crate::vendor::rcl_interfaces::srv::rmw::SetParametersAtomically_Request; type Response = crate::vendor::rcl_interfaces::srv::rmw::SetParametersAtomically_Response; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__SetParametersAtomically() @@ -1983,7 +1984,7 @@ pub mod rmw { #[link(name = "rcl_interfaces__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__SetParameters( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } // Corresponds to rcl_interfaces__srv__SetParameters @@ -1993,7 +1994,7 @@ pub mod rmw { type Request = crate::vendor::rcl_interfaces::srv::rmw::SetParameters_Request; type Response = crate::vendor::rcl_interfaces::srv::rmw::SetParameters_Response; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_service_type_support_handle__rcl_interfaces__srv__SetParameters() diff --git a/rclrs/src/vendor/rosgraph_msgs/mod.rs b/rclrs/src/vendor/rosgraph_msgs/mod.rs index a6365b3b8..4c61d56a1 100644 --- a/rclrs/src/vendor/rosgraph_msgs/mod.rs +++ b/rclrs/src/vendor/rosgraph_msgs/mod.rs @@ -1,3 +1,5 @@ #![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/rosgraph_msgs/msg.rs b/rclrs/src/vendor/rosgraph_msgs/msg.rs index 1f4af8b70..6190bfe62 100644 --- a/rclrs/src/vendor/rosgraph_msgs/msg.rs +++ b/rclrs/src/vendor/rosgraph_msgs/msg.rs @@ -5,7 +5,7 @@ pub mod rmw { #[link(name = "rosgraph_msgs__rosidl_typesupport_c")] extern "C" { fn rosidl_typesupport_c__get_message_type_support_handle__rosgraph_msgs__msg__Clock( - ) -> *const std::os::raw::c_void; + ) -> *const std::ffi::c_void; } #[link(name = "rosgraph_msgs__rosidl_generator_c")] @@ -77,7 +77,7 @@ pub mod rmw { Self: Sized, { const TYPE_NAME: &'static str = "rosgraph_msgs/msg/Clock"; - fn get_type_support() -> *const std::os::raw::c_void { + fn get_type_support() -> *const std::ffi::c_void { // SAFETY: No preconditions for this function. unsafe { rosidl_typesupport_c__get_message_type_support_handle__rosgraph_msgs__msg__Clock() diff --git a/rclrs/src/vendor/unique_identifier_msgs/mod.rs b/rclrs/src/vendor/unique_identifier_msgs/mod.rs new file mode 100644 index 000000000..4c61d56a1 --- /dev/null +++ b/rclrs/src/vendor/unique_identifier_msgs/mod.rs @@ -0,0 +1,5 @@ +#![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/unique_identifier_msgs/msg.rs b/rclrs/src/vendor/unique_identifier_msgs/msg.rs new file mode 100644 index 000000000..7d6085fb1 --- /dev/null +++ b/rclrs/src/vendor/unique_identifier_msgs/msg.rs @@ -0,0 +1,125 @@ +pub mod rmw { + #[cfg(feature = "serde")] + use serde::{Deserialize, Serialize}; + + #[link(name = "unique_identifier_msgs__rosidl_typesupport_c")] + extern "C" { + fn rosidl_typesupport_c__get_message_type_support_handle__unique_identifier_msgs__msg__UUID( + ) -> *const std::ffi::c_void; + } + + #[link(name = "unique_identifier_msgs__rosidl_generator_c")] + extern "C" { + fn unique_identifier_msgs__msg__UUID__init(msg: *mut UUID) -> bool; + fn unique_identifier_msgs__msg__UUID__Sequence__init( + seq: *mut rosidl_runtime_rs::Sequence, + size: usize, + ) -> bool; + fn unique_identifier_msgs__msg__UUID__Sequence__fini( + seq: *mut rosidl_runtime_rs::Sequence, + ); + fn unique_identifier_msgs__msg__UUID__Sequence__copy( + in_seq: &rosidl_runtime_rs::Sequence, + out_seq: *mut rosidl_runtime_rs::Sequence, + ) -> bool; + } + + // Corresponds to unique_identifier_msgs__msg__UUID + #[repr(C)] + #[cfg_attr(feature = "serde", derive(Deserialize, Serialize))] + #[derive(Clone, Debug, PartialEq, PartialOrd)] + pub struct UUID { + pub uuid: [u8; 16], + } + + impl Default for UUID { + fn default() -> Self { + unsafe { + let mut msg = std::mem::zeroed(); + if !unique_identifier_msgs__msg__UUID__init(&mut msg as *mut _) { + panic!("Call to unique_identifier_msgs__msg__UUID__init() failed"); + } + msg + } + } + } + + impl rosidl_runtime_rs::SequenceAlloc for UUID { + 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 { unique_identifier_msgs__msg__UUID__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 { unique_identifier_msgs__msg__UUID__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 { unique_identifier_msgs__msg__UUID__Sequence__copy(in_seq, out_seq as *mut _) } + } + } + + impl rosidl_runtime_rs::Message for UUID { + 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 UUID + where + Self: Sized, + { + const TYPE_NAME: &'static str = "unique_identifier_msgs/msg/UUID"; + fn get_type_support() -> *const std::ffi::c_void { + // SAFETY: No preconditions for this function. + unsafe { + rosidl_typesupport_c__get_message_type_support_handle__unique_identifier_msgs__msg__UUID() + } + } + } +} // mod rmw + +#[cfg(feature = "serde")] +use serde::{Deserialize, Serialize}; + +#[cfg_attr(feature = "serde", derive(Deserialize, Serialize))] +#[derive(Clone, Debug, PartialEq, PartialOrd)] +pub struct UUID { + pub uuid: [u8; 16], +} + +impl Default for UUID { + fn default() -> Self { + ::from_rmw_message( + crate::vendor::unique_identifier_msgs::msg::rmw::UUID::default(), + ) + } +} + +impl rosidl_runtime_rs::Message for UUID { + type RmwMsg = crate::vendor::unique_identifier_msgs::msg::rmw::UUID; + + 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 { uuid: msg.uuid }) + } + std::borrow::Cow::Borrowed(msg) => { + std::borrow::Cow::Owned(Self::RmwMsg { uuid: msg.uuid }) + } + } + } + + fn from_rmw_message(msg: Self::RmwMsg) -> Self { + Self { uuid: msg.uuid } + } +} diff --git a/rclrs/src/wait.rs b/rclrs/src/wait.rs index 2ef99c026..243c9d857 100644 --- a/rclrs/src/wait.rs +++ b/rclrs/src/wait.rs @@ -329,7 +329,7 @@ impl WaitSet { /// /// - Passing a wait set with no wait-able items in it will return an error. /// - The timeout must not be so large so as to overflow an `i64` with its nanosecond - /// representation, or an error will occur. + /// representation, or an error will occur. /// /// This list is not comprehensive, since further errors may occur in the `rmw` or `rcl` layers. /// diff --git a/rclrs/vendor_interfaces.py b/rclrs/vendor_interfaces.py old mode 100644 new mode 100755 index 6a0066869..8ffb4e4e0 --- a/rclrs/vendor_interfaces.py +++ b/rclrs/vendor_interfaces.py @@ -1,65 +1,70 @@ -# This script produces the `vendor` module inside `rclrs` by copying -# the generated code for the `rosgraph_msgs` and `rcl_interfaces` packages and -# its dependency `builtin_interfaces` and adjusting the submodule paths in the -# code. +#!/usr/bin/env python3 +# This script produces the `vendor` module inside `rclrs` by copying the +# generated code for the `rosgraph_msgs`, `rcl_interfaces`, and `action_msgs` +# packages and their dependencies `builtin_interfaces` and +# `unique_identifier_msgs` and adjusting the submodule paths in the code. # If these packages, or the `rosidl_generator_rs`, get changed, you can # update the `vendor` module by running this script. -# The purpose is to avoid an external dependency on `rcl_interfaces`, which -# is not published on crates.io. +# The purpose is to avoid an external dependency on these message packages, +# which are not published on crates.io. import argparse from pathlib import Path import shutil import subprocess +vendored_packages = [ + "action_msgs", + "builtin_interfaces", + "rcl_interfaces", + "rosgraph_msgs", + "unique_identifier_msgs", +] + def get_args(): - parser = argparse.ArgumentParser(description='Vendor the rcl_interfaces, builtin_interfaces and rosgraph_msgs packages into rclrs') + parser = argparse.ArgumentParser(description='Vendor interface packages into rclrs') parser.add_argument('install_base', metavar='install_base', type=Path, help='the install base (must have non-merged layout)') return parser.parse_args() -def adjust(pkg, text): - text = text.replace('builtin_interfaces::', 'crate::vendor::builtin_interfaces::') - text = text.replace('rcl_interfaces::', 'crate::vendor::rcl_interfaces::') - text = text.replace('rosgraph_msgs::', 'crate::vendor::rosgraph_msgs::') - text = text.replace('crate::msg', f'crate::vendor::{pkg}::msg') - text = text.replace('crate::srv', f'crate::vendor::{pkg}::srv') +def adjust(current_package, text): + for pkg in vendored_packages: + text = text.replace(f'{pkg}::', f'crate::vendor::{pkg}::') + text = text.replace('crate::msg', f'crate::vendor::{current_package}::msg') + text = text.replace('crate::srv', f'crate::vendor::{current_package}::srv') + text = text.replace('crate::action', f'crate::vendor::{current_package}::action') return text def copy_adjusted(pkg, src, dst): dst.write_text(adjust(pkg, src.read_text())) subprocess.check_call(['rustfmt', str(dst)]) -mod_contents = """//! Created by {} -#![allow(dead_code)] -#![allow(clippy::derive_partial_eq_without_eq)] - -pub mod builtin_interfaces; -pub mod rcl_interfaces; -pub mod rosgraph_msgs; -""".format(Path(__file__).name) - def main(): args = get_args() assert args.install_base.is_dir(), "Install base does not exist" - assert (args.install_base / 'builtin_interfaces').is_dir(), "Install base does not contain builtin_interfaces" - assert (args.install_base / 'rcl_interfaces').is_dir(), "Install base does not contain rcl_interfaces" - assert (args.install_base / 'rosgraph_msgs').is_dir(), "Install base does not contain rosgraph_msgs" + for pkg in vendored_packages: + assert (args.install_base / pkg).is_dir(), f"Install base does not contain {pkg}" rclrs_root = Path(__file__).parent vendor_dir = rclrs_root / 'src' / 'vendor' if vendor_dir.exists(): shutil.rmtree(vendor_dir) - for pkg in ['builtin_interfaces', 'rcl_interfaces', 'rosgraph_msgs']: + for pkg in vendored_packages: src = args.install_base / pkg / 'share' / pkg / 'rust' / 'src' dst = vendor_dir / pkg dst.mkdir(parents=True) copy_adjusted(pkg, src / 'msg.rs', dst / 'msg.rs') if (src / 'srv.rs').is_file(): copy_adjusted(pkg, src / 'srv.rs', dst / 'srv.rs') + if (src / 'action.rs').is_file(): + copy_adjusted(pkg, src / 'action.rs', dst / 'action.rs') copy_adjusted(pkg, src / 'lib.rs', dst / 'mod.rs') # Rename lib.rs to mod.rs - (vendor_dir / 'mod.rs').write_text(mod_contents) - + mod_contents = "//! Created by {}\n".format(Path(__file__).name) + mod_contents += "#![allow(dead_code)]\n" + mod_contents += "\n" + for pkg in vendored_packages: + mod_contents += f"pub mod {pkg};\n" + (vendor_dir / 'mod.rs').write_text(mod_contents) if __name__ == '__main__': main() diff --git a/ros2_rust_jazzy.repos b/ros2_rust_jazzy.repos new file mode 100644 index 000000000..3f72f560d --- /dev/null +++ b/ros2_rust_jazzy.repos @@ -0,0 +1,29 @@ +repositories: + ros2/common_interfaces: + type: git + url: https://github.com/ros2/common_interfaces.git + version: jazzy + ros2/example_interfaces: + type: git + url: https://github.com/ros2/example_interfaces.git + version: jazzy + ros2/rcl_interfaces: + type: git + url: https://github.com/ros2/rcl_interfaces.git + version: jazzy + ros2/test_interface_files: + type: git + url: https://github.com/ros2/test_interface_files.git + version: jazzy + ros2/rosidl_core: + type: git + url: https://github.com/ros2/rosidl_core.git + version: jazzy + ros2/rosidl_defaults: + type: git + url: https://github.com/ros2/rosidl_defaults.git + version: jazzy + ros2/unique_identifier_msgs: + type: git + url: https://github.com/ros2/unique_identifier_msgs.git + version: jazzy diff --git a/rosidl_generator_rs/resource/lib.rs.em b/rosidl_generator_rs/resource/lib.rs.em index 79a0e1def..1ef77924c 100644 --- a/rosidl_generator_rs/resource/lib.rs.em +++ b/rosidl_generator_rs/resource/lib.rs.em @@ -1,4 +1,6 @@ #![allow(non_camel_case_types)] +#![allow(clippy::derive_partial_eq_without_eq)] +#![allow(clippy::upper_case_acronyms)] @[if len(msg_specs) > 0]@ pub mod msg;