diff --git a/rcljava/CMakeLists.txt b/rcljava/CMakeLists.txt index 328bdecb..0f89a59b 100644 --- a/rcljava/CMakeLists.txt +++ b/rcljava/CMakeLists.txt @@ -66,6 +66,7 @@ set(${PROJECT_NAME}_jni_sources "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_qos_QoSProfile.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" diff --git a/rcljava/include/org_ros2_rcljava_qos_QoSProfile.h b/rcljava/include/org_ros2_rcljava_qos_QoSProfile.h new file mode 100644 index 00000000..ada8004c --- /dev/null +++ b/rcljava/include/org_ros2_rcljava_qos_QoSProfile.h @@ -0,0 +1,41 @@ +// 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_qos_QoSProfile */ + +#ifndef ORG_ROS2_RCLJAVA_QOS_QOSPROFILE_H_ +#define ORG_ROS2_RCLJAVA_QOS_QOSPROFILE_H_ +#ifdef __cplusplus +extern "C" { +#endif +/* + * Class: org_ros2_rcljava_qos_QoSProfile + * Method: nativeFromRCL + * Signature: (J)V + */ +JNIEXPORT void +JNICALL Java_org_ros2_rcljava_qos_QoSProfile_nativeFromRCL(JNIEnv *, jobject, jlong); + +/* + * Class: org_ros2_rcljava_qos_QoSProfile + * Method: nativeGetHandleFromName + * Signature: (Ljava/lang/String;)J + */ +JNIEXPORT jlong +JNICALL Java_org_ros2_rcljava_qos_QoSProfile_nativeGetHandleFromName(JNIEnv *, jclass, jstring); +#ifdef __cplusplus +} +#endif +#endif // ORG_ROS2_RCLJAVA_QOS_QOSPROFILE_H_ diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_qos_QoSProfile.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_qos_QoSProfile.cpp new file mode 100644 index 00000000..16239f7b --- /dev/null +++ b/rcljava/src/main/cpp/org_ros2_rcljava_qos_QoSProfile.cpp @@ -0,0 +1,250 @@ +// 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_qos_QoSProfile.h" + +#include +#include + +#include "rcljava_common/exceptions.hpp" +#include "rmw/qos_profiles.h" +#include "rmw/types.h" + +using rcljava_common::exceptions::rcljava_throw_exception; + +static void +qos_set_duration(JNIEnv * env, uint64_t seconds, uint64_t nanos, jobject jqos, jfieldID fid) +{ + if (static_cast(std::numeric_limits::max()) < seconds) { + // Throwing an exception here would be weird, as we cannot control the durability that was set + // on all other endpoints in the network. Set jqos seconds to jlong max. + seconds = static_cast(std::numeric_limits::max()); + } + if (static_cast(std::numeric_limits::max()) < nanos) { + // This should never happen, as nanoseconds within a second can perfectly be represented + // in a jlong. + nanos = static_cast(std::numeric_limits::max()); + } + jclass duration_clazz = env->FindClass("java/time/Duration"); + RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); + jmethodID factory_mid = env->GetStaticMethodID( + duration_clazz, "ofSeconds", "(JJ)Ljava/time/Duration;"); + RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); + jobject jduration = env->CallStaticObjectMethod( + duration_clazz, factory_mid, static_cast(seconds), static_cast(nanos)); + RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); + env->SetObjectField(jqos, fid, jduration); +} + +static void +qos_from_rcl(JNIEnv * env, const rmw_qos_profile_t & qos, jobject jqos) +{ + // TODO(ivanpauno): class and field lookup could be done at startup time + jclass clazz = env->GetObjectClass(jqos); + const char * history_class_path = "Lorg/ros2/rcljava/qos/policies/History;"; + jfieldID history_fid = env->GetFieldID(clazz, "history", history_class_path); + RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); + jfieldID depth_fid = env->GetFieldID(clazz, "depth", "I"); + RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); + const char * reliability_class_path = "Lorg/ros2/rcljava/qos/policies/Reliability;"; + jfieldID reliability_fid = env->GetFieldID(clazz, "reliability", reliability_class_path); + RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); + const char * durability_class_path = "Lorg/ros2/rcljava/qos/policies/Durability;"; + jfieldID durability_fid = env->GetFieldID(clazz, "durability", durability_class_path); + RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); + jfieldID deadline_fid = env->GetFieldID(clazz, "deadline", "Ljava/time/Duration;"); + RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); + jfieldID lifespan_fid = env->GetFieldID(clazz, "lifespan", "Ljava/time/Duration;"); + RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); + const char * liveliness_class_path = "Lorg/ros2/rcljava/qos/policies/Liveliness;"; + jfieldID liveliness_fid = env->GetFieldID(clazz, "liveliness", liveliness_class_path); + RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); + jfieldID liveliness_lease_fid = env->GetFieldID( + clazz, "livelinessLeaseDuration", "Ljava/time/Duration;"); + RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); + jfieldID avoid_ros_conventions_fid = env->GetFieldID( + clazz, "avoidROSNamespaceConventions", "Z"); + RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); + + jclass history_clazz = env->FindClass("org/ros2/rcljava/qos/policies/History"); + jfieldID history_value_fid; + switch (qos.history) { + case RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT: + history_value_fid = env->GetStaticFieldID( + history_clazz, "SYSTEM_DEFAULT", history_class_path); + break; + case RMW_QOS_POLICY_HISTORY_KEEP_LAST: + history_value_fid = env->GetStaticFieldID( + history_clazz, "KEEP_LAST", history_class_path); + break; + case RMW_QOS_POLICY_HISTORY_KEEP_ALL: + history_value_fid = env->GetStaticFieldID( + history_clazz, "KEEP_ALL", history_class_path); + break; + case RMW_QOS_POLICY_HISTORY_UNKNOWN: + history_value_fid = env->GetStaticFieldID( + history_clazz, "UNKNOWN", history_class_path); + break; + default: + rcljava_throw_exception( + env, "java/lang/IllegalStateException", "unknown history policy value"); + break; + } + RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); + jobject history_value = env->GetStaticObjectField(history_clazz, history_value_fid); + env->SetObjectField(jqos, history_fid, history_value); + + env->SetIntField(jqos, depth_fid, qos.depth); + + jclass reliability_clazz = env->FindClass("org/ros2/rcljava/qos/policies/Reliability"); + jfieldID reliability_value_fid; + switch (qos.reliability) { + case RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT: + reliability_value_fid = env->GetStaticFieldID( + reliability_clazz, "SYSTEM_DEFAULT", reliability_class_path); + break; + case RMW_QOS_POLICY_RELIABILITY_RELIABLE: + reliability_value_fid = env->GetStaticFieldID( + reliability_clazz, "RELIABLE", reliability_class_path); + break; + case RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT: + reliability_value_fid = env->GetStaticFieldID( + reliability_clazz, "BEST_EFFORT", reliability_class_path); + break; + case RMW_QOS_POLICY_RELIABILITY_UNKNOWN: + reliability_value_fid = env->GetStaticFieldID( + reliability_clazz, "UNKNOWN", reliability_class_path); + break; + default: + rcljava_throw_exception( + env, "java/lang/IllegalStateException", "unknown reliability policy value"); + break; + } + RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); + jobject reliability_value = env->GetStaticObjectField(reliability_clazz, reliability_value_fid); + env->SetObjectField(jqos, reliability_fid, reliability_value); + + jclass durability_clazz = env->FindClass("org/ros2/rcljava/qos/policies/Durability"); + jfieldID durability_value_fid; + switch (qos.durability) { + case RMW_QOS_POLICY_DURABILITY_SYSTEM_DEFAULT: + durability_value_fid = env->GetStaticFieldID( + durability_clazz, "SYSTEM_DEFAULT", durability_class_path); + break; + case RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL: + durability_value_fid = env->GetStaticFieldID( + durability_clazz, "TRANSIENT_LOCAL", durability_class_path); + break; + case RMW_QOS_POLICY_DURABILITY_VOLATILE: + durability_value_fid = env->GetStaticFieldID( + durability_clazz, "VOLATILE", durability_class_path); + break; + case RMW_QOS_POLICY_DURABILITY_UNKNOWN: + durability_value_fid = env->GetStaticFieldID( + durability_clazz, "UNKNOWN", durability_class_path); + break; + default: + rcljava_throw_exception( + env, "java/lang/IllegalStateException", "unknown durability policy value"); + break; + } + RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); + jobject durability_value = env->GetStaticObjectField(durability_clazz, durability_value_fid); + env->SetObjectField(jqos, durability_fid, durability_value); + + qos_set_duration(env, qos.deadline.sec, qos.deadline.nsec, jqos, deadline_fid); + RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); + qos_set_duration(env, qos.lifespan.sec, qos.lifespan.nsec, jqos, lifespan_fid); + RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); + qos_set_duration( + env, qos.liveliness_lease_duration.sec, + qos.liveliness_lease_duration.nsec, jqos, liveliness_lease_fid); + RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); + + jclass liveliness_clazz = env->FindClass("org/ros2/rcljava/qos/policies/Liveliness"); + jfieldID liveliness_value_fid; + switch (qos.liveliness) { + case RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT: + liveliness_value_fid = env->GetStaticFieldID( + liveliness_clazz, "SYSTEM_DEFAULT", liveliness_class_path); + break; + case RMW_QOS_POLICY_LIVELINESS_AUTOMATIC: + liveliness_value_fid = env->GetStaticFieldID( + liveliness_clazz, "AUTOMATIC", liveliness_class_path); + break; + case RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC: + liveliness_value_fid = env->GetStaticFieldID( + liveliness_clazz, "MANUAL_BY_TOPIC", liveliness_class_path); + break; + case RMW_QOS_POLICY_LIVELINESS_UNKNOWN: + liveliness_value_fid = env->GetStaticFieldID( + liveliness_clazz, "UNKNOWN", liveliness_class_path); + break; + default: + rcljava_throw_exception( + env, "java/lang/IllegalStateException", "unknown liveliness policy value"); + break; + } + RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); + jobject liveliness_value = env->GetStaticObjectField(liveliness_clazz, liveliness_value_fid); + env->SetObjectField(jqos, liveliness_fid, liveliness_value); + + env->SetBooleanField(jqos, avoid_ros_conventions_fid, qos.avoid_ros_namespace_conventions); +} + +JNIEXPORT void JNICALL +Java_org_ros2_rcljava_qos_QoSProfile_nativeFromRCL(JNIEnv * env, jobject jqos, jlong handle) +{ + auto * qos_profile = reinterpret_cast(handle); + if (!handle) { + rcljava_throw_exception( + env, "java/lang/IllegalArgumentException", "rmw qos profile handle is NULL"); + return; + } + qos_from_rcl(env, *qos_profile, jqos); +} + +JNIEXPORT jlong JNICALL +Java_org_ros2_rcljava_qos_QoSProfile_nativeGetHandleFromName( + JNIEnv * env, jclass, jstring jprofile_name) +{ + const rmw_qos_profile_t * qos = NULL; + const char * profile_name = env->GetStringUTFChars(jprofile_name, NULL); + if (strcmp(profile_name, "default") == 0) { + qos = &rmw_qos_profile_default; + } + if (strcmp(profile_name, "system_default") == 0) { + qos = &rmw_qos_profile_system_default; + } + if (strcmp(profile_name, "sensor_data") == 0) { + qos = &rmw_qos_profile_sensor_data; + } + if (strcmp(profile_name, "parameters") == 0) { + qos = &rmw_qos_profile_parameters; + } + if (strcmp(profile_name, "services") == 0) { + qos = &rmw_qos_profile_services_default; + } + if (strcmp(profile_name, "parameter_events") == 0) { + qos = &rmw_qos_profile_parameter_events; + } + + env->ReleaseStringUTFChars(jprofile_name, profile_name); + if (qos) { + return reinterpret_cast(qos); + } + rcljava_throw_exception( + env, "java/lang/IllegalArgumentException", "unexpected profile identifier"); + return 0; +} diff --git a/rcljava/src/main/java/org/ros2/rcljava/qos/QoSProfile.java b/rcljava/src/main/java/org/ros2/rcljava/qos/QoSProfile.java index 15b81712..73961faa 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/qos/QoSProfile.java +++ b/rcljava/src/main/java/org/ros2/rcljava/qos/QoSProfile.java @@ -17,37 +17,56 @@ import java.time.Duration; +import org.slf4j.Logger; +import org.slf4j.LoggerFactory; + +import org.ros2.rcljava.common.JNIUtils; import org.ros2.rcljava.qos.policies.Durability; import org.ros2.rcljava.qos.policies.History; import org.ros2.rcljava.qos.policies.Liveliness; import org.ros2.rcljava.qos.policies.QoSPolicy; import org.ros2.rcljava.qos.policies.Reliability; +/** + * Implementation of the ROS QoS profile abstraction. + * + * It works as a bridge with rmw_qos_profile_t. + * This class provides several static methods to instantiate the default profiles, + * getters for the different policies, and setters that allow method chaining. + * + * Examples: + * + * QoSProfile.keepLast(10); // default qos profile with depth 10 + * // keep all qos profile with best effort reliability and transient local durability + * QoSProfile.keepAll(). + * setReliability(Reliability.BEST_EFFORT).setDurability(Durability.TRANSIENT_LOCAL); + * QoSProfile.sensorData(); // get predefined sensor data qos profile + */ public class QoSProfile { // TODO(ivanpauno): Update all qos policies in a way that the objects are created from RCL, // to avoid depending on the enum values. - private History history; - - private int depth; - - private Reliability reliability; - - private Durability durability; - - private Duration deadline = Duration.ofSeconds(0, 0); - - private Duration lifespan = Duration.ofSeconds(0, 0); - - private Liveliness liveliness = Liveliness.SYSTEM_DEFAULT; - private Duration livelinessLeaseDuration = Duration.ofSeconds(0, 0); - - private boolean avoidROSNamespaceConventions; + /** + * Construct a keep last QoS profile with the specified depth. + * + * @param depth history depth. + * @return a new QoSProfile. + */ + public static QoSProfile keepLast(int depth) { + return defaultProfile().setDepth(depth); + } - public QoSProfile(int depth) { - this(History.KEEP_LAST, depth, Reliability.RELIABLE, Durability.VOLATILE, false); + /** + * Construct a keep all qos profile. + * + * @param depth history depth. + * @return a new QoSProfile. + */ + public static QoSProfile keepAll() { + return defaultProfile().setHistory(History.KEEP_ALL); } + // TODO(ivanpauno): Please deprecate me public QoSProfile(History history, int depth, Reliability reliability, Durability durability, boolean avoidROSNamespaceConventions) { this.history = history; @@ -57,131 +76,263 @@ public QoSProfile(History history, int depth, Reliability reliability, Durabilit this.avoidROSNamespaceConventions = avoidROSNamespaceConventions; } + /** + * @return history policy of the profile. + */ public final History getHistory() { return this.history; } + /** + * @param history history policy to be set. + * @return reference to `this` object, allowing method chaining. + */ public final QoSProfile setHistory(final History history) { this.history = history; return this; } + /** + * @return history depth of the profile. + */ public final int getDepth() { return this.depth; } + /** + * @param depth history depth to be set. + * @return reference to `this` object, allowing method chaining. + */ public final QoSProfile setDepth(final int depth) { this.depth = depth; return this; } + /** + * @return reliability policy of the profile. + */ public final Reliability getReliability() { return this.reliability; } + /** + * @param reliability reliability policy to be set. + * @return reference to `this` object, allowing method chaining. + */ public final QoSProfile setReliability(final Reliability reliability) { this.reliability = reliability; return this; } + /** + * @return durability policy of the profile. + */ public final Durability getDurability() { return this.durability; } + /** + * @param durability durability policy to be set. + * @return reference to `this` object, allowing method chaining. + */ public final QoSProfile setDurability(final Durability durability) { this.durability = durability; return this; } + /** + * @return deadline policy of the profile. + */ public final Duration getDeadline() { return this.deadline; } + /** + * @param deadline deadline policy to be set. See + * here. + * @return reference to `this` object, allowing method chaining. + */ public final QoSProfile setDeadline(final Duration deadline) { this.deadline = deadline; return this; } + /** + * @return lifespan policy of the profile. + */ public final Duration getLifespan() { return this.lifespan; } + /** + * @param lifespan lifespan policy to be set. See + * here. + * @return reference to `this` object, allowing method chaining. + */ public final QoSProfile setLifespan(final Duration lifespan) { this.lifespan = lifespan; return this; } + /** + * @return liveliness policy of the profile. + */ public final Liveliness getLiveliness() { return this.liveliness; } + /** + * @param liveliness liveliness policy to be set. See + * here. + * @return reference to `this` object, allowing method chaining. + */ public final QoSProfile setLiveliness(final Liveliness liveliness) { this.liveliness = liveliness; return this; } + /** + * @return liveliness lease duration of the profile. + */ public final Duration getLivelinessLeaseDuration() { return this.livelinessLeaseDuration; } + /** + * @param livelinessLeaseDuration liveliness lease duration to be set. See + * here. + * @return reference to `this` object, allowing method chaining. + */ public final QoSProfile setLivelinessLeaseDuration(final Duration livelinessLeaseDuration) { this.livelinessLeaseDuration = livelinessLeaseDuration; return this; } + /** + * @return `true` if ROS namespace conventions are ignored, else `false`. + */ public final boolean getAvoidROSNamespaceConventions() { return this.avoidROSNamespaceConventions; } + /** + * @param avoidROSConventions when `true`, ROS name mangling conventions will be ignored. + * @return reference to `this` object, allowing method chaining. + */ public final QoSProfile setAvoidROSNamespaceConventions(final boolean avoidROSConventions) { this.avoidROSNamespaceConventions = avoidROSConventions; return this; } - // TODO(ivanpauno): refactor all static default profiles methods, - // so that the return value is get from the rmw definition directly - // (leveraging a native function). + private static final Logger logger = LoggerFactory.getLogger(QoSProfile.class); + static { + try { + JNIUtils.loadImplementation(QoSProfile.class); + } catch (UnsatisfiedLinkError ule) { + logger.error("Native code library failed to load.\n" + ule); + System.exit(1); + } + } + + // TODO(ivanpauno): Deprecate and use a private alternative, to match rclcpp/rclpy. public static final QoSProfile defaultProfile() { - return new QoSProfile(10); + QoSProfile qos = new QoSProfile(); + qos.nativeFromRCL(qos.nativeGetHandleFromName("default")); + return qos; } + /** + * @return Construct a new instance of the predefined system default profile. + */ public static final QoSProfile systemDefault() { - return new QoSProfile( - History.SYSTEM_DEFAULT, QoSProfile.DEPTH_SYSTEM_DEFAULT, - Reliability.SYSTEM_DEFAULT, Durability.SYSTEM_DEFAULT, false); + QoSProfile qos = new QoSProfile(); + qos.nativeFromRCL(qos.nativeGetHandleFromName("system_default")); + return qos; } + /** + * @return Construct a new instance of the predefined sensor data profile. + */ public static final QoSProfile sensorData() { - return new QoSProfile( - History.KEEP_LAST, 5, Reliability.BEST_EFFORT, Durability.VOLATILE, false); + QoSProfile qos = new QoSProfile(); + qos.nativeFromRCL(qos.nativeGetHandleFromName("sensor_data")); + return qos; } + /** + * @return Construct a new instance of the predefined parameters default profile. + */ public static final QoSProfile parametersDefault() { - return new QoSProfile( - History.KEEP_LAST, 1000, Reliability.RELIABLE, Durability.VOLATILE, false); + QoSProfile qos = new QoSProfile(); + qos.nativeFromRCL(qos.nativeGetHandleFromName("parameters")); + return qos; } + /** + * @return Construct a new instance of the predefined services default profile. + */ public static final QoSProfile servicesDefault() { - return new QoSProfile( - History.KEEP_LAST, 10, Reliability.RELIABLE, Durability.VOLATILE, false); + QoSProfile qos = new QoSProfile(); + qos.nativeFromRCL(qos.nativeGetHandleFromName("services")); + return qos; } + /** + * @return Construct a new instance of the predefined parameter events default profile. + */ public static final QoSProfile parameterEventsDefault() { - return new QoSProfile( - History.KEEP_ALL, 1000, Reliability.RELIABLE, Durability.VOLATILE, false); + QoSProfile qos = new QoSProfile(); + qos.nativeFromRCL(qos.nativeGetHandleFromName("parameter_events")); + return qos; } + // TODO(ivanpauno): Deprecate. public static final int DEPTH_SYSTEM_DEFAULT = 0; + // TODO(ivanpauno): Deprecate. public static final QoSProfile SENSOR_DATA = sensorData(); + // TODO(ivanpauno): Deprecate. public static final QoSProfile PARAMETERS = parametersDefault(); + // TODO(ivanpauno): Deprecate. public static final QoSProfile DEFAULT = defaultProfile(); + // TODO(ivanpauno): Deprecate. public static final QoSProfile SERVICES_DEFAULT = servicesDefault(); + // TODO(ivanpauno): Deprecate. public static final QoSProfile PARAMETER_EVENTS = parameterEventsDefault(); + // TODO(ivanpauno): Deprecate. public static final QoSProfile SYSTEM_DEFAULT = systemDefault(); + + /** + * @internal + * Private default constructor. + * + * Used from native code or private methods. + * Typically combined with @{link QoSProfile#nativeFromRCL(handle)}. + */ + private QoSProfile() {} + + /** + * @internal + * Load from an rmw_qos_profile_t. + * + * @param handle A `rmw_qos_profile_t *`, from where the profile is loaded. + * The handle is only borrowed, and a reference to it is NOT kept. + */ + private final native void nativeFromRCL(long handle); + private final static native long nativeGetHandleFromName(String profileName); + + private History history; + private int depth; + private Reliability reliability; + private Durability durability; + private Duration deadline = Duration.ofSeconds(0, 0); + private Duration lifespan = Duration.ofSeconds(0, 0); + private Liveliness liveliness = Liveliness.SYSTEM_DEFAULT; + private Duration livelinessLeaseDuration = Duration.ofSeconds(0, 0); + private boolean avoidROSNamespaceConventions; } diff --git a/rcljava/src/main/java/org/ros2/rcljava/qos/policies/Durability.java b/rcljava/src/main/java/org/ros2/rcljava/qos/policies/Durability.java index 215602df..08a45329 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/qos/policies/Durability.java +++ b/rcljava/src/main/java/org/ros2/rcljava/qos/policies/Durability.java @@ -18,7 +18,8 @@ public enum Durability implements QoSPolicy { SYSTEM_DEFAULT(0), TRANSIENT_LOCAL(1), - VOLATILE(2); + VOLATILE(2), + UNKNOWN(3); private final int value; diff --git a/rcljava/src/main/java/org/ros2/rcljava/qos/policies/History.java b/rcljava/src/main/java/org/ros2/rcljava/qos/policies/History.java index 461d13d9..69d5b4c3 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/qos/policies/History.java +++ b/rcljava/src/main/java/org/ros2/rcljava/qos/policies/History.java @@ -18,7 +18,8 @@ public enum History implements QoSPolicy { SYSTEM_DEFAULT(0), KEEP_LAST(1), - KEEP_ALL(2); + KEEP_ALL(2), + UNKNOWN(3); private final int value; diff --git a/rcljava/src/main/java/org/ros2/rcljava/qos/policies/Liveliness.java b/rcljava/src/main/java/org/ros2/rcljava/qos/policies/Liveliness.java index 0a814e7f..3b25997f 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/qos/policies/Liveliness.java +++ b/rcljava/src/main/java/org/ros2/rcljava/qos/policies/Liveliness.java @@ -18,7 +18,8 @@ public enum Liveliness implements QoSPolicy { SYSTEM_DEFAULT(0), AUTOMATIC(1), - MANUAL_BY_TOPIC(3); + MANUAL_BY_TOPIC(3), + UNKNOWN(4); private final int value; diff --git a/rcljava/src/main/java/org/ros2/rcljava/qos/policies/Reliability.java b/rcljava/src/main/java/org/ros2/rcljava/qos/policies/Reliability.java index 3764d0bb..ea53f124 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/qos/policies/Reliability.java +++ b/rcljava/src/main/java/org/ros2/rcljava/qos/policies/Reliability.java @@ -18,7 +18,8 @@ public enum Reliability implements QoSPolicy { SYSTEM_DEFAULT(0), RELIABLE(1), - BEST_EFFORT(2); + BEST_EFFORT(2), + UNKNOWN(3); private final int value;