A quick summary, and then on to code samples:
- Build your driver node to be completely ROS-agnostic. In your class, define a series of (private) function pointers to logging functions for you different levels, Debug, Info, Error, etc.
- In your class, define a few "setters" to update these function pointers.
- In your class, create some generic loggers (or use the logging system of your choice), and make these default in the constructor
- In your node, create some wrappers to the ROS functions.
- When constructing the driver object, make sure to also update the logging function pointers to your new ROS function pointers.
C++
I think a decent example of this is @wjwwood's libsegwayrmp library.
To begin with, he typedef's a few functions:
typedef boost::function<void(const std::string&)> DebugMsgCallback;
typedef boost::function<void(const std::string&)> InfoMsgCallback;
typedef boost::function<void(const std::string&)> ErrorMsgCallback;
And then creates private class variables in his hardware driver;
...
private:
DebugMsgCallback debug;
InfoMsgCallback info;
ErrorMsgCallback error;
And he creates three public mutators to update these function pointers:
void setErrorMsgCallback(ErrorMsgCallback);
void setInfoMsgCallback(InfoMsgCallback);
void setDebugMsgCallback(DebugMsgCallback);
The logging functions can be called in your class by simply doing:
this->error("This is an error message")
this->debug("This is a debug message")
this->info("This is an info message")
So now, to use this WITHOUT ROS, you can create three simple callback functions that just log to the console, or modify these for your own logging suite:
inline void defaultDebugMsgCallback(const std::string &msg) {
std::cerr << "SegwayRMP Debug: " << msg << std::endl;
}
inline void defaultInfoMsgCallback(const std::string &msg) {
std::cerr << "SegwayRMP Info: " << msg << std::endl;
}
inline void defaultErrorMsgCallback(const std::string &msg) {
std::cerr << "SegwayRMP Error: " << msg << std::endl;
}
Or, to use it WITH ROS, you can create some functions that wrap the macros:
void handleDebugMessages(const std::string &msg) {ROS_DEBUG("%s",msg.c_str());}
void handleInfoMessages(const std::string &msg) {ROS_INFO("%s",msg.c_str());}
void handleErrorMessages(const std::string &msg) {ROS_ERROR("%s",msg.c_str());}
When you construct the device driver, you can then update these function pointers to your newly-wrapped functions:
this->segway_rmp->setDebugMsgCallback(handleDebugMessages);
this->segway_rmp->setInfoMsgCallback(handleInfoMessages);
this->segway_rmp->setErrorMsgCallback(handleErrorMessages);
Python
You do a similar thing with Python. I create my hardware interfaces to use the default Python logging
built-in. The signature for these functions is:
f(msg, *args)
Which happens to be the same as the ROS logging system.
Using a similar strategy, I create a few function references as class variables:
class DriverObject(object):
def __init__(self, param1, param2, param3, debug=None, info=None, error=None):
self.debug = logging.debug
self.info = logging.info
self.error = logging.error
if debug:
self.debug = debug
if error:
self.error = error
if info:
self.info = info
And to use these functions throughout my class, I simply do:
self.debug("This is a debug message")
self.error("This is an error message"
self.info("This is an info message")
And when I want to use the class within a ROS ... (more)