00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <list>
00038 #include <vector>
00039 #include <set>
00040 #include <string>
00041 #include <map>
00042 #include <sstream>
00043 #include <stdexcept>
00044
00045
00046 #include <cstdio>
00047 #include <boost/thread.hpp>
00048 #include <boost/thread/mutex.hpp>
00049 #include <boost/thread/condition.hpp>
00050 #include <boost/shared_ptr.hpp>
00051 #include <boost/thread/tss.hpp>
00052
00053
00054 #include <ros/init.h>
00055 #include <ros/time.h>
00056 #include <ros/master.h>
00057 #include <ros/this_node.h>
00058 #include <ros/node_handle.h>
00059 #include <ros/service.h>
00060 #include <rospack/rospack.h>
00061
00062 #include <signal.h>
00063
00064 #include "ros_roscpp_JNI.h"
00065
00066
00067 #define MY_ROS_ASSERT(cond) \
00068 do { \
00069 if (!(cond)) { \
00070 ROS_FATAL("ASSERTION FAILED\n\tfile = %s\n\tline = %d\n\tcond = %s\n", __FILE__, __LINE__, #cond); \
00071 ROS_ISSUE_BREAK() \
00072 } \
00073 } while (0)
00074
00075
00076
00077 #ifdef MSVC
00078 #define PRIdS "Id"
00079 #else
00080 #define PRIdS "zd"
00081 #endif
00082
00083 using namespace ros;
00084 using namespace std;
00085
00086
00087
00088
00089
00090
00091
00092
00093
00094 string getString(JNIEnv * env, jstring s)
00095 {
00096 if(s == NULL || env == NULL) return string("");
00097 const char* str = env->GetStringUTFChars(s, 0);
00098 string ret = str;
00099 env->ReleaseStringUTFChars(s, str);
00100
00101 return ret;
00102 }
00103
00104 jstring makeString(JNIEnv * env, const string &s) {
00105 return (jstring) env->NewStringUTF(s.c_str());
00106 }
00107
00108
00109
00110
00111
00112
00113 static JavaVM *vm = NULL;
00114
00115 bool dieOnException(JNIEnv * env, const char * message = "") {
00116 if (env->ExceptionOccurred()) {
00117 env->ExceptionDescribe();
00118 ROS_FATAL(message);
00119 MY_ROS_ASSERT(false);
00120 return false;
00121 }
00122 return true;
00123 }
00124
00125 class ThreadJNIEnv {
00126 public:
00127 bool _detach;
00128 JNIEnv *env;
00129 ThreadJNIEnv() {
00130 cout << "Attaching " << boost::this_thread::get_id() << endl;
00131 vm->AttachCurrentThread((void **) &env, NULL);
00132 MY_ROS_ASSERT(env != NULL);
00133 _detach = true;
00134
00135 }
00136
00137 ThreadJNIEnv(JNIEnv *e) {
00138 env = e;
00139 _detach = false;
00140 MY_ROS_ASSERT(env != NULL);
00141 }
00142
00143 ~ThreadJNIEnv() {
00144 if (_detach) {
00145 cout << "Detaching " << boost::this_thread::get_id() << endl;
00146 vm->DetachCurrentThread();
00147 }
00148 }
00149 };
00150
00151 static boost::thread_specific_ptr<ThreadJNIEnv> tp;
00152
00153 JNIEnv *getJNIEnv(){
00154 JNIEnv *ret;
00155
00156
00157
00158
00159
00160 ThreadJNIEnv *tenv = tp.get();
00161 if (tenv == NULL) {
00162 tenv = new ThreadJNIEnv();
00163 tp.reset(tenv);
00164 }
00165
00166 ret = tenv->env;
00167 MY_ROS_ASSERT(ret != NULL);
00168 dieOnException(ret, "Env already in exception state.");
00169 return ret;
00170 }
00171
00172
00173
00174
00175
00176
00177
00178
00179
00180 static jclass jObject;
00181
00182 static jclass jRosException;
00183 static jclass jTime;
00184 static jclass jString;
00185 static jclass jMessage;
00186 static jclass jSubscriberCallback;
00187 static jclass jServiceCallback;
00188 static jclass jByteBuffer;
00189
00190 static jmethodID jTimeCtor;
00191
00192 static jmethodID jMessageClone;
00193 static jmethodID jMessageGetDataType;
00194 static jmethodID jMessageGetMD5Sum;
00195 static jmethodID jMessageGetServerMD5Sum;
00196 static jmethodID jMessageGetMessageDefinition;
00197 static jmethodID jMessageSerializationLength;
00198 static jmethodID jMessageSerialize;
00199 static jmethodID jMessageDeserialize;
00200 static jmethodID jSubscriberCallbackCall;
00201 static jmethodID jServiceCallbackCall;
00202 static jmethodID jByteBufferOrder;
00203
00204 static jobject jByteOrderLittleEndian;
00205
00206
00207 bool cacheClass(JNIEnv * env, jclass &ref, const char * name) {
00208 ref = env->FindClass(name);
00209 if (ref == NULL) return false;
00210 ref = (jclass) env->NewGlobalRef(ref);
00211 return true;
00212 }
00213
00214 bool cacheMethod(JNIEnv * env, jmethodID &ref, jclass cls, const char * name, const char * args ) {
00215 ref = env->GetMethodID(cls, name, args);
00216 return (ref != NULL);
00217 }
00218
00219
00220
00221
00222
00223
00224
00225 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_init
00226 (JNIEnv * env, jclass __jni, jstring name, jboolean noSigintHandler, jboolean anonymousName, jboolean noRosout, jobjectArray args)
00227 {
00228 if (!env->GetJavaVM(&vm) < 0) return;
00229 tp.reset(new ThreadJNIEnv(env));
00230
00231 if (!cacheClass(env, jObject, "java/lang/Object")) return;
00232 if (!cacheClass(env, jString, "java/lang/String")) return;
00233
00234 if (!cacheClass(env, jRosException, "ros/RosException")) return;
00235 if (!cacheClass(env, jTime, "ros/communication/Time")) return;
00236 if (!cacheClass(env, jMessage, "ros/communication/Message")) return;
00237 if (!cacheClass(env, jSubscriberCallback, "ros/Subscriber$Callback")) return;
00238 if (!cacheClass(env, jServiceCallback, "ros/ServiceServer$Callback")) return;
00239 if (!cacheClass(env, jByteBuffer, "java/nio/ByteBuffer")) return;
00240
00241 if (!cacheMethod(env, jTimeCtor, jTime, "<init>", "(II)V")) return;
00242
00243 if (!cacheMethod(env, jMessageClone, jMessage, "clone", "()Lros/communication/Message;")) return;
00244 if (!cacheMethod(env, jMessageGetDataType, jMessage, "getDataType", "()Ljava/lang/String;")) return;
00245 if (!cacheMethod(env, jMessageGetMD5Sum, jMessage, "getMD5Sum", "()Ljava/lang/String;")) return;
00246 if (!cacheMethod(env, jMessageGetServerMD5Sum, jMessage, "getServerMD5Sum", "()Ljava/lang/String;")) return;
00247 if (!cacheMethod(env, jMessageGetMessageDefinition, jMessage, "getMessageDefinition", "()Ljava/lang/String;")) return;
00248 if (!cacheMethod(env, jMessageSerializationLength, jMessage, "serializationLength", "()I")) return;
00249 if (!cacheMethod(env, jMessageSerialize, jMessage, "serialize", "(Ljava/nio/ByteBuffer;I)V")) return;
00250 if (!cacheMethod(env, jMessageDeserialize, jMessage, "deserialize", "(Ljava/nio/ByteBuffer;)V")) return;
00251 if (!cacheMethod(env, jSubscriberCallbackCall, jSubscriberCallback, "call", "(Lros/communication/Message;)V")) return;
00252 if (!cacheMethod(env, jServiceCallbackCall, jServiceCallback, "call", "(Lros/communication/Message;)Lros/communication/Message;")) return;
00253 if (!cacheMethod(env, jByteBufferOrder, jByteBuffer, "order", "(Ljava/nio/ByteOrder;)Ljava/nio/ByteBuffer;")) return;
00254
00255 jclass jByteOrder = env->FindClass("java/nio/ByteOrder");
00256 if (jByteOrder == NULL) return;
00257 jfieldID fid = env->GetStaticFieldID(jByteOrder, "LITTLE_ENDIAN", "Ljava/nio/ByteOrder;");
00258 if (fid == NULL) return;
00259 jByteOrderLittleEndian = env->NewGlobalRef(env->GetStaticObjectField(jByteOrder, fid));
00260 if (jByteOrderLittleEndian == NULL) return;
00261
00262
00263 int len = env->GetArrayLength(args);
00264
00265 vector<string> vargs;
00266 for(int i = 0; i < len; i++) vargs.push_back(getString(env, (jstring) env->GetObjectArrayElement(args,i)));
00267
00268 vector<char*> argv(len);
00269 for(int i = 0; i < len; ++i)
00270 argv[i] = &vargs[i][0];
00271
00272 uint32_t options = (noSigintHandler ? ros::init_options::NoSigintHandler : 0) |
00273 (anonymousName ? ros::init_options::AnonymousName : 0) |
00274 (noRosout ? ros::init_options::NoRosout : 0);
00275 ros::init(len, len > 0 ? &argv[0] : NULL, getString(env, name), options);
00276 }
00277
00278 JNIEXPORT jlong JNICALL Java_ros_roscpp_JNI_createNodeHandle
00279 (JNIEnv * env, jclass __jni, jstring jns, jobjectArray jmappings)
00280 {
00281 map<string, string> remappings;
00282 int len = env->GetArrayLength(jmappings);
00283 MY_ROS_ASSERT(len % 2 == 0);
00284 for(int i = 0; i < len; i+=2)
00285 remappings[getString(env, (jstring) env->GetObjectArrayElement(jmappings, i))] =
00286 getString(env, (jstring) env->GetObjectArrayElement(jmappings, i+1));
00287
00288 return (long) (new NodeHandle(getString(env, jns), remappings));
00289 }
00290
00291 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_shutdown
00292 (JNIEnv * env, jclass __jni, jlong cppHandle)
00293 {
00294
00295
00296
00297
00298
00299
00300
00301
00302
00303
00304
00305 NodeHandle *handle = (NodeHandle *) cppHandle;
00306 handle->shutdown();
00307 delete handle;
00308 }
00309
00310 JNIEXPORT jboolean JNICALL Java_ros_roscpp_JNI_nhOk
00311 (JNIEnv * env, jclass __jni, jlong cppHandle)
00312 {
00313 NodeHandle *handle = (NodeHandle *) cppHandle;
00314 return handle->ok();
00315 }
00316
00317 JNIEXPORT jboolean JNICALL Java_ros_roscpp_JNI_rosOk
00318 (JNIEnv * env, jclass __jni)
00319 {
00320 return ros::ok();
00321 }
00322
00323
00324
00325
00326 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_spin
00327 (JNIEnv * env, jclass __jni)
00328 {
00329 ros::spin();
00330 }
00331
00332 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_spinOnce
00333 (JNIEnv * env, jclass __jni)
00334 {
00335 ros::spinOnce();
00336 }
00337
00338
00339
00340
00341 JNIEXPORT jboolean JNICALL Java_ros_roscpp_JNI_checkMaster
00342 (JNIEnv * env, jclass __jni, jlong cppHandle)
00343 {
00344 return ros::master::check();
00345 }
00346
00347 JNIEXPORT jstring JNICALL Java_ros_roscpp_JNI_getMasterHost
00348 (JNIEnv * env, jclass __jni, jlong cppHandle)
00349 {
00350
00351 return makeString(env, ros::master::getHost());
00352 }
00353
00354 JNIEXPORT jint JNICALL Java_ros_roscpp_JNI_getMasterPort
00355 (JNIEnv * env, jclass __jni, jlong cppHandle)
00356 {
00357
00358 return ros::master::getPort();
00359 }
00360
00361 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_setMasterRetryTimeout
00362 (JNIEnv * env, jclass __jni, jlong cppHandle, jint ms)
00363 {
00364
00365 ros::master::setRetryTimeout(WallDuration((ms/1000),(ms % 1000) * 1000000));
00366 }
00367
00368
00369
00370
00371 JNIEXPORT jstring JNICALL Java_ros_roscpp_JNI_getName
00372 (JNIEnv * env, jclass __jni, jlong cppHandle)
00373 {
00374
00375
00376 return makeString(env, ros::this_node::getName());
00377 }
00378
00379
00380 JNIEXPORT jstring JNICALL Java_ros_roscpp_JNI_mapName
00381 (JNIEnv * env, jclass __jni, jlong cppHandle, jstring jname)
00382 {
00383 NodeHandle *handle = (NodeHandle *) cppHandle;
00384 return makeString(env, handle->resolveName(getString(env, jname)));
00385 }
00386
00387
00388 JNIEXPORT jstring JNICALL Java_ros_roscpp_JNI_getPackageLocation
00389 (JNIEnv * env, jclass __jni, jstring jname)
00390 {
00391 string pkgName = getString(env,jname);
00392
00393 char a1[21], a2[21], a3[1025];
00394 snprintf(a1, 20, "rospack");
00395 snprintf(a2, 20, "find");
00396 snprintf(a3, 1024, "%s", pkgName.c_str());
00397 char* argv[3] = {a1, a2, a3};
00398 std::string retval = "";
00399 try {
00400 rospack::ROSPack rp;
00401 rp.run(3, argv);
00402 retval = rp.getOutput();
00403 retval.resize(retval.size()-1);
00404 }
00405 catch(std::runtime_error &e) {
00406 fprintf(stderr, "[rospack] %s\n", e.what());
00407 }
00408
00409 return makeString(env, retval);
00410 }
00411
00412
00413
00414
00415
00416 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_logDebug
00417 (JNIEnv * env, jclass __jni, jstring jmessage)
00418 {
00419 ROS_DEBUG(getString(env,jmessage).c_str());
00420 }
00421
00422 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_logInfo
00423 (JNIEnv * env, jclass __jni, jstring jmessage)
00424 {
00425 ROS_INFO(getString(env,jmessage).c_str());
00426 }
00427
00428 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_logWarn
00429 (JNIEnv * env, jclass __jni, jstring jmessage)
00430 {
00431 ROS_WARN(getString(env,jmessage).c_str());
00432 }
00433
00434 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_logError
00435 (JNIEnv * env, jclass __jni, jstring jmessage)
00436 {
00437 ROS_ERROR(getString(env,jmessage).c_str());
00438 }
00439
00440 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_logFatal
00441 (JNIEnv * env, jclass __jni, jstring jmessage)
00442 {
00443 ROS_FATAL(getString(env,jmessage).c_str());
00444 }
00445
00446
00447
00448
00449
00450
00451
00452
00453 JNIEXPORT jobject JNICALL Java_ros_roscpp_JNI_now
00454 (JNIEnv * env, jclass __jni) {
00455 ros::Time t = ros::Time::now();
00456 jobject ret = env->NewObject(jTime, jTimeCtor, t.sec, t.nsec);
00457 return ret;
00458 }
00459
00460 JNIEXPORT jobjectArray JNICALL Java_ros_roscpp_JNI_getSubscribedTopics
00461 (JNIEnv * env, jclass __jni, jlong cppHandle)
00462 {
00463
00464
00465 vector<string> topics;
00466 ros::this_node::getSubscribedTopics(topics);
00467
00468 int sz = topics.size();
00469 jobjectArray oa = env->NewObjectArray(sz, jString, env->NewStringUTF(""));
00470 if (oa == NULL) return NULL;
00471
00472 for(int i = 0; i < sz; i++) {
00473 env->SetObjectArrayElement(oa, i, makeString(env, topics[i]));
00474 }
00475
00476 return oa;
00477 }
00478
00479 JNIEXPORT jobjectArray JNICALL Java_ros_roscpp_JNI_getAdvertisedTopics
00480 (JNIEnv * env, jclass __jni, jlong cppHandle)
00481 {
00482
00483
00484 vector<string> topics;
00485 ros::this_node::getAdvertisedTopics(topics);
00486
00487 int sz = topics.size();
00488 jobjectArray oa = env->NewObjectArray(sz, jString, env->NewStringUTF(""));
00489 if (oa == NULL) return NULL;
00490
00491 for(int i = 0; i < sz; i++) {
00492 env->SetObjectArrayElement(oa, i, makeString(env, topics[i]));
00493 }
00494
00495 return oa;
00496 }
00497
00498 JNIEXPORT jobjectArray JNICALL Java_ros_roscpp_JNI_getPublishedTopics
00499 (JNIEnv * env, jclass __jni, jlong cppHandle)
00500 {
00501
00502
00503 vector<ros::master::TopicInfo> vtopics;
00504 ros::master::getTopics(vtopics);
00505
00506 int sz = vtopics.size();
00507 jobjectArray oa = env->NewObjectArray(sz * 3, jString, env->NewStringUTF(""));
00508 if (oa == NULL) return NULL;
00509
00510 for(int i = 0; i < sz; i++) {
00511 env->SetObjectArrayElement(oa, i * 3, env->NewStringUTF(vtopics[i].name.c_str()));
00512 env->SetObjectArrayElement(oa, i * 3 + 1, env->NewStringUTF(vtopics[i].datatype.c_str()));
00513
00514
00515 env->SetObjectArrayElement(oa, i * 3 + 2, env->NewStringUTF(""));
00516 }
00517
00518 return oa;
00519 }
00520
00521
00522
00523
00524
00525
00526
00527 JNIEXPORT jboolean JNICALL Java_ros_roscpp_JNI_hasParam
00528 (JNIEnv * env, jclass __jni, jlong cppHandle, jstring jparam)
00529 {
00530 NodeHandle *handle = (NodeHandle *) cppHandle;
00531 return handle->hasParam(getString(env, jparam));
00532 }
00533
00534 JNIEXPORT jboolean JNICALL Java_ros_roscpp_JNI_getBooleanParam
00535 (JNIEnv * env, jclass __jni, jlong cppHandle, jstring jparam, jboolean cache)
00536 {
00537 NodeHandle *handle = (NodeHandle *) cppHandle;
00538 bool ret;
00539 if (!handle->getParam(getString(env, jparam), ret)) {
00540 env->ThrowNew(jRosException, "Param could not be fetched!");
00541 return false;
00542 }
00543 return ret;
00544 }
00545
00546 JNIEXPORT jint JNICALL Java_ros_roscpp_JNI_getIntParam
00547 (JNIEnv * env, jclass __jni, jlong cppHandle, jstring jparam, jboolean cache)
00548 {
00549 NodeHandle *handle = (NodeHandle *) cppHandle;
00550 int ret;
00551 if (!handle->getParam(getString(env, jparam), ret)) {
00552 env->ThrowNew(jRosException, "Param could not be fetched!");
00553 return 0;
00554 }
00555 return ret;
00556 }
00557
00558 JNIEXPORT jdouble JNICALL Java_ros_roscpp_JNI_getDoubleParam
00559 (JNIEnv * env, jclass __jni, jlong cppHandle, jstring jparam, jboolean cache)
00560 {
00561 NodeHandle *handle = (NodeHandle *) cppHandle;
00562 double ret;
00563 if (!handle->getParam(getString(env, jparam), ret)) {
00564 env->ThrowNew(jRosException, "Param could not be fetched!");
00565 return 0;
00566 }
00567 return ret;
00568 }
00569
00570 JNIEXPORT jstring JNICALL Java_ros_roscpp_JNI_getStringParam
00571 (JNIEnv * env, jclass __jni, jlong cppHandle, jstring jparam, jboolean cache)
00572 {
00573 NodeHandle *handle = (NodeHandle *) cppHandle;
00574 string ret;
00575 if (!handle->getParam(getString(env, jparam), ret)) {
00576 env->ThrowNew(jRosException, "Param could not be fetched!");
00577 return 0;
00578 }
00579 return makeString(env, ret);
00580 }
00581
00582
00583
00584 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_setParam__JLjava_lang_String_2Z
00585 (JNIEnv * env, jclass __jni, jlong cppHandle, jstring jparam, jboolean val)
00586 {
00587 NodeHandle *handle = (NodeHandle *) cppHandle;
00588 return handle->setParam(getString(env, jparam), val);
00589 }
00590
00591 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_setParam__JLjava_lang_String_2I
00592 (JNIEnv * env, jclass __jni, jlong cppHandle, jstring jparam, jint val)
00593 {
00594 NodeHandle *handle = (NodeHandle *) cppHandle;
00595 return handle->setParam(getString(env, jparam), (int)val);
00596 }
00597
00598
00599 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_setParam__JLjava_lang_String_2D
00600 (JNIEnv * env, jclass __jni, jlong cppHandle, jstring jparam, jdouble val)
00601 {
00602 NodeHandle *handle = (NodeHandle *) cppHandle;
00603 return handle->setParam(getString(env, jparam), val);
00604 }
00605
00606
00607 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_setParam__JLjava_lang_String_2Ljava_lang_String_2
00608 (JNIEnv * env, jclass __jni, jlong cppHandle, jstring jparam, jstring val)
00609 {
00610 NodeHandle *handle = (NodeHandle *) cppHandle;
00611 return handle->setParam(getString(env, jparam), getString(env, val));
00612 }
00613
00614
00615
00616
00617
00618
00619
00620
00621
00622
00623 class JavaMessage : public ros::Message
00624 {
00625 public:
00626 jobject _message;
00627
00628 JavaMessage(jobject message) : _message(getJNIEnv()->NewGlobalRef(message)) {}
00629
00630 JavaMessage(const JavaMessage& r) : Message()
00631 {
00632
00633 JNIEnv * env = getJNIEnv();
00634 _message = env->CallObjectMethod(r._message,jMessageClone);
00635 MY_ROS_ASSERT(_message && dieOnException(env));
00636 _message = env->NewGlobalRef(_message);
00637 }
00638
00639 virtual ~JavaMessage() {
00640 getJNIEnv()->DeleteGlobalRef(_message);
00641 }
00642
00643 virtual void replaceContents (jobject newMessage) {
00644
00645 JNIEnv * env = getJNIEnv();
00646 env->DeleteGlobalRef(_message);
00647 _message = env->NewGlobalRef(newMessage);
00648 MY_ROS_ASSERT(_message && dieOnException(env));
00649 }
00650
00651 virtual const string __getDataType() const {
00652
00653 JNIEnv * env = getJNIEnv();
00654 jstring s = (jstring) env->CallObjectMethod(_message, jMessageGetDataType);
00655 MY_ROS_ASSERT(s && dieOnException(env));
00656
00657 return getString(env, s);
00658 }
00659
00660 virtual const string __getMD5Sum() const {
00661
00662 JNIEnv * env = getJNIEnv();
00663 jstring s = (jstring) env->CallObjectMethod(_message, jMessageGetMD5Sum);
00664 MY_ROS_ASSERT(s && dieOnException(env));
00665
00666 return getString(env, s);
00667 }
00668
00669 virtual const string __getServerMD5Sum() const {
00670
00671 JNIEnv * env = getJNIEnv();
00672 jstring s = (jstring) env->CallObjectMethod(_message, jMessageGetServerMD5Sum);
00673 MY_ROS_ASSERT(s && dieOnException(env));
00674
00675 return getString(env, s);
00676 }
00677
00678 virtual const string __getMessageDefinition() const {
00679
00680 JNIEnv * env = getJNIEnv();
00681 jstring s = (jstring) env->CallObjectMethod(_message, jMessageGetMessageDefinition);
00682 MY_ROS_ASSERT(s && dieOnException(env));
00683
00684 return getString(env, s);
00685 }
00686
00687 uint32_t serializationLength() const {
00688
00689 JNIEnv * env = getJNIEnv();
00690 int len = getJNIEnv()->CallIntMethod(_message, jMessageSerializationLength);
00691 dieOnException(env);
00692
00693 return len;
00694 }
00695
00696 virtual uint8_t *serialize(uint8_t *writePtr, uint32_t seqid) const {
00697
00698 JNIEnv * env = getJNIEnv();
00699 uint32_t len = serializationLength();
00700 jobject bb = env->NewDirectByteBuffer(writePtr, len);
00701 MY_ROS_ASSERT(bb && dieOnException(env));
00702 bb = env->CallObjectMethod(bb, jByteBufferOrder, jByteOrderLittleEndian);
00703 MY_ROS_ASSERT(bb && dieOnException(env));
00704 env->CallObjectMethod(_message, jMessageSerialize, bb, seqid);
00705 dieOnException(env);
00706 return writePtr + len;
00707 }
00708
00709 virtual uint8_t *deserialize(uint8_t *readPtr) {
00710
00711 JNIEnv * env = getJNIEnv();
00712 int sz = __serialized_length;
00713 if (sz == 0) {
00714
00715 return readPtr;
00716 }
00717 jobject bb = env->NewDirectByteBuffer(readPtr, sz);
00718 MY_ROS_ASSERT(bb && dieOnException(env));
00719 bb = env->CallObjectMethod(bb, jByteBufferOrder, jByteOrderLittleEndian);
00720 MY_ROS_ASSERT(bb && dieOnException(env));
00721 env->CallObjectMethod(_message, jMessageDeserialize, bb);
00722 dieOnException(env);
00723 return readPtr + sz;
00724 }
00725 };
00726
00727
00728
00729
00730
00731
00732 #if ROS_NEW_SERIALIZATION_API
00733 class SubscriptionMessage
00734 {
00735 public:
00736 jobject _scb;
00737 JavaMessage _msg;
00738 string md5, datatype;
00739
00740 SubscriptionMessage(jobject scb, jobject tmpl) : _scb(getJNIEnv()->NewGlobalRef(scb)), _msg(tmpl) {
00741 md5 = _msg.__getMD5Sum();
00742 datatype = _msg.__getDataType();
00743 }
00744
00745 ~SubscriptionMessage() { getJNIEnv()->DeleteGlobalRef(_scb); }
00746
00747 boost::shared_ptr<JavaMessage> create() { return boost::shared_ptr<JavaMessage>(new JavaMessage(_msg)); }
00748 void callback(const boost::shared_ptr<JavaMessage const>& msg)
00749 {
00750 getJNIEnv()->CallVoidMethod(_scb, jSubscriberCallbackCall, msg->_message);
00751 }
00752
00753 std::string getMD5Sum() { return md5; }
00754 std::string getDataType() { return datatype; }
00755 };
00756 #else
00757 class JavaSubscriptionMessageHelper : public ros::SubscriptionMessageHelper {
00758 public:
00759 jobject _scb;
00760 JavaMessage _msg;
00761 string md5, datatype;
00762
00763 JavaSubscriptionMessageHelper(jobject scb, jobject tmpl) : _scb(getJNIEnv()->NewGlobalRef(scb)), _msg(tmpl) {
00764 md5 = _msg.__getMD5Sum();
00765 datatype = _msg.__getDataType();
00766 }
00767 ~JavaSubscriptionMessageHelper() { getJNIEnv()->DeleteGlobalRef(_scb); }
00768
00769 virtual MessagePtr create() { return boost::shared_ptr<Message>(new JavaMessage(_msg)); }
00770
00771 virtual std::string getMD5Sum() { return md5; }
00772 virtual std::string getDataType() { return datatype; }
00773
00774 virtual void call(const MessagePtr &msg) {
00775 getJNIEnv()->CallVoidMethod(_scb, jSubscriberCallbackCall, ((JavaMessage *)msg.get())->_message);
00776 }
00777 };
00778 #endif
00779
00780 JNIEXPORT jlong JNICALL Java_ros_roscpp_JNI_createSubCallback
00781 (JNIEnv * env, jclass __jni, jobject jcallback, jobject messageTemplate)
00782 {
00783 #if ROS_NEW_SERIALIZATION_API
00784 return (jlong) new boost::shared_ptr<SubscriptionMessage>(new SubscriptionMessage(jcallback, messageTemplate));
00785 #else
00786 return (jlong) new boost::shared_ptr<JavaSubscriptionMessageHelper>(new JavaSubscriptionMessageHelper(jcallback, messageTemplate));
00787 #endif
00788 }
00789
00790 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_deleteSubCallback
00791 (JNIEnv * env, jclass __jni, jlong cppCallback)
00792 {
00793 #if ROS_NEW_SERIALIZATION_API
00794 boost::shared_ptr<SubscriptionMessage> *callback = (boost::shared_ptr<SubscriptionMessage> *) cppCallback;
00795 delete callback;
00796 #else
00797 boost::shared_ptr<JavaSubscriptionMessageHelper> *callback = (boost::shared_ptr<JavaSubscriptionMessageHelper> *) cppCallback;
00798 delete callback;
00799 #endif
00800 }
00801
00802 JNIEXPORT jlong JNICALL Java_ros_roscpp_JNI_subscribe
00803 (JNIEnv * env, jclass __jni, jlong cppHandle, jstring jtopic, jlong cppCallback, jint queueSize)
00804 {
00805 NodeHandle *handle = (NodeHandle *) cppHandle;
00806 #if ROS_NEW_SERIALIZATION_API
00807 boost::shared_ptr<SubscriptionMessage> *callback = (boost::shared_ptr<SubscriptionMessage> *) cppCallback;
00808 SubscribeOptions so(getString(env, jtopic), queueSize, (*callback)->getMD5Sum(), (*callback)->getDataType());
00809 so.helper.reset(new SubscriptionCallbackHelperT<const boost::shared_ptr<JavaMessage const>&>(boost::bind(&SubscriptionMessage::callback, *callback, _1),
00810 boost::bind(&SubscriptionMessage::create, *callback)));
00811 #else
00812 boost::shared_ptr<SubscriptionMessageHelper> *callback = (boost::shared_ptr<SubscriptionMessageHelper> *) cppCallback;
00813 SubscribeOptions so(getString(env, jtopic), queueSize, *callback);
00814 #endif
00815
00816
00817 Subscriber subscriber = handle->subscribe(so);
00818 if (subscriber) return (jlong) new Subscriber(subscriber);
00819 return 0;
00820 }
00821
00822 JNIEXPORT jboolean JNICALL Java_ros_roscpp_JNI_isSubscriberValid
00823 (JNIEnv * env, jclass __jni, jlong cppSubscriber)
00824 {
00825 Subscriber *subscriber = (Subscriber *) cppSubscriber;
00826 return (*subscriber) && ros::ok() ? true : false;
00827 }
00828
00829 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_shutdownSubscriber
00830 (JNIEnv * env, jclass __jni, jlong cppSubscriber)
00831 {
00832 Subscriber *subscriber = (Subscriber *) cppSubscriber;
00833 delete subscriber;
00834 }
00835
00836
00837
00838
00839
00840
00841
00842 JNIEXPORT jlong JNICALL Java_ros_roscpp_JNI_advertise
00843 (JNIEnv * env, jclass __jni, jlong cppHandle, jstring jtopic, jobject jmessage, jint queueSize, jboolean latch)
00844 {
00845 NodeHandle *handle = (NodeHandle *) cppHandle;
00846 JavaMessage msg(jmessage);
00847 AdvertiseOptions ao(getString(env, jtopic), queueSize, msg.__getMD5Sum(), msg.__getDataType(), msg.__getMessageDefinition());
00848 ao.latch = latch;
00849 Publisher publisher = handle->advertise(ao);
00850 if (publisher) return (jlong) new Publisher(publisher);
00851 return 0;
00852 }
00853
00854 JNIEXPORT jint JNICALL Java_ros_roscpp_JNI_getNumSubscribers
00855 (JNIEnv * env, jclass __jni, jlong cppPublisher) {
00856 Publisher *publisher = (Publisher *) cppPublisher;
00857 return publisher->getNumSubscribers();
00858 }
00859
00860 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_publish
00861 (JNIEnv * env, jclass __jni, jlong cppPublisher, jobject jmessage) {
00862 Publisher *publisher = (Publisher *) cppPublisher;
00863 JavaMessage message(jmessage);
00864 publisher->publish(message);
00865 }
00866
00867 JNIEXPORT jboolean JNICALL Java_ros_roscpp_JNI_isPublisherValid
00868 (JNIEnv * env, jclass __jni, jlong cppPublisher)
00869 {
00870 Publisher *publisher = (Publisher *) cppPublisher;
00871 return (*publisher) && ros::ok() ? true : false;
00872 }
00873
00874
00875 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_shutdownPublisher
00876 (JNIEnv * env, jclass __jni, jlong cppPublisher)
00877 {
00878 Publisher *publisher = (Publisher *) cppPublisher;
00879 delete publisher;
00880 }
00881
00882
00883
00884
00885
00886
00887
00888 JNIEXPORT jlong JNICALL Java_ros_roscpp_JNI_serviceClient
00889 (JNIEnv * env, jclass __jni, jlong cppHandle, jstring name, jstring md5, jboolean persist, jobjectArray jheaderValues)
00890 {
00891 NodeHandle *handle = (NodeHandle *) cppHandle;
00892 map<string, string> headers;
00893 int len = env->GetArrayLength(jheaderValues);
00894 for(int i = 0; i < len; i+=2) headers[getString(env, (jstring) env->GetObjectArrayElement(jheaderValues,i))] = getString(env, (jstring) env->GetObjectArrayElement(jheaderValues,i+1));
00895
00896 ServiceClientOptions sco(getString(env, name), getString(env, md5), persist, headers);
00897 ServiceClient client = handle->serviceClient(sco);
00898 if (client) return (jlong) new ServiceClient(client);
00899 return 0;
00900 }
00901
00902 JNIEXPORT jboolean JNICALL Java_ros_roscpp_JNI_callService
00903 (JNIEnv * env, jclass __jni, jlong cppServiceClient, jobject jrequest, jobject jresponse, jstring md5)
00904 {
00905 ServiceClient *client = (ServiceClient *) cppServiceClient;
00906 JavaMessage request(jrequest), response(jresponse);
00907
00908 return client->call(request, response, getString(env, md5));
00909 }
00910
00911 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_shutdownServiceClient
00912 (JNIEnv * env, jclass __jni, jlong cppServiceClient)
00913 {
00914 ServiceClient *client = (ServiceClient *) cppServiceClient;
00915 delete client;
00916 }
00917
00918
00919
00920
00921
00922
00923 #if ROS_NEW_SERIALIZATION_API
00924 class ServiceMessage
00925 {
00926 public:
00927 jobject _scb;
00928 JavaMessage _req, _res;
00929 string md5, datatype, requestDataType, responseDataType;
00930
00931 ServiceMessage(jobject scb, string smd5, string sdatatype, jobject req, jobject res)
00932 : _scb(getJNIEnv()->NewGlobalRef(scb)), _req(req), _res(res), md5(smd5), datatype(sdatatype) {
00933 requestDataType = _req.__getDataType();
00934 responseDataType = _res.__getDataType();
00935 }
00936 ~ServiceMessage() { getJNIEnv()->DeleteGlobalRef(_scb); }
00937
00938 boost::shared_ptr<JavaMessage> createRequest() { return boost::shared_ptr<JavaMessage>(new JavaMessage(_req)); }
00939 boost::shared_ptr<JavaMessage> createResponse() { return boost::shared_ptr<JavaMessage>(new JavaMessage(_res)); }
00940
00941 std::string getMD5Sum() { return md5; }
00942 std::string getDataType() { return datatype; }
00943 std::string getRequestDataType() { return requestDataType; }
00944 std::string getResponseDataType() { return responseDataType; }
00945
00946 bool callback(JavaMessage& req, JavaMessage& res) {
00947 JNIEnv * env = getJNIEnv();
00948 jobject jresponse = env->CallObjectMethod(_scb, jServiceCallbackCall, req._message);
00949 MY_ROS_ASSERT(jresponse != 0 && dieOnException(env));
00950 res.replaceContents(jresponse);
00951 return true;
00952 }
00953 };
00954 #else
00955 class JavaServiceMessageHelper : public ros::ServiceMessageHelper {
00956 public:
00957 jobject _scb;
00958 JavaMessage _req, _res;
00959 string md5, datatype, requestDataType, responseDataType;
00960
00961 JavaServiceMessageHelper(jobject scb, string smd5, string sdatatype, jobject req, jobject res)
00962 : _scb(getJNIEnv()->NewGlobalRef(scb)), _req(req), _res(res), md5(smd5), datatype(sdatatype) {
00963 requestDataType = _req.__getDataType();
00964 responseDataType = _res.__getDataType();
00965 }
00966 ~JavaServiceMessageHelper() { getJNIEnv()->DeleteGlobalRef(_scb); }
00967
00968 virtual MessagePtr createRequest() { return boost::shared_ptr<Message>(new JavaMessage(_req)); }
00969 virtual MessagePtr createResponse() { return boost::shared_ptr<Message>(new JavaMessage(_res)); }
00970
00971 virtual std::string getMD5Sum() { return md5; }
00972 virtual std::string getDataType() { return datatype; }
00973 virtual std::string getRequestDataType() { return requestDataType; }
00974 virtual std::string getResponseDataType() { return responseDataType; }
00975
00976 virtual bool call(const MessagePtr &req, const MessagePtr &res) {
00977 JNIEnv * env = getJNIEnv();
00978 jobject jresponse = env->CallObjectMethod(_scb, jServiceCallbackCall, ((JavaMessage *)req.get())->_message);
00979 MY_ROS_ASSERT(jresponse != 0 && dieOnException(env));
00980 ((JavaMessage *)res.get())->replaceContents(jresponse);
00981 return true;
00982 }
00983 };
00984 #endif
00985
00986
00987 JNIEXPORT jlong JNICALL Java_ros_roscpp_JNI_createSrvCallback
00988 (JNIEnv * env, jclass __jni, jobject jcallback, jstring serviceMD5, jstring serviceDataType, jobject jreq, jobject jres)
00989 {
00990 #if ROS_NEW_SERIALIZATION_API
00991 ServiceMessage *helper = new ServiceMessage(jcallback, getString(env, serviceMD5), getString(env, serviceDataType), jreq, jres);
00992 return (jlong) new boost::shared_ptr<ServiceMessage>(helper);
00993 #else
00994 JavaServiceMessageHelper *helper = new JavaServiceMessageHelper(jcallback, getString(env, serviceMD5), getString(env, serviceDataType), jreq, jres);
00995 return (jlong) new boost::shared_ptr<JavaServiceMessageHelper>(helper);
00996 #endif
00997 }
00998
00999 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_deleteSrvCallback
01000 (JNIEnv * env, jclass __jni, jlong cppCallback)
01001 {
01002 #if ROS_NEW_SERIALIZATION_API
01003 boost::shared_ptr<ServiceMessage> *callback = (boost::shared_ptr<ServiceMessage> *) cppCallback;
01004 delete callback;
01005 #else
01006 boost::shared_ptr<JavaServiceMessageHelper> *callback = (boost::shared_ptr<JavaServiceMessageHelper> *) cppCallback;
01007 delete callback;
01008 #endif
01009 }
01010
01011 JNIEXPORT jlong JNICALL Java_ros_roscpp_JNI_advertiseService
01012 (JNIEnv * env, jclass __jni, jlong cppHandle, jstring name, jlong cppCallback)
01013 {
01014 NodeHandle *handle = (NodeHandle *) cppHandle;
01015 #if ROS_NEW_SERIALIZATION_API
01016 boost::shared_ptr<ServiceMessage> *callback = (boost::shared_ptr<ServiceMessage> *) cppCallback;
01017 AdvertiseServiceOptions aso;
01018 aso.service = getString(env, name);
01019 aso.md5sum = (*callback)->getMD5Sum();
01020 aso.datatype = (*callback)->getDataType();
01021 aso.req_datatype = (*callback)->getRequestDataType();
01022 aso.res_datatype = (*callback)->getResponseDataType();
01023 aso.helper.reset(new ServiceCallbackHelperT<ServiceSpec<JavaMessage, JavaMessage> >(boost::bind(&ServiceMessage::callback, *callback, _1, _2),
01024 boost::bind(&ServiceMessage::createRequest, *callback),
01025 boost::bind(&ServiceMessage::createResponse, *callback)));
01026 #else
01027 boost::shared_ptr<ServiceMessageHelper> *callback = (boost::shared_ptr<ServiceMessageHelper> *) cppCallback;
01028 AdvertiseServiceOptions aso(getString(env, name), *callback);
01029 #endif
01030
01031 ServiceServer server = handle->advertiseService(aso);
01032 if (server) return (jlong) new ServiceServer(server);
01033 return 0;
01034 }
01035
01036 JNIEXPORT jboolean JNICALL Java_ros_roscpp_JNI_isServiceServerValid
01037 (JNIEnv * env, jclass __jni, jlong cppServiceServer)
01038 {
01039 ServiceServer *server = (ServiceServer *) cppServiceServer;
01040 return (*server) && ros::ok() ? true : false;
01041 }
01042
01043 JNIEXPORT void JNICALL Java_ros_roscpp_JNI_shutdownServiceServer
01044 (JNIEnv * env, jclass __jni, jlong cppServiceServer)
01045 {
01046 ServiceServer *server = (ServiceServer *) cppServiceServer;
01047 delete server;
01048 }
01049
01050
01051