Skip to content

Commit

Permalink
fix OSX travis
Browse files Browse the repository at this point in the history
  • Loading branch information
Theosakamg committed Jun 10, 2018
1 parent 17e61d8 commit a25db37
Show file tree
Hide file tree
Showing 32 changed files with 128 additions and 118 deletions.
1 change: 0 additions & 1 deletion .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,6 @@ matrix:
env:
- PYTHON_PATH="/usr/local/opt/python3/bin/python3.6"
- TRAVIS_OS_NAME="osx"
- PKG_EXCLUDE="$PKG_EXCLUDE console_bridge orocos_kdl class_loader rosidl_generator_py pendulum_msgs rttest rclcpp dummy_map_server tf2 tf2_msgs tf2_ros tf2_eigen urdfdom_headers urdfdom urdf kdl_parser robot_state_publisher dummy_robot_bringup common_interfaces test_msgs dummy_sensors image_geometry sros2 test_security tf2_geometry_msgs nav_msgs actionlib_msgs diagnostic_msgs rcljava_utils rcl_lifecycle"
osx_image: xcode9.1
allow_failures:
- env: DOCKER_DIST="debian-stable"
Expand Down
2 changes: 1 addition & 1 deletion ament_cmake_export_jars/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

<package format="3">
<name>ament_cmake_export_jars</name>
<version>0.0.0</version>
<version>0.4.0</version>
<description>The ability to export Java archives to downstream packages in the ament buildsystem in CMake.</description>
<maintainer email="esteve@apache.org">Esteve Fernandez</maintainer>
<license>Apache License 2.0</license>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,11 +38,11 @@ JNIEXPORT jlong JNICALL
/*
* Class: org_ros2_rcljava_node_service_NativeClient
* Method: nativeSendClientRequest
* Signature: (JJJJLjava/lang/Object;)V
* Signature: (JJJLjava/lang/Object;)J
*/
JNIEXPORT void JNICALL
JNIEXPORT jlong JNICALL
Java_org_ros2_rcljava_node_service_NativeClient_nativeSendClientRequest
(JNIEnv *, jclass, jlong, jlong, jlong, jlong, jobject);
(JNIEnv *, jclass, jlong, jlong, jlong, jobject);

/*
* Class: org_ros2_rcljava_node_service_NativeClient
Expand Down
2 changes: 1 addition & 1 deletion rcljava/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>rcljava</name>
<version>0.0.2</version>
<version>0.4.0</version>
<description>Package containing the Java client.</description>
<maintainer email="mick.gaillard@gmail.com">Mickael Gaillard</maintainer>
<license>Apache License 2.0</license>
Expand Down
1 change: 0 additions & 1 deletion rcljava/src/main/cpp/org_ros2_rcljava_node_NativeNode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,6 @@ Java_org_ros2_rcljava_node_NativeNode_nativeDispose(
rcl_node_t * node = handle2Instance<rcl_node_t>(jnode_handle);

rcl_ret_t ret = rcl_node_fini(node);
free(node);
if (ret != RCL_RET_OK) {
std::string message("Failed finish node: " +
std::string(rcl_get_error_string_safe()));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,12 +88,11 @@ Java_org_ros2_rcljava_node_service_NativeClient_nativeCreateClientHandle(
/*
* nativeSendClientRequest
*/
JNIEXPORT void JNICALL
JNIEXPORT jlong JNICALL
Java_org_ros2_rcljava_node_service_NativeClient_nativeSendClientRequest(
JNIEnv * env,
jclass,
jlong client_handle,
jlong sequence_number,
jlong jrequest_from_java_converter_handle,
jlong jrequest_to_java_converter_handle,
jobject jrequest_msg)
Expand All @@ -109,15 +108,18 @@ Java_org_ros2_rcljava_node_service_NativeClient_nativeSendClientRequest(
reinterpret_cast<convert_from_java_signature>(jrequest_from_java_converter_handle);

void * request_msg = convert_from_java(jrequest_msg, nullptr);
int64_t seq_number;

rcl_ret_t ret = rcl_send_request(client, request_msg, &sequence_number);
rcl_ret_t ret = rcl_send_request(client, request_msg, &seq_number);

if (ret != RCL_RET_OK) {
std::string message("Failed to send request from a client: " +
std::string(rcl_get_error_string_safe()));
rcl_reset_error();
throwException(env, message);
}

return seq_number;
}

/*
Expand All @@ -134,7 +136,6 @@ Java_org_ros2_rcljava_node_service_NativeClient_nativeDispose(
rcl_client_t * client = handle2Instance<rcl_client_t>(jclient_handle);

rcl_ret_t ret = rcl_client_fini(client, node);
free(client);
if (ret != RCL_RET_OK) {
std::string message("Failed to destroy client: " +
std::string(rcl_get_error_string_safe()));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,6 @@ Java_org_ros2_rcljava_node_service_NativeService_nativeDispose(
rcl_service_t * service = handle2Instance<rcl_service_t>(jservice_handle);

rcl_ret_t ret = rcl_service_fini(service, node);
free(service);
if (ret != RCL_RET_OK) {
std::string message("Failed to destroy service: " +
std::string(rcl_get_error_string_safe()));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,6 @@ Java_org_ros2_rcljava_node_topic_NativePublisher_nativeDispose(
rcl_publisher_t * publisher = handle2Instance<rcl_publisher_t>(jpublisher_handle);

rcl_ret_t ret = rcl_publisher_fini(publisher, node);
free(publisher);
if (ret != RCL_RET_OK) {
std::string message("Failed to destroy publisher: " +
std::string(rcl_get_error_string_safe()));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,6 @@ Java_org_ros2_rcljava_node_topic_NativeSubscription_nativeDispose(
rcl_subscription_t * subscription = handle2Instance<rcl_subscription_t>(jsubscription_handle);

rcl_ret_t ret = rcl_subscription_fini(subscription, node);
free(subscription);
if (ret != RCL_RET_OK) {
std::string message("Failed to destroy subscription: " +
std::string(rcl_get_error_string_safe()));
Expand Down
52 changes: 37 additions & 15 deletions rcljava/src/main/java/org/ros2/rcljava/RCLJava.java
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,9 @@ public final class RCLJava {

private static final Logger logger = LoggerFactory.getLogger(RCLJava.class);

private static final String DISPLAY_SEPARATOR =
"===============================================================";

/**
* The identifier of the currently active RMW implementation.
*/
Expand All @@ -54,6 +57,8 @@ public final class RCLJava {
*/
private static volatile boolean initialized = false;

private static String libExtention = ".unknow";

private static String[] arguments;

/**
Expand Down Expand Up @@ -129,16 +134,26 @@ private static String getRmwImplementationSuffix(final String rmwImplementation)
}

private static void displayContext() {
RCLJava.logger.debug(DISPLAY_SEPARATOR);
// https://docs.oracle.com/javase/7/docs/api/java/lang/System.html#getProperties
// http://lopica.sourceforge.net/os.html
final String libpath = System.getProperty("java.library.path");
final String arch = System.getProperty("os.arch");
final String os = System.getProperty("os.name");
final String osVer = System.getProperty("os.version");

final String pidAndHost = ManagementFactory.getRuntimeMXBean().getName();
final String pid = pidAndHost.substring(0, pidAndHost.indexOf('@'));
// For JAVA9 : long pid = ProcessHandle.current().getPid();

final String user = System.getProperty("user.name");
final String pathSeparator = System.getProperty("path.separator");

// Java Value
RCLJava.logger.debug(String.format("Process ID : %s", pid));
RCLJava.logger.debug(String.format("Process User : %s", user));

RCLJava.logger.debug(String.format("Java Home : %s", System.getProperty("java.home")));
RCLJava.logger.debug(String.format("Java JVM : %s %s %s",
System.getProperty("java.vm.vendor"),
System.getProperty("java.vm.name"),
Expand All @@ -151,9 +166,24 @@ private static void displayContext() {
System.getProperty("java.specification.version")));

// Native Value
RCLJava.logger.debug(String.format("Native Library OS : %s", os));
RCLJava.logger.debug(String.format("Native Library OS : %s %s", os, osVer));
RCLJava.logger.debug(String.format("Native Library Archi : %s", arch));
RCLJava.logger.debug(String.format("Native Library path : \n\t%s", libpath.replace(":", "\n\t")));
RCLJava.logger.debug(String.format("Native Library path : %n\t%s", libpath.replace(pathSeparator, System.lineSeparator() + "\t")));
RCLJava.logger.debug(DISPLAY_SEPARATOR);
}

private static void displayReport() {
RCLJava.logger.debug(DISPLAY_SEPARATOR);

// List loaded libraries.
final String[] list = NativeUtils.getLoadedLibraries(RCLJava.class.getClassLoader());
final StringBuilder msgLog = new StringBuilder();
for (final String key : list) {
msgLog.append(key);
msgLog.append(System.lineSeparator());
}
RCLJava.logger.debug(String.format("Native libraries Loaded: %n", msgLog.toString()));
RCLJava.logger.debug(DISPLAY_SEPARATOR);
}

/**
Expand Down Expand Up @@ -336,7 +366,7 @@ public static void setRMWImplementation(final String rmwImplementation)
if (rmwImplementation != null && !rmwImplementation.isEmpty()) {
if (!rmwImplementation.equals(RCLJava.rmwImplementation)) {
final String file = "rcljava"+ RCLJava.getRmwImplementationSuffix(rmwImplementation);
RCLJava.logger.debug("Load native RMW file : lib" + file + ".so");
RCLJava.logger.debug("Load native RMW file : " + System.mapLibraryName(file));

try {
System.loadLibrary(file);
Expand All @@ -363,7 +393,7 @@ public static void setRMWImplementation(final String rmwImplementation)
*/
@SuppressWarnings("PMD.AvoidUsingNativeCode")
public static void loadLibrary(final String name) {
RCLJava.logger.debug("Load native file : lib" + name + ".so");
RCLJava.logger.debug("Load native file :" + System.mapLibraryName(name));
RCLJava.lockAndCheckInitialized();

try {
Expand Down Expand Up @@ -392,20 +422,12 @@ private static void autoLoadRmw() {
}

protected static void shutdownHook() {
RCLJava.shutdown(true);

RCLJava.logger.debug("Final Shutdown...");

// List loaded libraries.
final String[] list = NativeUtils.getLoadedLibraries(RCLJava.class.getClassLoader());
final StringBuilder msgLog = new StringBuilder();
for (final String key : list) {
msgLog.append(key);
msgLog.append('\n');
}
RCLJava.logger.debug("Native libraries Loaded: \n" + msgLog.toString());

RCLJava.shutdown(true);
GraphName.dispose();

RCLJava.displayReport();
}

private static void lockAndCheckInitialized() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,6 @@ public MultiThreadedExecutor(final int numberOfThreads) {
* Pool-multiple threaded implementation of spin.
* This function will block until work comes in, execute it, and keep blocking.
* It will only be interrupt by a CTRL-C (managed by the global signal handler).
* @throws InterruptedException
*/
@Override
public void spin() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -254,7 +254,7 @@ private static void executeService(final Service service) {
}

if (requestMessage != null && responseMessage != null) {
final RMWRequestId rmwRequestId = (RMWRequestId) NativeExecutor.nativeTakeRequest(
final RMWRequestId rmwRequestId = NativeExecutor.nativeTakeRequest(
nativeService.getServiceHandle(),
nativeService.getRequest().getFromJavaConverterHandle(),
nativeService.getRequest().getToJavaConverterHandle(),
Expand Down Expand Up @@ -301,7 +301,7 @@ public static native void nativeWaitSetInit(
public static native void nativeWaitSetFini(long waitSetHandle);

public static native Message nativeTake(long SubscriptionHandle, Class<?> msgType);
public static native Object nativeTakeRequest(
public static native RMWRequestId nativeTakeRequest(
long serviceHandle,
long requestFromJavaConverterHandle,
long requestToJavaConverterHandle,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ public static String getFullName(final String nameSpace, final String nodeName)
/**
*
*
* <table>
* <table summary="Definition of rules.">
* <tr><td>Input Name </td><td>Node: my_node NS: none </td><td>Node: my_node NS: /my_ns</td></tr>
* <tr><td>ping </td><td>/ping </td><td>/my_ns/ping</td></tr>
* <tr><td>/ping </td><td>/ping </td><td>/ping</td></tr>
Expand Down
12 changes: 1 addition & 11 deletions rcljava/src/main/java/org/ros2/rcljava/node/NativeNode.java
Original file line number Diff line number Diff line change
Expand Up @@ -248,11 +248,6 @@ public WallTimer createWallTimer(
* @param serviceName The service to subscribe on.
* @param qosProfile The quality of service profile to pass on to the rmw implementation.
* @return Client instance of the service.
* @throws SecurityException
* @throws NoSuchFieldException
* @throws IllegalAccessException
* @throws IllegalArgumentException
* @throws NoSuchMethodException
*/
@Override
public <T extends MessageService> Client<T> createClient(
Expand Down Expand Up @@ -288,11 +283,6 @@ public <T extends MessageService> Client<T> createClient(
* @param callback The user-defined callback function.
* @param qosProfile The quality of service profile to pass on to the rmw implementation.
* @return Service instance of the service.
* @throws SecurityException
* @throws NoSuchFieldException
* @throws IllegalAccessException
* @throws IllegalArgumentException
* @throws NoSuchMethodException
*/
@Override
public <T extends MessageService> Service<T> createService(
Expand Down Expand Up @@ -415,7 +405,7 @@ public int countSubscribers(final String topic) {
/**
* TODO REMOVE !!!
* Return the rcl_node_t node handle (non-const version).
* @return
* @return Node handler.
*/
public long getNodeHandle() {
return this.nodeHandle;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,13 +25,13 @@ public interface NodeGraph {

/**
* This is typically only used by the rclcpp::graph_listener::GraphListener.
* Return the number of on loan graph events, see get_graph_event().
* @return The number of on loan graph events, see get_graph_event().
*/
int countGraphUsers();

/**
*
* @return
* @return Map of Services with list of type.
*/
Map<String, List<String>> getServiceNamesAndTypes();

Expand Down Expand Up @@ -60,13 +60,13 @@ public interface NodeGraph {
List<String> getNodeNames();

/**
* @param topic
* @param topic Topic name filter.
* @return Return the number of publishers that are advertised on a given topic.
*/
int countPublishers(final String topic);

/**
* @param topic
* @param topic Topic name filter.
* @return Return the number of subscribers who have created a subscription for a given topic.
*/
int countSubscribers(final String topic);
Expand All @@ -87,7 +87,7 @@ public interface NodeGraph {
* This is typically only used by the rclcpp::graph_listener::GraphListener.
*
* return Return a graph event, which will be set anytime a graph change occurs.
* @throws RCLBaseError (a child of that exception) when an rcl error occurs
* throws RCLBaseError (a child of that exception) when an rcl error occurs
*/
void notifyGraphChange();

Expand All @@ -108,9 +108,12 @@ public interface NodeGraph {
*
* The given Event must be acquire through the get_graph_event() method.
*
* @throws InvalidEventError if the given event is nullptr
* @throws EventNotRegisteredError if the given event was not acquired with
* throws InvalidEventError if the given event is nullptr
* throws EventNotRegisteredError if the given event was not acquired with
* get_graph_event().
*
* @param event Event.
* @param timeout Timeout.
*/
void waitForGraphChange(final Object event, final int timeout);

Expand Down

0 comments on commit a25db37

Please sign in to comment.