nodelet.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, Yujin Robot.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Yujin Robot nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
39 /*****************************************************************************
40  ** Includes
41  *****************************************************************************/
42 
43 #include <ecl/threads/thread.hpp>
45 #include <boost/concept_check.hpp>
46 
47 
48 namespace sawyer
49 {
50 
52 {
53 public:
56  {
57  ROS_DEBUG("Waiting for update thread to finish.");
58  shutdown_requested_ = true;
59  update_thread_.join();
60  }
61  void onInit()
62  {
63 
64  // resolve node(let) name
65  std::string name = nh.getUnresolvedNamespace();
66  int pos = name.find_last_of('/');
67  name = name.substr(pos + 1);
68  ROS_DEBUG("Initialising nodelet... [ %s ]",name.c_str());
69  controller_.reset(new SafetyController(nh, name));
70  if (controller_->init())
71  {
72  ROS_DEBUG("roch initialised. Spinning up update thread ... [ %s ]",name.c_str());
74  ROS_DEBUG("Nodelet initialised. [ %s ]",name.c_str());
75  }
76  else
77  {
78  ROS_DEBUG("Couldn't initialise nodelet! Please restart. [ %s ]",name.c_str());
79  }
80 
81  }
82 private:
83  void update()
84  {
85  ros::Rate spin_rate(10);
86  controller_->enable(); // enable the controller when loading the nodelet
87  while (! shutdown_requested_ && ros::ok())
88  {
89  controller_->spin();
90  spin_rate.sleep();
91  }
92  }
93 
95  ecl::Thread update_thread_;
98 };
99 
100 } // namespace roch
101 
102 int main(int argc, char** argv){
103 
104  ros::init(argc,argv,"roch_safety_controller_nodelet");
105 
107 
108  ros::spin();
109 
110  return 0;
111 }
const std::string & getUnresolvedNamespace() const
roch-specific safety controller
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
boost::shared_ptr< SafetyController > controller_
Definition: nodelet.cpp:94
int main(int argc, char **argv)
Definition: nodelet.cpp:102
ROSCPP_DECL bool ok()
ROSCPP_DECL void spin()
bool sleep()
#define ROS_DEBUG(...)


roch_safety_controller
Author(s): Marcus Liebhardt , Chen
autogenerated on Mon Jun 10 2019 14:41:24