diff --git a/rclrs/src/client.rs b/rclrs/src/client.rs index 971d4f88..2671c0d7 100644 --- a/rclrs/src/client.rs +++ b/rclrs/src/client.rs @@ -349,7 +349,7 @@ where let commands = node.commands().async_worker_commands(); let handle = Arc::new(ClientHandle { rcl_client: Mutex::new(rcl_client), - node: Arc::clone(&node), + node: Arc::clone(node), }); let board = Arc::new(Mutex::new(ClientRequestBoard::new())); @@ -359,7 +359,7 @@ where handle: Arc::clone(&handle), board: Arc::clone(&board), }), - Some(Arc::clone(&commands.get_guard_condition())), + Some(Arc::clone(commands.get_guard_condition())), ); commands.add_to_wait_set(waitable); @@ -419,7 +419,7 @@ where self.board.lock().unwrap().execute(&self.handle) } - fn handle(&self) -> RclPrimitiveHandle { + fn handle(&self) -> RclPrimitiveHandle<'_> { RclPrimitiveHandle::Client(self.handle.lock()) } @@ -542,7 +542,7 @@ struct ClientHandle { } impl ClientHandle { - fn lock(&self) -> MutexGuard { + fn lock(&self) -> MutexGuard<'_, rcl_client_t> { self.rcl_client.lock().unwrap() } } diff --git a/rclrs/src/executor/basic_executor.rs b/rclrs/src/executor/basic_executor.rs index 4df0db9a..c17312d7 100644 --- a/rclrs/src/executor/basic_executor.rs +++ b/rclrs/src/executor/basic_executor.rs @@ -24,8 +24,7 @@ use crate::{ Waitable, WeakActivityListener, WorkerChannel, }; -static FAILED_TO_SEND_WORKER: &'static str = - "Failed to send the new runner. This should never happen. \ +static FAILED_TO_SEND_WORKER: &str = "Failed to send the new runner. This should never happen. \ Please report this to the rclrs maintainers with a minimal reproducible example."; /// The implementation of this runtime is based off of the async Rust reference book: @@ -76,11 +75,7 @@ impl AllGuardConditions { fn push(&self, guard_condition: Weak) { let mut inner = self.inner.lock().unwrap(); - if inner - .iter() - .find(|other| guard_condition.ptr_eq(other)) - .is_some() - { + if inner.iter().any(|other| guard_condition.ptr_eq(other)) { // This guard condition is already known return; } @@ -351,7 +346,7 @@ impl TaskSender { task_sender: self.task_sender.clone(), }); - if let Err(_) = self.task_sender.send(task) { + if self.task_sender.send(task).is_err() { // This is a debug log because it is normal for this to happen while // an executor is winding down. log_debug!( diff --git a/rclrs/src/logging/log_params.rs b/rclrs/src/logging/log_params.rs index 4b67edc5..99eed7ca 100644 --- a/rclrs/src/logging/log_params.rs +++ b/rclrs/src/logging/log_params.rs @@ -36,7 +36,7 @@ impl<'a> LogParams<'a> { } /// Get the logger name - pub fn get_logger_name(&self) -> &LoggerName { + pub fn get_logger_name(&self) -> &LoggerName<'_> { &self.logger_name } diff --git a/rclrs/src/node.rs b/rclrs/src/node.rs index 7f4780d3..3fe406b5 100644 --- a/rclrs/src/node.rs +++ b/rclrs/src/node.rs @@ -965,7 +965,7 @@ impl NodeState { /// Enables usage of undeclared parameters for this node. /// /// Returns a [`Parameters`] struct that can be used to get and set all parameters. - pub fn use_undeclared_parameters(&self) -> Parameters { + pub fn use_undeclared_parameters(&self) -> Parameters<'_> { self.parameter.allow_undeclared(); Parameters { interface: &self.parameter, diff --git a/rclrs/src/node/graph.rs b/rclrs/src/node/graph.rs index 69e97e43..b079909f 100644 --- a/rclrs/src/node/graph.rs +++ b/rclrs/src/node/graph.rs @@ -490,7 +490,7 @@ mod tests { let check_rosout = |topics: HashMap>| { // rosout shows up in humble and iron, even if the graph is empty - #[cfg(any(ros_distro = "humble"))] + #[cfg(ros_distro = "humble")] { assert_eq!(topics.len(), 1); assert_eq!( diff --git a/rclrs/src/node/node_options.rs b/rclrs/src/node/node_options.rs index 4b82df4e..00908ba6 100644 --- a/rclrs/src/node/node_options.rs +++ b/rclrs/src/node/node_options.rs @@ -384,10 +384,10 @@ impl<'a> NodeOptions<'a> { ) }; commands.add_to_wait_set(graph_change_waitable); - let _ = commands.run(node_graph_task( + drop(commands.run(node_graph_task( graph_change_receiver, graph_change_guard_condition, - )); + ))); let node = Arc::new(NodeState { time_source: TimeSource::builder(self.clock_type) @@ -396,7 +396,7 @@ impl<'a> NodeOptions<'a> { parameter, logger: Logger::new(logger_name)?, graph_change_action, - commands: Arc::clone(&commands), + commands: Arc::clone(commands), handle, }); node.time_source.attach_node(&node); diff --git a/rclrs/src/parameter/service.rs b/rclrs/src/parameter/service.rs index 5d1c2521..de8a05d0 100644 --- a/rclrs/src/parameter/service.rs +++ b/rclrs/src/parameter/service.rs @@ -134,7 +134,7 @@ fn list_parameters(req: ListParameters_Request, map: &ParameterMap) -> ListParam .keys() .filter_map(|name| { let name: rosidl_runtime_rs::String = name.clone().into(); - if req.prefixes.len() == 0 && check_parameter_name_depth(&name[..]) { + if req.prefixes.is_empty() && check_parameter_name_depth(&name[..]) { return Some(name); } req.prefixes diff --git a/rclrs/src/service.rs b/rclrs/src/service.rs index aaa07abc..fa81be84 100644 --- a/rclrs/src/service.rs +++ b/rclrs/src/service.rs @@ -143,14 +143,14 @@ where let handle = Arc::new(ServiceHandle { rcl_service: Mutex::new(rcl_service), - node_handle: Arc::clone(&node_handle), + node_handle: Arc::clone(node_handle), }); let (waitable, lifecycle) = Waitable::new( Box::new(ServiceExecutable:: { handle: Arc::clone(&handle), callback: Arc::clone(&callback), - commands: Arc::clone(&commands), + commands: Arc::clone(commands), }), Some(Arc::clone(commands.get_guard_condition())), ); @@ -260,7 +260,7 @@ where RclPrimitiveKind::Service } - fn handle(&self) -> RclPrimitiveHandle { + fn handle(&self) -> RclPrimitiveHandle<'_> { RclPrimitiveHandle::Service(self.handle.lock()) } } @@ -280,7 +280,7 @@ pub struct ServiceHandle { } impl ServiceHandle { - fn lock(&self) -> MutexGuard { + fn lock(&self) -> MutexGuard<'_, rcl_service_t> { self.rcl_service.lock().unwrap() } diff --git a/rclrs/src/service/any_service_callback.rs b/rclrs/src/service/any_service_callback.rs index 6a4cc619..87782b82 100644 --- a/rclrs/src/service/any_service_callback.rs +++ b/rclrs/src/service/any_service_callback.rs @@ -30,7 +30,7 @@ where commands: &Arc, ) -> Result<(), RclrsError> { match self { - Self::Node(node) => node.execute(Arc::clone(&handle), commands), + Self::Node(node) => node.execute(Arc::clone(handle), commands), Self::Worker(worker) => worker.execute(handle, payload), } } diff --git a/rclrs/src/service/node_service_callback.rs b/rclrs/src/service/node_service_callback.rs index 6713396d..b48d0061 100644 --- a/rclrs/src/service/node_service_callback.rs +++ b/rclrs/src/service/node_service_callback.rs @@ -37,7 +37,7 @@ impl NodeServiceCallback { if let Err(err) = handle.send_response::(&mut rmw_request_id, response.await) { - log_service_send_error(&*handle, rmw_request_id, err); + log_service_send_error(&handle, rmw_request_id, err); } }); } @@ -49,7 +49,7 @@ impl NodeServiceCallback { if let Err(err) = handle.send_response::(&mut rmw_request_id, response.await) { - log_service_send_error(&*handle, rmw_request_id, err); + log_service_send_error(&handle, rmw_request_id, err); } }); } @@ -62,7 +62,7 @@ impl NodeServiceCallback { if let Err(err) = handle.send_response::(&mut rmw_request_id, response.await) { - log_service_send_error(&*handle, rmw_request_id, err); + log_service_send_error(&handle, rmw_request_id, err); } }); } diff --git a/rclrs/src/subscription.rs b/rclrs/src/subscription.rs index e094abfd..cbfd507a 100644 --- a/rclrs/src/subscription.rs +++ b/rclrs/src/subscription.rs @@ -272,7 +272,7 @@ where RclPrimitiveKind::Subscription } - fn handle(&self) -> RclPrimitiveHandle { + fn handle(&self) -> RclPrimitiveHandle<'_> { RclPrimitiveHandle::Subscription(self.handle.lock()) } } @@ -292,7 +292,7 @@ struct SubscriptionHandle { } impl SubscriptionHandle { - fn lock(&self) -> MutexGuard { + fn lock(&self) -> MutexGuard<'_, rcl_subscription_t> { self.rcl_subscription.lock().unwrap() } diff --git a/rclrs/src/wait_set.rs b/rclrs/src/wait_set.rs index a7951f00..dce544af 100644 --- a/rclrs/src/wait_set.rs +++ b/rclrs/src/wait_set.rs @@ -137,7 +137,7 @@ impl WaitSet { // For the remaining entities, check if they were activated and then run // the callback for those that were. - for waiter in self.primitives.values_mut().flat_map(|v| v) { + for waiter in self.primitives.values_mut().flatten() { if waiter.is_ready(&self.handle.rcl_wait_set) { f(&mut *waiter.primitive)?; } @@ -201,7 +201,7 @@ impl WaitSet { /// /// [1]: crate::RclReturnCode fn register_rcl_primitives(&mut self) -> Result<(), RclrsError> { - for entity in self.primitives.values_mut().flat_map(|c| c) { + for entity in self.primitives.values_mut().flatten() { entity.add_to_wait_set(&mut self.handle.rcl_wait_set)?; } Ok(()) diff --git a/rclrs/src/wait_set/guard_condition.rs b/rclrs/src/wait_set/guard_condition.rs index 8860e23a..f865053f 100644 --- a/rclrs/src/wait_set/guard_condition.rs +++ b/rclrs/src/wait_set/guard_condition.rs @@ -75,7 +75,7 @@ impl GuardCondition { let handle = Arc::new(GuardConditionHandle { rcl_guard_condition, - context_handle: Arc::clone(&context), + context_handle: Arc::clone(context), }); let (waitable, lifecycle) = Waitable::new( @@ -105,7 +105,7 @@ impl GuardCondition { let handle = Arc::new(GuardConditionHandle { rcl_guard_condition, - context_handle: Arc::clone(&context), + context_handle: Arc::clone(context), }); let (waitable, lifecycle) = Waitable::new( @@ -216,7 +216,7 @@ impl RclPrimitive for GuardConditionExecutable { RclPrimitiveKind::GuardCondition } - fn handle(&self) -> RclPrimitiveHandle { + fn handle(&self) -> RclPrimitiveHandle<'_> { RclPrimitiveHandle::GuardCondition(self.handle.rcl_guard_condition.lock().unwrap()) } } diff --git a/rclrs/src/wait_set/rcl_primitive.rs b/rclrs/src/wait_set/rcl_primitive.rs index 205926c6..43d3dbe4 100644 --- a/rclrs/src/wait_set/rcl_primitive.rs +++ b/rclrs/src/wait_set/rcl_primitive.rs @@ -26,7 +26,7 @@ pub trait RclPrimitive: Send + Sync { fn kind(&self) -> RclPrimitiveKind; /// Provide the handle for this primitive - fn handle(&self) -> RclPrimitiveHandle; + fn handle(&self) -> RclPrimitiveHandle<'_>; } /// Enum to describe the kind of an executable. diff --git a/rclrs/src/wait_set/wait_set_runner.rs b/rclrs/src/wait_set/wait_set_runner.rs index b60f0705..b323a79b 100644 --- a/rclrs/src/wait_set/wait_set_runner.rs +++ b/rclrs/src/wait_set/wait_set_runner.rs @@ -111,7 +111,7 @@ impl WaitSetRunner { let (sender, promise) = channel(); std::thread::spawn(move || { let result = self.run_blocking(conditions); - if let Err(_) = sender.send((self, result)) { + if sender.send((self, result)).is_err() { // This is a debug log because this is a normal thing to occur // when an executor is winding down. log_debug!( diff --git a/rclrs/src/wait_set/waitable.rs b/rclrs/src/wait_set/waitable.rs index d510d1f9..3317bb20 100644 --- a/rclrs/src/wait_set/waitable.rs +++ b/rclrs/src/wait_set/waitable.rs @@ -81,7 +81,7 @@ impl Waitable { rcl_wait_set_add_subscription(wait_set, &*handle, &mut index) } RclPrimitiveHandle::GuardCondition(handle) => handle.use_handle(|handle| { - rcl_wait_set_add_guard_condition(wait_set, &*handle, &mut index) + rcl_wait_set_add_guard_condition(wait_set, handle, &mut index) }), RclPrimitiveHandle::Service(handle) => { rcl_wait_set_add_service(wait_set, &*handle, &mut index)