Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion .github/workflows/generate-bindings.yml
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ jobs:
use-ros2-testing: ${{ matrix.ros_distribution == 'rolling' }}

- name: Setup Rust
uses: dtolnay/rust-toolchain@1.75
uses: dtolnay/rust-toolchain@1.85
with:
components: clippy, rustfmt

Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/rust-minimal.yml
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ jobs:
use-ros2-testing: ${{ matrix.ros_distribution == 'rolling' }}

- name: Setup Rust
uses: dtolnay/rust-toolchain@1.75
uses: dtolnay/rust-toolchain@1.85
with:
components: clippy, rustfmt

Expand Down
2 changes: 1 addition & 1 deletion Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ RUN apt-get update && apt-get install -y \
&& rm -rf /var/lib/apt/lists/*

# Install Rust
RUN curl --proto '=https' --tlsv1.2 -sSf https://sh.rustup.rs | sh -s -- --default-toolchain 1.75.0 -y
RUN curl --proto '=https' --tlsv1.2 -sSf https://sh.rustup.rs | sh -s -- --default-toolchain 1.85.0 -y
ENV PATH=/root/.cargo/bin:$PATH

COPY src/ros2_rust/docker/install_colcon_plugins.sh /
Expand Down
4 changes: 2 additions & 2 deletions docs/writing_a_simple_publisher_and_subscriber.md
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ In the [`Cargo.toml`](https://doc.rust-lang.org/book/ch01-03-hello-cargo.html) f
[package]
name = "rust_pubsub"
version = "0.1.0"
edition = "2021"
edition = "2024"
[dependencies]
rclrs = "*"
std_msgs = "*"
Expand Down Expand Up @@ -247,7 +247,7 @@ Of course, you can write for each node you want to implement its own package, an
[package]
name = "rust_pubsub"
version = "0.1.0"
edition = "2021"
edition = "2024"

# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html

Expand Down
4 changes: 2 additions & 2 deletions rclrs/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,10 @@ name = "rclrs"
version = "0.6.0"
# This project is not military-sponsored, Jacob's employment contract just requires him to use this email address
authors = ["Esteve Fernandez <[email protected]>", "Nikolai Morin <[email protected]>", "Jacob Hassold <[email protected]>"]
edition = "2021"
edition = "2024"
license = "Apache-2.0"
description = "A ROS 2 client library for developing robotics applications in Rust"
rust-version = "1.75"
rust-version = "1.85"

[lib]
path = "src/lib.rs"
Expand Down
4 changes: 2 additions & 2 deletions rclrs/generate_bindings.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,9 @@ def main():
bindgen_command.append('-o')
bindgen_command.append(f'{output_directory}/rcl_bindings_generated_{ros_distribution}.rs')
bindgen_command.append('--rust-edition')
bindgen_command.append('2021')
bindgen_command.append('2024')
bindgen_command.append('--rust-target')
bindgen_command.append('1.75')
bindgen_command.append('1.85')
bindgen_command.append('--no-derive-copy')
bindgen_command.append('--allowlist-type')
bindgen_command.append('rcl_.*')
Expand Down
40 changes: 21 additions & 19 deletions rclrs/src/action.rs
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ pub use action_goal_receiver::*;
pub(crate) mod action_server;
pub use action_server::*;

use crate::{log_error, rcl_bindings::*, vendor::builtin_interfaces::msg::Time, DropGuard};
use crate::{DropGuard, log_error, rcl_bindings::*, vendor::builtin_interfaces::msg::Time};
use std::fmt;

#[cfg(feature = "serde")]
Expand All @@ -31,24 +31,26 @@ impl GoalUuid {

impl fmt::Display for GoalUuid {
fn fmt(&self, f: &mut fmt::Formatter<'_>) -> Result<(), fmt::Error> {
write!(f, "{:02x}{:02x}{:02x}{:02x}-{:02x}{:02x}-{:02x}{:02x}-{:02x}{:02x}-{:02x}{:02x}{:02x}{:02x}{:02x}{:02x}",
self.0[0],
self.0[1],
self.0[2],
self.0[3],
self.0[4],
self.0[5],
self.0[6],
self.0[7],
self.0[8],
self.0[9],
self.0[10],
self.0[11],
self.0[12],
self.0[13],
self.0[14],
self.0[15],
)
write!(
f,
"{:02x}{:02x}{:02x}{:02x}-{:02x}{:02x}-{:02x}{:02x}-{:02x}{:02x}-{:02x}{:02x}{:02x}{:02x}{:02x}{:02x}",
self.0[0],
self.0[1],
self.0[2],
self.0[3],
self.0[4],
self.0[5],
self.0[6],
self.0[7],
self.0[8],
self.0[9],
self.0[10],
self.0[11],
self.0[12],
self.0[13],
self.0[14],
self.0[15],
)
}
}

Expand Down
13 changes: 6 additions & 7 deletions rclrs/src/action/action_client.rs
Original file line number Diff line number Diff line change
@@ -1,12 +1,11 @@
use super::empty_goal_status_array;
use crate::{
log_warn,
CancelResponse, CancelResponseCode, DropGuard, ENTITY_LIFECYCLE_MUTEX, GoalStatus,
GoalStatusCode, GoalUuid, MultiCancelResponse, Node, NodeHandle, QoSProfile, RclPrimitive,
RclPrimitiveHandle, RclPrimitiveKind, RclrsError, ReadyKind, TakeFailedAsNone, ToResult,
Waitable, WaitableLifecycle, log_warn,
rcl_bindings::*,
vendor::{action_msgs::srv::CancelGoal_Response, builtin_interfaces::msg::Time},
CancelResponse, CancelResponseCode, DropGuard, GoalStatus, GoalStatusCode, GoalUuid,
MultiCancelResponse, Node, NodeHandle, QoSProfile, RclPrimitive, RclPrimitiveHandle,
RclPrimitiveKind, RclrsError, ReadyKind, TakeFailedAsNone, ToResult, Waitable,
WaitableLifecycle, ENTITY_LIFECYCLE_MUTEX,
};
use rosidl_runtime_rs::{Action, Message, RmwFeedbackMessage, RmwGoalResponse, RmwResultResponse};
use std::{
Expand All @@ -17,8 +16,8 @@ use std::{
sync::{Arc, Mutex, MutexGuard, Weak},
};
use tokio::sync::{
mpsc::{unbounded_channel, UnboundedSender},
oneshot::{channel as oneshot_channel, Sender},
mpsc::{UnboundedSender, unbounded_channel},
oneshot::{Sender, channel as oneshot_channel},
watch::Sender as WatchSender,
};

Expand Down
4 changes: 2 additions & 2 deletions rclrs/src/action/action_client/goal_client.rs
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
use crate::{
vendor::builtin_interfaces::msg::Time, CancellationClient, FeedbackClient, GoalStatus,
GoalStatusCode, ResultClient, StatusWatcher,
CancellationClient, FeedbackClient, GoalStatus, GoalStatusCode, ResultClient, StatusWatcher,
vendor::builtin_interfaces::msg::Time,
};
use rosidl_runtime_rs::Action;
use std::{
Expand Down
2 changes: 1 addition & 1 deletion rclrs/src/action/action_client/result_client.rs
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
use super::GoalClientLifecycle;
use crate::GoalStatusCode;
use futures::{future::Shared, FutureExt};
use futures::{FutureExt, future::Shared};
use rosidl_runtime_rs::Action;
use std::{
future::Future,
Expand Down
2 changes: 1 addition & 1 deletion rclrs/src/action/action_goal_receiver.rs
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ use std::{
ops::{Deref, DerefMut},
sync::Arc,
};
use tokio::sync::mpsc::{unbounded_channel, UnboundedReceiver};
use tokio::sync::mpsc::{UnboundedReceiver, unbounded_channel};

/// This is an alternative tool for implementing an [`ActionServer`]. Instead of
/// specifying a callback to receive goal requests, you can use this receiver to
Expand Down
9 changes: 4 additions & 5 deletions rclrs/src/action/action_server.rs
Original file line number Diff line number Diff line change
@@ -1,10 +1,9 @@
use super::empty_goal_status_array;
use crate::{
action::GoalUuid, error::ToResult, rcl_bindings::*,
vendor::action_msgs::srv::CancelGoal_Response, ActionGoalReceiver, CancelResponseCode,
DropGuard, GoalStatusCode, Node, NodeHandle, QoSProfile, RclPrimitive, RclPrimitiveHandle,
RclPrimitiveKind, RclrsError, ReadyKind, TakeFailedAsNone, Waitable, WaitableLifecycle,
ENTITY_LIFECYCLE_MUTEX,
ActionGoalReceiver, CancelResponseCode, DropGuard, ENTITY_LIFECYCLE_MUTEX, GoalStatusCode,
Node, NodeHandle, QoSProfile, RclPrimitive, RclPrimitiveHandle, RclPrimitiveKind, RclrsError,
ReadyKind, TakeFailedAsNone, Waitable, WaitableLifecycle, action::GoalUuid, error::ToResult,
rcl_bindings::*, vendor::action_msgs::srv::CancelGoal_Response,
};
use futures::future::BoxFuture;
use rosidl_runtime_rs::{Action, Message, RmwGoalRequest, RmwResultRequest};
Expand Down
4 changes: 2 additions & 2 deletions rclrs/src/action/action_server/action_server_goal_handle.rs
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
use super::GoalStatusCode;
use crate::{
log_error, rcl_bindings::*, ActionServerHandle, GoalUuid, RclErrorMsg, RclReturnCode,
RclrsError, ToResult,
ActionServerHandle, GoalUuid, RclErrorMsg, RclReturnCode, RclrsError, ToResult, log_error,
rcl_bindings::*,
};
use rosidl_runtime_rs::{Action, RmwResultResponse};
use std::sync::{Mutex, MutexGuard};
Expand Down
7 changes: 3 additions & 4 deletions rclrs/src/action/action_server/cancellation_state.rs
Original file line number Diff line number Diff line change
@@ -1,15 +1,14 @@
use super::ActionServerHandle;
use crate::{
log_error,
CancelResponseCode, GoalUuid, Node, RclrsErrorFilter, ToResult, log_error,
rcl_bindings::*,
vendor::{
action_msgs::{msg::GoalInfo, srv::CancelGoal_Response},
unique_identifier_msgs::msg::UUID,
},
CancelResponseCode, GoalUuid, Node, RclrsErrorFilter, ToResult,
};
use futures::{
future::{select, Either},
future::{Either, select},
pin_mut,
};
use futures_lite::future::race;
Expand All @@ -20,7 +19,7 @@ use std::{
future::Future,
sync::{Arc, Mutex},
};
use tokio::sync::watch::{channel as watch_channel, Receiver, Sender};
use tokio::sync::watch::{Receiver, Sender, channel as watch_channel};

pub(super) struct CancellationState<A: Action> {
receiver: Receiver<bool>,
Expand Down
2 changes: 1 addition & 1 deletion rclrs/src/action/action_server/live_action_server_goal.rs
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ use super::{
ActionServerGoalHandle, ActionServerHandle, CancellationRequest, CancellationState,
GoalStatusCode, TerminalStatus,
};
use crate::{log_error, rcl_bindings::*, RclrsError, ToResult};
use crate::{RclrsError, ToResult, log_error, rcl_bindings::*};
use rosidl_runtime_rs::{Action, Message};
use std::{borrow::Cow, ops::Deref, sync::Arc};

Expand Down
2 changes: 1 addition & 1 deletion rclrs/src/action/action_server/requested_goal.rs
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ use super::{
AcceptedGoal, ActionServerGoalBoard, ActionServerGoalHandle, LiveActionServerGoal,
TerminatedGoal,
};
use crate::{log_error, rcl_bindings::*, GoalUuid, RclrsError, RclrsErrorFilter, ToResult};
use crate::{GoalUuid, RclrsError, RclrsErrorFilter, ToResult, log_error, rcl_bindings::*};
use rosidl_runtime_rs::Action;
use std::sync::Arc;

Expand Down
6 changes: 3 additions & 3 deletions rclrs/src/client.rs
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,9 @@ use std::{
use rosidl_runtime_rs::Message;

use crate::{
error::ToResult, log_fatal, rcl_bindings::*, IntoPrimitiveOptions, MessageCow, Node, Promise,
QoSProfile, RclPrimitive, RclPrimitiveHandle, RclPrimitiveKind, RclReturnCode, RclrsError,
ReadyKind, ServiceInfo, Waitable, WaitableLifecycle, ENTITY_LIFECYCLE_MUTEX,
ENTITY_LIFECYCLE_MUTEX, IntoPrimitiveOptions, MessageCow, Node, Promise, QoSProfile,
RclPrimitive, RclPrimitiveHandle, RclPrimitiveKind, RclReturnCode, RclrsError, ReadyKind,
ServiceInfo, Waitable, WaitableLifecycle, error::ToResult, log_fatal, rcl_bindings::*,
};

mod client_async_callback;
Expand Down
4 changes: 2 additions & 2 deletions rclrs/src/client/client_output.rs
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
use rosidl_runtime_rs::Message;

use futures::channel::oneshot::{channel, Sender};
use futures::channel::oneshot::{Sender, channel};

use crate::{rcl_bindings::rmw_service_info_t, Promise, RequestId, ServiceInfo};
use crate::{Promise, RequestId, ServiceInfo, rcl_bindings::rmw_service_info_t};

/// This trait allows us to deduce how much information a user wants to receive
/// from a client call. A user can choose to receive only the response from the
Expand Down
2 changes: 1 addition & 1 deletion rclrs/src/context.rs
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ use std::{
vec::Vec,
};

use crate::{rcl_bindings::*, Executor, ExecutorRuntime, LoggingLifecycle, RclrsError, ToResult};
use crate::{Executor, ExecutorRuntime, LoggingLifecycle, RclrsError, ToResult, rcl_bindings::*};

/// This is locked whenever initializing or dropping any middleware entity
/// because we have found issues in RCL and some RMW implementations that
Expand Down
2 changes: 1 addition & 1 deletion rclrs/src/error.rs
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ use std::{
sync::PoisonError,
};

use crate::{rcl_bindings::*, DeclarationError, ReadyKind};
use crate::{DeclarationError, ReadyKind, rcl_bindings::*};

/// The main error type.
#[derive(Debug, PartialEq, Eq)]
Expand Down
4 changes: 2 additions & 2 deletions rclrs/src/executor.rs
Original file line number Diff line number Diff line change
Expand Up @@ -8,14 +8,14 @@ use crate::{
pub use futures::channel::oneshot::Receiver as Promise;
use futures::{
channel::oneshot,
future::{select, BoxFuture, Either},
future::{BoxFuture, Either, select},
};
use std::{
any::Any,
future::Future,
sync::{
atomic::{AtomicBool, Ordering},
Arc,
atomic::{AtomicBool, Ordering},
},
time::Duration,
};
Expand Down
21 changes: 10 additions & 11 deletions rclrs/src/executor/basic_executor.rs
Original file line number Diff line number Diff line change
@@ -1,31 +1,30 @@
use futures::{
StreamExt,
channel::{
mpsc::{unbounded, UnboundedReceiver, UnboundedSender},
mpsc::{UnboundedReceiver, UnboundedSender, unbounded},
oneshot,
},
future::{select, select_all, BoxFuture, Either},
future::{BoxFuture, Either, select, select_all},
stream::StreamFuture,
task::{waker_ref, ArcWake},
StreamExt,
task::{ArcWake, waker_ref},
};
use std::{
sync::{
atomic::{AtomicBool, Ordering},
mpsc::{channel, Receiver, Sender},
Arc, Mutex, Weak,
atomic::{AtomicBool, Ordering},
mpsc::{Receiver, Sender, channel},
},
task::Context as TaskContext,
time::Instant,
};

use crate::{
log_debug, log_fatal, log_warn, ExecutorChannel, ExecutorRuntime, ExecutorWorkerOptions,
GuardCondition, PayloadTask, RclrsError, SpinConditions, WaitSetRunConditions, WaitSetRunner,
Waitable, WeakActivityListener, WorkerChannel,
ExecutorChannel, ExecutorRuntime, ExecutorWorkerOptions, GuardCondition, PayloadTask,
RclrsError, SpinConditions, WaitSetRunConditions, WaitSetRunner, Waitable,
WeakActivityListener, WorkerChannel, log_debug, log_fatal, log_warn,
};

static FAILED_TO_SEND_WORKER: &'static str =
"Failed to send the new runner. This should never happen. \
static FAILED_TO_SEND_WORKER: &'static 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:
Expand Down
2 changes: 1 addition & 1 deletion rclrs/src/logging.rs
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ use std::{
sync::{Mutex, OnceLock},
};

use crate::{rcl_bindings::*, ENTITY_LIFECYCLE_MUTEX};
use crate::{ENTITY_LIFECYCLE_MUTEX, rcl_bindings::*};

mod logging_configuration;
pub(crate) use logging_configuration::*;
Expand Down
2 changes: 1 addition & 1 deletion rclrs/src/logging/log_params.rs
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
use crate::{rcl_bindings::RCUTILS_LOG_SEVERITY, Clock};
use crate::{Clock, rcl_bindings::RCUTILS_LOG_SEVERITY};
use std::{borrow::Borrow, ffi::CString, time::Duration};

/// These parameters determine the behavior of an instance of logging.
Expand Down
2 changes: 1 addition & 1 deletion rclrs/src/logging/logger.rs
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
use std::{borrow::Borrow, ffi::CString, sync::Arc};

use crate::{
ENTITY_LIFECYCLE_MUTEX, LogParams, LogSeverity, LoggerName, RclrsError, ToLogParams, ToResult,
rcl_bindings::{rcutils_logging_set_default_logger_level, rcutils_logging_set_logger_level},
LogParams, LogSeverity, LoggerName, RclrsError, ToLogParams, ToResult, ENTITY_LIFECYCLE_MUTEX,
};

/// Logger can be passed in as the first argument into one of the [logging][1]
Expand Down
Loading
Loading