36 #ifndef __DRIVER_BASE__DRIVER_NODE_H__ 37 #define __DRIVER_BASE__DRIVER_NODE_H__ 42 #include <boost/thread.hpp> 43 #include <boost/bind.hpp> 44 #include <driver_base/SensorLevels.h> 46 #include <dynamic_reconfigure/server.h> 58 ROS_WARN(
"Unexpected SIGHUP caught. Ignoring it.");
67 template <
class DriverType>
68 int main(
int argc,
char **argv, std::string name)
78 DriverType driver(nh);
83 template <
class Driver>
88 typedef typename Driver::Config
Config;
92 virtual void addDiagnostics() = 0;
93 virtual void addStoppedTests() = 0;
94 virtual void addOpenedTests() = 0;
95 virtual void addRunningTests() = 0;
96 virtual void reconfigureHook(
int level) = 0;
136 ROS_DEBUG(
"Reconfigure called at level %x.", level);
137 boost::recursive_mutex::scoped_lock lock(driver_.
mutex_);
139 drv_state_t orig_state = driver_.
getState();
141 if ((level | driver_base::SensorLevels::RECONFIGURE_STOP) == level)
145 ROS_ERROR(
"Failed to stop streaming before reconfiguring. Reconfiguration may fail.");
148 if ((level | driver_base::SensorLevels::RECONFIGURE_CLOSE) == level)
152 ROS_ERROR(
"Failed to close device before reconfiguring. Reconfiguration may fail.");
155 driver_.config_update(config, level);
156 config = driver_.config_;
157 reconfigureHook(level);
193 driver_status_diagnostic_.
addTask(&driver_status_standard_diagnostic_);
194 diagnostic_.
add(driver_status_diagnostic_);
203 stat.
summary(2,
"not running");
226 pre_self_test_driver_state_ = driver_.
getState();
231 if (num_subscribed_topics_ > 0)
232 status.
summary(1,
"There were active subscribers. Running of self test interrupted operations.");
236 status.
summary(0,
"No operation interrupted.");
241 const int max_tries = 5;
244 drv_state_t current_state;
245 for (retries = 0; retries < max_tries; retries++)
251 if (current_state == target_state)
262 if (retries >= max_tries)
263 status.
summaryf(2,
"Failed to go to %s state despite %u retries, now in state %s.", target_state_name.c_str(), retries, current_state_name.c_str());
265 status.
summaryf(1,
"Successfully went to state %s after %u retries.", target_state_name.c_str(), retries);
267 status.
summaryf(0,
"Successfully went to state %s.", target_state_name.c_str());
277 std::string ID = driver_.
getID();
280 status.
summaryf(0,
"Device ID is %s", ID.c_str());
281 self_test_.
setID(ID);
284 status.
summaryf(2,
"Error reading Device ID");
304 reliableGoStateTest(status, pre_self_test_driver_state_);
312 prepareDiagnostics();
315 reconfigure_server_.setCallback(f);
317 ros_thread_.reset(
new boost::thread(boost::bind(&
ros::spin)));
324 std::string last_status_message;
331 boost::recursive_mutex::scoped_lock lock_(driver_.
mutex_);
339 ROS_ERROR(
"%s", new_status_message.c_str());
341 last_status_message = new_status_message;
358 if (ros_thread_ && !ros_thread_->timed_join((boost::posix_time::milliseconds) 2000))
360 ROS_ERROR(
"ROS thread did not die after two seconds. Pretending that it did. This is probably a bad sign.");
369 private_node_handle_(
"~"),
370 self_test_(node_handle_),
372 reconfigure_server_(driver_.mutex_,
ros::NodeHandle(
"~")),
373 driver_status_diagnostic_(
"Driver Status"),
374 driver_status_standard_diagnostic_(
"Driver Status",
boost::bind(&
DriverNode::statusDiagnostic, this, _1))
376 num_subscribed_topics_ = 0;
void resumeTest(diagnostic_updater::DiagnosticStatusWrapper &status)
bool getRecoveryComplete()
self_test::TestRunner self_test_
void clearRecoveryComplete()
static const state_t CLOSED
void reliableGoStateTest(diagnostic_updater::DiagnosticStatusWrapper &status, drv_state_t target_state)
static const state_t RUNNING
diagnostic_updater::CompositeDiagnosticTask driver_status_diagnostic_
void runTest(diagnostic_updater::DiagnosticStatusWrapper &status)
void closeTest(diagnostic_updater::DiagnosticStatusWrapper &status)
void summary(unsigned char lvl, const std::string s)
dynamic_reconfigure::Server< Config > reconfigure_server_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void add(const std::string &name, TaskFunction f)
int main(int argc, char **argv, std::string name)
static void hupCalled(int sig)
diagnostic_updater::Updater diagnostic_
void summaryf(unsigned char lvl, const char *format,...)
const std::string getStatusMessage()
int num_subscribed_topics_
ros::NodeHandle private_node_handle_
void interruptionTest(diagnostic_updater::DiagnosticStatusWrapper &status)
DriverNode(ros::NodeHandle &nh)
void idTest(diagnostic_updater::DiagnosticStatusWrapper &status)
drv_state_t pre_self_test_driver_state_
static int ctrl_c_hit_count_
static void sigCalled(int sig)
const std::string getStateName()
bool goState(state_t target)
boost::recursive_mutex mutex_
diagnostic_updater::FunctionDiagnosticTask driver_status_standard_diagnostic_
boost::shared_ptr< boost::thread > ros_thread_
void prepareDiagnostics()
void setID(std::string id)
ROSCPP_DECL void shutdown()
void add(const std::string &key, const T &val)
Driver::state_t drv_state_t
ros::NodeHandle node_handle_
void stopTest(diagnostic_updater::DiagnosticStatusWrapper &status)
void openTest(diagnostic_updater::DiagnosticStatusWrapper &status)
void statusDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
static const state_t OPENED
void reconfigure(Config &config, uint32_t level)
void addTask(DiagnosticTask *t)
virtual std::string getID()=0