Skip to content

Remove unnecessary casts to raw pointers #134

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 4 commits into from
May 2, 2022
Merged
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
75 changes: 42 additions & 33 deletions rclrs/build.rs
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,23 @@ use std::fs::read_dir;
use std::path::{Path, PathBuf};

const AMENT_PREFIX_PATH: &str = "AMENT_PREFIX_PATH";
const ROS_DISTRO: &str = "ROS_DISTRO";

fn get_env_var_or_abort(env_var: &'static str) -> String {
if let Ok(value) = env::var(env_var) {
value
} else {
panic!(
"{} environment variable not set - please source ROS 2 installation first.",
env_var
);
}
}

fn main() {
let ros_distro = get_env_var_or_abort(ROS_DISTRO);
println!("cargo:rustc-cfg=ros_distro=\"{ros_distro}\"");

let mut builder = bindgen::Builder::default()
.header("src/rcl_wrapper.h")
.derive_copy(false)
Expand Down Expand Up @@ -39,47 +54,41 @@ fn main() {
//
// See REP 122 for more details: https://www.ros.org/reps/rep-0122.html#filesystem-layout

if let Ok(ament_prefix_paths) = env::var(AMENT_PREFIX_PATH) {
for ament_prefix_path in ament_prefix_paths.split(':').map(Path::new) {
// Locate the ament index
let ament_index = ament_prefix_path.join("share/ament_index/resource_index/packages");
if !ament_index.is_dir() {
continue;
}
let ament_prefix_paths = get_env_var_or_abort(AMENT_PREFIX_PATH);
for ament_prefix_path in ament_prefix_paths.split(':').map(Path::new) {
// Locate the ament index
let ament_index = ament_prefix_path.join("share/ament_index/resource_index/packages");
if !ament_index.is_dir() {
continue;
}

// Old-style include directory
let include_dir = ament_prefix_path.join("include");
// Old-style include directory
let include_dir = ament_prefix_path.join("include");

// Including the old-style packages
builder = builder.clang_arg(format!("-isystem{}", include_dir.display()));
// Including the old-style packages
builder = builder.clang_arg(format!("-isystem{}", include_dir.display()));

// Search for and include new-style-converted package paths
for dir_entry in read_dir(&ament_index).unwrap().filter_map(|p| p.ok()) {
let package = dir_entry.file_name();
let package_include_dir = include_dir.join(&package);
// Search for and include new-style-converted package paths
for dir_entry in read_dir(&ament_index).unwrap().filter_map(|p| p.ok()) {
let package = dir_entry.file_name();
let package_include_dir = include_dir.join(&package);

if package_include_dir.is_dir() {
let new_style_include_dir = package_include_dir.join(&package);
if package_include_dir.is_dir() {
let new_style_include_dir = package_include_dir.join(&package);

// CycloneDDS is a special case - it needs to be included as if it were a new-style path, but
// doesn't actually have a secondary folder within it called "CycloneDDS"
// TODO(jhdcs): if this changes in future, remove this check
if package == "CycloneDDS" || new_style_include_dir.is_dir() {
builder =
builder.clang_arg(format!("-isystem{}", package_include_dir.display()));
}
// CycloneDDS is a special case - it needs to be included as if it were a new-style path, but
// doesn't actually have a secondary folder within it called "CycloneDDS"
// TODO(jhdcs): if this changes in future, remove this check
if package == "CycloneDDS" || new_style_include_dir.is_dir() {
builder =
builder.clang_arg(format!("-isystem{}", package_include_dir.display()));
}
}

// Link the native libraries
let library_path = ament_prefix_path.join("lib");
println!("cargo:rustc-link-search=native={}", library_path.display());
}
} else {
panic!(
"{} environment variable not set - please source ROS 2 installation first.",
AMENT_PREFIX_PATH
);

// Link the native libraries
let library_path = ament_prefix_path.join("lib");
println!("cargo:rustc-link-search=native={}", library_path.display());
}

println!("cargo:rustc-link-lib=dylib=rcl");
Expand Down
14 changes: 7 additions & 7 deletions rclrs/src/context.rs
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,8 @@ impl Drop for rcl_context_t {
fn drop(&mut self) {
// SAFETY: These functions have no preconditions besides a valid/initialized handle
unsafe {
rcl_shutdown(self as *mut _);
rcl_context_fini(self as *mut _);
rcl_shutdown(self);
rcl_context_fini(self);
}
}
}
Expand Down Expand Up @@ -74,7 +74,7 @@ impl Context {
let mut init_options = rcl_get_zero_initialized_init_options();
// SAFETY: Passing in a zero-initialized value is expected.
// In the case where this returns not ok, there's nothing to clean up.
rcl_init_options_init(&mut init_options as *mut _, allocator).ok()?;
rcl_init_options_init(&mut init_options, allocator).ok()?;
// SAFETY: This function does not store the ephemeral init_options and c_args
// pointers. Passing in a zero-initialized handle is expected.
let ret = rcl_init(
Expand All @@ -84,12 +84,12 @@ impl Context {
} else {
c_args.as_ptr()
},
&init_options as *const _,
handle as *mut _,
&init_options,
handle,
);
// SAFETY: It's safe to pass in an initialized object.
// Early return will not leak memory, because this is the last fini function.
rcl_init_options_fini(&mut init_options as *mut _).ok()?;
rcl_init_options_fini(&mut init_options).ok()?;
// Move the check after the last fini()
ret.ok()?;
}
Expand Down Expand Up @@ -123,6 +123,6 @@ impl Context {
// handler could call `rcl_shutdown()`, hence making the context invalid.
let handle = &mut *self.handle.lock();
// SAFETY: No preconditions for this function.
unsafe { rcl_context_is_valid(handle as *mut _) }
unsafe { rcl_context_is_valid(handle) }
}
}
9 changes: 8 additions & 1 deletion rclrs/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -54,8 +54,15 @@ pub fn spin_once(node: &Node, timeout: Option<Duration>) -> Result<(), RclReturn
///
/// This function additionally checks that the context is still valid.
pub fn spin(node: &Node) -> Result<(), RclReturnCode> {
// The context_is_valid functions exists only to abstract away ROS distro differences
#[cfg(ros_distro = "foxy")]
// SAFETY: No preconditions for this function.
while unsafe { rcl_context_is_valid(&mut *node.context.lock() as *mut _) } {
let context_is_valid = || unsafe { rcl_context_is_valid(&mut *node.context.lock()) };
#[cfg(not(ros_distro = "foxy"))]
// SAFETY: No preconditions for this function.
let context_is_valid = || unsafe { rcl_context_is_valid(&*node.context.lock()) };

while context_is_valid() {
if let Some(error) = spin_once(node, None).err() {
match error {
RclReturnCode::Timeout => continue,
Expand Down
8 changes: 4 additions & 4 deletions rclrs/src/node/mod.rs
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ use rosidl_runtime_rs::Message;
impl Drop for rcl_node_t {
fn drop(&mut self) {
// SAFETY: No preconditions for this function
unsafe { rcl_node_fini(self as *mut _).unwrap() };
unsafe { rcl_node_fini(self).unwrap() };
}
}

Expand Down Expand Up @@ -70,11 +70,11 @@ impl Node {
// to keep them alive.
// The context handle is kept alive because it is co-owned by the node.
rcl_node_init(
&mut node_handle as *mut _,
&mut node_handle,
raw_node_name.as_ptr(),
raw_node_ns.as_ptr(),
context_handle as *mut _,
&node_options as *const _,
context_handle,
&node_options,
)
.ok()?;
}
Expand Down
8 changes: 4 additions & 4 deletions rclrs/src/node/publisher.rs
Original file line number Diff line number Diff line change
Expand Up @@ -81,11 +81,11 @@ where
// afterwards.
// TODO: type support?
rcl_publisher_init(
&mut publisher_handle as *mut _,
node_handle as *mut _,
&mut publisher_handle,
node_handle,
type_support,
topic_c_string.as_ptr(),
&publisher_options as *const _,
&publisher_options,
)
.ok()?;
}
Expand Down Expand Up @@ -125,7 +125,7 @@ where
// The message does not need to be valid beyond the duration of this function call.
// The third argument is explictly allowed to be NULL.
rcl_publish(
handle as *mut _,
handle,
rmw_message.as_ref() as *const <T as Message>::RmwMsg as *mut _,
std::ptr::null_mut(),
)
Expand Down
10 changes: 5 additions & 5 deletions rclrs/src/node/subscription.rs
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ impl Drop for SubscriptionHandle {
let node_handle = &mut *self.node_handle.lock();
// SAFETY: No preconditions for this function (besides the arguments being valid).
unsafe {
rcl_subscription_fini(handle as *mut _, node_handle as *mut _);
rcl_subscription_fini(handle, node_handle);
}
}
}
Expand Down Expand Up @@ -100,11 +100,11 @@ where
// afterwards.
// TODO: type support?
rcl_subscription_init(
&mut subscription_handle as *mut _,
node_handle as *mut _,
&mut subscription_handle,
node_handle,
type_support,
topic_c_string.as_ptr(),
&subscription_options as *const _,
&subscription_options,
)
.ok()?;
}
Expand Down Expand Up @@ -152,7 +152,7 @@ where
// beyond the function call.
// The latter two pointers are explicitly allowed to be NULL.
rcl_take(
handle as *const _,
handle,
&mut rmw_message as *mut <T as Message>::RmwMsg as *mut _,
std::ptr::null_mut(),
std::ptr::null_mut(),
Expand Down
14 changes: 7 additions & 7 deletions rclrs/src/wait.rs
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ pub struct ReadyEntities {
impl Drop for rcl_wait_set_t {
fn drop(&mut self) {
// SAFETY: No preconditions for this function (besides passing in a valid wait set).
let rc = unsafe { rcl_wait_set_fini(self as *mut _) };
let rc = unsafe { rcl_wait_set_fini(self) };
if let Err(e) = to_rcl_result(rc) {
panic!("Unable to release WaitSet. {:?}", e)
}
Expand All @@ -64,14 +64,14 @@ impl WaitSet {
// SAFETY: We're passing in a zero-initialized wait set and a valid context.
// There are no other preconditions.
rcl_wait_set_init(
&mut rcl_wait_set as *mut _,
&mut rcl_wait_set,
number_of_subscriptions,
0,
0,
0,
0,
0,
&mut *context.handle.lock() as *mut _,
&mut *context.handle.lock(),
rcutils_get_default_allocator(),
)
.ok()?;
Expand All @@ -94,7 +94,7 @@ impl WaitSet {
// valid, which it always is in our case. Hence, only debug_assert instead of returning
// Result.
// SAFETY: No preconditions for this function (besides passing in a valid wait set).
let ret = unsafe { rcl_wait_set_clear(&mut self.handle as *mut _) };
let ret = unsafe { rcl_wait_set_clear(&mut self.handle) };
debug_assert_eq!(ret, 0);
}

Expand All @@ -116,8 +116,8 @@ impl WaitSet {
// for as long as the wait set exists, because it's stored in self.subscriptions.
// Passing in a null pointer for the third argument is explicitly allowed.
rcl_wait_set_add_subscription(
&mut self.handle as *mut _,
&*subscription.handle().lock() as *const _,
&mut self.handle,
&*subscription.handle().lock(),
std::ptr::null_mut(),
)
}
Expand Down Expand Up @@ -162,7 +162,7 @@ impl WaitSet {
// We cannot currently guarantee that the wait sets may not share content, but it is
// mentioned in the doc comment for `add_subscription`.
// Also, the handle is obviously valid.
unsafe { rcl_wait(&mut self.handle as *mut _, timeout_ns) }.ok()?;
unsafe { rcl_wait(&mut self.handle, timeout_ns) }.ok()?;
let mut ready_entities = ReadyEntities {
subscriptions: Vec::new(),
};
Expand Down