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
4 changes: 4 additions & 0 deletions rcljava/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand All @@ -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"
)
Expand Down Expand Up @@ -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"
Expand Down Expand Up @@ -171,6 +174,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"
Expand Down
54 changes: 54 additions & 0 deletions rcljava/include/org_ros2_rcljava_detail_QosIncompatibleStatus.h
Original file line number Diff line number Diff line change
@@ -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 <jni.h>
/* 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_
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
@@ -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 <jni.h>
/* 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_
113 changes: 113 additions & 0 deletions rcljava/src/main/cpp/org_ros2_rcljava_detail_QosIncompatibleStatus.cpp
Original file line number Diff line number Diff line change
@@ -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 <jni.h>
#include <stdlib.h>

#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<jlong>(p);
}

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

JNIEXPORT void JNICALL
Java_org_ros2_rcljava_detail_QosIncompatibleStatus_nativeFromRCLEvent(
JNIEnv * env, jobject self, jlong handle)
{
auto * p = reinterpret_cast<rmw_qos_incompatible_event_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);
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);
}
Original file line number Diff line number Diff line change
Expand Up @@ -15,105 +15,11 @@
#include "org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible.h"

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

#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<jlong>(p);
}

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

JNIEXPORT void JNICALL
Java_org_ros2_rcljava_publisher_statuses_OfferedQosIncompatible_nFromRCLEvent(
JNIEnv * env, jobject self, jlong handle)
{
auto * p = reinterpret_cast<rmw_offered_qos_incompatible_event_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);
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;
Expand Down
Loading