rosR.cpp
Go to the documentation of this file.
00001 #include "rosR.h"
00002 
00003 void rrosSpinOnce()     { ros::spinOnce(); }
00004 void rrosSpin()                 { ros::spin(); }
00005 bool rrosOK()                   { return ros::ok(); }
00006 double rrosTimeNow()    {
00007         //std::ostringstream out;
00008         //out << std::fixed << std::setprecision(16) << ros::Time::now().toSec();
00009         //return const_cast<char*>(out.str().c_str());
00010         return ros::Time::now().toSec();
00011 }
00012 
00013 void rrosLog(char *message, unsigned char type){
00014         switch(type){
00015                 case 0: { ROS_DEBUG("%s",message); break;}
00016                 case 1: { ROS_INFO("%s",message); break;}
00017                 case 2: { ROS_WARN("%s",message); break;}
00018                 case 3: { ROS_ERROR("%s",message); break;}
00019                 case 4: { ROS_FATAL("%s",message); break;}
00020                 default: {      ROS_INFO("%s",message); }
00021         }
00022 }
00023 
00024 ros::NodeHandle* rrosInitNode(char *name){
00025         int argc = 0;
00026 
00027         ros::init(argc, NULL, name);
00028         ros::NodeHandle *handle = new ros::NodeHandle();
00029         
00030         return handle;
00031 }
00032 


rosR
Author(s): André Dietrich, Sebastian Zug
autogenerated on Sun Jan 5 2014 11:10:28