$search
00001 #include "ros/ros.h" 00002 #include <iostream> 00003 #include <list> 00004 #include <map> 00005 #include "ros/time.h" 00006 #include "ros/duration.h" 00007 #include "ros/console.h" 00008 //#include <dlfcn.h> 00009 //#include "messageMapper.h" 00010 #include "CsSubscriber.h" 00011 <?messageIncludes?> 00012 00013 using namespace std; 00014 00015 //list<ros::Publisher> pubs; 00016 list<ros::Subscriber> subs; 00017 00018 /* 00019 void *dlhandle; 00020 00021 00022 extern "C" void loadCode(char* lib) { 00023 dlhandle = dlopen(lib,RTLD_NOW|RTLD_GLOBAL); 00024 if (dlhandle == NULL) { 00025 cerr << "Unable to load "<<lib<<endl; 00026 exit(-1); 00027 } 00028 } 00029 */ 00030 00031 extern "C" uint64_t getRosNow() { 00032 ros::Time now = ros::Time::now(); 00033 return ((uint64_t)now.sec)*1000000000ull+(uint64_t)now.nsec; 00034 } 00035 extern "C" void rosSleep(uint32_t ms) { 00036 ros::Duration d = ros::Duration(ms/1000, (ms%1000)*1000000); 00037 d.sleep(); 00038 } 00039 00040 00041 extern "C" void rosInit(char* name, int argc, char** argv, uint32_t initOptions) { 00042 ros::init(argc, argv, name,initOptions); 00043 /*cout<<"Args: "<<argc<<endl; 00044 for(int i=0; i< argc; i++) { 00045 cout << argv[i]<<endl; 00046 }*/ 00047 } 00048 extern "C" void rosShutdown() { 00049 ros::shutdown(); 00050 } 00051 extern "C" bool getRosOk() { 00052 return ros::ok(); 00053 } 00054 extern "C" bool checkMaster() { 00055 return ros::master::check(); 00056 } 00057 00058 00059 extern "C" ros::NodeHandle* getNode(char* name) { 00060 return new ros::NodeHandle(name); 00061 } 00062 00063 extern "C" void destroyNode(ros::NodeHandle* node) { 00064 if(node!=NULL && node->ok()) { 00065 node->shutdown(); 00066 delete node; 00067 } 00068 } 00069 00070 extern "C" ros::Publisher* advertiseTopic(ros::NodeHandle* node, char* topic, uint64_t messageId, int queueSize) { 00071 ros::Publisher tmp; 00072 00073 //RosCs::messageMapper::getTypeSpecificPublisher(node, tmp, topic,messageId,queueSize); 00074 <?cppMakePublisher?> 00075 //ros::Publisher* ptr = (ros::Publisher*)malloc(sizeof(tmp)); 00076 //*ptr = tmp; 00077 ros::Publisher* ptr = new ros::Publisher(tmp); 00078 return ptr; 00079 //pubs.push_back(tmp); 00080 //return &(pubs.back()); 00081 } 00082 00083 00084 00085 00086 <?cppGetSizeOfMessage?> 00087 00088 <?cppArray2RosMethods?> 00089 extern "C" void sendmsg(ros::Publisher* pub, uint64_t messageId, int* data) { 00090 switch(messageId) { 00091 <?cppSendBody?> 00092 default: 00093 std::cerr << "Unknown message id in sendmsg: "<<messageId<<std::endl; 00094 } 00095 } 00096 00097 <?cppMessageHandleMethods?> 00098 00099 <?cppSubscriptionMethods?> 00100 00101 extern "C" bool isNodeOk(ros::NodeHandle* node) { 00102 return (node!=NULL && node->ok()); 00103 } 00104 00105 extern "C" void rosDebug(char* str) { 00106 ROS_DEBUG_THROTTLE(5,"%s",str); 00107 } 00108 extern "C" void rosWarn(char* str) { 00109 ROS_WARN_THROTTLE(3,"%s",str); 00110 } 00111 extern "C" void rosError(char* str) { 00112 ROS_ERROR_THROTTLE(1,"%s",str); 00113 } 00114 extern "C" void rosFatal(char* str) { 00115 ROS_FATAL("%s",str); 00116 } 00117 extern "C" void rosInfo(char* str) { 00118 ROS_INFO_THROTTLE(10,"%s",str); 00119 } 00120 00121 extern "C" void stopSubscriber(void** ptr) { 00122 ((RosCs::Runable*)(*ptr))->Shutdown(); 00123 } 00124 extern "C" char* getParam(ros::NodeHandle* node, char* paramName) { 00125 //std::cout<<"here"<<std::endl; 00126 //std::cout<<"param is: "<<paramName<<std::endl; 00127 XmlRpc::XmlRpcValue val; 00128 node->getParam(paramName,val); 00129 stringstream s; 00130 s<<val; 00131 //std::cout<<"called: "<<ok<<" | "<<val<<std::endl; 00132 std::string str = s.str(); 00133 char* ret = (char*)malloc((str.size()+1)*sizeof(char)); 00134 strcpy(ret,str.c_str()); 00135 00136 return ret; 00137 } 00138 extern "C" char* searchParam(ros::NodeHandle* node, char* paramName) { 00139 std::string val; 00140 node->searchParam(paramName,val); 00141 char* ret = (char*)malloc((val.size()+1)*sizeof(char)); 00142 strcpy(ret,val.c_str()); 00143 return ret; 00144 } 00145 extern "C" bool hasParam(ros::NodeHandle* node, char* paramName) { 00146 return node->hasParam(paramName); 00147 } 00148 00149 extern "C" void deleteParam(ros::NodeHandle* node, char* paramName) { 00150 node->deleteParam(paramName); 00151 return; 00152 } 00153 extern "C" void setParamInt(ros::NodeHandle* node, char* key, int val) { 00154 node->setParam(key,val); 00155 return; 00156 } 00157 extern "C" void setParamBool(ros::NodeHandle* node, char* key, bool val) { 00158 node->setParam(key,val); 00159 return; 00160 } 00161 extern "C" void setParamDouble(ros::NodeHandle* node, char* key, double val) { 00162 node->setParam(key,val); 00163 return; 00164 } 00165 extern "C" void setParamString(ros::NodeHandle* node, char* key, char* val) { 00166 node->setParam(key,val); 00167 return; 00168 } 00169 00170 extern "C" void freeCharPtr(char* p) { 00171 free(p); 00172 }