From b9e9fdd36b538b1a29ccdd967e1b27972c318629 Mon Sep 17 00:00:00 2001 From: Ivan Santiago Paunovic Date: Thu, 20 Aug 2020 09:54:30 -0300 Subject: [PATCH 01/11] Some code that compiles and doesn't break existing tests (osrf/ros2_java#10) Signed-off-by: Ivan Santiago Paunovic --- .../org_ros2_rcljava_executors_BaseExecutor.h | 18 +++++++ ...rg_ros2_rcljava_executors_BaseExecutor.cpp | 23 ++++++++ .../ros2/rcljava/executors/AnyExecutable.java | 2 + .../ros2/rcljava/executors/BaseExecutor.java | 54 ++++++++++++++++++- .../org/ros2/rcljava/publisher/Publisher.java | 8 +++ .../ros2/rcljava/publisher/PublisherImpl.java | 10 +++- 6 files changed, 113 insertions(+), 2 deletions(-) diff --git a/rcljava/include/org_ros2_rcljava_executors_BaseExecutor.h b/rcljava/include/org_ros2_rcljava_executors_BaseExecutor.h index c94a7959..5522ac8d 100644 --- a/rcljava/include/org_ros2_rcljava_executors_BaseExecutor.h +++ b/rcljava/include/org_ros2_rcljava_executors_BaseExecutor.h @@ -134,6 +134,15 @@ JNIEXPORT void JNICALL Java_org_ros2_rcljava_executors_BaseExecutor_nativeWaitSetAddTimer( JNIEnv *, jclass, jlong, jlong); +/* + * Class: org_ros2_rcljava_executors_BaseExecutor + * Method: nativeWaitSetAddEvent + * Signature: (JJ)V + */ +JNIEXPORT void +JNICALL Java_org_ros2_rcljava_executors_BaseExecutor_nativeWaitSetAddEvent( + JNIEnv *, jclass, jlong, jlong); + /* * Class: org_ros2_rcljava_executors_BaseExecutor * Method: nativeWaitSetSubscriptionIsReady @@ -152,6 +161,15 @@ JNIEXPORT jboolean JNICALL Java_org_ros2_rcljava_executors_BaseExecutor_nativeWaitSetTimerIsReady( JNIEnv *, jclass, jlong, jlong); +/* + * Class: org_ros2_rcljava_executors_BaseExecutor + * Method: nativeWaitSetEventIsReady + * Signature: (JJ)Z + */ +JNIEXPORT jboolean +JNICALL Java_org_ros2_rcljava_executors_BaseExecutor_nativeWaitSetEventIsReady( + JNIEnv *, jclass, jlong, jlong); + /* * Class: org_ros2_rcljava_executors_BaseExecutor * Method: nativeWaitSetServiceIsReady diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_executors_BaseExecutor.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_executors_BaseExecutor.cpp index ad515de5..287a175f 100644 --- a/rcljava/src/main/cpp/org_ros2_rcljava_executors_BaseExecutor.cpp +++ b/rcljava/src/main/cpp/org_ros2_rcljava_executors_BaseExecutor.cpp @@ -276,6 +276,21 @@ Java_org_ros2_rcljava_executors_BaseExecutor_nativeWaitSetAddTimer( } } +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_executors_BaseExecutor_nativeWaitSetAddEvent( + JNIEnv * env, jclass, jlong wait_set_handle, jlong event_handle) +{ + auto * wait_set = reinterpret_cast(wait_set_handle); + auto * event = reinterpret_cast(event_handle); + rcl_ret_t ret = rcl_wait_set_add_event(wait_set, event, nullptr); + if (ret != RCL_RET_OK) { + std::string msg = + "Failed to add event to wait set: " + std::string(rcl_get_error_string().str); + rcl_reset_error(); + rcljava_throw_rclexception(env, ret, msg); + } +} + JNIEXPORT jobject JNICALL Java_org_ros2_rcljava_executors_BaseExecutor_nativeTakeRequest( JNIEnv * env, jclass, jlong service_handle, jlong jrequest_from_java_converter_handle, @@ -435,6 +450,14 @@ Java_org_ros2_rcljava_executors_BaseExecutor_nativeWaitSetTimerIsReady( return wait_set->timers[index] != nullptr; } +JNIEXPORT jboolean JNICALL +Java_org_ros2_rcljava_executors_BaseExecutor_nativeWaitSetEventIsReady( + JNIEnv *, jclass, jlong wait_set_handle, jlong index) +{ + rcl_wait_set_t * wait_set = reinterpret_cast(wait_set_handle); + return wait_set->events[index] != nullptr; +} + JNIEXPORT jboolean JNICALL Java_org_ros2_rcljava_executors_BaseExecutor_nativeWaitSetServiceIsReady( JNIEnv *, jclass, jlong wait_set_handle, jlong index) diff --git a/rcljava/src/main/java/org/ros2/rcljava/executors/AnyExecutable.java b/rcljava/src/main/java/org/ros2/rcljava/executors/AnyExecutable.java index f6ce97b9..dd3d3039 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/executors/AnyExecutable.java +++ b/rcljava/src/main/java/org/ros2/rcljava/executors/AnyExecutable.java @@ -16,6 +16,7 @@ package org.ros2.rcljava.executors; import org.ros2.rcljava.client.Client; +import org.ros2.rcljava.events.EventHandler; import org.ros2.rcljava.subscription.Subscription; import org.ros2.rcljava.service.Service; import org.ros2.rcljava.timer.Timer; @@ -25,4 +26,5 @@ public class AnyExecutable { public Subscription subscription; public Service service; public Client client; + public EventHandler eventHandler; } diff --git a/rcljava/src/main/java/org/ros2/rcljava/executors/BaseExecutor.java b/rcljava/src/main/java/org/ros2/rcljava/executors/BaseExecutor.java index f00ddf75..e7c59619 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/executors/BaseExecutor.java +++ b/rcljava/src/main/java/org/ros2/rcljava/executors/BaseExecutor.java @@ -21,6 +21,7 @@ import java.util.List; import java.util.Map; +import java.util.Collection; import java.util.concurrent.BlockingQueue; import java.util.concurrent.ConcurrentHashMap; import java.util.concurrent.LinkedBlockingQueue; @@ -31,11 +32,13 @@ import org.ros2.rcljava.RCLJava; import org.ros2.rcljava.client.Client; import org.ros2.rcljava.common.JNIUtils; +import org.ros2.rcljava.events.EventHandler; import org.ros2.rcljava.executors.AnyExecutable; import org.ros2.rcljava.executors.Executor; import org.ros2.rcljava.interfaces.MessageDefinition; import org.ros2.rcljava.interfaces.ServiceDefinition; import org.ros2.rcljava.node.ComposableNode; +import org.ros2.rcljava.publisher.Publisher; import org.ros2.rcljava.service.RMWRequestId; import org.ros2.rcljava.service.Service; import org.ros2.rcljava.subscription.Subscription; @@ -64,6 +67,8 @@ public class BaseExecutor { private List> clientHandles = new ArrayList>(); + private List> eventHandles = new ArrayList>(); + protected void addNode(ComposableNode node) { this.nodes.add(node); } @@ -158,6 +163,11 @@ protected void executeAnyExecutable(AnyExecutable anyExecutable) { } clientHandles.remove(anyExecutable.client.getHandle()); } + + if (anyExecutable.eventHandler != null) { + anyExecutable.eventHandler.executeCallback(); + eventHandles.remove(anyExecutable.eventHandler.getHandle()); + } } protected void waitForWork(long timeout) { @@ -165,6 +175,7 @@ protected void waitForWork(long timeout) { this.timerHandles.clear(); this.serviceHandles.clear(); this.clientHandles.clear(); + this.eventHandles.clear(); for (ComposableNode node : this.nodes) { for (Subscription subscription : node.getNode().getSubscriptions()) { @@ -172,6 +183,14 @@ protected void waitForWork(long timeout) { subscription.getHandle(), subscription)); } + for (Publisher publisher : node.getNode().getPublishers()) { + Collection eventHandlers = publisher.getEventHandlers(); + for (EventHandler eventHandler : eventHandlers) { + this.eventHandles.add(new AbstractMap.SimpleEntry( + eventHandler.getHandle(), eventHandler)); + } + } + for (Timer timer : node.getNode().getTimers()) { this.timerHandles.add(new AbstractMap.SimpleEntry(timer.getHandle(), timer)); } @@ -191,6 +210,7 @@ protected void waitForWork(long timeout) { int timersSize = 0; int clientsSize = 0; int servicesSize = 0; + int eventsSize = this.eventHandles.size(); for (ComposableNode node : this.nodes) { subscriptionsSize += node.getNode().getSubscriptions().size(); @@ -205,7 +225,9 @@ protected void waitForWork(long timeout) { long waitSetHandle = nativeGetZeroInitializedWaitSet(); long contextHandle = RCLJava.getDefaultContext().getHandle(); - nativeWaitSetInit(waitSetHandle, contextHandle, subscriptionsSize, 0, timersSize, clientsSize, servicesSize, 0); + nativeWaitSetInit( + waitSetHandle, contextHandle, subscriptionsSize, 0, + timersSize, clientsSize, servicesSize, eventsSize); nativeWaitSetClear(waitSetHandle); @@ -225,6 +247,10 @@ protected void waitForWork(long timeout) { nativeWaitSetAddClient(waitSetHandle, entry.getKey()); } + for (Map.Entry entry : this.eventHandles) { + nativeWaitSetAddEvent(waitSetHandle, entry.getKey()); + } + nativeWait(waitSetHandle, timeout); for (int i = 0; i < this.subscriptionHandles.size(); ++i) { @@ -251,6 +277,12 @@ protected void waitForWork(long timeout) { } } + for (int i = 0; i < this.eventHandles.size(); ++i) { + if (!nativeWaitSetEventIsReady(waitSetHandle, i)) { + this.eventHandles.get(i).setValue(null); + } + } + Iterator> subscriptionIterator = this.subscriptionHandles.iterator(); while (subscriptionIterator.hasNext()) { @@ -284,6 +316,14 @@ protected void waitForWork(long timeout) { } } + Iterator> eventIterator = this.eventHandles.iterator(); + while (eventIterator.hasNext()) { + Map.Entry entry = eventIterator.next(); + if (entry.getValue() == null) { + eventIterator.remove(); + } + } + nativeDisposeWaitSet(waitSetHandle); } @@ -325,6 +365,14 @@ protected AnyExecutable getNextExecutable() { } } + for (Map.Entry entry : this.eventHandles) { + if (entry.getValue() != null) { + anyExecutable.eventHandler = entry.getValue(); + entry.setValue(null); + return anyExecutable; + } + } + return null; } @@ -405,6 +453,8 @@ private static native MessageDefinition nativeTake( private static native void nativeWaitSetAddTimer(long waitSetHandle, long timerHandle); + private static native void nativeWaitSetAddEvent(long waitSetHandle, long eventHandle); + private static native RMWRequestId nativeTakeRequest(long serviceHandle, long requestFromJavaConverterHandle, long requestToJavaConverterHandle, long requestDestructorHandle, MessageDefinition requestMessage); @@ -421,6 +471,8 @@ private static native RMWRequestId nativeTakeResponse(long clientHandle, private static native boolean nativeWaitSetTimerIsReady(long waitSetHandle, long index); + private static native boolean nativeWaitSetEventIsReady(long waitSetHandle, long index); + private static native boolean nativeWaitSetServiceIsReady(long waitSetHandle, long index); private static native boolean nativeWaitSetClientIsReady(long waitSetHandle, long index); diff --git a/rcljava/src/main/java/org/ros2/rcljava/publisher/Publisher.java b/rcljava/src/main/java/org/ros2/rcljava/publisher/Publisher.java index d21eece2..47c857ff 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/publisher/Publisher.java +++ b/rcljava/src/main/java/org/ros2/rcljava/publisher/Publisher.java @@ -16,6 +16,7 @@ package org.ros2.rcljava.publisher; import java.lang.ref.WeakReference; +import java.util.Collection; import java.util.function.Supplier; import org.ros2.rcljava.consumers.Consumer; @@ -64,4 +65,11 @@ EventHandler createEventHandler( */ void removeEventHandler( EventHandler eventHandler); + + /** + * Get the event handlers that were registered in this Publisher. + * + * @return The registered event handlers. + */ + Collection getEventHandlers(); } diff --git a/rcljava/src/main/java/org/ros2/rcljava/publisher/PublisherImpl.java b/rcljava/src/main/java/org/ros2/rcljava/publisher/PublisherImpl.java index 2bba3892..17018f87 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/publisher/PublisherImpl.java +++ b/rcljava/src/main/java/org/ros2/rcljava/publisher/PublisherImpl.java @@ -139,7 +139,15 @@ void removeEventHandler( } /** - * Create a publisher event (rcl_event_t). + * {@inheritDoc} + */ + public final + Collection getEventHandlers() { + return this.eventHandlers; + } + + /** + * Create a publisher event (rcl_event_t) * * The ownership of the created event handle will immediately be transferred to an * @{link EventHandlerImpl}, that will be responsible of disposing it. From e80c5df6045fb87744ac90c17823228ee8d0f148 Mon Sep 17 00:00:00 2001 From: Ivan Santiago Paunovic Date: Thu, 20 Aug 2020 12:48:37 -0300 Subject: [PATCH 02/11] Add offered qos incompatible event and event executor test (osrf/ros2_java#11) Signed-off-by: Ivan Santiago Paunovic --- rcljava/CMakeLists.txt | 2 + ...ublisher_statuses_OfferedQosIncompatible.h | 63 +++++++++ ...ents_publisher_statuses_LivelinessLost.cpp | 6 +- ...lisher_statuses_OfferedQosIncompatible.cpp | 120 ++++++++++++++++++ .../publisher_statuses/LivelinessLost.java | 4 +- .../OfferedQosIncompatible.java | 76 +++++++++++ .../test/java/org/ros2/rcljava/SpinTest.java | 67 ++++++++++ .../ros2/rcljava/publisher/PublisherTest.java | 36 +++++- 8 files changed, 368 insertions(+), 6 deletions(-) create mode 100644 rcljava/include/org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.h create mode 100644 rcljava/src/main/cpp/org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.cpp create mode 100644 rcljava/src/main/java/org/ros2/rcljava/events/publisher_statuses/OfferedQosIncompatible.java diff --git a/rcljava/CMakeLists.txt b/rcljava/CMakeLists.txt index 159d45e8..1bfd2bb2 100644 --- a/rcljava/CMakeLists.txt +++ b/rcljava/CMakeLists.txt @@ -61,6 +61,7 @@ set(${PROJECT_NAME}_jni_sources "src/main/cpp/org_ros2_rcljava_executors_BaseExecutor.cpp" "src/main/cpp/org_ros2_rcljava_events_EventHandlerImpl.cpp" "src/main/cpp/org_ros2_rcljava_events_publisher_statuses_LivelinessLost.cpp" + "src/main/cpp/org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.cpp" "src/main/cpp/org_ros2_rcljava_node_NodeImpl.cpp" "src/main/cpp/org_ros2_rcljava_publisher_PublisherImpl.cpp" "src/main/cpp/org_ros2_rcljava_service_ServiceImpl.cpp" @@ -133,6 +134,7 @@ set(${PROJECT_NAME}_sources "src/main/java/org/ros2/rcljava/events/PublisherEventStatus.java" "src/main/java/org/ros2/rcljava/events/SubscriptionEventStatus.java" "src/main/java/org/ros2/rcljava/events/publisher_statuses/LivelinessLost.java" + "src/main/java/org/ros2/rcljava/events/publisher_statuses/OfferedQosIncompatible.java" "src/main/java/org/ros2/rcljava/executors/AnyExecutable.java" "src/main/java/org/ros2/rcljava/executors/BaseExecutor.java" "src/main/java/org/ros2/rcljava/executors/Executor.java" diff --git a/rcljava/include/org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.h b/rcljava/include/org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.h new file mode 100644 index 00000000..0c17d341 --- /dev/null +++ b/rcljava/include/org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.h @@ -0,0 +1,63 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +/* Header for class org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible */ + +#ifndef ORG_ROS2_RCLJAVA_EVENTS_PUBLISHER_STATUSES_OFFEREDQOSINCOMPATIBLE_H_ +#define ORG_ROS2_RCLJAVA_EVENTS_PUBLISHER_STATUSES_OFFEREDQOSINCOMPATIBLE_H_ +#ifdef __cplusplus +extern "C" { +#endif + +/* + * Class: org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible + * Method: nAllocateRCLStatusEvent + * Signature: ()J + */ +JNIEXPORT jlong JNICALL +Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nAllocateRCLStatusEvent( + JNIEnv *, jclass); + +/* + * Class: org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible + * Method: nDeallocateRCLStatusEvent + * Signature: (J)V + */ +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nDeallocateRCLStatusEvent( + JNIEnv *, jclass, jlong); + +/* + * Class: org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible + * Method: nFromRCLEvent + * Signature: (J)V + */ +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nFromRCLEvent( + JNIEnv *, jobject, jlong); + +/* + * Class: org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible + * Method: nGetPublisherEventType + * Signature: ()I + */ +JNIEXPORT jint JNICALL +Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nGetPublisherEventType( + JNIEnv *, jclass); + +#ifdef __cplusplus +} +#endif +#endif // ORG_ROS2_RCLJAVA_EVENTS_PUBLISHER_STATUSES_OFFEREDQOSINCOMPATIBLE_H_ diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_events_publisher_statuses_LivelinessLost.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_events_publisher_statuses_LivelinessLost.cpp index 95bad689..1b658a28 100644 --- a/rcljava/src/main/cpp/org_ros2_rcljava_events_publisher_statuses_LivelinessLost.cpp +++ b/rcljava/src/main/cpp/org_ros2_rcljava_events_publisher_statuses_LivelinessLost.cpp @@ -17,7 +17,7 @@ #include #include -#include "rmw/events_statuses/liveliness_lost.h" +#include "rmw/types.h" #include "rcl/event.h" #include "rcljava_common/exceptions.hpp" @@ -53,11 +53,11 @@ Java_org_ros2_rcljava_events_publisher_1statuses_LivelinessLost_nativeFromRCLEve } // TODO(ivanpauno): class and field lookup could be done at startup time jclass clazz = env->GetObjectClass(self); - jfieldID total_count_fid = env->GetFieldID(clazz, "total_count", "I"); + jfieldID total_count_fid = env->GetFieldID(clazz, "totalCount", "I"); if (env->ExceptionCheck()) { return; } - jfieldID total_count_change_fid = env->GetFieldID(clazz, "total_count_change", "I"); + jfieldID total_count_change_fid = env->GetFieldID(clazz, "totalCountChange", "I"); if (env->ExceptionCheck()) { return; } diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.cpp new file mode 100644 index 00000000..ed3f4fcd --- /dev/null +++ b/rcljava/src/main/cpp/org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.cpp @@ -0,0 +1,120 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.h" + +#include +#include + +#include "rmw/incompatible_qos_events_statuses.h" +#include "rmw/types.h" +#include "rcl/event.h" +#include "rcljava_common/exceptions.hpp" + +using rcljava_common::exceptions::rcljava_throw_exception; + +JNIEXPORT jlong JNICALL +Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nAllocateRCLStatusEvent( + JNIEnv * env, jclass) +{ + void * p = malloc(sizeof(rmw_offered_qos_incompatible_event_status_t)); + if (!p) { + rcljava_throw_exception( + env, "java/lang/OutOfMemoryError", "failed to allocate offered qos incompatible status"); + } + return reinterpret_cast(p); +} + +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nDeallocateRCLStatusEvent( + JNIEnv *, jclass, jlong handle) +{ + free(reinterpret_cast(handle)); +} + +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nFromRCLEvent( + JNIEnv * env, jobject self, jlong handle) +{ + auto * p = reinterpret_cast(handle); + if (!p) { + rcljava_throw_exception( + env, "java/lang/IllegalArgumentException", "passed rmw object handle is NULL"); + } + // TODO(ivanpauno): class and field lookup could be done at startup time + jclass clazz = env->GetObjectClass(self); + jclass qos_kind_clazz = env->FindClass( + "org/ros2/rcljava/events/publisher_statuses/OfferedQosIncompatible$PolicyKind"); + if (env->ExceptionCheck()) { + return; + } + jfieldID total_count_fid = env->GetFieldID(clazz, "totalCount", "I"); + if (env->ExceptionCheck()) { + return; + } + jfieldID total_count_change_fid = env->GetFieldID(clazz, "totalCountChange", "I"); + if (env->ExceptionCheck()) { + return; + } + const char * enum_class_path = + "Lorg/ros2/rcljava/events/publisher_statuses/OfferedQosIncompatible$PolicyKind;"; + jfieldID policy_kind_fid = env->GetFieldID(clazz, "lastPolicyKind", enum_class_path); + if (env->ExceptionCheck()) { + return; + } + + jfieldID enum_value_fid; + switch (p->last_policy_kind) { + case RMW_QOS_POLICY_INVALID: + enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "INVALID", enum_class_path); + break; + case RMW_QOS_POLICY_DURABILITY: + enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "DURABILITY", enum_class_path); + break; + case RMW_QOS_POLICY_DEADLINE: + enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "DEADLINE", enum_class_path); + break; + case RMW_QOS_POLICY_LIVELINESS: + enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "LIVELINESS", enum_class_path); + break; + case RMW_QOS_POLICY_RELIABILITY: + enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "RELIABILITY", enum_class_path); + break; + case RMW_QOS_POLICY_HISTORY: + enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "HISTORY", enum_class_path); + break; + case RMW_QOS_POLICY_LIFESPAN: + enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "LIFESPAN", enum_class_path); + break; + default: + rcljava_throw_exception( + env, "java/lang/IllegalStateException", "unknown rmw qos policy kind"); + break; + } + if (env->ExceptionCheck()) { + return; + } + jobject enum_value = env->GetStaticObjectField(qos_kind_clazz, enum_value_fid); + + env->SetIntField(self, total_count_fid, p->total_count); + env->SetIntField(self, total_count_change_fid, p->total_count_change); + env->SetObjectField(self, policy_kind_fid, enum_value); +} + +JNIEXPORT jint JNICALL +Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nGetPublisherEventType( + JNIEnv *, jclass) +{ + return RCL_PUBLISHER_OFFERED_INCOMPATIBLE_QOS; +} diff --git a/rcljava/src/main/java/org/ros2/rcljava/events/publisher_statuses/LivelinessLost.java b/rcljava/src/main/java/org/ros2/rcljava/events/publisher_statuses/LivelinessLost.java index 615126be..003e3ff5 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/events/publisher_statuses/LivelinessLost.java +++ b/rcljava/src/main/java/org/ros2/rcljava/events/publisher_statuses/LivelinessLost.java @@ -26,8 +26,8 @@ * This class serves as a bridge between a rmw_liveliness_lost_status_t and RCLJava. */ public class LivelinessLost implements PublisherEventStatus { - int total_count; - int total_count_change; + public int totalCount; + public int totalCountChange; public final long allocateRCLStatusEvent() { return nativeAllocateRCLStatusEvent(); diff --git a/rcljava/src/main/java/org/ros2/rcljava/events/publisher_statuses/OfferedQosIncompatible.java b/rcljava/src/main/java/org/ros2/rcljava/events/publisher_statuses/OfferedQosIncompatible.java new file mode 100644 index 00000000..9b506703 --- /dev/null +++ b/rcljava/src/main/java/org/ros2/rcljava/events/publisher_statuses/OfferedQosIncompatible.java @@ -0,0 +1,76 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +package org.ros2.rcljava.events.publisher_statuses; + +import java.util.function.Supplier; + +import org.ros2.rcljava.common.JNIUtils; +import org.ros2.rcljava.events.PublisherEventStatus; + +import org.slf4j.Logger; +import org.slf4j.LoggerFactory; + +/** + * This class serves as a bridge between a rmw_qos_incompatible_event_status_t and RCLJava. + */ +public class OfferedQosIncompatible implements PublisherEventStatus { + public int totalCount; + public int totalCountChange; + public PolicyKind lastPolicyKind; + + public enum PolicyKind { + INVALID, + DURABILITY, + DEADLINE, + LIVELINESS, + RELIABILITY, + HISTORY, + LIFESPAN; + } + + public final long allocateRCLStatusEvent() { + return nAllocateRCLStatusEvent(); + } + public final void deallocateRCLStatusEvent(long handle) { + nDeallocateRCLStatusEvent(handle); + } + public final void fromRCLEvent(long handle) { + nFromRCLEvent(handle); + } + public final int getPublisherEventType() { + return nGetPublisherEventType(); + } + // TODO(ivanpauno): Remove this when -source 8 can be used (method references for the win) + public static final Supplier factory = new Supplier() { + public OfferedQosIncompatible get() { + return new OfferedQosIncompatible(); + } + }; + + private static final Logger logger = LoggerFactory.getLogger(OfferedQosIncompatible.class); + static { + try { + JNIUtils.loadImplementation(OfferedQosIncompatible.class); + } catch (UnsatisfiedLinkError ule) { + logger.error("Native code library failed to load.\n" + ule); + System.exit(1); + } + } + + private static native long nAllocateRCLStatusEvent(); + private static native void nDeallocateRCLStatusEvent(long handle); + private native void nFromRCLEvent(long handle); + private static native int nGetPublisherEventType(); +} diff --git a/rcljava/src/test/java/org/ros2/rcljava/SpinTest.java b/rcljava/src/test/java/org/ros2/rcljava/SpinTest.java index e8d97644..4d3cfa8f 100644 --- a/rcljava/src/test/java/org/ros2/rcljava/SpinTest.java +++ b/rcljava/src/test/java/org/ros2/rcljava/SpinTest.java @@ -18,6 +18,7 @@ import static org.junit.Assert.assertEquals; import static org.junit.Assert.assertNotEquals; +import java.lang.System; import java.lang.reflect.Method; import java.util.concurrent.TimeUnit; @@ -27,11 +28,20 @@ import org.ros2.rcljava.RCLJava; import org.ros2.rcljava.concurrent.Callback; +import org.ros2.rcljava.consumers.Consumer; +import org.ros2.rcljava.events.EventHandler; +import org.ros2.rcljava.events.publisher_statuses.OfferedQosIncompatible; import org.ros2.rcljava.executors.Executor; import org.ros2.rcljava.executors.SingleThreadedExecutor; import org.ros2.rcljava.node.ComposableNode; import org.ros2.rcljava.node.Node; import org.ros2.rcljava.timer.WallTimer; +import org.ros2.rcljava.publisher.Publisher; +import org.ros2.rcljava.qos.policies.Durability; +import org.ros2.rcljava.qos.policies.History; +import org.ros2.rcljava.qos.policies.Reliability; +import org.ros2.rcljava.qos.QoSProfile; +import org.ros2.rcljava.subscription.Subscription; public class SpinTest { public static class TimerCallback implements Callback { @@ -345,4 +355,61 @@ public Node getNode() { executor.spinAll(100*1000*1000); assertEquals(1, timerCallback.getCounter()); } + + // custom event consumer + public static class EventConsumer implements Consumer { + public boolean done = false; + + public void accept(final OfferedQosIncompatible status) { + assertEquals(status.totalCount, 1); + assertEquals(status.totalCountChange, 1); + assertEquals(status.lastPolicyKind, OfferedQosIncompatible.PolicyKind.RELIABILITY); + this.done = true; + } + } + + @Test + public final void testSpinEvent() { + String identifier = RCLJava.getRMWIdentifier(); + if (identifier.equals("rmw_fastrtps_cpp") || identifier.equals("rmw_fastrtps_dynamic_cpp")) { + // OfferedQosIncompatible event not supported in these implementations + return; + } + final Node node = RCLJava.createNode("test_node_spin_event"); + Publisher publisher = node.createPublisher( + std_msgs.msg.String.class, "test_topic_spin_event", new QoSProfile( + History.KEEP_LAST, 1, + Reliability.BEST_EFFORT, + Durability.VOLATILE, + false)); + // create a OfferedQoSIncompatible event handler with custom event consumer + EventConsumer eventConsumer = new EventConsumer(); + EventHandler eventHandler = publisher.createEventHandler( + OfferedQosIncompatible.factory, eventConsumer + ); + // create an incompatible subscription (reliable vs best effort publisher) + Subscription subscription = node.createSubscription( + std_msgs.msg.String.class, "test_topic_spin_event", + new Consumer() { + public void accept(final std_msgs.msg.String msg) {} + }, + new QoSProfile( + History.KEEP_LAST, 1, + Reliability.RELIABLE, + Durability.VOLATILE, + false)); + // set up executor + ComposableNode composableNode = new ComposableNode() { + public Node getNode() { + return node; + } + }; + Executor executor = new SingleThreadedExecutor(); + executor.addNode(composableNode); + long start = System.currentTimeMillis(); + do { + executor.spinAll((1000 + System.currentTimeMillis() - start) * 1000 * 1000); + } while (!eventConsumer.done && System.currentTimeMillis() < start + 1000); + assert(eventConsumer.done); + } } diff --git a/rcljava/src/test/java/org/ros2/rcljava/publisher/PublisherTest.java b/rcljava/src/test/java/org/ros2/rcljava/publisher/PublisherTest.java index c4e0bd99..9e617840 100644 --- a/rcljava/src/test/java/org/ros2/rcljava/publisher/PublisherTest.java +++ b/rcljava/src/test/java/org/ros2/rcljava/publisher/PublisherTest.java @@ -27,6 +27,8 @@ import org.ros2.rcljava.consumers.Consumer; import org.ros2.rcljava.events.EventHandler; import org.ros2.rcljava.events.publisher_statuses.LivelinessLost; +import org.ros2.rcljava.events.publisher_statuses.OfferedQosIncompatible; +import org.ros2.rcljava.exceptions.RCLException; import org.ros2.rcljava.node.Node; public class PublisherTest { @@ -75,10 +77,42 @@ public final void testCreateLivelinessLostEvent() { node.createPublisher(std_msgs.msg.String.class, "test_topic"); EventHandler eventHandler = publisher.createEventHandler( LivelinessLost.factory, new Consumer() { - public void accept(final LivelinessLost status) {} + public void accept(final LivelinessLost status) { + assertEquals(status.totalCount, 0); + assertEquals(status.totalCountChange, 0); + } } ); assertNotEquals(0, eventHandler.getHandle()); + // force executing the callback, so we check that taking an event works + eventHandler.executeCallback(); + RCLJava.shutdown(); + assertEquals(0, eventHandler.getHandle()); + } + + @Test + public final void testCreateOfferedQosIncompatibleEvent() { + String identifier = RCLJava.getRMWIdentifier(); + if (identifier.equals("rmw_fastrtps_cpp") || identifier.equals("rmw_fastrtps_dynamic_cpp")) { + // event not supported in these implementations + return; + } + RCLJava.rclJavaInit(); + Node node = RCLJava.createNode("test_node"); + Publisher publisher = + node.createPublisher(std_msgs.msg.String.class, "test_topic"); + EventHandler eventHandler = publisher.createEventHandler( + OfferedQosIncompatible.factory, new Consumer() { + public void accept(final OfferedQosIncompatible status) { + assertEquals(status.totalCount, 0); + assertEquals(status.totalCountChange, 0); + assertEquals(status.lastPolicyKind, OfferedQosIncompatible.PolicyKind.INVALID); + } + } + ); + assertNotEquals(0, eventHandler.getHandle()); + // force executing the callback, so we check that taking an event works + eventHandler.executeCallback(); RCLJava.shutdown(); assertEquals(0, eventHandler.getHandle()); } From af60743351ef4f47b6e7a8e48a2ba570dfb0001e Mon Sep 17 00:00:00 2001 From: Ivan Santiago Paunovic Date: Mon, 24 Aug 2020 13:32:59 -0300 Subject: [PATCH 03/11] Move events.publisher_statuses to publisher.statuses (osrf/ros2_java#12) Signed-off-by: Ivan Santiago Paunovic --- rcljava/CMakeLists.txt | 8 +++---- ...ljava_publisher_statuses_LivelinessLost.h} | 24 +++++++++---------- ...blisher_statuses_OfferedQosIncompatible.h} | 24 +++++++++---------- ...ava_publisher_statuses_LivelinessLost.cpp} | 10 ++++---- ...isher_statuses_OfferedQosIncompatible.cpp} | 14 +++++------ .../statuses}/LivelinessLost.java | 2 +- .../statuses}/OfferedQosIncompatible.java | 2 +- .../test/java/org/ros2/rcljava/SpinTest.java | 2 +- .../ros2/rcljava/publisher/PublisherTest.java | 4 ++-- 9 files changed, 45 insertions(+), 45 deletions(-) rename rcljava/include/{org_ros2_rcljava_events_publisher_statuses_LivelinessLost.h => org_ros2_rcljava_publisher_statuses_LivelinessLost.h} (55%) rename rcljava/include/{org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.h => org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.h} (52%) rename rcljava/src/main/cpp/{org_ros2_rcljava_events_publisher_statuses_LivelinessLost.cpp => org_ros2_rcljava_publisher_statuses_LivelinessLost.cpp} (82%) rename rcljava/src/main/cpp/{org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.cpp => org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.cpp} (85%) rename rcljava/src/main/java/org/ros2/rcljava/{events/publisher_statuses => publisher/statuses}/LivelinessLost.java (97%) rename rcljava/src/main/java/org/ros2/rcljava/{events/publisher_statuses => publisher/statuses}/OfferedQosIncompatible.java (97%) diff --git a/rcljava/CMakeLists.txt b/rcljava/CMakeLists.txt index 1bfd2bb2..06ea9079 100644 --- a/rcljava/CMakeLists.txt +++ b/rcljava/CMakeLists.txt @@ -60,8 +60,8 @@ set(${PROJECT_NAME}_jni_sources "src/main/cpp/org_ros2_rcljava_contexts_ContextImpl.cpp" "src/main/cpp/org_ros2_rcljava_executors_BaseExecutor.cpp" "src/main/cpp/org_ros2_rcljava_events_EventHandlerImpl.cpp" - "src/main/cpp/org_ros2_rcljava_events_publisher_statuses_LivelinessLost.cpp" - "src/main/cpp/org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.cpp" + "src/main/cpp/org_ros2_rcljava_publisher_statuses_LivelinessLost.cpp" + "src/main/cpp/org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.cpp" "src/main/cpp/org_ros2_rcljava_node_NodeImpl.cpp" "src/main/cpp/org_ros2_rcljava_publisher_PublisherImpl.cpp" "src/main/cpp/org_ros2_rcljava_service_ServiceImpl.cpp" @@ -133,8 +133,8 @@ set(${PROJECT_NAME}_sources "src/main/java/org/ros2/rcljava/events/EventStatus.java" "src/main/java/org/ros2/rcljava/events/PublisherEventStatus.java" "src/main/java/org/ros2/rcljava/events/SubscriptionEventStatus.java" - "src/main/java/org/ros2/rcljava/events/publisher_statuses/LivelinessLost.java" - "src/main/java/org/ros2/rcljava/events/publisher_statuses/OfferedQosIncompatible.java" + "src/main/java/org/ros2/rcljava/publisher/statuses/LivelinessLost.java" + "src/main/java/org/ros2/rcljava/publisher/statuses/OfferedQosIncompatible.java" "src/main/java/org/ros2/rcljava/executors/AnyExecutable.java" "src/main/java/org/ros2/rcljava/executors/BaseExecutor.java" "src/main/java/org/ros2/rcljava/executors/Executor.java" diff --git a/rcljava/include/org_ros2_rcljava_events_publisher_statuses_LivelinessLost.h b/rcljava/include/org_ros2_rcljava_publisher_statuses_LivelinessLost.h similarity index 55% rename from rcljava/include/org_ros2_rcljava_events_publisher_statuses_LivelinessLost.h rename to rcljava/include/org_ros2_rcljava_publisher_statuses_LivelinessLost.h index 53126f7b..b8af4373 100644 --- a/rcljava/include/org_ros2_rcljava_events_publisher_statuses_LivelinessLost.h +++ b/rcljava/include/org_ros2_rcljava_publisher_statuses_LivelinessLost.h @@ -13,51 +13,51 @@ // limitations under the License. #include -/* Header for class org_ros2_rcljava_events_publisher_statuses_LivelinessLost */ +/* Header for class org_ros2_rcljava_publisher_statuses_LivelinessLost */ -#ifndef ORG_ROS2_RCLJAVA_EVENTS_PUBLISHER_STATUSES_LIVELINESSLOST_H_ -#define ORG_ROS2_RCLJAVA_EVENTS_PUBLISHER_STATUSES_LIVELINESSLOST_H_ +#ifndef ORG_ROS2_RCLJAVA_PUBLISHER_STATUSES_LIVELINESSLOST_H_ +#define ORG_ROS2_RCLJAVA_PUBLISHER_STATUSES_LIVELINESSLOST_H_ #ifdef __cplusplus extern "C" { #endif /* - * Class: org_ros2_rcljava_events_publisher_statuses_LivelinessLost + * Class: org_ros2_rcljava_publisher_statuses_LivelinessLost * Method: nativeAllocateRCLStatusEvent * Signature: ()J */ JNIEXPORT jlong JNICALL -Java_org_ros2_rcljava_events_publisher_1statuses_LivelinessLost_nativeAllocateRCLStatusEvent( +Java_org_ros2_rcljava_publisher_statuses_LivelinessLost_nativeAllocateRCLStatusEvent( JNIEnv *, jclass); /* - * Class: org_ros2_rcljava_events_publisher_statuses_LivelinessLost + * Class: org_ros2_rcljava_publisher_statuses_LivelinessLost * Method: nativeDeallocateRCLStatusEvent * Signature: (J)V */ JNIEXPORT void JNICALL -Java_org_ros2_rcljava_events_publisher_1statuses_LivelinessLost_nativeDeallocateRCLStatusEvent( +Java_org_ros2_rcljava_publisher_statuses_LivelinessLost_nativeDeallocateRCLStatusEvent( JNIEnv *, jclass, jlong); /* - * Class: org_ros2_rcljava_events_publisher_statuses_LivelinessLost + * Class: org_ros2_rcljava_publisher_statuses_LivelinessLost * Method: nativeFromRCLEvent * Signature: (J)V */ JNIEXPORT void JNICALL -Java_org_ros2_rcljava_events_publisher_1statuses_LivelinessLost_nativeFromRCLEvent( +Java_org_ros2_rcljava_publisher_statuses_LivelinessLost_nativeFromRCLEvent( JNIEnv *, jobject, jlong); /* - * Class: org_ros2_rcljava_events_publisher_statuses_LivelinessLost + * Class: org_ros2_rcljava_publisher_statuses_LivelinessLost * Method: nativeGetPublisherEventType * Signature: ()I */ JNIEXPORT jint JNICALL -Java_org_ros2_rcljava_events_publisher_1statuses_LivelinessLost_nativeGetPublisherEventType( +Java_org_ros2_rcljava_publisher_statuses_LivelinessLost_nativeGetPublisherEventType( JNIEnv *, jclass); #ifdef __cplusplus } #endif -#endif // ORG_ROS2_RCLJAVA_EVENTS_PUBLISHER_STATUSES_LIVELINESSLOST_H_ +#endif // ORG_ROS2_RCLJAVA_PUBLISHER_STATUSES_LIVELINESSLOST_H_ diff --git a/rcljava/include/org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.h b/rcljava/include/org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.h similarity index 52% rename from rcljava/include/org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.h rename to rcljava/include/org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.h index 0c17d341..44b8ea07 100644 --- a/rcljava/include/org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.h +++ b/rcljava/include/org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.h @@ -13,51 +13,51 @@ // limitations under the License. #include -/* Header for class org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible */ +/* Header for class org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible */ -#ifndef ORG_ROS2_RCLJAVA_EVENTS_PUBLISHER_STATUSES_OFFEREDQOSINCOMPATIBLE_H_ -#define ORG_ROS2_RCLJAVA_EVENTS_PUBLISHER_STATUSES_OFFEREDQOSINCOMPATIBLE_H_ +#ifndef ORG_ROS2_RCLJAVA_PUBLISHER_STATUSES_OFFEREDQOSINCOMPATIBLE_H_ +#define ORG_ROS2_RCLJAVA_PUBLISHER_STATUSES_OFFEREDQOSINCOMPATIBLE_H_ #ifdef __cplusplus extern "C" { #endif /* - * Class: org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible + * Class: org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible * Method: nAllocateRCLStatusEvent * Signature: ()J */ JNIEXPORT jlong JNICALL -Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nAllocateRCLStatusEvent( +Java_org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible_nAllocateRCLStatusEvent( JNIEnv *, jclass); /* - * Class: org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible + * Class: org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible * Method: nDeallocateRCLStatusEvent * Signature: (J)V */ JNIEXPORT void JNICALL -Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nDeallocateRCLStatusEvent( +Java_org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible_nDeallocateRCLStatusEvent( JNIEnv *, jclass, jlong); /* - * Class: org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible + * Class: org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible * Method: nFromRCLEvent * Signature: (J)V */ JNIEXPORT void JNICALL -Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nFromRCLEvent( +Java_org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible_nFromRCLEvent( JNIEnv *, jobject, jlong); /* - * Class: org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible + * Class: org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible * Method: nGetPublisherEventType * Signature: ()I */ JNIEXPORT jint JNICALL -Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nGetPublisherEventType( +Java_org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible_nGetPublisherEventType( JNIEnv *, jclass); #ifdef __cplusplus } #endif -#endif // ORG_ROS2_RCLJAVA_EVENTS_PUBLISHER_STATUSES_OFFEREDQOSINCOMPATIBLE_H_ +#endif // ORG_ROS2_RCLJAVA_PUBLISHER_STATUSES_OFFEREDQOSINCOMPATIBLE_H_ diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_events_publisher_statuses_LivelinessLost.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_LivelinessLost.cpp similarity index 82% rename from rcljava/src/main/cpp/org_ros2_rcljava_events_publisher_statuses_LivelinessLost.cpp rename to rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_LivelinessLost.cpp index 1b658a28..4e5558e4 100644 --- a/rcljava/src/main/cpp/org_ros2_rcljava_events_publisher_statuses_LivelinessLost.cpp +++ b/rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_LivelinessLost.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "org_ros2_rcljava_events_publisher_statuses_LivelinessLost.h" +#include "org_ros2_rcljava_publisher_statuses_LivelinessLost.h" #include #include @@ -24,7 +24,7 @@ using rcljava_common::exceptions::rcljava_throw_exception; JNIEXPORT jlong JNICALL -Java_org_ros2_rcljava_events_publisher_1statuses_LivelinessLost_nativeAllocateRCLStatusEvent( +Java_org_ros2_rcljava_publisher_statuses_LivelinessLost_nativeAllocateRCLStatusEvent( JNIEnv * env, jclass) { void * p = malloc(sizeof(rmw_liveliness_lost_status_t)); @@ -36,14 +36,14 @@ Java_org_ros2_rcljava_events_publisher_1statuses_LivelinessLost_nativeAllocateRC } JNIEXPORT void JNICALL -Java_org_ros2_rcljava_events_publisher_1statuses_LivelinessLost_nativeDeallocateRCLStatusEvent( +Java_org_ros2_rcljava_publisher_statuses_LivelinessLost_nativeDeallocateRCLStatusEvent( JNIEnv *, jclass, jlong handle) { free(reinterpret_cast(handle)); } JNIEXPORT void JNICALL -Java_org_ros2_rcljava_events_publisher_1statuses_LivelinessLost_nativeFromRCLEvent( +Java_org_ros2_rcljava_publisher_statuses_LivelinessLost_nativeFromRCLEvent( JNIEnv * env, jobject self, jlong handle) { auto * p = reinterpret_cast(handle); @@ -66,7 +66,7 @@ Java_org_ros2_rcljava_events_publisher_1statuses_LivelinessLost_nativeFromRCLEve } JNIEXPORT jint JNICALL -Java_org_ros2_rcljava_events_publisher_1statuses_LivelinessLost_nativeGetPublisherEventType( +Java_org_ros2_rcljava_publisher_statuses_LivelinessLost_nativeGetPublisherEventType( JNIEnv *, jclass) { return RCL_PUBLISHER_LIVELINESS_LOST; diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.cpp similarity index 85% rename from rcljava/src/main/cpp/org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.cpp rename to rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.cpp index ed3f4fcd..9fab2f2b 100644 --- a/rcljava/src/main/cpp/org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.cpp +++ b/rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "org_ros2_rcljava_events_publisher_statuses_OfferedQosIncompatible.h" +#include "org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.h" #include #include @@ -25,7 +25,7 @@ using rcljava_common::exceptions::rcljava_throw_exception; JNIEXPORT jlong JNICALL -Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nAllocateRCLStatusEvent( +Java_org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible_nAllocateRCLStatusEvent( JNIEnv * env, jclass) { void * p = malloc(sizeof(rmw_offered_qos_incompatible_event_status_t)); @@ -37,14 +37,14 @@ Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nAllocat } JNIEXPORT void JNICALL -Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nDeallocateRCLStatusEvent( +Java_org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible_nDeallocateRCLStatusEvent( JNIEnv *, jclass, jlong handle) { free(reinterpret_cast(handle)); } JNIEXPORT void JNICALL -Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nFromRCLEvent( +Java_org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible_nFromRCLEvent( JNIEnv * env, jobject self, jlong handle) { auto * p = reinterpret_cast(handle); @@ -55,7 +55,7 @@ Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nFromRCL // TODO(ivanpauno): class and field lookup could be done at startup time jclass clazz = env->GetObjectClass(self); jclass qos_kind_clazz = env->FindClass( - "org/ros2/rcljava/events/publisher_statuses/OfferedQosIncompatible$PolicyKind"); + "org/ros2/rcljava/publisher/statuses/OfferedQosIncompatible$PolicyKind"); if (env->ExceptionCheck()) { return; } @@ -68,7 +68,7 @@ Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nFromRCL return; } const char * enum_class_path = - "Lorg/ros2/rcljava/events/publisher_statuses/OfferedQosIncompatible$PolicyKind;"; + "Lorg/ros2/rcljava/publisher/statuses/OfferedQosIncompatible$PolicyKind;"; jfieldID policy_kind_fid = env->GetFieldID(clazz, "lastPolicyKind", enum_class_path); if (env->ExceptionCheck()) { return; @@ -113,7 +113,7 @@ Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nFromRCL } JNIEXPORT jint JNICALL -Java_org_ros2_rcljava_events_publisher_1statuses_OfferedQosIncompatible_nGetPublisherEventType( +Java_org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible_nGetPublisherEventType( JNIEnv *, jclass) { return RCL_PUBLISHER_OFFERED_INCOMPATIBLE_QOS; diff --git a/rcljava/src/main/java/org/ros2/rcljava/events/publisher_statuses/LivelinessLost.java b/rcljava/src/main/java/org/ros2/rcljava/publisher/statuses/LivelinessLost.java similarity index 97% rename from rcljava/src/main/java/org/ros2/rcljava/events/publisher_statuses/LivelinessLost.java rename to rcljava/src/main/java/org/ros2/rcljava/publisher/statuses/LivelinessLost.java index 003e3ff5..bf49a1f0 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/events/publisher_statuses/LivelinessLost.java +++ b/rcljava/src/main/java/org/ros2/rcljava/publisher/statuses/LivelinessLost.java @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -package org.ros2.rcljava.events.publisher_statuses; +package org.ros2.rcljava.publisher.statuses; import java.util.function.Supplier; diff --git a/rcljava/src/main/java/org/ros2/rcljava/events/publisher_statuses/OfferedQosIncompatible.java b/rcljava/src/main/java/org/ros2/rcljava/publisher/statuses/OfferedQosIncompatible.java similarity index 97% rename from rcljava/src/main/java/org/ros2/rcljava/events/publisher_statuses/OfferedQosIncompatible.java rename to rcljava/src/main/java/org/ros2/rcljava/publisher/statuses/OfferedQosIncompatible.java index 9b506703..7f572c71 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/events/publisher_statuses/OfferedQosIncompatible.java +++ b/rcljava/src/main/java/org/ros2/rcljava/publisher/statuses/OfferedQosIncompatible.java @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -package org.ros2.rcljava.events.publisher_statuses; +package org.ros2.rcljava.publisher.statuses; import java.util.function.Supplier; diff --git a/rcljava/src/test/java/org/ros2/rcljava/SpinTest.java b/rcljava/src/test/java/org/ros2/rcljava/SpinTest.java index 4d3cfa8f..70f4d119 100644 --- a/rcljava/src/test/java/org/ros2/rcljava/SpinTest.java +++ b/rcljava/src/test/java/org/ros2/rcljava/SpinTest.java @@ -30,7 +30,7 @@ import org.ros2.rcljava.concurrent.Callback; import org.ros2.rcljava.consumers.Consumer; import org.ros2.rcljava.events.EventHandler; -import org.ros2.rcljava.events.publisher_statuses.OfferedQosIncompatible; +import org.ros2.rcljava.publisher.statuses.OfferedQosIncompatible; import org.ros2.rcljava.executors.Executor; import org.ros2.rcljava.executors.SingleThreadedExecutor; import org.ros2.rcljava.node.ComposableNode; diff --git a/rcljava/src/test/java/org/ros2/rcljava/publisher/PublisherTest.java b/rcljava/src/test/java/org/ros2/rcljava/publisher/PublisherTest.java index 9e617840..04e55fb0 100644 --- a/rcljava/src/test/java/org/ros2/rcljava/publisher/PublisherTest.java +++ b/rcljava/src/test/java/org/ros2/rcljava/publisher/PublisherTest.java @@ -26,8 +26,8 @@ import org.ros2.rcljava.RCLJava; import org.ros2.rcljava.consumers.Consumer; import org.ros2.rcljava.events.EventHandler; -import org.ros2.rcljava.events.publisher_statuses.LivelinessLost; -import org.ros2.rcljava.events.publisher_statuses.OfferedQosIncompatible; +import org.ros2.rcljava.publisher.statuses.LivelinessLost; +import org.ros2.rcljava.publisher.statuses.OfferedQosIncompatible; import org.ros2.rcljava.exceptions.RCLException; import org.ros2.rcljava.node.Node; From 1a50f3ff6e36d70ebd9f747cdfcc698b91e24ee4 Mon Sep 17 00:00:00 2001 From: Ivan Santiago Paunovic Date: Mon, 24 Aug 2020 13:56:25 -0300 Subject: [PATCH 04/11] Add support for events in subscriptions (osrf/ros2_java#13) Signed-off-by: Ivan Santiago Paunovic --- ...s2_rcljava_subscription_SubscriptionImpl.h | 9 +++ ..._rcljava_subscription_SubscriptionImpl.cpp | 30 +++++++++ .../ros2/rcljava/executors/BaseExecutor.java | 5 ++ .../rcljava/subscription/Subscription.java | 30 +++++++++ .../subscription/SubscriptionImpl.java | 61 +++++++++++++++++++ 5 files changed, 135 insertions(+) diff --git a/rcljava/include/org_ros2_rcljava_subscription_SubscriptionImpl.h b/rcljava/include/org_ros2_rcljava_subscription_SubscriptionImpl.h index afb3456c..1f788aef 100644 --- a/rcljava/include/org_ros2_rcljava_subscription_SubscriptionImpl.h +++ b/rcljava/include/org_ros2_rcljava_subscription_SubscriptionImpl.h @@ -29,6 +29,15 @@ JNIEXPORT void JNICALL Java_org_ros2_rcljava_subscription_SubscriptionImpl_nativeDispose( JNIEnv *, jclass, jlong, jlong); +/* + * Class: org_ros2_rcljava_subscription_SubscriptionImpl + * Method: nativeCreateEvent + * Signature: (JJ)J + */ +JNIEXPORT jlong +JNICALL Java_org_ros2_rcljava_subscription_SubscriptionImpl_nativeCreateEvent( + JNIEnv *, jclass, jlong, jint); + #ifdef __cplusplus } #endif diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_subscription_SubscriptionImpl.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_subscription_SubscriptionImpl.cpp index 151bc0a0..5c995f26 100644 --- a/rcljava/src/main/cpp/org_ros2_rcljava_subscription_SubscriptionImpl.cpp +++ b/rcljava/src/main/cpp/org_ros2_rcljava_subscription_SubscriptionImpl.cpp @@ -19,6 +19,7 @@ #include #include "rcl/error_handling.h" +#include "rcl/event.h" #include "rcl/node.h" #include "rcl/rcl.h" #include "rmw/rmw.h" @@ -29,6 +30,7 @@ #include "org_ros2_rcljava_subscription_SubscriptionImpl.h" +using rcljava_common::exceptions::rcljava_throw_exception; using rcljava_common::exceptions::rcljava_throw_rclexception; JNIEXPORT void JNICALL @@ -61,3 +63,31 @@ Java_org_ros2_rcljava_subscription_SubscriptionImpl_nativeDispose( rcljava_throw_rclexception(env, ret, msg); } } + +JNIEXPORT jlong +JNICALL Java_org_ros2_rcljava_subscription_SubscriptionImpl_nativeCreateEvent( + JNIEnv * env, jclass, jlong subscription_handle, jint event_type) +{ + auto * subscription = reinterpret_cast(subscription_handle); + if (!subscription) { + rcljava_throw_exception( + env, "java/lang/IllegalArgumentException", "passed rcl_subscription_t handle is NULL"); + return 0; + } + auto * event = static_cast(malloc(sizeof(rcl_event_t))); + if (!event) { + rcljava_throw_exception(env, "java/lang/OutOfMemoryError", "failed to allocate rcl_event_t"); + return 0; + } + *event = rcl_get_zero_initialized_event(); + rcl_ret_t ret = rcl_subscription_event_init( + event, subscription, static_cast(event_type)); + if (RCL_RET_OK != ret) { + std::string msg = "Failed to create event: " + std::string(rcl_get_error_string().str); + rcl_reset_error(); + rcljava_throw_rclexception(env, ret, msg); + free(event); + return 0; + } + return reinterpret_cast(event); +} diff --git a/rcljava/src/main/java/org/ros2/rcljava/executors/BaseExecutor.java b/rcljava/src/main/java/org/ros2/rcljava/executors/BaseExecutor.java index e7c59619..1ed9218e 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/executors/BaseExecutor.java +++ b/rcljava/src/main/java/org/ros2/rcljava/executors/BaseExecutor.java @@ -181,6 +181,11 @@ protected void waitForWork(long timeout) { for (Subscription subscription : node.getNode().getSubscriptions()) { this.subscriptionHandles.add(new AbstractMap.SimpleEntry( subscription.getHandle(), subscription)); + Collection eventHandlers = subscription.getEventHandlers(); + for (EventHandler eventHandler : eventHandlers) { + this.eventHandles.add(new AbstractMap.SimpleEntry( + eventHandler.getHandle(), eventHandler)); + } } for (Publisher publisher : node.getNode().getPublishers()) { diff --git a/rcljava/src/main/java/org/ros2/rcljava/subscription/Subscription.java b/rcljava/src/main/java/org/ros2/rcljava/subscription/Subscription.java index c74cc9bd..732d8bbb 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/subscription/Subscription.java +++ b/rcljava/src/main/java/org/ros2/rcljava/subscription/Subscription.java @@ -16,8 +16,12 @@ package org.ros2.rcljava.subscription; import java.lang.ref.WeakReference; +import java.util.Collection; +import java.util.function.Supplier; import org.ros2.rcljava.consumers.Consumer; +import org.ros2.rcljava.events.EventHandler; +import org.ros2.rcljava.events.SubscriptionEventStatus; import org.ros2.rcljava.interfaces.Disposable; import org.ros2.rcljava.interfaces.MessageDefinition; import org.ros2.rcljava.node.Node; @@ -42,4 +46,30 @@ public interface Subscription extends Disposable { WeakReference getNodeReference(); void executeCallback(T message); + + /** + * Create an event handler. + * + * @param A subscription event status type. + * @param factory A factory that can instantiate an event status of type T. + * @param callback Callback that will be called when the event is triggered. + */ + EventHandler createEventHandler( + Supplier factory, Consumer callback); + + /** + * Remove a previously registered event handler. + * + * @param A subscription event status type. + * @param eventHandler An event handler that was registered previously in this object. + */ + void removeEventHandler( + EventHandler eventHandler); + + /** + * Get the event handlers that were registered in this Subscription. + * + * @return The registered event handlers. + */ + Collection getEventHandlers(); } diff --git a/rcljava/src/main/java/org/ros2/rcljava/subscription/SubscriptionImpl.java b/rcljava/src/main/java/org/ros2/rcljava/subscription/SubscriptionImpl.java index 47fce59a..34b8b79c 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/subscription/SubscriptionImpl.java +++ b/rcljava/src/main/java/org/ros2/rcljava/subscription/SubscriptionImpl.java @@ -16,10 +16,16 @@ package org.ros2.rcljava.subscription; import java.lang.ref.WeakReference; +import java.util.Collection; +import java.util.concurrent.LinkedBlockingQueue; +import java.util.function.Supplier; import org.ros2.rcljava.RCLJava; import org.ros2.rcljava.common.JNIUtils; import org.ros2.rcljava.consumers.Consumer; +import org.ros2.rcljava.events.EventHandler; +import org.ros2.rcljava.events.EventHandlerImpl; +import org.ros2.rcljava.events.SubscriptionEventStatus; import org.ros2.rcljava.interfaces.MessageDefinition; import org.ros2.rcljava.node.Node; @@ -68,6 +74,8 @@ public class SubscriptionImpl implements Subscripti */ private final Consumer callback; + private final Collection eventHandlers; + /** * Constructor. * @@ -90,6 +98,7 @@ public SubscriptionImpl(final WeakReference nodeReference, final long hand this.messageType = messageType; this.topic = topic; this.callback = callback; + this.eventHandlers = new LinkedBlockingQueue(); } /** @@ -113,6 +122,54 @@ public final WeakReference getNodeReference() { return this.nodeReference; } + /** + * {@inheritDoc} + */ + public final + EventHandler + createEventHandler(Supplier factory, Consumer callback) { + T status = factory.get(); + long eventHandle = nativeCreateEvent(this.handle, status.getSubscriptionEventType()); + EventHandler eventHandler = new EventHandlerImpl( + new WeakReference(this), eventHandle, factory, callback); + this.eventHandlers.add(eventHandler); + return eventHandler; + } + + /** + * {@inheritDoc} + */ + public final + void removeEventHandler( + EventHandler eventHandler) + { + if (!this.eventHandlers.remove(eventHandler)) { + throw new IllegalArgumentException( + "The passed eventHandler wasn't created by this subscription"); + } + eventHandler.dispose(); + } + + /** + * {@inheritDoc} + */ + public final + Collection getEventHandlers() { + return this.eventHandlers; + } + + /** + * Create a subscription event (rcl_event_t) + * + * The ownership of the created event handle will immediately be transferred to an + * @{link EventHandlerImpl}, that will be responsible of disposing it. + * + * @param handle A pointer to the underlying ROS 2 subscription structure. + * Must not be zero. + * @param eventType The rcl event type. + */ + private static native long nativeCreateEvent(long handle, int eventType); + /** * Destroy a ROS2 subscription (rcl_subscription_t). * @@ -127,6 +184,10 @@ public final WeakReference getNodeReference() { * {@inheritDoc} */ public final void dispose() { + for (EventHandler eventHandler : this.eventHandlers) { + eventHandler.dispose(); + } + this.eventHandlers.clear(); Node node = this.nodeReference.get(); if (node != null) { node.removeSubscription(this); From 6c41709654987797ff58cab096f6c1eba764038f Mon Sep 17 00:00:00 2001 From: Ivan Santiago Paunovic Date: Mon, 24 Aug 2020 18:36:00 -0300 Subject: [PATCH 05/11] Add RequestedQosIncompatible subscription event status (osrf/ros2_java#14) Signed-off-by: Ivan Santiago Paunovic --- rcljava/CMakeLists.txt | 4 + ...os2_rcljava_detail_QosIncompatibleStatus.h | 54 +++++++++ ...ublisher_statuses_OfferedQosIncompatible.h | 31 +---- ...iption_statuses_RequestedQosIncompatible.h | 36 ++++++ ...2_rcljava_detail_QosIncompatibleStatus.cpp | 113 ++++++++++++++++++ ...lisher_statuses_OfferedQosIncompatible.cpp | 96 +-------------- ...tion_statuses_RequestedQosIncompatible.cpp | 26 ++++ .../rcljava/detail/QosIncompatibleStatus.java | 65 ++++++++++ .../statuses/OfferedQosIncompatible.java | 39 ++---- .../statuses/RequestedQosIncompatible.java | 54 +++++++++ 10 files changed, 363 insertions(+), 155 deletions(-) create mode 100644 rcljava/include/org_ros2_rcljava_detail_QosIncompatibleStatus.h create mode 100644 rcljava/include/org_ros2_rcljava_subscription_statuses_RequestedQosIncompatible.h create mode 100644 rcljava/src/main/cpp/org_ros2_rcljava_detail_QosIncompatibleStatus.cpp create mode 100644 rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_RequestedQosIncompatible.cpp create mode 100644 rcljava/src/main/java/org/ros2/rcljava/detail/QosIncompatibleStatus.java create mode 100644 rcljava/src/main/java/org/ros2/rcljava/subscription/statuses/RequestedQosIncompatible.java diff --git a/rcljava/CMakeLists.txt b/rcljava/CMakeLists.txt index 06ea9079..c29753ff 100644 --- a/rcljava/CMakeLists.txt +++ b/rcljava/CMakeLists.txt @@ -58,6 +58,7 @@ set(${PROJECT_NAME}_jni_sources "src/main/cpp/org_ros2_rcljava_Time.cpp" "src/main/cpp/org_ros2_rcljava_client_ClientImpl.cpp" "src/main/cpp/org_ros2_rcljava_contexts_ContextImpl.cpp" + "src/main/cpp/org_ros2_rcljava_detail_QosIncompatibleStatus.cpp" "src/main/cpp/org_ros2_rcljava_executors_BaseExecutor.cpp" "src/main/cpp/org_ros2_rcljava_events_EventHandlerImpl.cpp" "src/main/cpp/org_ros2_rcljava_publisher_statuses_LivelinessLost.cpp" @@ -66,6 +67,7 @@ set(${PROJECT_NAME}_jni_sources "src/main/cpp/org_ros2_rcljava_publisher_PublisherImpl.cpp" "src/main/cpp/org_ros2_rcljava_service_ServiceImpl.cpp" "src/main/cpp/org_ros2_rcljava_subscription_SubscriptionImpl.cpp" + "src/main/cpp/org_ros2_rcljava_subscription_statuses_RequestedQosIncompatible.cpp" "src/main/cpp/org_ros2_rcljava_time_Clock.cpp" "src/main/cpp/org_ros2_rcljava_timer_WallTimerImpl.cpp" ) @@ -128,6 +130,7 @@ set(${PROJECT_NAME}_sources "src/main/java/org/ros2/rcljava/consumers/BiConsumer.java" "src/main/java/org/ros2/rcljava/consumers/Consumer.java" "src/main/java/org/ros2/rcljava/consumers/TriConsumer.java" + "src/main/java/org/ros2/rcljava/detail/QosIncompatibleStatus.java" "src/main/java/org/ros2/rcljava/events/EventHandler.java" "src/main/java/org/ros2/rcljava/events/EventHandlerImpl.java" "src/main/java/org/ros2/rcljava/events/EventStatus.java" @@ -172,6 +175,7 @@ set(${PROJECT_NAME}_sources "src/main/java/org/ros2/rcljava/service/ServiceImpl.java" "src/main/java/org/ros2/rcljava/subscription/Subscription.java" "src/main/java/org/ros2/rcljava/subscription/SubscriptionImpl.java" + "src/main/java/org/ros2/rcljava/subscription/statuses/RequestedQosIncompatible.java" "src/main/java/org/ros2/rcljava/time/Clock.java" "src/main/java/org/ros2/rcljava/time/ClockType.java" "src/main/java/org/ros2/rcljava/timer/Timer.java" diff --git a/rcljava/include/org_ros2_rcljava_detail_QosIncompatibleStatus.h b/rcljava/include/org_ros2_rcljava_detail_QosIncompatibleStatus.h new file mode 100644 index 00000000..af8f7319 --- /dev/null +++ b/rcljava/include/org_ros2_rcljava_detail_QosIncompatibleStatus.h @@ -0,0 +1,54 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +/* Header for class org_ros2_rcljava_detail_QosIncompatibleStatus */ + +#ifndef ORG_ROS2_RCLJAVA_DETAIL_QOSINCOMPATIBLESTATUS_H_ +#define ORG_ROS2_RCLJAVA_DETAIL_QOSINCOMPATIBLESTATUS_H_ +#ifdef __cplusplus +extern "C" { +#endif + +/* + * Class: org_ros2_rcljava_detail_QosIncompatibleStatus + * Method: nativeAllocateRCLStatusEvent + * Signature: ()J + */ +JNIEXPORT jlong JNICALL +Java_org_ros2_rcljava_detail_QosIncompatibleStatus_nativeAllocateRCLStatusEvent( + JNIEnv *, jclass); + +/* + * Class: org_ros2_rcljava_detail_QosIncompatibleStatus + * Method: nativeDeallocateRCLStatusEvent + * Signature: (J)V + */ +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_detail_QosIncompatibleStatus_nativeDeallocateRCLStatusEvent( + JNIEnv *, jclass, jlong); + +/* + * Class: org_ros2_rcljava_detail_QosIncompatibleStatus + * Method: nativeFromRCLEvent + * Signature: (J)V + */ +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_detail_QosIncompatibleStatus_nativeFromRCLEvent( + JNIEnv *, jobject, jlong); + +#ifdef __cplusplus +} +#endif +#endif // ORG_ROS2_RCLJAVA_DETAIL_QOSINCOMPATIBLESTATUS_H_ diff --git a/rcljava/include/org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.h b/rcljava/include/org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.h index 44b8ea07..15860176 100644 --- a/rcljava/include/org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.h +++ b/rcljava/include/org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.h @@ -23,38 +23,11 @@ extern "C" { /* * Class: org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible - * Method: nAllocateRCLStatusEvent - * Signature: ()J - */ -JNIEXPORT jlong JNICALL -Java_org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible_nAllocateRCLStatusEvent( - JNIEnv *, jclass); - -/* - * Class: org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible - * Method: nDeallocateRCLStatusEvent - * Signature: (J)V - */ -JNIEXPORT void JNICALL -Java_org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible_nDeallocateRCLStatusEvent( - JNIEnv *, jclass, jlong); - -/* - * Class: org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible - * Method: nFromRCLEvent - * Signature: (J)V - */ -JNIEXPORT void JNICALL -Java_org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible_nFromRCLEvent( - JNIEnv *, jobject, jlong); - -/* - * Class: org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible - * Method: nGetPublisherEventType + * Method: nativeGetEventType * Signature: ()I */ JNIEXPORT jint JNICALL -Java_org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible_nGetPublisherEventType( +Java_org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible_nativeGetEventType( JNIEnv *, jclass); #ifdef __cplusplus diff --git a/rcljava/include/org_ros2_rcljava_subscription_statuses_RequestedQosIncompatible.h b/rcljava/include/org_ros2_rcljava_subscription_statuses_RequestedQosIncompatible.h new file mode 100644 index 00000000..ef7a0236 --- /dev/null +++ b/rcljava/include/org_ros2_rcljava_subscription_statuses_RequestedQosIncompatible.h @@ -0,0 +1,36 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +/* Header for class org_ros2_rcljava_subscription_statuses_RequestedQosIncompatible */ + +#ifndef ORG_ROS2_RCLJAVA_SUBSCRIPTION_STATUSES_REQUESTEDQOSINCOMPATIBLE_H_ +#define ORG_ROS2_RCLJAVA_SUBSCRIPTION_STATUSES_REQUESTEDQOSINCOMPATIBLE_H_ +#ifdef __cplusplus +extern "C" { +#endif + +/* + * Class: org_ros2_rcljava_subscription_statuses_RequestedQosIncompatible + * Method: nativeGetEventType + * Signature: ()I + */ +JNIEXPORT jint JNICALL +Java_org_ros2_rcljava_subscription_statuses_RequestedQosIncompatible_nativeGetEventType( + JNIEnv *, jclass); + +#ifdef __cplusplus +} +#endif +#endif // ORG_ROS2_RCLJAVA_SUBSCRIPTION_STATUSES_REQUESTEDQOSINCOMPATIBLE_H_ diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_detail_QosIncompatibleStatus.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_detail_QosIncompatibleStatus.cpp new file mode 100644 index 00000000..85dde30f --- /dev/null +++ b/rcljava/src/main/cpp/org_ros2_rcljava_detail_QosIncompatibleStatus.cpp @@ -0,0 +1,113 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "org_ros2_rcljava_detail_QosIncompatibleStatus.h" + +#include +#include + +#include "rmw/incompatible_qos_events_statuses.h" +#include "rmw/types.h" +#include "rcl/event.h" +#include "rcljava_common/exceptions.hpp" + +using rcljava_common::exceptions::rcljava_throw_exception; + +JNIEXPORT jlong JNICALL +Java_org_ros2_rcljava_detail_QosIncompatibleStatus_nativeAllocateRCLStatusEvent( + JNIEnv * env, jclass) +{ + void * p = malloc(sizeof(rmw_qos_incompatible_event_status_t)); + if (!p) { + rcljava_throw_exception( + env, "java/lang/OutOfMemoryError", "failed to allocate qos incompatible status"); + } + return reinterpret_cast(p); +} + +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_detail_QosIncompatibleStatus_nativeDeallocateRCLStatusEvent( + JNIEnv *, jclass, jlong handle) +{ + free(reinterpret_cast(handle)); +} + +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_detail_QosIncompatibleStatus_nativeFromRCLEvent( + JNIEnv * env, jobject self, jlong handle) +{ + auto * p = reinterpret_cast(handle); + if (!p) { + rcljava_throw_exception( + env, "java/lang/IllegalArgumentException", "passed rmw object handle is NULL"); + } + // TODO(ivanpauno): class and field lookup could be done at startup time + jclass clazz = env->GetObjectClass(self); + jclass qos_kind_clazz = env->FindClass( + "org/ros2/rcljava/detail/QosIncompatibleStatus$PolicyKind"); + if (env->ExceptionCheck()) { + return; + } + jfieldID total_count_fid = env->GetFieldID(clazz, "totalCount", "I"); + if (env->ExceptionCheck()) { + return; + } + jfieldID total_count_change_fid = env->GetFieldID(clazz, "totalCountChange", "I"); + if (env->ExceptionCheck()) { + return; + } + const char * enum_class_path = + "Lorg/ros2/rcljava/detail/QosIncompatibleStatus$PolicyKind;"; + jfieldID policy_kind_fid = env->GetFieldID(clazz, "lastPolicyKind", enum_class_path); + if (env->ExceptionCheck()) { + return; + } + + jfieldID enum_value_fid; + switch (p->last_policy_kind) { + case RMW_QOS_POLICY_INVALID: + enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "INVALID", enum_class_path); + break; + case RMW_QOS_POLICY_DURABILITY: + enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "DURABILITY", enum_class_path); + break; + case RMW_QOS_POLICY_DEADLINE: + enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "DEADLINE", enum_class_path); + break; + case RMW_QOS_POLICY_LIVELINESS: + enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "LIVELINESS", enum_class_path); + break; + case RMW_QOS_POLICY_RELIABILITY: + enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "RELIABILITY", enum_class_path); + break; + case RMW_QOS_POLICY_HISTORY: + enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "HISTORY", enum_class_path); + break; + case RMW_QOS_POLICY_LIFESPAN: + enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "LIFESPAN", enum_class_path); + break; + default: + rcljava_throw_exception( + env, "java/lang/IllegalArgumentException", "unknown rmw qos policy kind"); + break; + } + if (env->ExceptionCheck()) { + return; + } + jobject enum_value = env->GetStaticObjectField(qos_kind_clazz, enum_value_fid); + + env->SetIntField(self, total_count_fid, p->total_count); + env->SetIntField(self, total_count_change_fid, p->total_count_change); + env->SetObjectField(self, policy_kind_fid, enum_value); +} diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.cpp index 9fab2f2b..d2e681c3 100644 --- a/rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.cpp +++ b/rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.cpp @@ -15,105 +15,11 @@ #include "org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.h" #include -#include -#include "rmw/incompatible_qos_events_statuses.h" -#include "rmw/types.h" #include "rcl/event.h" -#include "rcljava_common/exceptions.hpp" - -using rcljava_common::exceptions::rcljava_throw_exception; - -JNIEXPORT jlong JNICALL -Java_org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible_nAllocateRCLStatusEvent( - JNIEnv * env, jclass) -{ - void * p = malloc(sizeof(rmw_offered_qos_incompatible_event_status_t)); - if (!p) { - rcljava_throw_exception( - env, "java/lang/OutOfMemoryError", "failed to allocate offered qos incompatible status"); - } - return reinterpret_cast(p); -} - -JNIEXPORT void JNICALL -Java_org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible_nDeallocateRCLStatusEvent( - JNIEnv *, jclass, jlong handle) -{ - free(reinterpret_cast(handle)); -} - -JNIEXPORT void JNICALL -Java_org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible_nFromRCLEvent( - JNIEnv * env, jobject self, jlong handle) -{ - auto * p = reinterpret_cast(handle); - if (!p) { - rcljava_throw_exception( - env, "java/lang/IllegalArgumentException", "passed rmw object handle is NULL"); - } - // TODO(ivanpauno): class and field lookup could be done at startup time - jclass clazz = env->GetObjectClass(self); - jclass qos_kind_clazz = env->FindClass( - "org/ros2/rcljava/publisher/statuses/OfferedQosIncompatible$PolicyKind"); - if (env->ExceptionCheck()) { - return; - } - jfieldID total_count_fid = env->GetFieldID(clazz, "totalCount", "I"); - if (env->ExceptionCheck()) { - return; - } - jfieldID total_count_change_fid = env->GetFieldID(clazz, "totalCountChange", "I"); - if (env->ExceptionCheck()) { - return; - } - const char * enum_class_path = - "Lorg/ros2/rcljava/publisher/statuses/OfferedQosIncompatible$PolicyKind;"; - jfieldID policy_kind_fid = env->GetFieldID(clazz, "lastPolicyKind", enum_class_path); - if (env->ExceptionCheck()) { - return; - } - - jfieldID enum_value_fid; - switch (p->last_policy_kind) { - case RMW_QOS_POLICY_INVALID: - enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "INVALID", enum_class_path); - break; - case RMW_QOS_POLICY_DURABILITY: - enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "DURABILITY", enum_class_path); - break; - case RMW_QOS_POLICY_DEADLINE: - enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "DEADLINE", enum_class_path); - break; - case RMW_QOS_POLICY_LIVELINESS: - enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "LIVELINESS", enum_class_path); - break; - case RMW_QOS_POLICY_RELIABILITY: - enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "RELIABILITY", enum_class_path); - break; - case RMW_QOS_POLICY_HISTORY: - enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "HISTORY", enum_class_path); - break; - case RMW_QOS_POLICY_LIFESPAN: - enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "LIFESPAN", enum_class_path); - break; - default: - rcljava_throw_exception( - env, "java/lang/IllegalStateException", "unknown rmw qos policy kind"); - break; - } - if (env->ExceptionCheck()) { - return; - } - jobject enum_value = env->GetStaticObjectField(qos_kind_clazz, enum_value_fid); - - env->SetIntField(self, total_count_fid, p->total_count); - env->SetIntField(self, total_count_change_fid, p->total_count_change); - env->SetObjectField(self, policy_kind_fid, enum_value); -} JNIEXPORT jint JNICALL -Java_org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible_nGetPublisherEventType( +Java_org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible_nativeGetEventType( JNIEnv *, jclass) { return RCL_PUBLISHER_OFFERED_INCOMPATIBLE_QOS; diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_RequestedQosIncompatible.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_RequestedQosIncompatible.cpp new file mode 100644 index 00000000..fc506e5e --- /dev/null +++ b/rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_RequestedQosIncompatible.cpp @@ -0,0 +1,26 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "org_ros2_rcljava_subscription_statuses_RequestedQosIncompatible.h" + +#include + +#include "rcl/event.h" + +JNIEXPORT jint JNICALL +Java_org_ros2_rcljava_subscription_statuses_RequestedQosIncompatible_nativeGetEventType( + JNIEnv *, jclass) +{ + return RCL_SUBSCRIPTION_REQUESTED_INCOMPATIBLE_QOS; +} diff --git a/rcljava/src/main/java/org/ros2/rcljava/detail/QosIncompatibleStatus.java b/rcljava/src/main/java/org/ros2/rcljava/detail/QosIncompatibleStatus.java new file mode 100644 index 00000000..91a3e9b4 --- /dev/null +++ b/rcljava/src/main/java/org/ros2/rcljava/detail/QosIncompatibleStatus.java @@ -0,0 +1,65 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +package org.ros2.rcljava.detail; + +import org.ros2.rcljava.common.JNIUtils; +import org.ros2.rcljava.events.EventStatus; + +import org.slf4j.Logger; +import org.slf4j.LoggerFactory; + +/** + * This class serves as a bridge between rmw_qos_incompatible_event_status_t + * and RCLJava. + */ +public class QosIncompatibleStatus implements EventStatus { + public int totalCount; + public int totalCountChange; + public PolicyKind lastPolicyKind; + + public enum PolicyKind { + INVALID, + DURABILITY, + DEADLINE, + LIVELINESS, + RELIABILITY, + HISTORY, + LIFESPAN; + } + + public final long allocateRCLStatusEvent() { + return nativeAllocateRCLStatusEvent(); + } + public final void deallocateRCLStatusEvent(long handle) { + nativeDeallocateRCLStatusEvent(handle); + } + public final void fromRCLEvent(long handle) { + nativeFromRCLEvent(handle); + } + + private static final Logger logger = LoggerFactory.getLogger(QosIncompatibleStatus.class); + static { + try { + JNIUtils.loadImplementation(QosIncompatibleStatus.class); + } catch (UnsatisfiedLinkError ule) { + logger.error("Native code library failed to load.\n" + ule); + System.exit(1); + } + } + + private static native long nativeAllocateRCLStatusEvent(); + private static native void nativeDeallocateRCLStatusEvent(long handle); + private native void nativeFromRCLEvent(long handle); +} diff --git a/rcljava/src/main/java/org/ros2/rcljava/publisher/statuses/OfferedQosIncompatible.java b/rcljava/src/main/java/org/ros2/rcljava/publisher/statuses/OfferedQosIncompatible.java index 7f572c71..ba633cd6 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/publisher/statuses/OfferedQosIncompatible.java +++ b/rcljava/src/main/java/org/ros2/rcljava/publisher/statuses/OfferedQosIncompatible.java @@ -17,43 +17,23 @@ import java.util.function.Supplier; import org.ros2.rcljava.common.JNIUtils; +import org.ros2.rcljava.detail.QosIncompatibleStatus; import org.ros2.rcljava.events.PublisherEventStatus; import org.slf4j.Logger; import org.slf4j.LoggerFactory; /** - * This class serves as a bridge between a rmw_qos_incompatible_event_status_t and RCLJava. + * This class serves as a bridge between rmw_offered_qos_incompatible_event_status_t and RCLJava. */ -public class OfferedQosIncompatible implements PublisherEventStatus { - public int totalCount; - public int totalCountChange; - public PolicyKind lastPolicyKind; - - public enum PolicyKind { - INVALID, - DURABILITY, - DEADLINE, - LIVELINESS, - RELIABILITY, - HISTORY, - LIFESPAN; - } - - public final long allocateRCLStatusEvent() { - return nAllocateRCLStatusEvent(); - } - public final void deallocateRCLStatusEvent(long handle) { - nDeallocateRCLStatusEvent(handle); - } - public final void fromRCLEvent(long handle) { - nFromRCLEvent(handle); - } +public class OfferedQosIncompatible +extends QosIncompatibleStatus implements PublisherEventStatus { public final int getPublisherEventType() { - return nGetPublisherEventType(); + return nativeGetEventType(); } // TODO(ivanpauno): Remove this when -source 8 can be used (method references for the win) - public static final Supplier factory = new Supplier() { + public static final Supplier + factory = new Supplier() { public OfferedQosIncompatible get() { return new OfferedQosIncompatible(); } @@ -69,8 +49,5 @@ public OfferedQosIncompatible get() { } } - private static native long nAllocateRCLStatusEvent(); - private static native void nDeallocateRCLStatusEvent(long handle); - private native void nFromRCLEvent(long handle); - private static native int nGetPublisherEventType(); + private static native int nativeGetEventType(); } diff --git a/rcljava/src/main/java/org/ros2/rcljava/subscription/statuses/RequestedQosIncompatible.java b/rcljava/src/main/java/org/ros2/rcljava/subscription/statuses/RequestedQosIncompatible.java new file mode 100644 index 00000000..33c0ea38 --- /dev/null +++ b/rcljava/src/main/java/org/ros2/rcljava/subscription/statuses/RequestedQosIncompatible.java @@ -0,0 +1,54 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +package org.ros2.rcljava.subscription.statuses; + +import java.util.function.Supplier; + +import org.ros2.rcljava.common.JNIUtils; +import org.ros2.rcljava.detail.QosIncompatibleStatus; +import org.ros2.rcljava.events.SubscriptionEventStatus; + +import org.slf4j.Logger; +import org.slf4j.LoggerFactory; + +/** + * This class serves as a bridge between rmw_requested_qos_incompatible_event_status_t + * and RCLJava. + */ +public class RequestedQosIncompatible +extends QosIncompatibleStatus implements SubscriptionEventStatus { + public final int getSubscriptionEventType() { + return nativeGetEventType(); + } + // TODO(ivanpauno): Remove this when -source 8 can be used (method references for the win) + public static final Supplier + factory = new Supplier() { + public RequestedQosIncompatible get() { + return new RequestedQosIncompatible(); + } + }; + + private static final Logger logger = LoggerFactory.getLogger(RequestedQosIncompatible.class); + static { + try { + JNIUtils.loadImplementation(RequestedQosIncompatible.class); + } catch (UnsatisfiedLinkError ule) { + logger.error("Native code library failed to load.\n" + ule); + System.exit(1); + } + } + + private static native int nativeGetEventType(); +} From d3d740fd17c3889385ef76b668902e2b0d473d36 Mon Sep 17 00:00:00 2001 From: Ivan Santiago Paunovic Date: Wed, 26 Aug 2020 11:20:20 -0300 Subject: [PATCH 06/11] Test subscription events (osrf/ros2_java#15) Signed-off-by: Ivan Santiago Paunovic --- .../test/java/org/ros2/rcljava/SpinTest.java | 89 +++++++++++++++---- .../subscription/SubscriptionTest.java | 31 +++++++ 2 files changed, 105 insertions(+), 15 deletions(-) diff --git a/rcljava/src/test/java/org/ros2/rcljava/SpinTest.java b/rcljava/src/test/java/org/ros2/rcljava/SpinTest.java index 70f4d119..c5b8beb3 100644 --- a/rcljava/src/test/java/org/ros2/rcljava/SpinTest.java +++ b/rcljava/src/test/java/org/ros2/rcljava/SpinTest.java @@ -42,6 +42,7 @@ import org.ros2.rcljava.qos.policies.Reliability; import org.ros2.rcljava.qos.QoSProfile; import org.ros2.rcljava.subscription.Subscription; +import org.ros2.rcljava.subscription.statuses.RequestedQosIncompatible; public class SpinTest { public static class TimerCallback implements Callback { @@ -357,7 +358,7 @@ public Node getNode() { } // custom event consumer - public static class EventConsumer implements Consumer { + public static class OfferedQosIncompatibleConsumer implements Consumer { public boolean done = false; public void accept(final OfferedQosIncompatible status) { @@ -369,35 +370,93 @@ public void accept(final OfferedQosIncompatible status) { } @Test - public final void testSpinEvent() { + public final void testSpinPublisherEvent() { String identifier = RCLJava.getRMWIdentifier(); if (identifier.equals("rmw_fastrtps_cpp") || identifier.equals("rmw_fastrtps_dynamic_cpp")) { - // OfferedQosIncompatible event not supported in these implementations + // OfferedQosIncompatible events is not supported in these implementations. return; } - final Node node = RCLJava.createNode("test_node_spin_event"); + final Node node = RCLJava.createNode("test_node_spin_publisher_event"); Publisher publisher = node.createPublisher( - std_msgs.msg.String.class, "test_topic_spin_event", new QoSProfile( + std_msgs.msg.String.class, "test_topic_spin_publisher_event", new QoSProfile( History.KEEP_LAST, 1, Reliability.BEST_EFFORT, Durability.VOLATILE, false)); // create a OfferedQoSIncompatible event handler with custom event consumer - EventConsumer eventConsumer = new EventConsumer(); + OfferedQosIncompatibleConsumer eventConsumer = new OfferedQosIncompatibleConsumer(); EventHandler eventHandler = publisher.createEventHandler( OfferedQosIncompatible.factory, eventConsumer ); // create an incompatible subscription (reliable vs best effort publisher) Subscription subscription = node.createSubscription( - std_msgs.msg.String.class, "test_topic_spin_event", - new Consumer() { - public void accept(final std_msgs.msg.String msg) {} - }, - new QoSProfile( - History.KEEP_LAST, 1, - Reliability.RELIABLE, - Durability.VOLATILE, - false)); + std_msgs.msg.String.class, "test_topic_spin_publisher_event", + new Consumer() { + public void accept(final std_msgs.msg.String msg) {} + }, + new QoSProfile( + History.KEEP_LAST, 1, + Reliability.RELIABLE, + Durability.VOLATILE, + false)); + // set up executor + ComposableNode composableNode = new ComposableNode() { + public Node getNode() { + return node; + } + }; + Executor executor = new SingleThreadedExecutor(); + executor.addNode(composableNode); + long start = System.currentTimeMillis(); + do { + executor.spinAll((1000 + System.currentTimeMillis() - start) * 1000 * 1000); + } while (!eventConsumer.done && System.currentTimeMillis() < start + 1000); + assert(eventConsumer.done); + } + + public static class RequestedQosIncompatibleConsumer + implements Consumer { + public boolean done = false; + + public void accept(final RequestedQosIncompatible status) { + assertEquals(status.totalCount, 1); + assertEquals(status.totalCountChange, 1); + assertEquals(status.lastPolicyKind, RequestedQosIncompatible.PolicyKind.RELIABILITY); + this.done = true; + } + } + + @Test + public final void testSpinSubscriptionEvent() { + String identifier = RCLJava.getRMWIdentifier(); + if (identifier.equals("rmw_fastrtps_cpp") || identifier.equals("rmw_fastrtps_dynamic_cpp")) { + // RequestedQosIncompatible events is not supported in these implementations. + return; + } + final Node node = RCLJava.createNode("test_node_spin_subscription_event"); + // create an incompatible subscription (reliable vs best effort publisher) + Subscription subscription = node.createSubscription( + std_msgs.msg.String.class, "test_topic_spin_subscription_event", + new Consumer() { + public void accept(final std_msgs.msg.String msg) {} + }, + new QoSProfile( + History.KEEP_LAST, 1, + Reliability.RELIABLE, + Durability.VOLATILE, + false)); + // create a RequestedQoSIncompatible event handler with custom event consumer + RequestedQosIncompatibleConsumer eventConsumer = new RequestedQosIncompatibleConsumer(); + EventHandler eventHandler = subscription.createEventHandler( + RequestedQosIncompatible.factory, eventConsumer + ); + Publisher publisher = node.createPublisher( + std_msgs.msg.String.class, "test_topic_spin_subscription_event", new QoSProfile( + History.KEEP_LAST, 1, + Reliability.BEST_EFFORT, + Durability.VOLATILE, + false)); + // set up executor ComposableNode composableNode = new ComposableNode() { public Node getNode() { diff --git a/rcljava/src/test/java/org/ros2/rcljava/subscription/SubscriptionTest.java b/rcljava/src/test/java/org/ros2/rcljava/subscription/SubscriptionTest.java index 61e9c448..8f39ddbd 100644 --- a/rcljava/src/test/java/org/ros2/rcljava/subscription/SubscriptionTest.java +++ b/rcljava/src/test/java/org/ros2/rcljava/subscription/SubscriptionTest.java @@ -25,7 +25,9 @@ import org.ros2.rcljava.RCLJava; import org.ros2.rcljava.consumers.Consumer; +import org.ros2.rcljava.events.EventHandler; import org.ros2.rcljava.node.Node; +import org.ros2.rcljava.subscription.statuses.RequestedQosIncompatible; public class SubscriptionTest { @BeforeClass @@ -66,4 +68,33 @@ public void accept(final std_msgs.msg.String msg) {} RCLJava.shutdown(); } + + @Test + public final void testCreateRequestedQosIncompatibleEvent() { + String identifier = RCLJava.getRMWIdentifier(); + if (identifier.equals("rmw_fastrtps_cpp") || identifier.equals("rmw_fastrtps_dynamic_cpp")) { + // event not supported in these implementations + return; + } + RCLJava.rclJavaInit(); + Node node = RCLJava.createNode("test_node"); + Subscription subscription = node.createSubscription( + std_msgs.msg.String.class, "test_topic", new Consumer() { + public void accept(final std_msgs.msg.String msg) {} + }); + EventHandler eventHandler = subscription.createEventHandler( + RequestedQosIncompatible.factory, new Consumer() { + public void accept(final RequestedQosIncompatible status) { + assertEquals(status.totalCount, 0); + assertEquals(status.totalCountChange, 0); + assertEquals(status.lastPolicyKind, RequestedQosIncompatible.PolicyKind.INVALID); + } + } + ); + assertNotEquals(0, eventHandler.getHandle()); + // force executing the callback, so we check that taking an event works + eventHandler.executeCallback(); + RCLJava.shutdown(); + assertEquals(0, eventHandler.getHandle()); + } } From ac6f493dc135df926f6138a0a3263227568eb47c Mon Sep 17 00:00:00 2001 From: Ivan Santiago Paunovic Date: Wed, 26 Aug 2020 11:34:33 -0300 Subject: [PATCH 07/11] Add OfferedDeadlineMissed QoS event (osrf/ros2_java#17) Signed-off-by: Ivan Santiago Paunovic --- rcljava/CMakeLists.txt | 2 + ...publisher_statuses_OfferedDeadlineMissed.h | 63 ++++++++++++++++ ...blisher_statuses_OfferedDeadlineMissed.cpp | 73 +++++++++++++++++++ .../statuses/OfferedDeadlineMissed.java | 65 +++++++++++++++++ .../ros2/rcljava/publisher/PublisherTest.java | 22 ++++++ 5 files changed, 225 insertions(+) create mode 100644 rcljava/include/org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed.h create mode 100644 rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed.cpp create mode 100644 rcljava/src/main/java/org/ros2/rcljava/publisher/statuses/OfferedDeadlineMissed.java diff --git a/rcljava/CMakeLists.txt b/rcljava/CMakeLists.txt index c29753ff..c47359cb 100644 --- a/rcljava/CMakeLists.txt +++ b/rcljava/CMakeLists.txt @@ -62,6 +62,7 @@ set(${PROJECT_NAME}_jni_sources "src/main/cpp/org_ros2_rcljava_executors_BaseExecutor.cpp" "src/main/cpp/org_ros2_rcljava_events_EventHandlerImpl.cpp" "src/main/cpp/org_ros2_rcljava_publisher_statuses_LivelinessLost.cpp" + "src/main/cpp/org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed.cpp" "src/main/cpp/org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.cpp" "src/main/cpp/org_ros2_rcljava_node_NodeImpl.cpp" "src/main/cpp/org_ros2_rcljava_publisher_PublisherImpl.cpp" @@ -137,6 +138,7 @@ set(${PROJECT_NAME}_sources "src/main/java/org/ros2/rcljava/events/PublisherEventStatus.java" "src/main/java/org/ros2/rcljava/events/SubscriptionEventStatus.java" "src/main/java/org/ros2/rcljava/publisher/statuses/LivelinessLost.java" + "src/main/java/org/ros2/rcljava/publisher/statuses/OfferedDeadlineMissed.java" "src/main/java/org/ros2/rcljava/publisher/statuses/OfferedQosIncompatible.java" "src/main/java/org/ros2/rcljava/executors/AnyExecutable.java" "src/main/java/org/ros2/rcljava/executors/BaseExecutor.java" diff --git a/rcljava/include/org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed.h b/rcljava/include/org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed.h new file mode 100644 index 00000000..2f0575c9 --- /dev/null +++ b/rcljava/include/org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed.h @@ -0,0 +1,63 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +/* Header for class org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed */ + +#ifndef ORG_ROS2_RCLJAVA_PUBLISHER_STATUSES_OFFEREDDEADLINEMISSED_H_ +#define ORG_ROS2_RCLJAVA_PUBLISHER_STATUSES_OFFEREDDEADLINEMISSED_H_ +#ifdef __cplusplus +extern "C" { +#endif + +/* + * Class: org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed + * Method: nativeAllocateRCLStatusEvent + * Signature: ()J + */ +JNIEXPORT jlong JNICALL +Java_org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed_nativeAllocateRCLStatusEvent( + JNIEnv *, jclass); + +/* + * Class: org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed + * Method: nativeDeallocateRCLStatusEvent + * Signature: (J)V + */ +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed_nativeDeallocateRCLStatusEvent( + JNIEnv *, jclass, jlong); + +/* + * Class: org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed + * Method: nativeFromRCLEvent + * Signature: (J)V + */ +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed_nativeFromRCLEvent( + JNIEnv *, jobject, jlong); + +/* + * Class: org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed + * Method: nativeGetPublisherEventType + * Signature: ()I + */ +JNIEXPORT jint JNICALL +Java_org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed_nativeGetPublisherEventType( + JNIEnv *, jclass); + +#ifdef __cplusplus +} +#endif +#endif // ORG_ROS2_RCLJAVA_PUBLISHER_STATUSES_OFFEREDDEADLINEMISSED_H_ diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed.cpp new file mode 100644 index 00000000..4cdac4bf --- /dev/null +++ b/rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed.cpp @@ -0,0 +1,73 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed.h" + +#include +#include + +#include "rmw/types.h" +#include "rcl/event.h" +#include "rcljava_common/exceptions.hpp" + +using rcljava_common::exceptions::rcljava_throw_exception; + +JNIEXPORT jlong JNICALL +Java_org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed_nativeAllocateRCLStatusEvent( + JNIEnv * env, jclass) +{ + void * p = malloc(sizeof(rmw_offered_deadline_missed_status_t)); + if (!p) { + rcljava_throw_exception( + env, "java/lang/OutOfMemoryError", "failed to allocate deadline missed status"); + } + return reinterpret_cast(p); +} + +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed_nativeDeallocateRCLStatusEvent( + JNIEnv *, jclass, jlong handle) +{ + free(reinterpret_cast(handle)); +} + +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed_nativeFromRCLEvent( + JNIEnv * env, jobject self, jlong handle) +{ + auto * p = reinterpret_cast(handle); + if (!p) { + rcljava_throw_exception( + env, "java/lang/IllegalArgumentException", "passed rmw object handle is NULL"); + } + // TODO(ivanpauno): class and field lookup could be done at startup time + jclass clazz = env->GetObjectClass(self); + jfieldID total_count_fid = env->GetFieldID(clazz, "totalCount", "I"); + if (env->ExceptionCheck()) { + return; + } + jfieldID total_count_change_fid = env->GetFieldID(clazz, "totalCountChange", "I"); + if (env->ExceptionCheck()) { + return; + } + env->SetIntField(self, total_count_fid, p->total_count); + env->SetIntField(self, total_count_change_fid, p->total_count_change); +} + +JNIEXPORT jint JNICALL +Java_org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed_nativeGetPublisherEventType( + JNIEnv *, jclass) +{ + return RCL_PUBLISHER_OFFERED_DEADLINE_MISSED; +} diff --git a/rcljava/src/main/java/org/ros2/rcljava/publisher/statuses/OfferedDeadlineMissed.java b/rcljava/src/main/java/org/ros2/rcljava/publisher/statuses/OfferedDeadlineMissed.java new file mode 100644 index 00000000..f4409806 --- /dev/null +++ b/rcljava/src/main/java/org/ros2/rcljava/publisher/statuses/OfferedDeadlineMissed.java @@ -0,0 +1,65 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +package org.ros2.rcljava.publisher.statuses; + +import java.util.function.Supplier; + +import org.ros2.rcljava.common.JNIUtils; +import org.ros2.rcljava.events.PublisherEventStatus; + +import org.slf4j.Logger; +import org.slf4j.LoggerFactory; + +/** + * This class serves as a bridge between a rmw_offered_deadline_missed_status_t and RCLJava. + */ +public class OfferedDeadlineMissed implements PublisherEventStatus { + public int totalCount; + public int totalCountChange; + + public final long allocateRCLStatusEvent() { + return nativeAllocateRCLStatusEvent(); + } + public final void deallocateRCLStatusEvent(long handle) { + nativeDeallocateRCLStatusEvent(handle); + } + public final void fromRCLEvent(long handle) { + nativeFromRCLEvent(handle); + } + public final int getPublisherEventType() { + return nativeGetPublisherEventType(); + } + // TODO(ivanpauno): Remove this when -source 8 can be used (method references for the win) + public static final Supplier factory = new Supplier() { + public OfferedDeadlineMissed get() { + return new OfferedDeadlineMissed(); + } + }; + + private static final Logger logger = LoggerFactory.getLogger(OfferedDeadlineMissed.class); + static { + try { + JNIUtils.loadImplementation(OfferedDeadlineMissed.class); + } catch (UnsatisfiedLinkError ule) { + logger.error("Native code library failed to load.\n" + ule); + System.exit(1); + } + } + + private static native long nativeAllocateRCLStatusEvent(); + private static native void nativeDeallocateRCLStatusEvent(long handle); + private native void nativeFromRCLEvent(long handle); + private static native int nativeGetPublisherEventType(); +} diff --git a/rcljava/src/test/java/org/ros2/rcljava/publisher/PublisherTest.java b/rcljava/src/test/java/org/ros2/rcljava/publisher/PublisherTest.java index 04e55fb0..cc449c1e 100644 --- a/rcljava/src/test/java/org/ros2/rcljava/publisher/PublisherTest.java +++ b/rcljava/src/test/java/org/ros2/rcljava/publisher/PublisherTest.java @@ -27,6 +27,7 @@ import org.ros2.rcljava.consumers.Consumer; import org.ros2.rcljava.events.EventHandler; import org.ros2.rcljava.publisher.statuses.LivelinessLost; +import org.ros2.rcljava.publisher.statuses.OfferedDeadlineMissed; import org.ros2.rcljava.publisher.statuses.OfferedQosIncompatible; import org.ros2.rcljava.exceptions.RCLException; import org.ros2.rcljava.node.Node; @@ -116,4 +117,25 @@ public void accept(final OfferedQosIncompatible status) { RCLJava.shutdown(); assertEquals(0, eventHandler.getHandle()); } + + @Test + public final void testCreateOfferedDeadlineMissedEvent() { + RCLJava.rclJavaInit(); + Node node = RCLJava.createNode("test_node"); + Publisher publisher = + node.createPublisher(std_msgs.msg.String.class, "test_topic"); + EventHandler eventHandler = publisher.createEventHandler( + OfferedDeadlineMissed.factory, new Consumer() { + public void accept(final OfferedDeadlineMissed status) { + assertEquals(status.totalCount, 0); + assertEquals(status.totalCountChange, 0); + } + } + ); + assertNotEquals(0, eventHandler.getHandle()); + // force executing the callback, so we check that taking an event works + eventHandler.executeCallback(); + RCLJava.shutdown(); + assertEquals(0, eventHandler.getHandle()); + } } From 7e251904f4355d8b682a6e43b27834fdbdd58c36 Mon Sep 17 00:00:00 2001 From: Ivan Santiago Paunovic Date: Wed, 26 Aug 2020 17:56:23 -0300 Subject: [PATCH 08/11] Autoremove EventHandler from parent entity (osrf/ros2_java#16) Signed-off-by: Ivan Santiago Paunovic --- .../org/ros2/rcljava/events/EventHandlerImpl.java | 14 ++++++++++---- .../org/ros2/rcljava/publisher/PublisherImpl.java | 12 +++++++++++- .../rcljava/subscription/SubscriptionImpl.java | 13 ++++++++++++- .../org/ros2/rcljava/publisher/PublisherTest.java | 5 ++++- 4 files changed, 37 insertions(+), 7 deletions(-) diff --git a/rcljava/src/main/java/org/ros2/rcljava/events/EventHandlerImpl.java b/rcljava/src/main/java/org/ros2/rcljava/events/EventHandlerImpl.java index 25545c7f..74e4e6dd 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/events/EventHandlerImpl.java +++ b/rcljava/src/main/java/org/ros2/rcljava/events/EventHandlerImpl.java @@ -64,16 +64,19 @@ public class EventHandlerImpl< * @param eventStatusFactory Factory of an event status. * @param callback The callback function that will be called when the event * is triggered. + * @param disposeCallback Callback that will be called when this object is disposed. */ public EventHandlerImpl( final WeakReference parentReference, final long handle, final Supplier eventStatusFactory, - final Consumer callback) { + final Consumer callback, + final Consumer disposeCallback) { this.parentReference = parentReference; this.handle = handle; this.eventStatusFactory = eventStatusFactory; this.callback = callback; + this.disposeCallback = disposeCallback; } /** @@ -102,9 +105,11 @@ public final long getHandle() { * {@inheritDoc} */ public synchronized final void dispose() { - if (this.handle != 0) { - nativeDispose(this.handle); + if (this.handle == 0) { + return; } + this.disposeCallback.accept(this); + nativeDispose(this.handle); this.handle = 0; } @@ -126,11 +131,12 @@ public synchronized final void executeCallback() { nativeTake(this.handle, nativeEventStatusHandle); eventStatus.fromRCLEvent(nativeEventStatusHandle); eventStatus.deallocateRCLStatusEvent(nativeEventStatusHandle); - callback.accept(eventStatus); + this.callback.accept(eventStatus); } private final Supplier eventStatusFactory; private final WeakReference parentReference; private long handle; private final Consumer callback; + private final Consumer disposeCallback; } diff --git a/rcljava/src/main/java/org/ros2/rcljava/publisher/PublisherImpl.java b/rcljava/src/main/java/org/ros2/rcljava/publisher/PublisherImpl.java index 17018f87..0e93531e 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/publisher/PublisherImpl.java +++ b/rcljava/src/main/java/org/ros2/rcljava/publisher/PublisherImpl.java @@ -117,10 +117,20 @@ public final WeakReference getNodeReference() { public final EventHandler createEventHandler(Supplier factory, Consumer callback) { + final WeakReference> weakEventHandlers = new WeakReference( + this.eventHandlers); + Consumer disposeCallback = new Consumer() { + public void accept(EventHandler eventHandler) { + Collection eventHandlers = weakEventHandlers.get(); + if (eventHandlers != null) { + eventHandlers.remove(eventHandler); + } + } + }; T status = factory.get(); long eventHandle = nativeCreateEvent(this.handle, status.getPublisherEventType()); EventHandler eventHandler = new EventHandlerImpl( - new WeakReference(this), eventHandle, factory, callback); + new WeakReference(this), eventHandle, factory, callback, disposeCallback); this.eventHandlers.add(eventHandler); return eventHandler; } diff --git a/rcljava/src/main/java/org/ros2/rcljava/subscription/SubscriptionImpl.java b/rcljava/src/main/java/org/ros2/rcljava/subscription/SubscriptionImpl.java index 34b8b79c..8e20d81d 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/subscription/SubscriptionImpl.java +++ b/rcljava/src/main/java/org/ros2/rcljava/subscription/SubscriptionImpl.java @@ -22,6 +22,7 @@ import org.ros2.rcljava.RCLJava; import org.ros2.rcljava.common.JNIUtils; +import org.ros2.rcljava.consumers.BiConsumer; import org.ros2.rcljava.consumers.Consumer; import org.ros2.rcljava.events.EventHandler; import org.ros2.rcljava.events.EventHandlerImpl; @@ -128,10 +129,20 @@ public final WeakReference getNodeReference() { public final EventHandler createEventHandler(Supplier factory, Consumer callback) { + final WeakReference> weakEventHandlers = new WeakReference( + this.eventHandlers); + Consumer disposeCallback = new Consumer() { + public void accept(EventHandler eventHandler) { + Collection eventHandlers = weakEventHandlers.get(); + if (eventHandlers != null) { + eventHandlers.remove(eventHandler); + } + } + }; T status = factory.get(); long eventHandle = nativeCreateEvent(this.handle, status.getSubscriptionEventType()); EventHandler eventHandler = new EventHandlerImpl( - new WeakReference(this), eventHandle, factory, callback); + new WeakReference(this), eventHandle, factory, callback, disposeCallback); this.eventHandlers.add(eventHandler); return eventHandler; } diff --git a/rcljava/src/test/java/org/ros2/rcljava/publisher/PublisherTest.java b/rcljava/src/test/java/org/ros2/rcljava/publisher/PublisherTest.java index cc449c1e..ed9d7bd0 100644 --- a/rcljava/src/test/java/org/ros2/rcljava/publisher/PublisherTest.java +++ b/rcljava/src/test/java/org/ros2/rcljava/publisher/PublisherTest.java @@ -112,10 +112,13 @@ public void accept(final OfferedQosIncompatible status) { } ); assertNotEquals(0, eventHandler.getHandle()); + assertEquals(1, publisher.getEventHandlers().size()); // force executing the callback, so we check that taking an event works eventHandler.executeCallback(); - RCLJava.shutdown(); + eventHandler.dispose(); assertEquals(0, eventHandler.getHandle()); + assertEquals(0, publisher.getEventHandlers().size()); + RCLJava.shutdown(); } @Test From a7b976daf702473ad6ee9b98415aed3ec4adec43 Mon Sep 17 00:00:00 2001 From: Ivan Santiago Paunovic Date: Thu, 27 Aug 2020 15:46:16 -0300 Subject: [PATCH 09/11] Add RequestedDeadlineMissed subscription event (osrf/ros2_java#19) Signed-off-by: Ivan Santiago Paunovic --- rcljava/CMakeLists.txt | 2 + ...ription_statuses_RequestedDeadlineMissed.h | 63 ++++++++++++++++ ...ption_statuses_RequestedDeadlineMissed.cpp | 73 +++++++++++++++++++ .../statuses/RequestedDeadlineMissed.java | 65 +++++++++++++++++ .../subscription/SubscriptionTest.java | 25 +++++++ 5 files changed, 228 insertions(+) create mode 100644 rcljava/include/org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed.h create mode 100644 rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed.cpp create mode 100644 rcljava/src/main/java/org/ros2/rcljava/subscription/statuses/RequestedDeadlineMissed.java diff --git a/rcljava/CMakeLists.txt b/rcljava/CMakeLists.txt index c47359cb..18a3c7a8 100644 --- a/rcljava/CMakeLists.txt +++ b/rcljava/CMakeLists.txt @@ -68,6 +68,7 @@ set(${PROJECT_NAME}_jni_sources "src/main/cpp/org_ros2_rcljava_publisher_PublisherImpl.cpp" "src/main/cpp/org_ros2_rcljava_service_ServiceImpl.cpp" "src/main/cpp/org_ros2_rcljava_subscription_SubscriptionImpl.cpp" + "src/main/cpp/org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed.cpp" "src/main/cpp/org_ros2_rcljava_subscription_statuses_RequestedQosIncompatible.cpp" "src/main/cpp/org_ros2_rcljava_time_Clock.cpp" "src/main/cpp/org_ros2_rcljava_timer_WallTimerImpl.cpp" @@ -177,6 +178,7 @@ set(${PROJECT_NAME}_sources "src/main/java/org/ros2/rcljava/service/ServiceImpl.java" "src/main/java/org/ros2/rcljava/subscription/Subscription.java" "src/main/java/org/ros2/rcljava/subscription/SubscriptionImpl.java" + "src/main/java/org/ros2/rcljava/subscription/statuses/RequestedDeadlineMissed.java" "src/main/java/org/ros2/rcljava/subscription/statuses/RequestedQosIncompatible.java" "src/main/java/org/ros2/rcljava/time/Clock.java" "src/main/java/org/ros2/rcljava/time/ClockType.java" diff --git a/rcljava/include/org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed.h b/rcljava/include/org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed.h new file mode 100644 index 00000000..47c09fdd --- /dev/null +++ b/rcljava/include/org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed.h @@ -0,0 +1,63 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +/* Header for class org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed */ + +#ifndef ORG_ROS2_RCLJAVA_SUBSCRIPTION_STATUSES_REQUESTEDDEADLINEMISSED_H_ +#define ORG_ROS2_RCLJAVA_SUBSCRIPTION_STATUSES_REQUESTEDDEADLINEMISSED_H_ +#ifdef __cplusplus +extern "C" { +#endif + +/* + * Class: org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed + * Method: nativeAllocateRCLStatusEvent + * Signature: ()J + */ +JNIEXPORT jlong JNICALL +Java_org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed_nativeAllocateRCL( + JNIEnv *, jclass); + +/* + * Class: org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed + * Method: nativeDeallocateRCLStatusEvent + * Signature: (J)V + */ +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed_nativeDeallocateRCL( + JNIEnv *, jclass, jlong); + +/* + * Class: org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed + * Method: nativeFromRCLEvent + * Signature: (J)V + */ +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed_nativeFromRCL( + JNIEnv *, jobject, jlong); + +/* + * Class: org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed + * Method: nativeGetSubscriptionEventType + * Signature: ()I + */ +JNIEXPORT jint JNICALL +Java_org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed_nativeGetEventType( + JNIEnv *, jclass); + +#ifdef __cplusplus +} +#endif +#endif // ORG_ROS2_RCLJAVA_SUBSCRIPTION_STATUSES_REQUESTEDDEADLINEMISSED_H_ diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed.cpp new file mode 100644 index 00000000..0d9c29c1 --- /dev/null +++ b/rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed.cpp @@ -0,0 +1,73 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed.h" + +#include +#include + +#include "rmw/types.h" +#include "rcl/event.h" +#include "rcljava_common/exceptions.hpp" + +using rcljava_common::exceptions::rcljava_throw_exception; + +JNIEXPORT jlong JNICALL +Java_org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed_nativeAllocateRCL( + JNIEnv * env, jclass) +{ + void * p = malloc(sizeof(rmw_requested_deadline_missed_status_t)); + if (!p) { + rcljava_throw_exception( + env, "java/lang/OutOfMemoryError", "failed to allocate missed deadline status"); + } + return reinterpret_cast(p); +} + +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed_nativeDeallocateRCL( + JNIEnv *, jclass, jlong handle) +{ + free(reinterpret_cast(handle)); +} + +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed_nativeFromRCL( + JNIEnv * env, jobject self, jlong handle) +{ + auto * p = reinterpret_cast(handle); + if (!p) { + rcljava_throw_exception( + env, "java/lang/IllegalArgumentException", "passed rmw object handle is NULL"); + } + // TODO(ivanpauno): class and field lookup could be done at startup time + jclass clazz = env->GetObjectClass(self); + jfieldID total_count_fid = env->GetFieldID(clazz, "totalCount", "I"); + if (env->ExceptionCheck()) { + return; + } + jfieldID total_count_change_fid = env->GetFieldID(clazz, "totalCountChange", "I"); + if (env->ExceptionCheck()) { + return; + } + env->SetIntField(self, total_count_fid, p->total_count); + env->SetIntField(self, total_count_change_fid, p->total_count_change); +} + +JNIEXPORT jint JNICALL +Java_org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed_nativeGetEventType( + JNIEnv *, jclass) +{ + return RCL_SUBSCRIPTION_REQUESTED_DEADLINE_MISSED; +} diff --git a/rcljava/src/main/java/org/ros2/rcljava/subscription/statuses/RequestedDeadlineMissed.java b/rcljava/src/main/java/org/ros2/rcljava/subscription/statuses/RequestedDeadlineMissed.java new file mode 100644 index 00000000..fa56f36d --- /dev/null +++ b/rcljava/src/main/java/org/ros2/rcljava/subscription/statuses/RequestedDeadlineMissed.java @@ -0,0 +1,65 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +package org.ros2.rcljava.subscription.statuses; + +import java.util.function.Supplier; + +import org.ros2.rcljava.common.JNIUtils; +import org.ros2.rcljava.events.SubscriptionEventStatus; + +import org.slf4j.Logger; +import org.slf4j.LoggerFactory; + +/** + * This class serves as a bridge between a rmw_requested_deadline_missed_status_t and RCLJava. + */ +public class RequestedDeadlineMissed implements SubscriptionEventStatus { + public int totalCount; + public int totalCountChange; + + public final long allocateRCLStatusEvent() { + return nativeAllocateRCL(); + } + public final void deallocateRCLStatusEvent(long handle) { + nativeDeallocateRCL(handle); + } + public final void fromRCLEvent(long handle) { + nativeFromRCL(handle); + } + public final int getSubscriptionEventType() { + return nativeGetEventType(); + } + // TODO(ivanpauno): Remove this when -source 8 can be used (method references for the win) + public static final Supplier factory = new Supplier() { + public RequestedDeadlineMissed get() { + return new RequestedDeadlineMissed(); + } + }; + + private static final Logger logger = LoggerFactory.getLogger(RequestedDeadlineMissed.class); + static { + try { + JNIUtils.loadImplementation(RequestedDeadlineMissed.class); + } catch (UnsatisfiedLinkError ule) { + logger.error("Native code library failed to load.\n" + ule); + System.exit(1); + } + } + + private static native long nativeAllocateRCL(); + private static native void nativeDeallocateRCL(long handle); + private native void nativeFromRCL(long handle); + private static native int nativeGetEventType(); +} diff --git a/rcljava/src/test/java/org/ros2/rcljava/subscription/SubscriptionTest.java b/rcljava/src/test/java/org/ros2/rcljava/subscription/SubscriptionTest.java index 8f39ddbd..11b30360 100644 --- a/rcljava/src/test/java/org/ros2/rcljava/subscription/SubscriptionTest.java +++ b/rcljava/src/test/java/org/ros2/rcljava/subscription/SubscriptionTest.java @@ -27,6 +27,7 @@ import org.ros2.rcljava.consumers.Consumer; import org.ros2.rcljava.events.EventHandler; import org.ros2.rcljava.node.Node; +import org.ros2.rcljava.subscription.statuses.RequestedDeadlineMissed; import org.ros2.rcljava.subscription.statuses.RequestedQosIncompatible; public class SubscriptionTest { @@ -69,6 +70,30 @@ public void accept(final std_msgs.msg.String msg) {} RCLJava.shutdown(); } + @Test + public final void testCreateRequestedDeadlineMissedEvent() { + String identifier = RCLJava.getRMWIdentifier(); + RCLJava.rclJavaInit(); + Node node = RCLJava.createNode("test_node"); + Subscription subscription = node.createSubscription( + std_msgs.msg.String.class, "test_topic", new Consumer() { + public void accept(final std_msgs.msg.String msg) {} + }); + EventHandler eventHandler = subscription.createEventHandler( + RequestedDeadlineMissed.factory, new Consumer() { + public void accept(final RequestedDeadlineMissed status) { + assertEquals(status.totalCount, 0); + assertEquals(status.totalCountChange, 0); + } + } + ); + assertNotEquals(0, eventHandler.getHandle()); + // force executing the callback, so we check that taking an event works + eventHandler.executeCallback(); + RCLJava.shutdown(); + assertEquals(0, eventHandler.getHandle()); + } + @Test public final void testCreateRequestedQosIncompatibleEvent() { String identifier = RCLJava.getRMWIdentifier(); From ab00818e855d74cdb4a0fad14812e8010ebf5012 Mon Sep 17 00:00:00 2001 From: Ivan Santiago Paunovic Date: Fri, 28 Aug 2020 18:10:22 -0300 Subject: [PATCH 10/11] Add LivelinessChanged subscription event (osrf/ros2_java#18) Signed-off-by: Ivan Santiago Paunovic --- rcljava/CMakeLists.txt | 2 + ..._subscription_statuses_LivelinessChanged.h | 63 ++++++++++++++ ...ubscription_statuses_LivelinessChanged.cpp | 83 +++++++++++++++++++ .../statuses/LivelinessChanged.java | 69 +++++++++++++++ .../subscription/SubscriptionTest.java | 27 ++++++ 5 files changed, 244 insertions(+) create mode 100644 rcljava/include/org_ros2_rcljava_subscription_statuses_LivelinessChanged.h create mode 100644 rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_LivelinessChanged.cpp create mode 100644 rcljava/src/main/java/org/ros2/rcljava/subscription/statuses/LivelinessChanged.java diff --git a/rcljava/CMakeLists.txt b/rcljava/CMakeLists.txt index 18a3c7a8..dbd3d649 100644 --- a/rcljava/CMakeLists.txt +++ b/rcljava/CMakeLists.txt @@ -68,6 +68,7 @@ set(${PROJECT_NAME}_jni_sources "src/main/cpp/org_ros2_rcljava_publisher_PublisherImpl.cpp" "src/main/cpp/org_ros2_rcljava_service_ServiceImpl.cpp" "src/main/cpp/org_ros2_rcljava_subscription_SubscriptionImpl.cpp" + "src/main/cpp/org_ros2_rcljava_subscription_statuses_LivelinessChanged.cpp" "src/main/cpp/org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed.cpp" "src/main/cpp/org_ros2_rcljava_subscription_statuses_RequestedQosIncompatible.cpp" "src/main/cpp/org_ros2_rcljava_time_Clock.cpp" @@ -178,6 +179,7 @@ set(${PROJECT_NAME}_sources "src/main/java/org/ros2/rcljava/service/ServiceImpl.java" "src/main/java/org/ros2/rcljava/subscription/Subscription.java" "src/main/java/org/ros2/rcljava/subscription/SubscriptionImpl.java" + "src/main/java/org/ros2/rcljava/subscription/statuses/LivelinessChanged.java" "src/main/java/org/ros2/rcljava/subscription/statuses/RequestedDeadlineMissed.java" "src/main/java/org/ros2/rcljava/subscription/statuses/RequestedQosIncompatible.java" "src/main/java/org/ros2/rcljava/time/Clock.java" diff --git a/rcljava/include/org_ros2_rcljava_subscription_statuses_LivelinessChanged.h b/rcljava/include/org_ros2_rcljava_subscription_statuses_LivelinessChanged.h new file mode 100644 index 00000000..d34198f9 --- /dev/null +++ b/rcljava/include/org_ros2_rcljava_subscription_statuses_LivelinessChanged.h @@ -0,0 +1,63 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +/* Header for class org_ros2_rcljava_subscription_statuses_LivelinessChanged */ + +#ifndef ORG_ROS2_RCLJAVA_SUBSCRIPTION_STATUSES_LIVELINESSCHANGED_H_ +#define ORG_ROS2_RCLJAVA_SUBSCRIPTION_STATUSES_LIVELINESSCHANGED_H_ +#ifdef __cplusplus +extern "C" { +#endif + +/* + * Class: org_ros2_rcljava_subscription_statuses_LivelinessChanged + * Method: nativeAllocateRCLStatusEvent + * Signature: ()J + */ +JNIEXPORT jlong JNICALL +Java_org_ros2_rcljava_subscription_statuses_LivelinessChanged_nativeAllocateRCLStatusEvent( + JNIEnv *, jclass); + +/* + * Class: org_ros2_rcljava_subscription_statuses_LivelinessChanged + * Method: nativeDeallocateRCLStatusEvent + * Signature: (J)V + */ +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_subscription_statuses_LivelinessChanged_nativeDeallocateRCLStatusEvent( + JNIEnv *, jclass, jlong); + +/* + * Class: org_ros2_rcljava_subscription_statuses_LivelinessChanged + * Method: nativeFromRCLEvent + * Signature: (J)V + */ +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_subscription_statuses_LivelinessChanged_nativeFromRCLEvent( + JNIEnv *, jobject, jlong); + +/* + * Class: org_ros2_rcljava_subscription_statuses_LivelinessChanged + * Method: nativeGetsubscriptionEventType + * Signature: ()I + */ +JNIEXPORT jint JNICALL +Java_org_ros2_rcljava_subscription_statuses_LivelinessChanged_nativeGetSubscriptionEventType( + JNIEnv *, jclass); + +#ifdef __cplusplus +} +#endif +#endif // ORG_ROS2_RCLJAVA_SUBSCRIPTION_STATUSES_LIVELINESSCHANGED_H_ diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_LivelinessChanged.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_LivelinessChanged.cpp new file mode 100644 index 00000000..e1b12466 --- /dev/null +++ b/rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_LivelinessChanged.cpp @@ -0,0 +1,83 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "org_ros2_rcljava_subscription_statuses_LivelinessChanged.h" + +#include +#include + +#include "rmw/types.h" +#include "rcl/event.h" +#include "rcljava_common/exceptions.hpp" + +using rcljava_common::exceptions::rcljava_throw_exception; + +JNIEXPORT jlong JNICALL +Java_org_ros2_rcljava_subscription_statuses_LivelinessChanged_nativeAllocateRCLStatusEvent( + JNIEnv * env, jclass) +{ + void * p = malloc(sizeof(rmw_liveliness_changed_status_t)); + if (!p) { + rcljava_throw_exception( + env, "java/lang/OutOfMemoryError", "failed to allocate liveliness changed status"); + } + return reinterpret_cast(p); +} + +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_subscription_statuses_LivelinessChanged_nativeDeallocateRCLStatusEvent( + JNIEnv *, jclass, jlong handle) +{ + free(reinterpret_cast(handle)); +} + +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_subscription_statuses_LivelinessChanged_nativeFromRCLEvent( + JNIEnv * env, jobject self, jlong handle) +{ + auto * p = reinterpret_cast(handle); + if (!p) { + rcljava_throw_exception( + env, "java/lang/IllegalArgumentException", "passed rmw object handle is NULL"); + } + // TODO(ivanpauno): class and field lookup could be done at startup time + jclass clazz = env->GetObjectClass(self); + jfieldID alive_count_fid = env->GetFieldID(clazz, "aliveCount", "I"); + if (env->ExceptionCheck()) { + return; + } + jfieldID not_alive_count_fid = env->GetFieldID(clazz, "notAliveCount", "I"); + if (env->ExceptionCheck()) { + return; + } + jfieldID alive_count_change_fid = env->GetFieldID(clazz, "aliveCountChange", "I"); + if (env->ExceptionCheck()) { + return; + } + jfieldID not_alive_count_change_fid = env->GetFieldID(clazz, "notAliveCountChange", "I"); + if (env->ExceptionCheck()) { + return; + } + env->SetIntField(self, alive_count_fid, p->alive_count); + env->SetIntField(self, not_alive_count_fid, p->not_alive_count); + env->SetIntField(self, alive_count_change_fid, p->alive_count_change); + env->SetIntField(self, not_alive_count_change_fid, p->not_alive_count_change); +} + +JNIEXPORT jint JNICALL +Java_org_ros2_rcljava_subscription_statuses_LivelinessChanged_nativeGetSubscriptionEventType( + JNIEnv *, jclass) +{ + return RCL_SUBSCRIPTION_LIVELINESS_CHANGED; +} diff --git a/rcljava/src/main/java/org/ros2/rcljava/subscription/statuses/LivelinessChanged.java b/rcljava/src/main/java/org/ros2/rcljava/subscription/statuses/LivelinessChanged.java new file mode 100644 index 00000000..f126508b --- /dev/null +++ b/rcljava/src/main/java/org/ros2/rcljava/subscription/statuses/LivelinessChanged.java @@ -0,0 +1,69 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +package org.ros2.rcljava.subscription.statuses; + +import java.util.function.Supplier; + +import org.ros2.rcljava.common.JNIUtils; +import org.ros2.rcljava.events.SubscriptionEventStatus; + +import org.slf4j.Logger; +import org.slf4j.LoggerFactory; + +/** + * This class serves as a bridge between rmw_liveliness_changed_status_t + * and RCLJava. + */ +public class LivelinessChanged implements SubscriptionEventStatus { + public int aliveCount; + public int notAliveCount; + public int aliveCountChange; + public int notAliveCountChange; + + public final long allocateRCLStatusEvent() { + return nativeAllocateRCLStatusEvent(); + } + public final void deallocateRCLStatusEvent(long handle) { + nativeDeallocateRCLStatusEvent(handle); + } + public final void fromRCLEvent(long handle) { + nativeFromRCLEvent(handle); + } + public final int getSubscriptionEventType() { + return nativeGetSubscriptionEventType(); + } + // TODO(ivanpauno): Remove this when -source 8 can be used (method references for the win) + public static final Supplier + factory = new Supplier() { + public LivelinessChanged get() { + return new LivelinessChanged(); + } + }; + + private static final Logger logger = LoggerFactory.getLogger(LivelinessChanged.class); + static { + try { + JNIUtils.loadImplementation(LivelinessChanged.class); + } catch (UnsatisfiedLinkError ule) { + logger.error("Native code library failed to load.\n" + ule); + System.exit(1); + } + } + + private static native long nativeAllocateRCLStatusEvent(); + private static native void nativeDeallocateRCLStatusEvent(long handle); + private native void nativeFromRCLEvent(long handle); + private static native int nativeGetSubscriptionEventType(); +} diff --git a/rcljava/src/test/java/org/ros2/rcljava/subscription/SubscriptionTest.java b/rcljava/src/test/java/org/ros2/rcljava/subscription/SubscriptionTest.java index 11b30360..21299024 100644 --- a/rcljava/src/test/java/org/ros2/rcljava/subscription/SubscriptionTest.java +++ b/rcljava/src/test/java/org/ros2/rcljava/subscription/SubscriptionTest.java @@ -27,6 +27,7 @@ import org.ros2.rcljava.consumers.Consumer; import org.ros2.rcljava.events.EventHandler; import org.ros2.rcljava.node.Node; +import org.ros2.rcljava.subscription.statuses.LivelinessChanged; import org.ros2.rcljava.subscription.statuses.RequestedDeadlineMissed; import org.ros2.rcljava.subscription.statuses.RequestedQosIncompatible; @@ -70,6 +71,32 @@ public void accept(final std_msgs.msg.String msg) {} RCLJava.shutdown(); } + @Test + public final void testCreateLivelinessChangedEvent() { + String identifier = RCLJava.getRMWIdentifier(); + RCLJava.rclJavaInit(); + Node node = RCLJava.createNode("test_node"); + Subscription subscription = node.createSubscription( + std_msgs.msg.String.class, "test_topic", new Consumer() { + public void accept(final std_msgs.msg.String msg) {} + }); + EventHandler eventHandler = subscription.createEventHandler( + LivelinessChanged.factory, new Consumer() { + public void accept(final LivelinessChanged status) { + assertEquals(status.aliveCount, 0); + assertEquals(status.notAliveCount, 0); + assertEquals(status.aliveCountChange, 0); + assertEquals(status.notAliveCountChange, 0); + } + } + ); + assertNotEquals(0, eventHandler.getHandle()); + // force executing the callback, so we check that taking an event works + eventHandler.executeCallback(); + RCLJava.shutdown(); + assertEquals(0, eventHandler.getHandle()); + } + @Test public final void testCreateRequestedDeadlineMissedEvent() { String identifier = RCLJava.getRMWIdentifier(); From cb1c8fd5eea47955bce73d93a0113e39f843870b Mon Sep 17 00:00:00 2001 From: Ivan Santiago Paunovic Date: Fri, 28 Aug 2020 18:42:27 -0300 Subject: [PATCH 11/11] Add missing returns (osrf/ros2_java#23) Signed-off-by: Ivan Santiago Paunovic --- .../main/cpp/org_ros2_rcljava_detail_QosIncompatibleStatus.cpp | 1 + .../cpp/org_ros2_rcljava_publisher_statuses_LivelinessLost.cpp | 1 + ...org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed.cpp | 1 + .../org_ros2_rcljava_subscription_statuses_LivelinessChanged.cpp | 1 + ...os2_rcljava_subscription_statuses_RequestedDeadlineMissed.cpp | 1 + 5 files changed, 5 insertions(+) diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_detail_QosIncompatibleStatus.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_detail_QosIncompatibleStatus.cpp index 85dde30f..149b90c6 100644 --- a/rcljava/src/main/cpp/org_ros2_rcljava_detail_QosIncompatibleStatus.cpp +++ b/rcljava/src/main/cpp/org_ros2_rcljava_detail_QosIncompatibleStatus.cpp @@ -51,6 +51,7 @@ Java_org_ros2_rcljava_detail_QosIncompatibleStatus_nativeFromRCLEvent( if (!p) { rcljava_throw_exception( env, "java/lang/IllegalArgumentException", "passed rmw object handle is NULL"); + return; } // TODO(ivanpauno): class and field lookup could be done at startup time jclass clazz = env->GetObjectClass(self); diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_LivelinessLost.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_LivelinessLost.cpp index 4e5558e4..8e1118fc 100644 --- a/rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_LivelinessLost.cpp +++ b/rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_LivelinessLost.cpp @@ -50,6 +50,7 @@ Java_org_ros2_rcljava_publisher_statuses_LivelinessLost_nativeFromRCLEvent( if (!p) { rcljava_throw_exception( env, "java/lang/IllegalArgumentException", "passed rmw object handle is NULL"); + return; } // TODO(ivanpauno): class and field lookup could be done at startup time jclass clazz = env->GetObjectClass(self); diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed.cpp index 4cdac4bf..bce491af 100644 --- a/rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed.cpp +++ b/rcljava/src/main/cpp/org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed.cpp @@ -50,6 +50,7 @@ Java_org_ros2_rcljava_publisher_statuses_OfferedDeadlineMissed_nativeFromRCLEven if (!p) { rcljava_throw_exception( env, "java/lang/IllegalArgumentException", "passed rmw object handle is NULL"); + return; } // TODO(ivanpauno): class and field lookup could be done at startup time jclass clazz = env->GetObjectClass(self); diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_LivelinessChanged.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_LivelinessChanged.cpp index e1b12466..4c6102d5 100644 --- a/rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_LivelinessChanged.cpp +++ b/rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_LivelinessChanged.cpp @@ -50,6 +50,7 @@ Java_org_ros2_rcljava_subscription_statuses_LivelinessChanged_nativeFromRCLEvent if (!p) { rcljava_throw_exception( env, "java/lang/IllegalArgumentException", "passed rmw object handle is NULL"); + return; } // TODO(ivanpauno): class and field lookup could be done at startup time jclass clazz = env->GetObjectClass(self); diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed.cpp index 0d9c29c1..b3f06cbc 100644 --- a/rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed.cpp +++ b/rcljava/src/main/cpp/org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed.cpp @@ -50,6 +50,7 @@ Java_org_ros2_rcljava_subscription_statuses_RequestedDeadlineMissed_nativeFromRC if (!p) { rcljava_throw_exception( env, "java/lang/IllegalArgumentException", "passed rmw object handle is NULL"); + return; } // TODO(ivanpauno): class and field lookup could be done at startup time jclass clazz = env->GetObjectClass(self);