diff --git a/.github/workflows/rust.yml b/.github/workflows/rust.yml index 662ef293a..dc0336ace 100644 --- a/.github/workflows/rust.yml +++ b/.github/workflows/rust.yml @@ -45,12 +45,8 @@ jobs: required-ros-distributions: ${{ matrix.ros_distribution }} use-ros2-testing: ${{ matrix.ros_distribution == 'rolling' }} - - name: Downgrade pydocstyle as a workaround for https://github.com/ament/ament_lint/issues/434 - run: | - sudo pip install pydocstyle==6.1.1 - - name: Setup Rust - uses: dtolnay/rust-toolchain@1.63.0 + uses: dtolnay/rust-toolchain@1.71.0 with: components: clippy, rustfmt diff --git a/Dockerfile b/Dockerfile index e3929e089..ad4a17d4b 100644 --- a/Dockerfile +++ b/Dockerfile @@ -11,7 +11,7 @@ RUN apt-get update && apt-get install -y \ && rm -rf /var/lib/apt/lists/* # Install Rust and the cargo-ament-build plugin -RUN curl --proto '=https' --tlsv1.2 -sSf https://sh.rustup.rs | sh -s -- --default-toolchain 1.63.0 -y +RUN curl --proto '=https' --tlsv1.2 -sSf https://sh.rustup.rs | sh -s -- --default-toolchain 1.71.0 -y ENV PATH=/root/.cargo/bin:$PATH RUN cargo install cargo-ament-build diff --git a/rclrs/src/dynamic_message.rs b/rclrs/src/dynamic_message.rs index ba6dce1fc..9bbcf7e75 100644 --- a/rclrs/src/dynamic_message.rs +++ b/rclrs/src/dynamic_message.rs @@ -72,7 +72,7 @@ fn get_type_support_library( let ament = ament_rs::Ament::new().map_err(|_| RequiredPrefixNotSourced { package: package_name.to_owned(), })?; - let prefix = PathBuf::from(ament.find_package(&package_name).ok_or( + let prefix = PathBuf::from(ament.find_package(package_name).ok_or( RequiredPrefixNotSourced { package: package_name.to_owned(), }, diff --git a/rclrs/src/error.rs b/rclrs/src/error.rs index b84f4d4d3..84bc602b1 100644 --- a/rclrs/src/error.rs +++ b/rclrs/src/error.rs @@ -347,6 +347,6 @@ pub(crate) trait ToResult { impl ToResult for rcl_ret_t { fn ok(&self) -> Result<(), RclrsError> { - to_rclrs_result(*self as i32) + to_rclrs_result(*self) } } diff --git a/rclrs/src/node.rs b/rclrs/src/node.rs index 4df07ba90..52fd3b3cf 100644 --- a/rclrs/src/node.rs +++ b/rclrs/src/node.rs @@ -173,7 +173,7 @@ impl Node { &self, getter: unsafe extern "C" fn(*const rcl_node_t) -> *const c_char, ) -> String { - unsafe { call_string_getter_with_handle(&*self.rcl_node_mtx.lock().unwrap(), getter) } + unsafe { call_string_getter_with_handle(&self.rcl_node_mtx.lock().unwrap(), getter) } } /// Creates a [`Client`][1]. diff --git a/rclrs/src/parameter/value.rs b/rclrs/src/parameter/value.rs index 04b64322a..b49108a6d 100644 --- a/rclrs/src/parameter/value.rs +++ b/rclrs/src/parameter/value.rs @@ -163,8 +163,8 @@ mod tests { assert!(!rcl_params.is_null()); assert_eq!(unsafe { (*rcl_params).num_nodes }, 1); let rcl_node_params = unsafe { &(*(*rcl_params).params) }; - assert_eq!((*rcl_node_params).num_params, 1); - let rcl_variant = unsafe { &(*(*rcl_node_params).parameter_values) }; + assert_eq!(rcl_node_params.num_params, 1); + let rcl_variant = unsafe { &(*rcl_node_params.parameter_values) }; let param_value = unsafe { ParameterValue::from_rcl_variant(rcl_variant) }; assert_eq!(param_value, pair.1); unsafe { rcl_yaml_node_struct_fini(rcl_params) }; diff --git a/rclrs/src/subscription.rs b/rclrs/src/subscription.rs index 9e551becd..e684866c2 100644 --- a/rclrs/src/subscription.rs +++ b/rclrs/src/subscription.rs @@ -183,7 +183,7 @@ where /// /// This can be more efficient for messages containing large arrays. pub fn take_boxed(&self) -> Result<(Box, MessageInfo), RclrsError> { - let mut rmw_message = Box::new(::RmwMsg::default()); + let mut rmw_message = Box::<::RmwMsg>::default(); let message_info = self.take_inner(&mut *rmw_message)?; // TODO: This will still use the stack in general. Change signature of // from_rmw_message to allow placing the result in a Box directly. diff --git a/rclrs/src/vendor/rcl_interfaces/msg.rs b/rclrs/src/vendor/rcl_interfaces/msg.rs index c3f474b19..39c029ae1 100644 --- a/rclrs/src/vendor/rcl_interfaces/msg.rs +++ b/rclrs/src/vendor/rcl_interfaces/msg.rs @@ -404,6 +404,7 @@ pub mod rmw { pub description: rosidl_runtime_rs::String, pub additional_constraints: rosidl_runtime_rs::String, pub read_only: bool, + pub dynamic_typing: bool, pub floating_point_range: rosidl_runtime_rs::BoundedSequence< crate::vendor::rcl_interfaces::msg::rmw::FloatingPointRange, 1, @@ -1269,6 +1270,7 @@ pub struct ParameterDescriptor { pub description: std::string::String, pub additional_constraints: std::string::String, pub read_only: bool, + pub dynamic_typing: bool, pub floating_point_range: rosidl_runtime_rs::BoundedSequence< crate::vendor::rcl_interfaces::msg::rmw::FloatingPointRange, 1, @@ -1298,6 +1300,7 @@ impl rosidl_runtime_rs::Message for ParameterDescriptor { description: msg.description.as_str().into(), additional_constraints: msg.additional_constraints.as_str().into(), read_only: msg.read_only, + dynamic_typing: msg.dynamic_typing, floating_point_range: msg.floating_point_range, integer_range: msg.integer_range, }), @@ -1307,6 +1310,7 @@ impl rosidl_runtime_rs::Message for ParameterDescriptor { description: msg.description.as_str().into(), additional_constraints: msg.additional_constraints.as_str().into(), read_only: msg.read_only, + dynamic_typing: msg.dynamic_typing, floating_point_range: msg.floating_point_range.clone(), integer_range: msg.integer_range.clone(), }), @@ -1320,6 +1324,7 @@ impl rosidl_runtime_rs::Message for ParameterDescriptor { description: msg.description.to_string(), additional_constraints: msg.additional_constraints.to_string(), read_only: msg.read_only, + dynamic_typing: msg.dynamic_typing, floating_point_range: msg.floating_point_range, integer_range: msg.integer_range, } diff --git a/rclrs/vendor_interfaces.py b/rclrs/vendor_interfaces.py index 59a840d58..37d01e2f5 100644 --- a/rclrs/vendor_interfaces.py +++ b/rclrs/vendor_interfaces.py @@ -58,4 +58,4 @@ def main(): if __name__ == '__main__': - main() \ No newline at end of file + main()