Go to the documentation of this file.
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>
51 class AbstractDriverNode
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;
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);
203 stat.
summary(2,
"not running");
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;
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());
280 status.
summaryf(0,
"Device ID is %s", ID.c_str());
284 status.
summaryf(2,
"Error reading Device ID");
324 std::string last_status_message;
339 ROS_ERROR(
"%s", new_status_message.c_str());
341 last_status_message = new_status_message;
360 ROS_ERROR(
"ROS thread did not die after two seconds. Pretending that it did. This is probably a bad sign.");
void addTask(DiagnosticTask *t)
dynamic_reconfigure::Server< Config > reconfigure_server_
diagnostic_updater::FunctionDiagnosticTask driver_status_standard_diagnostic_
self_test::TestRunner self_test_
void runTest(diagnostic_updater::DiagnosticStatusWrapper &status)
void openTest(diagnostic_updater::DiagnosticStatusWrapper &status)
static int ctrl_c_hit_count_
static void sigCalled(int sig)
void add(const std::string &key, const bool &b)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
virtual void reconfigureHook(int level)=0
boost::recursive_mutex mutex_
void statusDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Driver::state_t drv_state_t
const std::string getStateName()
virtual void addOpenedTests()=0
bool goState(state_t target)
void closeTest(diagnostic_updater::DiagnosticStatusWrapper &status)
ROSCPP_DECL void shutdown()
diagnostic_updater::CompositeDiagnosticTask driver_status_diagnostic_
void reliableGoStateTest(diagnostic_updater::DiagnosticStatusWrapper &status, drv_state_t target_state)
int main(int argc, char **argv, std::string name)
diagnostic_updater::Updater diagnostic_
boost::shared_ptr< boost::thread > ros_thread_
void add(const std::string &name, TaskFunction f)
void summary(const diagnostic_msgs::DiagnosticStatus &src)
virtual void addStoppedTests()=0
bool getRecoveryComplete()
static const state_t OPENED
virtual std::string getID()=0
void clearRecoveryComplete()
ros::NodeHandle private_node_handle_
void interruptionTest(diagnostic_updater::DiagnosticStatusWrapper &status)
ros::NodeHandle node_handle_
void stopTest(diagnostic_updater::DiagnosticStatusWrapper &status)
void setID(std::string id)
static const state_t CLOSED
static const state_t RUNNING
virtual void addDiagnostics()=0
void resumeTest(diagnostic_updater::DiagnosticStatusWrapper &status)
void prepareDiagnostics()
int num_subscribed_topics_
virtual void addRunningTests()=0
void reconfigure(Config &config, uint32_t level)
void idTest(diagnostic_updater::DiagnosticStatusWrapper &status)
const std::string getStatusMessage()
void add(const std::string &name, TaskFunction f)
drv_state_t pre_self_test_driver_state_
static void hupCalled(int sig)
void summaryf(unsigned char lvl, const char *format,...)
DriverNode(ros::NodeHandle &nh)
driver_base
Author(s): Blaise Gassend
autogenerated on Wed Mar 2 2022 00:11:50