Skip to content
Closed
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 ament_cmake_export_crates/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>ament_cmake_export_crates</name>
<version>0.0.3</version>
<version>0.2.0</version>
<description>The ability to export Rust crates to downstream packages in the ament buildsystem in CMake.</description>
<author email="[email protected]">Esteve Fernandez</author>
<maintainer email="[email protected]">Esteve Fernandez</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion rclrs/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>rclrs</name>
<version>0.0.3</version>
<version>0.2.0</version>
<description>Package containing the Rust client.</description>
<author email="[email protected]">Esteve Fernandez</author>
<maintainer email="[email protected]">Esteve Fernandez</maintainer>
Expand Down
30 changes: 21 additions & 9 deletions rclrs/src/c/rclrs.c
Original file line number Diff line number Diff line change
Expand Up @@ -4,15 +4,27 @@
#include <rcl/error_handling.h>
#include <rcl/rcl.h>

bool rclrs_native_ok() { return rcl_ok(); }
rcl_context_t ctx;

int32_t rclrs_native_init() {
// TODO(esteve): parse args
return rcl_init(0, NULL, rcl_get_default_allocator());
rcl_init_options_t opts;
ctx = rcl_get_zero_initialized_context();
rcl_ret_t ret;
ret = rcl_init_options_init(&opts, rcl_get_default_allocator());
if(ret!=RCL_RET_OK || ret!=RCL_RET_ALREADY_INIT) { return ret; }

ret = rcl_init(0, NULL, &opts, &ctx);
if(ret!=RCL_RET_OK || ret!=RCL_RET_ALREADY_INIT) { return ret; }

ret = rcl_init_options_fini(&opts);
if(ret!=RCL_RET_OK) { return ret; }

return RCL_RET_OK;
}

const char *rclrs_native_get_error_string_safe() {
return rcl_get_error_string_safe();
return rcl_get_error_string().str;
}

void rclrs_native_reset_error() { rcl_reset_error(); }
Expand All @@ -24,7 +36,7 @@ int32_t rclrs_native_create_node_handle(uintptr_t *node_handle,
*node = rcl_get_zero_initialized_node();

rcl_node_options_t default_options = rcl_node_get_default_options();
rcl_ret_t ret = rcl_node_init(node, name, namespace, &default_options);
rcl_ret_t ret = rcl_node_init(node, name, namespace, &ctx, &default_options);
*node_handle = (uintptr_t)node;
return ret;
}
Expand Down Expand Up @@ -95,21 +107,21 @@ int32_t rclrs_native_wait_set_init(uintptr_t wait_set_handle,

int32_t rclrs_native_wait_set_clear_subscriptions(uintptr_t wait_set_handle) {
rcl_wait_set_t *wait_set = (rcl_wait_set_t *)wait_set_handle;
rcl_ret_t ret = rcl_wait_set_clear_subscriptions(wait_set);
rcl_ret_t ret = rcl_wait_set_clear(wait_set);

return ret;
}

int32_t rclrs_native_wait_set_clear_services(uintptr_t wait_set_handle) {
rcl_wait_set_t *wait_set = (rcl_wait_set_t *)wait_set_handle;
rcl_ret_t ret = rcl_wait_set_clear_services(wait_set);
rcl_ret_t ret = rcl_wait_set_clear(wait_set);

return ret;
}

int32_t rclrs_native_wait_set_clear_clients(uintptr_t wait_set_handle) {
rcl_wait_set_t *wait_set = (rcl_wait_set_t *)wait_set_handle;
rcl_ret_t ret = rcl_wait_set_clear_clients(wait_set);
rcl_ret_t ret = rcl_wait_set_clear(wait_set);

return ret;
}
Expand All @@ -118,7 +130,7 @@ int32_t rclrs_native_wait_set_add_subscription(uintptr_t wait_set_handle,
uintptr_t subscription_handle) {
rcl_wait_set_t *wait_set = (rcl_wait_set_t *)wait_set_handle;
rcl_subscription_t *subscription = (rcl_subscription_t *)subscription_handle;
rcl_ret_t ret = rcl_wait_set_add_subscription(wait_set, subscription);
rcl_ret_t ret = rcl_wait_set_add_subscription(wait_set, subscription, NULL);

return ret;
}
Expand Down Expand Up @@ -160,7 +172,7 @@ int32_t rclrs_native_create_subscription_handle(

int32_t rclrs_native_take(uintptr_t subscription_handle, uintptr_t message_handle) {
rcl_subscription_t * subscription = (rcl_subscription_t *)subscription_handle;
void * taken_msg = message_handle;
void * taken_msg = (void *)message_handle;

rcl_ret_t ret = rcl_take(subscription, taken_msg, NULL);

Expand Down
2 changes: 1 addition & 1 deletion rclrs/src/rust/Cargo.toml.in
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
[package]
name = "rclrs"
version = "0.1.0"
version = "0.2.0"
authors = ["Esteve Fernandez <[email protected]>"]

[dependencies]
Expand Down
2 changes: 1 addition & 1 deletion rclrs_common/Cargo.toml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
[package]
name = "rclrs_common"
version = "0.1.0"
version = "0.2.0"
authors = ["Esteve Fernandez <[email protected]>"]

[dependencies]
Expand Down
2 changes: 1 addition & 1 deletion rclrs_common/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>rclrs_common</name>
<version>0.0.3</version>
<version>0.2.0</version>
<description>Common files for the Rust client.</description>
<author email="[email protected]">Esteve Fernandez</author>
<maintainer email="[email protected]">Esteve Fernandez</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion rclrs_examples/Cargo.toml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
[package]
name = "rclrs_examples"
version = "0.1.0"
version = "0.2.0"
authors = ["Esteve Fernandez <[email protected]>"]

[[bin]]
Expand Down
2 changes: 1 addition & 1 deletion rclrs_examples/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>rclrs_examples</name>
<version>0.0.0</version>
<version>0.2.0</version>
<description>Package containing examples of how to use the rclrs API.</description>
<maintainer email="[email protected]">Esteve Fernandez</maintainer>
<license>Apache License 2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion rosidl_generator_rs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>rosidl_generator_rs</name>
<version>0.0.3</version>
<version>0.2.0</version>
<description>Generate the ROS interfaces in Rust.</description>
<author email="[email protected]">Esteve Fernandez</author>
<maintainer email="[email protected]">Esteve Fernandez</maintainer>
Expand Down