00001 #include "rosR.h" 00002 00003 void rrosSpinOnce() { ros::spinOnce(); } 00004 void rrosSpin() { ros::spin(); } 00005 bool rrosOK() { return ros::ok(); } 00006 00007 double rrosTimeNow() { 00008 return ros::Time::now().toSec(); 00009 } 00010 00011 void rrosLog(char *message, unsigned char type){ 00012 switch(type){ 00013 case 0: { ROS_DEBUG("%s",message); break;} 00014 case 1: { ROS_INFO("%s",message); break;} 00015 case 2: { ROS_WARN("%s",message); break;} 00016 case 3: { ROS_ERROR("%s",message); break;} 00017 case 4: { ROS_FATAL("%s",message); break;} 00018 default:{ ROS_INFO("%s",message); } 00019 } 00020 } 00021 00022 NodeR* rrosInitNode(char *name){ 00023 int argc = 0; 00024 ros::init(argc, NULL, name); 00025 return new NodeR(); 00026 }