jni.cc
Go to the documentation of this file.
00001 // Copyright 2017 Intermodalics All Rights Reserved.
00002 //
00003 // Licensed under the Apache License, Version 2.0 (the "License");
00004 // you may not use this file except in compliance with the License.
00005 // You may obtain a copy of the License at
00006 //
00007 //      http://www.apache.org/licenses/LICENSE-2.0
00008 //
00009 // Unless required by applicable law or agreed to in writing, software
00010 // distributed under the License is distributed on an "AS IS" BASIS,
00011 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00012 // See the License for the specific language governing permissions and
00013 // limitations under the License.
00014 #include <string>
00015 
00016 #include <jni.h>
00017 
00018 #include <glog/logging.h>
00019 #include <image_transport/publisher_plugin.h>
00020 #include <nodelet/loader.h>
00021 #include <pluginlib/class_loader.h>
00022 #include <ros/ros.h>
00023 
00024 #include "tango_helper.h"
00025 
00026 #ifdef __cplusplus
00027 extern "C" {
00028 #endif
00029 
00030 JNIEXPORT jboolean JNICALL
00031 Java_eu_intermodalics_nodelet_1manager_TangoInitializationHelper_setBinderTangoService(
00032     JNIEnv* env, jclass /*class*/, jobject binder) {
00033   return tango_helper::SetBinder(env, binder);
00034 }
00035 
00036 JNIEXPORT jboolean JNICALL
00037 Java_eu_intermodalics_nodelet_1manager_TangoInitializationHelper_isTangoVersionOk(
00038     JNIEnv* env, jclass /*class*/, jobject activity) {
00039   return tango_helper::IsTangoVersionOk(env, activity);
00040 }
00041 
00042 JNIEXPORT jint JNICALL
00043 Java_eu_intermodalics_nodelet_1manager_TangoNodeletManager_execute(
00044         JNIEnv* env, jobject /*obj*/, jstring master_uri_value,
00045         jstring host_ip_value, jstring node_name_value,
00046         jobjectArray remapping_objects_value) {
00047     const char* master_uri = env->GetStringUTFChars(master_uri_value, NULL);
00048     const char* host_ip = env->GetStringUTFChars(host_ip_value, NULL);
00049     const char* node_name = env->GetStringUTFChars(node_name_value, NULL);
00050     int argc = 3;
00051     std::string master_uri_string("__master:=" + std::string(master_uri));
00052     std::string host_ip_string("__ip:=" + std::string(host_ip));
00053     const std::string node_name_string(node_name);
00054     char* argv[] = {"/", &master_uri_string[0], &host_ip_string[0]};
00055 
00056     env->ReleaseStringUTFChars(master_uri_value, master_uri);
00057     env->ReleaseStringUTFChars(host_ip_value, host_ip);
00058     env->ReleaseStringUTFChars(node_name_value, node_name);
00059 
00060     std::map<std::string, std::string> remappings;
00061     if (remapping_objects_value == NULL || env->GetArrayLength(remapping_objects_value) == 0) {
00062       LOG(INFO) << "No remapping to be done.";
00063     } else {
00064       int remappingStringCount = env->GetArrayLength(remapping_objects_value);
00065       for (int i = 0; i < remappingStringCount; ++i) {
00066         jstring remap_arg_value = (jstring) (env->GetObjectArrayElement(remapping_objects_value, i));
00067         const char* remap_arg = env->GetStringUTFChars(remap_arg_value, NULL);
00068         // Parse remapping argument to extract old and new names.
00069         // According to ROS doc, the syntax for remapping arguments is: old_name:=new_name.
00070         // See http://wiki.ros.org/Remapping%20Arguments.
00071         std::string remap_arg_string = std::string(remap_arg);
00072         std::string delimiter = ":=";
00073         size_t delimiter_position = remap_arg_string.find(delimiter);
00074         if (delimiter_position == std::string::npos) {
00075           LOG(ERROR) << "Invalid remapping argument: " << remap_arg << ". The correct syntax is old_name:=new_name.";
00076           return 1;
00077         }
00078         std::string remap_old_name = remap_arg_string.substr(0, delimiter_position);
00079         remap_arg_string.erase(0, delimiter_position + delimiter.length());
00080         std::string remap_new_name = remap_arg_string;
00081         remappings.insert(std::pair<std::string, std::string>(remap_old_name, remap_new_name));
00082         LOG(INFO) << "Remapping " << remap_old_name << " to " << remap_new_name;
00083         env->ReleaseStringUTFChars(remap_arg_value, remap_arg);
00084       }
00085     }
00086 
00087     ros::init(argc, argv, node_name_string.c_str());
00088     nodelet::Loader loader;
00089     std::vector<std::string> nodelet_argv;
00090 
00091     LOG(INFO) << "Start loading nodelets.";
00092     const bool result = loader.load("/tango", "tango_ros_native/TangoRosNodelet", remappings, nodelet_argv);
00093     if (!result) {
00094         LOG(ERROR) << "Problem loading Tango ROS nodelet!";
00095         return 1;
00096     }
00097     LOG(INFO) << "Finished loading nodelets.";
00098 
00099     // Check that all necessary plugins are available.
00100     pluginlib::ClassLoader<image_transport::PublisherPlugin> image_transport_pub_loader("image_transport", "image_transport::PublisherPlugin");
00101     if (!image_transport_pub_loader.isClassAvailable("image_transport/raw_pub")) {
00102       LOG(ERROR) << "Plugin image_transport/raw_pub is not available.";
00103       return 1;
00104     }
00105     if (!image_transport_pub_loader.isClassAvailable("image_transport/compressed_pub")) {
00106       LOG(ERROR) << "Plugin image_transport/compressed_pub is not available.";
00107       return 1;
00108     }
00109 
00110     ros::AsyncSpinner spinner(4);
00111     spinner.start();
00112     ros::waitForShutdown();
00113     return 0;
00114 }
00115 
00116 JNIEXPORT jint JNICALL
00117 Java_eu_intermodalics_nodelet_1manager_TangoNodeletManager_shutdown(
00118         JNIEnv* /*env*/, jobject /*obj*/) {
00119     return 0;
00120 }
00121 
00122 #ifdef __cplusplus
00123 }
00124 #endif


TangoRosStreamer
Author(s):
autogenerated on Thu Jun 6 2019 19:49:57