18 #include <glog/logging.h> 30 JNIEXPORT jboolean JNICALL
32 JNIEnv* env, jclass , jobject binder) {
36 JNIEXPORT jboolean JNICALL
38 JNIEnv* env, jclass , jobject activity) {
42 JNIEXPORT jint JNICALL
44 JNIEnv* env, jobject , jstring master_uri_value,
45 jstring host_ip_value, jstring node_name_value,
46 jobjectArray remapping_objects_value) {
47 const char*
master_uri = env->GetStringUTFChars(master_uri_value, NULL);
48 const char*
host_ip = env->GetStringUTFChars(host_ip_value, NULL);
49 const char* node_name = env->GetStringUTFChars(node_name_value, NULL);
51 std::string master_uri_string(
"__master:=" + std::string(master_uri));
52 std::string host_ip_string(
"__ip:=" + std::string(host_ip));
53 const std::string node_name_string(node_name);
54 char* argv[] = {
"/", &master_uri_string[0], &host_ip_string[0]};
56 env->ReleaseStringUTFChars(master_uri_value, master_uri);
57 env->ReleaseStringUTFChars(host_ip_value, host_ip);
58 env->ReleaseStringUTFChars(node_name_value, node_name);
60 std::map<std::string, std::string> remappings;
61 if (remapping_objects_value == NULL || env->GetArrayLength(remapping_objects_value) == 0) {
62 LOG(INFO) <<
"No remapping to be done.";
64 int remappingStringCount = env->GetArrayLength(remapping_objects_value);
65 for (
int i = 0; i < remappingStringCount; ++i) {
66 jstring remap_arg_value = (jstring) (env->GetObjectArrayElement(remapping_objects_value, i));
67 const char* remap_arg = env->GetStringUTFChars(remap_arg_value, NULL);
71 std::string remap_arg_string = std::string(remap_arg);
72 std::string delimiter =
":=";
73 size_t delimiter_position = remap_arg_string.find(delimiter);
74 if (delimiter_position == std::string::npos) {
75 LOG(ERROR) <<
"Invalid remapping argument: " << remap_arg <<
". The correct syntax is old_name:=new_name.";
78 std::string remap_old_name = remap_arg_string.substr(0, delimiter_position);
79 remap_arg_string.erase(0, delimiter_position + delimiter.length());
80 std::string remap_new_name = remap_arg_string;
81 remappings.insert(std::pair<std::string, std::string>(remap_old_name, remap_new_name));
82 LOG(INFO) <<
"Remapping " << remap_old_name <<
" to " << remap_new_name;
83 env->ReleaseStringUTFChars(remap_arg_value, remap_arg);
87 ros::init(argc, argv, node_name_string.c_str());
89 std::vector<std::string> nodelet_argv;
91 LOG(INFO) <<
"Start loading nodelets.";
92 const bool result = loader.load(
"/tango",
"tango_ros_native/TangoRosNodelet", remappings, nodelet_argv);
94 LOG(ERROR) <<
"Problem loading Tango ROS nodelet!";
97 LOG(INFO) <<
"Finished loading nodelets.";
101 if (!image_transport_pub_loader.
isClassAvailable(
"image_transport/raw_pub")) {
102 LOG(ERROR) <<
"Plugin image_transport/raw_pub is not available.";
105 if (!image_transport_pub_loader.
isClassAvailable(
"image_transport/compressed_pub")) {
106 LOG(ERROR) <<
"Plugin image_transport/compressed_pub is not available.";
116 JNIEXPORT jint JNICALL
118 JNIEnv* , jobject ) {
JNIEXPORT jint JNICALL Java_eu_intermodalics_nodelet_1manager_TangoNodeletManager_execute(JNIEnv *env, jobject, jstring master_uri_value, jstring host_ip_value, jstring node_name_value, jobjectArray remapping_objects_value)
bool IsTangoVersionOk(JNIEnv *env, jobject activity)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool SetBinder(JNIEnv *env, jobject binder)
JNIEXPORT jint JNICALL Java_eu_intermodalics_nodelet_1manager_TangoNodeletManager_shutdown(JNIEnv *, jobject)
JNIEXPORT jboolean JNICALL Java_eu_intermodalics_nodelet_1manager_TangoInitializationHelper_isTangoVersionOk(JNIEnv *env, jclass, jobject activity)
JNIEXPORT jboolean JNICALL Java_eu_intermodalics_nodelet_1manager_TangoInitializationHelper_setBinderTangoService(JNIEnv *env, jclass, jobject binder)
virtual bool isClassAvailable(const std::string &lookup_name)
ROSCPP_DECL void waitForShutdown()