From 562dd10731bc2552f5a94c38fe0c8268f16c540e Mon Sep 17 00:00:00 2001 From: Ivan Santiago Paunovic Date: Fri, 14 May 2021 09:43:22 -0300 Subject: [PATCH] Fix cpp compiler warnings Signed-off-by: Ivan Santiago Paunovic --- .../org_ros2_rcljava_action_ActionServerImpl.h | 6 +++--- .../org_ros2_rcljava_client_ClientImpl.h | 2 +- .../org_ros2_rcljava_executors_BaseExecutor.h | 2 +- ...org_ros2_rcljava_action_ActionServerImpl.cpp | 16 +++++++--------- .../cpp/org_ros2_rcljava_client_ClientImpl.cpp | 4 +--- ...os2_rcljava_detail_QosIncompatibleStatus.cpp | 2 +- .../org_ros2_rcljava_executors_BaseExecutor.cpp | 17 ++++------------- .../cpp/org_ros2_rcljava_graph_EndpointInfo.cpp | 2 +- .../cpp/org_ros2_rcljava_qos_QoSProfile.cpp | 8 ++++---- .../ros2/rcljava/action/ActionServerImpl.java | 12 ++---------- .../org/ros2/rcljava/client/ClientImpl.java | 6 +++--- .../ros2/rcljava/executors/BaseExecutor.java | 7 +++---- 12 files changed, 31 insertions(+), 53 deletions(-) diff --git a/rcljava/include/org_ros2_rcljava_action_ActionServerImpl.h b/rcljava/include/org_ros2_rcljava_action_ActionServerImpl.h index fe3097bb..ae42dd5e 100644 --- a/rcljava/include/org_ros2_rcljava_action_ActionServerImpl.h +++ b/rcljava/include/org_ros2_rcljava_action_ActionServerImpl.h @@ -92,7 +92,7 @@ JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeTakeResultRequest( */ JNIEXPORT void JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeSendGoalResponse( - JNIEnv *, jclass, jlong, jobject, jlong, jlong, jlong, jobject); + JNIEnv *, jclass, jlong, jobject, jlong, jlong, jobject); /* * Class: org_ros2_rcljava_action_ActionServerImpl @@ -101,7 +101,7 @@ JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeSendGoalResponse( */ JNIEXPORT void JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeSendCancelResponse( - JNIEnv *, jclass, jlong, jobject, jlong, jlong, jlong, jobject); + JNIEnv *, jclass, jlong, jobject, jlong, jlong, jobject); /* * Class: org_ros2_rcljava_action_ActionServerImpl @@ -110,7 +110,7 @@ JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeSendCancelResponse( */ JNIEXPORT void JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeSendResultResponse( - JNIEnv *, jclass, jlong, jobject, jlong, jlong, jlong, jobject); + JNIEnv *, jclass, jlong, jobject, jlong, jlong, jobject); /* * Class: org_ros2_rcljava_action_ActionServerImpl diff --git a/rcljava/include/org_ros2_rcljava_client_ClientImpl.h b/rcljava/include/org_ros2_rcljava_client_ClientImpl.h index 9a3b20e5..56bc2082 100644 --- a/rcljava/include/org_ros2_rcljava_client_ClientImpl.h +++ b/rcljava/include/org_ros2_rcljava_client_ClientImpl.h @@ -27,7 +27,7 @@ extern "C" { */ JNIEXPORT jlong JNICALL Java_org_ros2_rcljava_client_ClientImpl_nativeSendClientRequest( - JNIEnv *, jclass, jlong, jlong, jlong, jlong, jobject); + JNIEnv *, jclass, jlong, jlong, jlong, jobject); /* * Class: org_ros2_rcljava_client_ClientImpl diff --git a/rcljava/include/org_ros2_rcljava_executors_BaseExecutor.h b/rcljava/include/org_ros2_rcljava_executors_BaseExecutor.h index e96b88c8..08b95c08 100644 --- a/rcljava/include/org_ros2_rcljava_executors_BaseExecutor.h +++ b/rcljava/include/org_ros2_rcljava_executors_BaseExecutor.h @@ -123,7 +123,7 @@ JNICALL Java_org_ros2_rcljava_executors_BaseExecutor_nativeTakeRequest( */ JNIEXPORT void JNICALL Java_org_ros2_rcljava_executors_BaseExecutor_nativeSendServiceResponse( - JNIEnv *, jclass, jlong, jobject, jlong, jlong, jlong, jobject); + JNIEnv *, jclass, jlong, jobject, jlong, jlong, jobject); /* * Class: org_ros2_rcljava_executors_BaseExecutor diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_action_ActionServerImpl.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_action_ActionServerImpl.cpp index 47a89440..7ed6d699 100644 --- a/rcljava/src/main/cpp/org_ros2_rcljava_action_ActionServerImpl.cpp +++ b/rcljava/src/main/cpp/org_ros2_rcljava_action_ActionServerImpl.cpp @@ -212,9 +212,8 @@ Java_org_ros2_rcljava_action_ActionServerImpl_nativeCreateActionServer( return nullptr; \ } \ if (RCL_RET_OK == ret) { \ - jobject jtaken_msg = convert_to_java(taken_msg, jrequest_msg); \ + convert_to_java(taken_msg, jrequest_msg); \ destroy_ros_message(taken_msg); \ - assert(jtaken_msg != nullptr); \ jobject jheader = rcljava::convert_rmw_request_id_to_java(env, &header); \ return jheader; \ } \ @@ -226,7 +225,6 @@ Java_org_ros2_rcljava_action_ActionServerImpl_nativeCreateActionServer( #define RCLJAVA_ACTION_SERVER_SEND_RESPONSE(Type) \ do { \ assert(jresponse_from_java_converter_handle != 0); \ - assert(jresponse_to_java_converter_handle != 0); \ assert(jresponse_destructor_handle != 0); \ rcl_action_server_t * action_server = reinterpret_cast( \ action_server_handle); \ @@ -275,8 +273,8 @@ JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeTakeResultRequest( JNIEXPORT void JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeSendGoalResponse( JNIEnv * env, jclass, jlong action_server_handle, jobject jrequest_id, - jlong jresponse_from_java_converter_handle, jlong jresponse_to_java_converter_handle, - jlong jresponse_destructor_handle, jobject jresponse_msg) + jlong jresponse_from_java_converter_handle, jlong jresponse_destructor_handle, + jobject jresponse_msg) { RCLJAVA_ACTION_SERVER_SEND_RESPONSE(goal); } @@ -284,8 +282,8 @@ JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeSendGoalResponse( JNIEXPORT void JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeSendCancelResponse( JNIEnv * env, jclass, jlong action_server_handle, jobject jrequest_id, - jlong jresponse_from_java_converter_handle, jlong jresponse_to_java_converter_handle, - jlong jresponse_destructor_handle, jobject jresponse_msg) + jlong jresponse_from_java_converter_handle, jlong jresponse_destructor_handle, + jobject jresponse_msg) { RCLJAVA_ACTION_SERVER_SEND_RESPONSE(cancel); } @@ -293,8 +291,8 @@ JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeSendCancelResponse( JNIEXPORT void JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeSendResultResponse( JNIEnv * env, jclass, jlong action_server_handle, jobject jrequest_id, - jlong jresponse_from_java_converter_handle, jlong jresponse_to_java_converter_handle, - jlong jresponse_destructor_handle, jobject jresponse_msg) + jlong jresponse_from_java_converter_handle, jlong jresponse_destructor_handle, + jobject jresponse_msg) { RCLJAVA_ACTION_SERVER_SEND_RESPONSE(result); } diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_client_ClientImpl.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_client_ClientImpl.cpp index 842b7d99..b4fe8e09 100644 --- a/rcljava/src/main/cpp/org_ros2_rcljava_client_ClientImpl.cpp +++ b/rcljava/src/main/cpp/org_ros2_rcljava_client_ClientImpl.cpp @@ -36,13 +36,11 @@ using rcljava_common::signatures::destroy_ros_message_signature; JNIEXPORT jlong JNICALL Java_org_ros2_rcljava_client_ClientImpl_nativeSendClientRequest( - JNIEnv * env, jclass, jlong client_handle, - jlong jrequest_from_java_converter_handle, jlong jrequest_to_java_converter_handle, + JNIEnv * env, jclass, jlong client_handle, jlong jrequest_from_java_converter_handle, jlong jrequest_destructor_handle, jobject jrequest_msg) { assert(client_handle != 0); assert(jrequest_from_java_converter_handle != 0); - assert(jrequest_to_java_converter_handle != 0); assert(jrequest_destructor_handle != 0); assert(jrequest_msg != nullptr); 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 149b90c6..a09d7867 100644 --- a/rcljava/src/main/cpp/org_ros2_rcljava_detail_QosIncompatibleStatus.cpp +++ b/rcljava/src/main/cpp/org_ros2_rcljava_detail_QosIncompatibleStatus.cpp @@ -75,7 +75,7 @@ Java_org_ros2_rcljava_detail_QosIncompatibleStatus_nativeFromRCLEvent( return; } - jfieldID enum_value_fid; + jfieldID enum_value_fid = nullptr; switch (p->last_policy_kind) { case RMW_QOS_POLICY_INVALID: enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "INVALID", enum_class_path); 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 2a784dab..7cbdb6cc 100644 --- a/rcljava/src/main/cpp/org_ros2_rcljava_executors_BaseExecutor.cpp +++ b/rcljava/src/main/cpp/org_ros2_rcljava_executors_BaseExecutor.cpp @@ -165,9 +165,7 @@ Java_org_ros2_rcljava_executors_BaseExecutor_nativeTake( reinterpret_cast(jto_java_converter); jobject jtaken_msg = convert_to_java(taken_msg, nullptr); - destroy_ros_message(taken_msg); - return jtaken_msg; } @@ -291,12 +289,9 @@ Java_org_ros2_rcljava_executors_BaseExecutor_nativeTakeRequest( } if (ret != RCL_RET_SERVICE_TAKE_FAILED) { - jobject jtaken_msg = convert_to_java(taken_msg, jrequest_msg); - + convert_to_java(taken_msg, jrequest_msg); destroy_ros_message(taken_msg); - assert(jtaken_msg != nullptr); - jobject jheader = rcljava::convert_rmw_request_id_to_java(env, &header); return jheader; } @@ -309,12 +304,11 @@ Java_org_ros2_rcljava_executors_BaseExecutor_nativeTakeRequest( JNIEXPORT void JNICALL Java_org_ros2_rcljava_executors_BaseExecutor_nativeSendServiceResponse( JNIEnv * env, jclass, jlong service_handle, jobject jrequest_id, - jlong jresponse_from_java_converter_handle, jlong jresponse_to_java_converter_handle, - jlong jresponse_destructor_handle, jobject jresponse_msg) + jlong jresponse_from_java_converter_handle, jlong jresponse_destructor_handle, + jobject jresponse_msg) { assert(service_handle != 0); assert(jresponse_from_java_converter_handle != 0); - assert(jresponse_to_java_converter_handle != 0); assert(jresponse_destructor_handle != 0); assert(jresponse_msg != nullptr); @@ -381,12 +375,9 @@ Java_org_ros2_rcljava_executors_BaseExecutor_nativeTakeResponse( } if (ret != RCL_RET_CLIENT_TAKE_FAILED) { - jobject jtaken_msg = convert_to_java(taken_msg, jresponse_msg); - + convert_to_java(taken_msg, jresponse_msg); destroy_ros_message(taken_msg); - assert(jtaken_msg != nullptr); - jobject jheader = rcljava::convert_rmw_request_id_to_java(env, &header); return jheader; } diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_graph_EndpointInfo.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_graph_EndpointInfo.cpp index 1e7763d4..db0f48dc 100644 --- a/rcljava/src/main/cpp/org_ros2_rcljava_graph_EndpointInfo.cpp +++ b/rcljava/src/main/cpp/org_ros2_rcljava_graph_EndpointInfo.cpp @@ -59,7 +59,7 @@ Java_org_ros2_rcljava_graph_EndpointInfo_nativeFromRCL(JNIEnv * env, jobject sel jstring jtopic_type = env->NewStringUTF(p->topic_type); RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); env->SetObjectField(self, topic_type_fid, jtopic_type); - jfieldID enum_value_fid; + jfieldID enum_value_fid = nullptr; switch (p->endpoint_type) { case RMW_ENDPOINT_INVALID: enum_value_fid = env->GetStaticFieldID( diff --git a/rcljava/src/main/cpp/org_ros2_rcljava_qos_QoSProfile.cpp b/rcljava/src/main/cpp/org_ros2_rcljava_qos_QoSProfile.cpp index 16239f7b..e082dca5 100644 --- a/rcljava/src/main/cpp/org_ros2_rcljava_qos_QoSProfile.cpp +++ b/rcljava/src/main/cpp/org_ros2_rcljava_qos_QoSProfile.cpp @@ -78,7 +78,7 @@ qos_from_rcl(JNIEnv * env, const rmw_qos_profile_t & qos, jobject jqos) RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); jclass history_clazz = env->FindClass("org/ros2/rcljava/qos/policies/History"); - jfieldID history_value_fid; + jfieldID history_value_fid = nullptr; switch (qos.history) { case RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT: history_value_fid = env->GetStaticFieldID( @@ -108,7 +108,7 @@ qos_from_rcl(JNIEnv * env, const rmw_qos_profile_t & qos, jobject jqos) env->SetIntField(jqos, depth_fid, qos.depth); jclass reliability_clazz = env->FindClass("org/ros2/rcljava/qos/policies/Reliability"); - jfieldID reliability_value_fid; + jfieldID reliability_value_fid = nullptr; switch (qos.reliability) { case RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT: reliability_value_fid = env->GetStaticFieldID( @@ -136,7 +136,7 @@ qos_from_rcl(JNIEnv * env, const rmw_qos_profile_t & qos, jobject jqos) env->SetObjectField(jqos, reliability_fid, reliability_value); jclass durability_clazz = env->FindClass("org/ros2/rcljava/qos/policies/Durability"); - jfieldID durability_value_fid; + jfieldID durability_value_fid = nullptr; switch (qos.durability) { case RMW_QOS_POLICY_DURABILITY_SYSTEM_DEFAULT: durability_value_fid = env->GetStaticFieldID( @@ -173,7 +173,7 @@ qos_from_rcl(JNIEnv * env, const rmw_qos_profile_t & qos, jobject jqos) RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env); jclass liveliness_clazz = env->FindClass("org/ros2/rcljava/qos/policies/Liveliness"); - jfieldID liveliness_value_fid; + jfieldID liveliness_value_fid = nullptr; switch (qos.liveliness) { case RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT: liveliness_value_fid = env->GetStaticFieldID( diff --git a/rcljava/src/main/java/org/ros2/rcljava/action/ActionServerImpl.java b/rcljava/src/main/java/org/ros2/rcljava/action/ActionServerImpl.java index 0a2aee98..31369ede 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/action/ActionServerImpl.java +++ b/rcljava/src/main/java/org/ros2/rcljava/action/ActionServerImpl.java @@ -415,14 +415,12 @@ private void sendResultResponse( ResultResponseDefinition resultResponse) { long resultFromJavaConverterHandle = resultResponse.getFromJavaConverterInstance(); - long resultToJavaConverterHandle = resultResponse.getToJavaConverterInstance(); long resultDestructorHandle = resultResponse.getDestructorInstance(); nativeSendResultResponse( this.handle, rmwRequestId, resultFromJavaConverterHandle, - resultToJavaConverterHandle, resultDestructorHandle, resultResponse); } @@ -452,7 +450,6 @@ private static native void nativeSendGoalResponse( long actionServerHandle, RMWRequestId header, long responseFromJavaConverterHandle, - long responseToJavaConverterHandle, long responseDestructorHandle, MessageDefinition responseMessage); @@ -460,7 +457,6 @@ private static native void nativeSendCancelResponse( long actionServerHandle, RMWRequestId header, long responseFromJavaConverterHandle, - long responseToJavaConverterHandle, long responseDestructorHandle, MessageDefinition responseMessage); @@ -468,7 +464,6 @@ private static native void nativeSendResultResponse( long actionServerHandle, RMWRequestId header, long responseFromJavaConverterHandle, - long responseToJavaConverterHandle, long responseDestructorHandle, MessageDefinition responseMessage); @@ -600,7 +595,6 @@ public void execute() { long requestToJavaConverterHandle = requestMessage.getToJavaConverterInstance(); long requestDestructorHandle = requestMessage.getDestructorInstance(); long responseFromJavaConverterHandle = responseMessage.getFromJavaConverterInstance(); - long responseToJavaConverterHandle = responseMessage.getToJavaConverterInstance(); long responseDestructorHandle = responseMessage.getDestructorInstance(); RMWRequestId rmwRequestId = @@ -612,8 +606,7 @@ public void execute() { ActionServerGoalHandle goalHandle = this.executeGoalRequest( rmwRequestId, requestMessage, responseMessage); nativeSendGoalResponse( - this.handle, rmwRequestId, - responseFromJavaConverterHandle, responseToJavaConverterHandle, + this.handle, rmwRequestId, responseFromJavaConverterHandle, responseDestructorHandle, responseMessage); } } @@ -646,8 +639,7 @@ public void execute() { responseMessage = executeCancelRequest(responseMessage); nativeSendCancelResponse( this.handle, rmwRequestId, - responseFromJavaConverterHandle, responseToJavaConverterHandle, - responseDestructorHandle, responseMessage); + responseFromJavaConverterHandle, responseDestructorHandle, responseMessage); } } diff --git a/rcljava/src/main/java/org/ros2/rcljava/client/ClientImpl.java b/rcljava/src/main/java/org/ros2/rcljava/client/ClientImpl.java index c5189b49..3c3187e3 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/client/ClientImpl.java +++ b/rcljava/src/main/java/org/ros2/rcljava/client/ClientImpl.java @@ -81,7 +81,7 @@ public void accept(Future input) {} synchronized (pendingRequests) { long sequenceNumber = nativeSendClientRequest( handle, request.getFromJavaConverterInstance(), - request.getToJavaConverterInstance(), request.getDestructorInstance(), request); + request.getDestructorInstance(), request); RCLFuture future = new RCLFuture(this.nodeReference); Map.Entry entry = @@ -109,8 +109,8 @@ public final void handleResponse( } private static native long nativeSendClientRequest( - long handle, long requestFromJavaConverterHandle, long requestToJavaConverterHandle, - long requestDestructorHandle, MessageDefinition requestMessage); + long handle, long requestFromJavaConverterHandle, long requestDestructorHandle, + MessageDefinition requestMessage); public final Class getRequestType() { return this.requestType; 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 9ad11e52..f6ed8c02 100644 --- a/rcljava/src/main/java/org/ros2/rcljava/executors/BaseExecutor.java +++ b/rcljava/src/main/java/org/ros2/rcljava/executors/BaseExecutor.java @@ -127,8 +127,7 @@ protected void executeAnyExecutable(AnyExecutable anyExecutable) { if (rmwRequestId != null) { anyExecutable.service.executeCallback(rmwRequestId, requestMessage, responseMessage); nativeSendServiceResponse(anyExecutable.service.getHandle(), rmwRequestId, - responseFromJavaConverterHandle, responseToJavaConverterHandle, - responseDestructorHandle, responseMessage); + responseFromJavaConverterHandle, responseDestructorHandle, responseMessage); } } serviceHandles.remove(anyExecutable.service.getHandle()); @@ -515,8 +514,8 @@ private static native RMWRequestId nativeTakeRequest(long serviceHandle, long requestFromJavaConverterHandle, long requestToJavaConverterHandle, long requestDestructorHandle, MessageDefinition requestMessage); - private static native void nativeSendServiceResponse(long serviceHandle, RMWRequestId header, - long responseFromJavaConverterHandle, long responseToJavaConverterHandle, + private static native void nativeSendServiceResponse( + long serviceHandle, RMWRequestId header, long responseFromJavaConverterHandle, long responseDestructorHandle, MessageDefinition responseMessage); private static native RMWRequestId nativeTakeResponse(long clientHandle,