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

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 11 additions & 0 deletions rcljava/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,8 @@ set(${PROJECT_NAME}_jni_sources
"src/main/cpp/org_ros2_rcljava_client_ClientImpl.cpp"
"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_node_NodeImpl.cpp"
"src/main/cpp/org_ros2_rcljava_publisher_PublisherImpl.cpp"
"src/main/cpp/org_ros2_rcljava_service_ServiceImpl.cpp"
Expand Down Expand Up @@ -125,6 +127,12 @@ 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/events/EventHandler.java"
"src/main/java/org/ros2/rcljava/events/EventHandlerImpl.java"
"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/executors/AnyExecutable.java"
"src/main/java/org/ros2/rcljava/executors/BaseExecutor.java"
"src/main/java/org/ros2/rcljava/executors/Executor.java"
Expand Down Expand Up @@ -153,6 +161,7 @@ set(${PROJECT_NAME}_sources
"src/main/java/org/ros2/rcljava/publisher/PublisherImpl.java"
"src/main/java/org/ros2/rcljava/qos/policies/Durability.java"
"src/main/java/org/ros2/rcljava/qos/policies/History.java"
"src/main/java/org/ros2/rcljava/qos/policies/Liveliness.java"
"src/main/java/org/ros2/rcljava/qos/policies/QoSPolicy.java"
"src/main/java/org/ros2/rcljava/qos/policies/Reliability.java"
"src/main/java/org/ros2/rcljava/qos/QoSProfile.java"
Expand Down Expand Up @@ -237,6 +246,7 @@ if(BUILD_TESTING)
# "src/test/java/org/ros2/rcljava/parameters/AsyncParametersClientTest.java"
# "src/test/java/org/ros2/rcljava/parameters/SyncParametersClientTest.java"
"src/test/java/org/ros2/rcljava/publisher/PublisherTest.java"
"src/test/java/org/ros2/rcljava/qos/QoSProfileTest.java"
"src/test/java/org/ros2/rcljava/subscription/SubscriptionTest.java"
"src/test/java/org/ros2/rcljava/timer/TimerTest.java"
)
Expand All @@ -252,6 +262,7 @@ if(BUILD_TESTING)
"org.ros2.rcljava.node.NodeTest"
# "org.ros2.rcljava.parameters.SyncParametersClientTest"
"org.ros2.rcljava.publisher.PublisherTest"
"org.ros2.rcljava.qos.QoSProfileTest"
"org.ros2.rcljava.subscription.SubscriptionTest"
"org.ros2.rcljava.timer.TimerTest"
)
Expand Down
3 changes: 2 additions & 1 deletion rcljava/include/org_ros2_rcljava_RCLJava.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,8 @@ JNICALL Java_org_ros2_rcljava_RCLJava_nativeGetRMWIdentifier(JNIEnv *, jclass);
*/
JNIEXPORT jlong
JNICALL Java_org_ros2_rcljava_RCLJava_nativeConvertQoSProfileToHandle(
JNIEnv *, jclass, jint, jint, jint, jint, jboolean);
JNIEnv *, jclass,
jint, jint, jint, jint, jlong, jint, jlong, jint, jint, jlong, jint, jboolean);

/*
* Class: org_ros2_rcljava_RCLJava
Expand Down
45 changes: 45 additions & 0 deletions rcljava/include/org_ros2_rcljava_events_EventHandlerImpl.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
// 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 <jni.h>
/* Header for class org_ros2_rcljava_events_EventHandlerImpl */

#ifndef ORG_ROS2_RCLJAVA_EVENTS_EVENTHANDLERIMPL_H_
#define ORG_ROS2_RCLJAVA_EVENTS_EVENTHANDLERIMPL_H_
#ifdef __cplusplus
extern "C" {
#endif

/*
* Class: org_ros2_rcljava_events_EventHandlerImpl
* Method: nativeDispose
* Signature: (J)V
*/
JNIEXPORT void
JNICALL Java_org_ros2_rcljava_events_EventHandlerImpl_nativeDispose(
JNIEnv *, jclass, jlong event_handle);

/*
* Class: org_ros2_rcljava_events_EventHandlerImpl
* Method: nativeTake
* Signature: (JJ)V
*/
JNIEXPORT void
JNICALL Java_org_ros2_rcljava_events_EventHandlerImpl_nativeTake(
JNIEnv *, jclass, jlong event_handle, jlong event_status_handle);

#ifdef __cplusplus
}
#endif
#endif // ORG_ROS2_RCLJAVA_EVENTS_EVENTHANDLERIMPL_H_
Original file line number Diff line number Diff line change
@@ -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 <jni.h>
/* Header for class org_ros2_rcljava_events_publisher_statuses_LivelinessLost */

#ifndef ORG_ROS2_RCLJAVA_EVENTS_PUBLISHER_STATUSES_LIVELINESSLOST_H_
#define ORG_ROS2_RCLJAVA_EVENTS_PUBLISHER_STATUSES_LIVELINESSLOST_H_
#ifdef __cplusplus
extern "C" {
#endif

/*
* Class: org_ros2_rcljava_events_publisher_statuses_LivelinessLost
* Method: nativeAllocateRCLStatusEvent
* Signature: ()J
*/
JNIEXPORT jlong JNICALL
Java_org_ros2_rcljava_events_publisher_1statuses_LivelinessLost_nativeAllocateRCLStatusEvent(
JNIEnv *, jclass);

/*
* Class: org_ros2_rcljava_events_publisher_statuses_LivelinessLost
* Method: nativeDeallocateRCLStatusEvent
* Signature: (J)V
*/
JNIEXPORT void JNICALL
Java_org_ros2_rcljava_events_publisher_1statuses_LivelinessLost_nativeDeallocateRCLStatusEvent(
JNIEnv *, jclass, jlong);

/*
* Class: org_ros2_rcljava_events_publisher_statuses_LivelinessLost
* Method: nativeFromRCLEvent
* Signature: (J)V
*/
JNIEXPORT void JNICALL
Java_org_ros2_rcljava_events_publisher_1statuses_LivelinessLost_nativeFromRCLEvent(
JNIEnv *, jobject, jlong);

/*
* Class: org_ros2_rcljava_events_publisher_statuses_LivelinessLost
* Method: nativeGetPublisherEventType
* Signature: ()I
*/
JNIEXPORT jint JNICALL
Java_org_ros2_rcljava_events_publisher_1statuses_LivelinessLost_nativeGetPublisherEventType(
JNIEnv *, jclass);

#ifdef __cplusplus
}
#endif
#endif // ORG_ROS2_RCLJAVA_EVENTS_PUBLISHER_STATUSES_LIVELINESSLOST_H_
9 changes: 9 additions & 0 deletions rcljava/include/org_ros2_rcljava_publisher_PublisherImpl.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,15 @@ JNIEXPORT void
JNICALL Java_org_ros2_rcljava_publisher_PublisherImpl_nativeDispose(
JNIEnv *, jclass, jlong, jlong);

/*
* Class: org_ros2_rcljava_publisher_PublisherImpl
* Method: nativeCreateEvent
* Signature: (JJ)J
*/
JNIEXPORT jlong
JNICALL Java_org_ros2_rcljava_publisher_PublisherImpl_nativeCreateEvent(
JNIEnv *, jclass, jlong, jint);

#ifdef __cplusplus
}
#endif
Expand Down
35 changes: 29 additions & 6 deletions rcljava/src/main/cpp/org_ros2_rcljava_RCLJava.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@

#include "org_ros2_rcljava_RCLJava.h"

using rcljava_common::exceptions::rcljava_throw_exception;
using rcljava_common::exceptions::rcljava_throw_rclexception;
using rcljava_common::signatures::convert_from_java_signature;
using rcljava_common::signatures::convert_to_java_signature;
Expand Down Expand Up @@ -152,9 +153,31 @@ Java_org_ros2_rcljava_RCLJava_nativeGetRMWIdentifier(JNIEnv * env, jclass)
return env->NewStringUTF(rmw_implementation_identifier);
}

#define RCLJAVA_QOS_SET_RMW_TIME(qos_profile, policy_name, seconds, nanos) \
do { \
if (seconds < 0) { \
rcljava_throw_exception( \
env, "java/lang/IllegalArgumentException", \
"seconds must not be negative for " #policy_name); \
free(qos_profile); \
return 0; \
} \
if (nanos < 0) { \
rcljava_throw_exception( \
env, "java/lang/IllegalArgumentException", \
"nanoseconds must not be negative for " #policy_name); \
free(qos_profile); \
return 0; \
} \
qos_profile->policy_name.sec = static_cast<uint64_t>(seconds); \
qos_profile->policy_name.nsec = static_cast<uint64_t>(nanos); \
} while (0)

JNIEXPORT jlong JNICALL
Java_org_ros2_rcljava_RCLJava_nativeConvertQoSProfileToHandle(
JNIEnv *, jclass, jint history, jint depth, jint reliability, jint durability,
JNIEnv * env, jclass, jint history, jint depth, jint reliability, jint durability,
jlong deadline_sec, jint deadline_nanos, jlong lifespan_sec, jint lifespan_nanos,
jint liveliness, jlong liveliness_lease_sec, jint liveliness_lease_nanos,
jboolean avoidROSNamespaceConventions)
{
rmw_qos_profile_t * qos_profile =
Expand All @@ -163,11 +186,11 @@ Java_org_ros2_rcljava_RCLJava_nativeConvertQoSProfileToHandle(
qos_profile->depth = depth;
qos_profile->reliability = static_cast<rmw_qos_reliability_policy_t>(reliability);
qos_profile->durability = static_cast<rmw_qos_durability_policy_t>(durability);
// TODO(jacobperron): Expose deadline, lifespan, and liveliness settings as parameters
qos_profile->deadline = rmw_qos_profile_default.deadline;
qos_profile->lifespan = rmw_qos_profile_default.lifespan;
qos_profile->liveliness = rmw_qos_profile_default.liveliness;
qos_profile->liveliness_lease_duration = rmw_qos_profile_default.liveliness_lease_duration;
RCLJAVA_QOS_SET_RMW_TIME(qos_profile, deadline, deadline_sec, deadline_nanos);
RCLJAVA_QOS_SET_RMW_TIME(qos_profile, lifespan, lifespan_sec, lifespan_nanos);
qos_profile->liveliness = static_cast<rmw_qos_liveliness_policy_t>(liveliness);
RCLJAVA_QOS_SET_RMW_TIME(
qos_profile, liveliness_lease_duration, liveliness_lease_sec, liveliness_lease_nanos);
qos_profile->avoid_ros_namespace_conventions = avoidROSNamespaceConventions;
return reinterpret_cast<jlong>(qos_profile);
}
Expand Down
72 changes: 72 additions & 0 deletions rcljava/src/main/cpp/org_ros2_rcljava_events_EventHandlerImpl.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
// 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 <jni.h>

#include <string>

#include "rcl/error_handling.h"
#include "rcl/event.h"

#include "rcljava_common/exceptions.hpp"

#include "org_ros2_rcljava_events_EventHandlerImpl.h"

using rcljava_common::exceptions::rcljava_throw_exception;
using rcljava_common::exceptions::rcljava_throw_rclexception;

JNIEXPORT void JNICALL
Java_org_ros2_rcljava_events_EventHandlerImpl_nativeDispose(
JNIEnv * env, jclass, jlong event_handle)
{
if (event_handle == 0) {
// everything is ok, already destroyed
return;
}

auto * event = reinterpret_cast<rcl_event_t *>(event_handle);

rcl_ret_t ret = rcl_event_fini(event);

if (RCL_RET_OK != ret) {
std::string msg = "Failed to destroy event: " + std::string(rcl_get_error_string().str);
rcl_reset_error();
rcljava_throw_exception(env, "java/lang/IllegalStateException", msg);
}
}

JNIEXPORT void JNICALL
Java_org_ros2_rcljava_events_EventHandlerImpl_nativeTake(
JNIEnv * env, jclass, jlong event_handle, jlong event_status_handle)
{
auto * event = reinterpret_cast<rcl_event_t *>(event_handle);
if (!event) {
rcljava_throw_exception(
env,
"java/lang/IllegalArgumentException",
"The underlying rcl_event_t has been already disposed");
}
void * event_status = reinterpret_cast<void *>(event_status_handle);
if (!event_status) {
rcljava_throw_exception(
env,
"java/lang/IllegalArgumentException",
"The passed event status is NULL");
}
rcl_ret_t ret = rcl_take_event(event, event_status);
if (RCL_RET_OK != ret) {
rcljava_throw_rclexception(env, ret, rcl_get_error_string().str);
rcl_reset_error();
}
}
Original file line number Diff line number Diff line change
@@ -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_events_publisher_statuses_LivelinessLost.h"

#include <jni.h>
#include <stdlib.h>

#include "rmw/events_statuses/liveliness_lost.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_LivelinessLost_nativeAllocateRCLStatusEvent(
JNIEnv * env, jclass)
{
void * p = malloc(sizeof(rmw_liveliness_lost_status_t));
if (!p) {
rcljava_throw_exception(
env, "java/lang/OutOfMemoryError", "failed to allocate liveliness lost status");
}
return reinterpret_cast<jlong>(p);
}

JNIEXPORT void JNICALL
Java_org_ros2_rcljava_events_publisher_1statuses_LivelinessLost_nativeDeallocateRCLStatusEvent(
JNIEnv *, jclass, jlong handle)
{
free(reinterpret_cast<void *>(handle));
}

JNIEXPORT void JNICALL
Java_org_ros2_rcljava_events_publisher_1statuses_LivelinessLost_nativeFromRCLEvent(
JNIEnv * env, jobject self, jlong handle)
{
auto * p = reinterpret_cast<rmw_liveliness_lost_status_t *>(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, "total_count", "I");
if (env->ExceptionCheck()) {
return;
}
jfieldID total_count_change_fid = env->GetFieldID(clazz, "total_count_change", "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_events_publisher_1statuses_LivelinessLost_nativeGetPublisherEventType(
JNIEnv *, jclass)
{
return RCL_PUBLISHER_LIVELINESS_LOST;
}
Loading