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
6 changes: 3 additions & 3 deletions rcljava/include/org_ros2_rcljava_action_ActionServerImpl.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand All @@ -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
Expand Down
2 changes: 1 addition & 1 deletion rcljava/include/org_ros2_rcljava_client_ClientImpl.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion rcljava/include/org_ros2_rcljava_executors_BaseExecutor.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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; \
} \
Expand All @@ -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<rcl_action_server_t *>( \
action_server_handle); \
Expand Down Expand Up @@ -275,26 +273,26 @@ 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);
}

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);
}

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);
}
Expand Down
4 changes: 1 addition & 3 deletions rcljava/src/main/cpp/org_ros2_rcljava_client_ClientImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
17 changes: 4 additions & 13 deletions rcljava/src/main/cpp/org_ros2_rcljava_executors_BaseExecutor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,9 +165,7 @@ Java_org_ros2_rcljava_executors_BaseExecutor_nativeTake(
reinterpret_cast<convert_to_java_signature>(jto_java_converter);

jobject jtaken_msg = convert_to_java(taken_msg, nullptr);

destroy_ros_message(taken_msg);

return jtaken_msg;
}

Expand Down Expand Up @@ -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;
}
Expand All @@ -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);

Expand Down Expand Up @@ -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;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down
8 changes: 4 additions & 4 deletions rcljava/src/main/cpp/org_ros2_rcljava_qos_QoSProfile.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down Expand Up @@ -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(
Expand Down Expand Up @@ -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(
Expand Down Expand Up @@ -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(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -415,14 +415,12 @@ private void sendResultResponse(
ResultResponseDefinition<T> resultResponse)
{
long resultFromJavaConverterHandle = resultResponse.getFromJavaConverterInstance();
long resultToJavaConverterHandle = resultResponse.getToJavaConverterInstance();
long resultDestructorHandle = resultResponse.getDestructorInstance();

nativeSendResultResponse(
this.handle,
rmwRequestId,
resultFromJavaConverterHandle,
resultToJavaConverterHandle,
resultDestructorHandle,
resultResponse);
}
Expand Down Expand Up @@ -452,23 +450,20 @@ private static native void nativeSendGoalResponse(
long actionServerHandle,
RMWRequestId header,
long responseFromJavaConverterHandle,
long responseToJavaConverterHandle,
long responseDestructorHandle,
MessageDefinition responseMessage);

private static native void nativeSendCancelResponse(
long actionServerHandle,
RMWRequestId header,
long responseFromJavaConverterHandle,
long responseToJavaConverterHandle,
long responseDestructorHandle,
MessageDefinition responseMessage);

private static native void nativeSendResultResponse(
long actionServerHandle,
RMWRequestId header,
long responseFromJavaConverterHandle,
long responseToJavaConverterHandle,
long responseDestructorHandle,
MessageDefinition responseMessage);

Expand Down Expand Up @@ -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 =
Expand All @@ -612,8 +606,7 @@ public void execute() {
ActionServerGoalHandle<T> goalHandle = this.executeGoalRequest(
rmwRequestId, requestMessage, responseMessage);
nativeSendGoalResponse(
this.handle, rmwRequestId,
responseFromJavaConverterHandle, responseToJavaConverterHandle,
this.handle, rmwRequestId, responseFromJavaConverterHandle,
responseDestructorHandle, responseMessage);
}
}
Expand Down Expand Up @@ -646,8 +639,7 @@ public void execute() {
responseMessage = executeCancelRequest(responseMessage);
nativeSendCancelResponse(
this.handle, rmwRequestId,
responseFromJavaConverterHandle, responseToJavaConverterHandle,
responseDestructorHandle, responseMessage);
responseFromJavaConverterHandle, responseDestructorHandle, responseMessage);
}
}

Expand Down
6 changes: 3 additions & 3 deletions rcljava/src/main/java/org/ros2/rcljava/client/ClientImpl.java
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ public void accept(Future<V> input) {}
synchronized (pendingRequests) {
long sequenceNumber = nativeSendClientRequest(
handle, request.getFromJavaConverterInstance(),
request.getToJavaConverterInstance(), request.getDestructorInstance(), request);
request.getDestructorInstance(), request);
RCLFuture<V> future = new RCLFuture<V>(this.nodeReference);

Map.Entry<Consumer, RCLFuture> entry =
Expand Down Expand Up @@ -109,8 +109,8 @@ public final <U extends MessageDefinition> 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<MessageDefinition> getRequestType() {
return this.requestType;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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());
Expand Down Expand Up @@ -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,
Expand Down