Skip to content

Commit c15a9f8

Browse files
authored
Fix cpp compiler warnings (#71)
Signed-off-by: Ivan Santiago Paunovic <ivanpauno@ekumenlabs.com>
1 parent 823156a commit c15a9f8

12 files changed

Lines changed: 31 additions & 53 deletions

rcljava/include/org_ros2_rcljava_action_ActionServerImpl.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -92,7 +92,7 @@ JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeTakeResultRequest(
9292
*/
9393
JNIEXPORT void
9494
JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeSendGoalResponse(
95-
JNIEnv *, jclass, jlong, jobject, jlong, jlong, jlong, jobject);
95+
JNIEnv *, jclass, jlong, jobject, jlong, jlong, jobject);
9696

9797
/*
9898
* Class: org_ros2_rcljava_action_ActionServerImpl
@@ -101,7 +101,7 @@ JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeSendGoalResponse(
101101
*/
102102
JNIEXPORT void
103103
JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeSendCancelResponse(
104-
JNIEnv *, jclass, jlong, jobject, jlong, jlong, jlong, jobject);
104+
JNIEnv *, jclass, jlong, jobject, jlong, jlong, jobject);
105105

106106
/*
107107
* Class: org_ros2_rcljava_action_ActionServerImpl
@@ -110,7 +110,7 @@ JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeSendCancelResponse(
110110
*/
111111
JNIEXPORT void
112112
JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeSendResultResponse(
113-
JNIEnv *, jclass, jlong, jobject, jlong, jlong, jlong, jobject);
113+
JNIEnv *, jclass, jlong, jobject, jlong, jlong, jobject);
114114

115115
/*
116116
* Class: org_ros2_rcljava_action_ActionServerImpl

rcljava/include/org_ros2_rcljava_client_ClientImpl.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ extern "C" {
2727
*/
2828
JNIEXPORT jlong
2929
JNICALL Java_org_ros2_rcljava_client_ClientImpl_nativeSendClientRequest(
30-
JNIEnv *, jclass, jlong, jlong, jlong, jlong, jobject);
30+
JNIEnv *, jclass, jlong, jlong, jlong, jobject);
3131

3232
/*
3333
* Class: org_ros2_rcljava_client_ClientImpl

rcljava/include/org_ros2_rcljava_executors_BaseExecutor.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -123,7 +123,7 @@ JNICALL Java_org_ros2_rcljava_executors_BaseExecutor_nativeTakeRequest(
123123
*/
124124
JNIEXPORT void
125125
JNICALL Java_org_ros2_rcljava_executors_BaseExecutor_nativeSendServiceResponse(
126-
JNIEnv *, jclass, jlong, jobject, jlong, jlong, jlong, jobject);
126+
JNIEnv *, jclass, jlong, jobject, jlong, jlong, jobject);
127127

128128
/*
129129
* Class: org_ros2_rcljava_executors_BaseExecutor

rcljava/src/main/cpp/org_ros2_rcljava_action_ActionServerImpl.cpp

Lines changed: 7 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -212,9 +212,8 @@ Java_org_ros2_rcljava_action_ActionServerImpl_nativeCreateActionServer(
212212
return nullptr; \
213213
} \
214214
if (RCL_RET_OK == ret) { \
215-
jobject jtaken_msg = convert_to_java(taken_msg, jrequest_msg); \
215+
convert_to_java(taken_msg, jrequest_msg); \
216216
destroy_ros_message(taken_msg); \
217-
assert(jtaken_msg != nullptr); \
218217
jobject jheader = rcljava::convert_rmw_request_id_to_java(env, &header); \
219218
return jheader; \
220219
} \
@@ -226,7 +225,6 @@ Java_org_ros2_rcljava_action_ActionServerImpl_nativeCreateActionServer(
226225
#define RCLJAVA_ACTION_SERVER_SEND_RESPONSE(Type) \
227226
do { \
228227
assert(jresponse_from_java_converter_handle != 0); \
229-
assert(jresponse_to_java_converter_handle != 0); \
230228
assert(jresponse_destructor_handle != 0); \
231229
rcl_action_server_t * action_server = reinterpret_cast<rcl_action_server_t *>( \
232230
action_server_handle); \
@@ -275,26 +273,26 @@ JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeTakeResultRequest(
275273
JNIEXPORT void
276274
JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeSendGoalResponse(
277275
JNIEnv * env, jclass, jlong action_server_handle, jobject jrequest_id,
278-
jlong jresponse_from_java_converter_handle, jlong jresponse_to_java_converter_handle,
279-
jlong jresponse_destructor_handle, jobject jresponse_msg)
276+
jlong jresponse_from_java_converter_handle, jlong jresponse_destructor_handle,
277+
jobject jresponse_msg)
280278
{
281279
RCLJAVA_ACTION_SERVER_SEND_RESPONSE(goal);
282280
}
283281

284282
JNIEXPORT void
285283
JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeSendCancelResponse(
286284
JNIEnv * env, jclass, jlong action_server_handle, jobject jrequest_id,
287-
jlong jresponse_from_java_converter_handle, jlong jresponse_to_java_converter_handle,
288-
jlong jresponse_destructor_handle, jobject jresponse_msg)
285+
jlong jresponse_from_java_converter_handle, jlong jresponse_destructor_handle,
286+
jobject jresponse_msg)
289287
{
290288
RCLJAVA_ACTION_SERVER_SEND_RESPONSE(cancel);
291289
}
292290

293291
JNIEXPORT void
294292
JNICALL Java_org_ros2_rcljava_action_ActionServerImpl_nativeSendResultResponse(
295293
JNIEnv * env, jclass, jlong action_server_handle, jobject jrequest_id,
296-
jlong jresponse_from_java_converter_handle, jlong jresponse_to_java_converter_handle,
297-
jlong jresponse_destructor_handle, jobject jresponse_msg)
294+
jlong jresponse_from_java_converter_handle, jlong jresponse_destructor_handle,
295+
jobject jresponse_msg)
298296
{
299297
RCLJAVA_ACTION_SERVER_SEND_RESPONSE(result);
300298
}

rcljava/src/main/cpp/org_ros2_rcljava_client_ClientImpl.cpp

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -36,13 +36,11 @@ using rcljava_common::signatures::destroy_ros_message_signature;
3636

3737
JNIEXPORT jlong JNICALL
3838
Java_org_ros2_rcljava_client_ClientImpl_nativeSendClientRequest(
39-
JNIEnv * env, jclass, jlong client_handle,
40-
jlong jrequest_from_java_converter_handle, jlong jrequest_to_java_converter_handle,
39+
JNIEnv * env, jclass, jlong client_handle, jlong jrequest_from_java_converter_handle,
4140
jlong jrequest_destructor_handle, jobject jrequest_msg)
4241
{
4342
assert(client_handle != 0);
4443
assert(jrequest_from_java_converter_handle != 0);
45-
assert(jrequest_to_java_converter_handle != 0);
4644
assert(jrequest_destructor_handle != 0);
4745
assert(jrequest_msg != nullptr);
4846

rcljava/src/main/cpp/org_ros2_rcljava_detail_QosIncompatibleStatus.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -75,7 +75,7 @@ Java_org_ros2_rcljava_detail_QosIncompatibleStatus_nativeFromRCLEvent(
7575
return;
7676
}
7777

78-
jfieldID enum_value_fid;
78+
jfieldID enum_value_fid = nullptr;
7979
switch (p->last_policy_kind) {
8080
case RMW_QOS_POLICY_INVALID:
8181
enum_value_fid = env->GetStaticFieldID(qos_kind_clazz, "INVALID", enum_class_path);

rcljava/src/main/cpp/org_ros2_rcljava_executors_BaseExecutor.cpp

Lines changed: 4 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -165,9 +165,7 @@ Java_org_ros2_rcljava_executors_BaseExecutor_nativeTake(
165165
reinterpret_cast<convert_to_java_signature>(jto_java_converter);
166166

167167
jobject jtaken_msg = convert_to_java(taken_msg, nullptr);
168-
169168
destroy_ros_message(taken_msg);
170-
171169
return jtaken_msg;
172170
}
173171

@@ -291,12 +289,9 @@ Java_org_ros2_rcljava_executors_BaseExecutor_nativeTakeRequest(
291289
}
292290

293291
if (ret != RCL_RET_SERVICE_TAKE_FAILED) {
294-
jobject jtaken_msg = convert_to_java(taken_msg, jrequest_msg);
295-
292+
convert_to_java(taken_msg, jrequest_msg);
296293
destroy_ros_message(taken_msg);
297294

298-
assert(jtaken_msg != nullptr);
299-
300295
jobject jheader = rcljava::convert_rmw_request_id_to_java(env, &header);
301296
return jheader;
302297
}
@@ -309,12 +304,11 @@ Java_org_ros2_rcljava_executors_BaseExecutor_nativeTakeRequest(
309304
JNIEXPORT void JNICALL
310305
Java_org_ros2_rcljava_executors_BaseExecutor_nativeSendServiceResponse(
311306
JNIEnv * env, jclass, jlong service_handle, jobject jrequest_id,
312-
jlong jresponse_from_java_converter_handle, jlong jresponse_to_java_converter_handle,
313-
jlong jresponse_destructor_handle, jobject jresponse_msg)
307+
jlong jresponse_from_java_converter_handle, jlong jresponse_destructor_handle,
308+
jobject jresponse_msg)
314309
{
315310
assert(service_handle != 0);
316311
assert(jresponse_from_java_converter_handle != 0);
317-
assert(jresponse_to_java_converter_handle != 0);
318312
assert(jresponse_destructor_handle != 0);
319313
assert(jresponse_msg != nullptr);
320314

@@ -381,12 +375,9 @@ Java_org_ros2_rcljava_executors_BaseExecutor_nativeTakeResponse(
381375
}
382376

383377
if (ret != RCL_RET_CLIENT_TAKE_FAILED) {
384-
jobject jtaken_msg = convert_to_java(taken_msg, jresponse_msg);
385-
378+
convert_to_java(taken_msg, jresponse_msg);
386379
destroy_ros_message(taken_msg);
387380

388-
assert(jtaken_msg != nullptr);
389-
390381
jobject jheader = rcljava::convert_rmw_request_id_to_java(env, &header);
391382
return jheader;
392383
}

rcljava/src/main/cpp/org_ros2_rcljava_graph_EndpointInfo.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,7 @@ Java_org_ros2_rcljava_graph_EndpointInfo_nativeFromRCL(JNIEnv * env, jobject sel
5959
jstring jtopic_type = env->NewStringUTF(p->topic_type);
6060
RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env);
6161
env->SetObjectField(self, topic_type_fid, jtopic_type);
62-
jfieldID enum_value_fid;
62+
jfieldID enum_value_fid = nullptr;
6363
switch (p->endpoint_type) {
6464
case RMW_ENDPOINT_INVALID:
6565
enum_value_fid = env->GetStaticFieldID(

rcljava/src/main/cpp/org_ros2_rcljava_qos_QoSProfile.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -78,7 +78,7 @@ qos_from_rcl(JNIEnv * env, const rmw_qos_profile_t & qos, jobject jqos)
7878
RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env);
7979

8080
jclass history_clazz = env->FindClass("org/ros2/rcljava/qos/policies/History");
81-
jfieldID history_value_fid;
81+
jfieldID history_value_fid = nullptr;
8282
switch (qos.history) {
8383
case RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT:
8484
history_value_fid = env->GetStaticFieldID(
@@ -108,7 +108,7 @@ qos_from_rcl(JNIEnv * env, const rmw_qos_profile_t & qos, jobject jqos)
108108
env->SetIntField(jqos, depth_fid, qos.depth);
109109

110110
jclass reliability_clazz = env->FindClass("org/ros2/rcljava/qos/policies/Reliability");
111-
jfieldID reliability_value_fid;
111+
jfieldID reliability_value_fid = nullptr;
112112
switch (qos.reliability) {
113113
case RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT:
114114
reliability_value_fid = env->GetStaticFieldID(
@@ -136,7 +136,7 @@ qos_from_rcl(JNIEnv * env, const rmw_qos_profile_t & qos, jobject jqos)
136136
env->SetObjectField(jqos, reliability_fid, reliability_value);
137137

138138
jclass durability_clazz = env->FindClass("org/ros2/rcljava/qos/policies/Durability");
139-
jfieldID durability_value_fid;
139+
jfieldID durability_value_fid = nullptr;
140140
switch (qos.durability) {
141141
case RMW_QOS_POLICY_DURABILITY_SYSTEM_DEFAULT:
142142
durability_value_fid = env->GetStaticFieldID(
@@ -173,7 +173,7 @@ qos_from_rcl(JNIEnv * env, const rmw_qos_profile_t & qos, jobject jqos)
173173
RCLJAVA_COMMON_CHECK_FOR_EXCEPTION(env);
174174

175175
jclass liveliness_clazz = env->FindClass("org/ros2/rcljava/qos/policies/Liveliness");
176-
jfieldID liveliness_value_fid;
176+
jfieldID liveliness_value_fid = nullptr;
177177
switch (qos.liveliness) {
178178
case RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT:
179179
liveliness_value_fid = env->GetStaticFieldID(

rcljava/src/main/java/org/ros2/rcljava/action/ActionServerImpl.java

Lines changed: 2 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -415,14 +415,12 @@ private void sendResultResponse(
415415
ResultResponseDefinition<T> resultResponse)
416416
{
417417
long resultFromJavaConverterHandle = resultResponse.getFromJavaConverterInstance();
418-
long resultToJavaConverterHandle = resultResponse.getToJavaConverterInstance();
419418
long resultDestructorHandle = resultResponse.getDestructorInstance();
420419

421420
nativeSendResultResponse(
422421
this.handle,
423422
rmwRequestId,
424423
resultFromJavaConverterHandle,
425-
resultToJavaConverterHandle,
426424
resultDestructorHandle,
427425
resultResponse);
428426
}
@@ -452,23 +450,20 @@ private static native void nativeSendGoalResponse(
452450
long actionServerHandle,
453451
RMWRequestId header,
454452
long responseFromJavaConverterHandle,
455-
long responseToJavaConverterHandle,
456453
long responseDestructorHandle,
457454
MessageDefinition responseMessage);
458455

459456
private static native void nativeSendCancelResponse(
460457
long actionServerHandle,
461458
RMWRequestId header,
462459
long responseFromJavaConverterHandle,
463-
long responseToJavaConverterHandle,
464460
long responseDestructorHandle,
465461
MessageDefinition responseMessage);
466462

467463
private static native void nativeSendResultResponse(
468464
long actionServerHandle,
469465
RMWRequestId header,
470466
long responseFromJavaConverterHandle,
471-
long responseToJavaConverterHandle,
472467
long responseDestructorHandle,
473468
MessageDefinition responseMessage);
474469

@@ -600,7 +595,6 @@ public void execute() {
600595
long requestToJavaConverterHandle = requestMessage.getToJavaConverterInstance();
601596
long requestDestructorHandle = requestMessage.getDestructorInstance();
602597
long responseFromJavaConverterHandle = responseMessage.getFromJavaConverterInstance();
603-
long responseToJavaConverterHandle = responseMessage.getToJavaConverterInstance();
604598
long responseDestructorHandle = responseMessage.getDestructorInstance();
605599

606600
RMWRequestId rmwRequestId =
@@ -612,8 +606,7 @@ public void execute() {
612606
ActionServerGoalHandle<T> goalHandle = this.executeGoalRequest(
613607
rmwRequestId, requestMessage, responseMessage);
614608
nativeSendGoalResponse(
615-
this.handle, rmwRequestId,
616-
responseFromJavaConverterHandle, responseToJavaConverterHandle,
609+
this.handle, rmwRequestId, responseFromJavaConverterHandle,
617610
responseDestructorHandle, responseMessage);
618611
}
619612
}
@@ -646,8 +639,7 @@ public void execute() {
646639
responseMessage = executeCancelRequest(responseMessage);
647640
nativeSendCancelResponse(
648641
this.handle, rmwRequestId,
649-
responseFromJavaConverterHandle, responseToJavaConverterHandle,
650-
responseDestructorHandle, responseMessage);
642+
responseFromJavaConverterHandle, responseDestructorHandle, responseMessage);
651643
}
652644
}
653645

0 commit comments

Comments
 (0)