$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2009, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 // Author: Blaise Gassend 00036 #ifndef __DRIVER_BASE__DRIVER_NODE_H__ 00037 #define __DRIVER_BASE__DRIVER_NODE_H__ 00038 00039 #include <diagnostic_updater/diagnostic_updater.h> 00040 #include <self_test/self_test.h> 00041 #include <ros/node_handle.h> 00042 #include <boost/thread.hpp> 00043 #include <boost/bind.hpp> 00044 #include <driver_base/SensorLevels.h> 00045 #include <signal.h> 00046 #include <dynamic_reconfigure/server.h> 00047 00048 namespace driver_base 00049 { 00050 00051 class AbstractDriverNode 00052 { 00053 static int ctrl_c_hit_count_; 00054 00055 static void hupCalled(int sig) 00056 { 00057 ROS_WARN("Unexpected SIGHUP caught. Ignoring it."); 00058 } 00059 00060 static void sigCalled(int sig) 00061 { 00062 ctrl_c_hit_count_++; 00063 } 00064 }; 00065 00066 template <class DriverType> 00067 int main(int argc, char **argv, std::string name) 00068 { 00071 ros::init(argc, argv, name); 00072 //ros::init(argc, argv, name, ros::init_options::NoSigintHandler); 00073 //signal(SIGINT, &AbstractDriverNode::sigCalled); 00074 //signal(SIGTERM, &AbstractDriverNode::sigCalled); 00075 signal(SIGHUP, &AbstractDriverNode::hupCalled); 00076 ros::NodeHandle nh; 00077 DriverType driver(nh); 00078 return driver.spin(); 00080 } 00081 00082 template <class Driver> 00083 class DriverNode : public AbstractDriverNode 00084 { 00085 public: 00086 //typedef char state_t; 00087 typedef typename Driver::Config Config; 00088 00089 protected: 00090 // Hooks 00091 virtual void addDiagnostics() = 0; 00092 virtual void addStoppedTests() = 0; 00093 virtual void addOpenedTests() = 0; 00094 virtual void addRunningTests() = 0; 00095 virtual void reconfigureHook(int level) = 0; 00096 00097 // Helper classes 00098 ros::NodeHandle node_handle_; 00099 ros::NodeHandle private_node_handle_; 00100 self_test::TestRunner self_test_; 00101 diagnostic_updater::Updater diagnostic_; 00102 00103 Driver driver_; 00104 dynamic_reconfigure::Server<Config> reconfigure_server_; 00105 diagnostic_updater::CompositeDiagnosticTask driver_status_diagnostic_; 00106 // driver_ declaration must precede reconfigure_server_ for constructor 00107 // calling order reasons. 00108 00109 private: 00110 // Subscriber tracking 00111 int num_subscribed_topics_; // Number of topics that have subscribers. 00112 00113 //static const state_t DISABLED = 0; 00114 //static const state_t LAZY_ON = 1; 00115 //static const state_t ALWAYS_ON = 2; 00116 //static const state_t SELF_TEST = 3; 00117 //static const state_t EXITING = 4; 00118 00119 //state_t state_; 00120 00121 boost::shared_ptr<boost::thread> ros_thread_; 00122 00123 int exit_status_; 00124 00125 // The device 00126 typedef typename Driver::state_t drv_state_t; 00127 00128 drv_state_t pre_self_test_driver_state_; 00129 00130 diagnostic_updater::FunctionDiagnosticTask driver_status_standard_diagnostic_; 00131 00132 void reconfigure(Config &config, uint32_t level) 00133 { 00135 ROS_DEBUG("Reconfigure called at level %x.", level); 00136 boost::recursive_mutex::scoped_lock lock(driver_.mutex_); 00137 00138 drv_state_t orig_state = driver_.getState(); 00139 00140 if ((level | driver_base::SensorLevels::RECONFIGURE_STOP) == level) 00141 { 00142 driver_.stop(); 00143 if (!driver_.isStopped()) 00144 ROS_ERROR("Failed to stop streaming before reconfiguring. Reconfiguration may fail."); 00145 } 00146 00147 if ((level | driver_base::SensorLevels::RECONFIGURE_CLOSE) == level) 00148 { 00149 driver_.close(); 00150 if (!driver_.isClosed()) 00151 ROS_ERROR("Failed to close device before reconfiguring. Reconfiguration may fail."); 00152 } 00153 00154 driver_.config_update(config, level); 00155 config = driver_.config_; 00156 reconfigureHook(level); 00157 00158 driver_.goState(orig_state); 00159 00160 /* Other errors will show up when this happens. No need to have it 00161 * here. 00162 if (driver_.getState() != orig_state) 00163 { 00164 ROS_ERROR("Failed to resume original device state after reconfiguring. The requested configuration may contain errors."); 00165 } 00166 */ 00167 00168 ROS_DEBUG("Reconfigure completed."); 00169 } 00170 00171 private: 00172 /* void connectCallback(const ros::PublisherPtr &pub) 00173 { 00174 if (pub.numSubscribers == 1) 00175 num_subscribed_topics_++; 00176 00177 if (num_subscribed_topics_ == 1) 00178 start(); 00179 } 00180 00181 void disconnectCallback(const ros::PublisherPtr &pub) 00182 { 00183 if (pub.numSubscribers == 0) 00184 num_subscribed_topics_++; 00185 00186 if (num_subscribed_topics_ == 0) 00187 stop(); 00188 }*/ 00189 00190 void prepareDiagnostics() 00191 { 00192 driver_status_diagnostic_.addTask(&driver_status_standard_diagnostic_); 00193 diagnostic_.add(driver_status_diagnostic_); 00194 addDiagnostics(); 00195 } 00196 00197 void statusDiagnostic(diagnostic_updater::DiagnosticStatusWrapper& stat) 00198 { 00199 if (driver_.isRunning()) 00200 stat.summary(0, "OK"); 00201 else 00202 stat.summary(2, "not running"); 00203 00204 stat.add("Driver state:", driver_.getStateName()); 00205 stat.add("Latest status message:", driver_.getStatusMessage()); 00207 } 00208 00209 void prepareSelfTests() 00210 { 00211 self_test_.add( "Interruption Test", this, &DriverNode::interruptionTest ); 00212 addStoppedTests(); 00213 self_test_.add( "Connection Test", this, &DriverNode::openTest ); 00214 self_test_.add( "ID Test", this, &DriverNode::idTest ); 00215 addOpenedTests(); 00216 self_test_.add( "Start Streaming Test", this, &DriverNode::runTest ); 00217 addRunningTests(); 00218 self_test_.add( "Stop Streaming Test", this, &DriverNode::stopTest ); 00219 self_test_.add( "Disconnection Test", this, &DriverNode::closeTest ); 00220 self_test_.add( "Resume Activity", this, &DriverNode::resumeTest ); 00221 } 00222 00223 void interruptionTest(diagnostic_updater::DiagnosticStatusWrapper& status) 00224 { 00225 pre_self_test_driver_state_ = driver_.getState(); 00226 driver_.goClosed(); 00227 00228 drv_state_t s = driver_.getState(); 00229 00230 if (num_subscribed_topics_ > 0) 00231 status.summary(1, "There were active subscribers. Running of self test interrupted operations."); 00232 else if (s != Driver::CLOSED) 00233 status.summaryf(2, "Could not close device, currently in state %s.", Driver::getStateName(s).c_str()); 00234 else 00235 status.summary(0, "No operation interrupted."); 00236 } 00237 00238 void reliableGoStateTest(diagnostic_updater::DiagnosticStatusWrapper &status, drv_state_t target_state) 00239 { 00240 const int max_tries = 5; 00241 ROS_ASSERT(max_tries > 0); 00242 int retries; 00243 drv_state_t current_state; 00244 for (retries = 0; retries < max_tries; retries++) 00245 { 00246 sleep(1); 00247 driver_.goState(target_state); 00248 00249 current_state = driver_.getState(); 00250 if (current_state == target_state) 00251 break; 00252 } 00253 00254 std::string target_state_name = Driver::getStateName(target_state); 00255 std::string current_state_name = Driver::getStateName(current_state); 00256 00257 // We carefully avoid rechecking the state here, as it may have 00258 // changed since we last checked. We aren't here to check that we 00259 // stayed in the target state, just want to check that we made it 00260 // there... 00261 if (retries >= max_tries) 00262 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()); 00263 else if (retries) 00264 status.summaryf(1, "Successfully went to state %s after %u retries.", target_state_name.c_str(), retries); 00265 else 00266 status.summaryf(0, "Successfully went to state %s.", target_state_name.c_str()); 00267 } 00268 00269 void openTest(diagnostic_updater::DiagnosticStatusWrapper& status) 00270 { 00271 reliableGoStateTest(status, Driver::OPENED); 00272 } 00273 00274 void idTest(diagnostic_updater::DiagnosticStatusWrapper& status) 00275 { 00276 std::string ID = driver_.getID(); 00277 if (ID.compare("")) 00278 { 00279 status.summaryf(0, "Device ID is %s", ID.c_str()); 00280 self_test_.setID(ID); 00281 } 00282 else 00283 status.summaryf(2, "Error reading Device ID"); 00284 } 00285 00286 void runTest(diagnostic_updater::DiagnosticStatusWrapper& status) 00287 { 00288 reliableGoStateTest(status, Driver::RUNNING); 00289 } 00290 00291 void stopTest(diagnostic_updater::DiagnosticStatusWrapper& status) 00292 { 00293 reliableGoStateTest(status, Driver::OPENED); 00294 } 00295 00296 void closeTest(diagnostic_updater::DiagnosticStatusWrapper& status) 00297 { 00298 reliableGoStateTest(status, Driver::CLOSED); 00299 } 00300 00301 void resumeTest(diagnostic_updater::DiagnosticStatusWrapper& status) 00302 { 00303 reliableGoStateTest(status, pre_self_test_driver_state_); 00304 } 00305 00306 public: 00307 virtual ~DriverNode() {} 00308 00309 int spin() 00310 { 00311 prepareDiagnostics(); 00312 prepareSelfTests(); 00313 typename dynamic_reconfigure::Server<Config>::CallbackType f = boost::bind(&DriverNode::reconfigure, this, _1, _2); 00314 reconfigure_server_.setCallback(f); 00315 00316 ros_thread_.reset(new boost::thread(boost::bind(&ros::spin))); 00318 assert(ros_thread_); 00319 00320 driver_.goRunning(); 00321 00323 std::string last_status_message; 00324 while (node_handle_.ok() && /*state_ != EXITING &&*/ !ctrl_c_hit_count_) 00325 { 00326 { 00327 // Must lock here, otherwise operations like reconfigure will cause 00328 // the test to pass, and an unnecessary restart will happen when the 00329 // reconfigure is done. 00330 boost::recursive_mutex::scoped_lock lock_(driver_.mutex_); 00331 00332 if (!driver_.isRunning()) 00333 { 00334 std::string new_status_message = driver_.getStatusMessage(); 00335 if ((last_status_message != new_status_message || driver_.getRecoveryComplete()) 00336 && !driver_.getStatusOk()) 00337 { 00338 ROS_ERROR("%s", new_status_message.c_str()); 00339 driver_.clearRecoveryComplete(); 00340 last_status_message = new_status_message; 00341 } 00342 ros::WallDuration(1).sleep(); 00343 driver_.goClosed(); 00344 driver_.goRunning(); 00345 } 00346 00347 diagnostic_.update(); 00348 self_test_.checkTest(); 00349 } 00350 ros::WallDuration(0.1).sleep(); 00351 } 00352 00353 driver_.goClosed(); 00354 00355 ros::shutdown(); 00356 00357 if (ros_thread_ && !ros_thread_->timed_join((boost::posix_time::milliseconds) 2000)) 00358 { 00359 ROS_ERROR("ROS thread did not die after two seconds. Pretending that it did. This is probably a bad sign."); 00360 } 00361 ros_thread_.reset(); 00362 00363 return 0; 00364 } 00365 00366 DriverNode(ros::NodeHandle &nh) : 00367 node_handle_(nh), 00368 private_node_handle_("~"), 00369 self_test_(node_handle_), 00370 diagnostic_(), 00371 reconfigure_server_(driver_.mutex_, ros::NodeHandle("~")), 00372 driver_status_diagnostic_("Driver Status"), 00373 driver_status_standard_diagnostic_("Driver Status", boost::bind(&DriverNode::statusDiagnostic, this, _1)) 00374 { 00375 num_subscribed_topics_ = 0; 00376 exit_status_ = 0; 00377 00378 // Defer most initialization to spin so that virtual calls in derived 00379 // classes will succeed. 00380 } 00381 }; 00382 00383 int AbstractDriverNode::ctrl_c_hit_count_ = 0; 00384 00385 // @todo exit status. 00386 // @todo take over ctrl_c. 00387 00388 }; 00389 00390 #endif