nodelet.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Marcus Liebhardt, 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 
30 /*****************************************************************************
31 ** Includes
32 *****************************************************************************/
33 #include <string>
34 #include <nodelet/nodelet.h>
36 #include <ecl/threads/thread.hpp>
38 
39 namespace yocs
40 {
41 
43 {
44 public:
47  {
48  NODELET_DEBUG_STREAM("Waiting for update thread to finish. [" << name_ << "]");
49  shutdown_requested_ = true;
50  update_thread_.join();
51  }
52 
53  void onInit()
54  {
56  // resolve node(let) name
58  int pos = name_.find_last_of('/');
59  name_ = name_.substr(pos + 1);
60  NODELET_INFO_STREAM("Initialising nodelet... [" << name_ << "]");
61  double spin_rate_param = 20;
62  if(nh.getParam("spin_rate", spin_rate_param))
63  {
64  ROS_DEBUG_STREAM("Controller will spin at " << spin_rate_param << " hz. [" << name_ <<"]");
65  }
66  else
67  {
68  ROS_WARN_STREAM("Couldn't retrieve parameter 'spin_rate' from parameter server! Using default '"
69  << spin_rate_param << "'. [" << name_ <<"]");
70  }
71  spin_rate_ = ros::Rate(spin_rate_param);
72  bool start_enabled = true;
73  nh.getParam("start_enabled", start_enabled);
75  if (controller_->init())
76  {
77  if (start_enabled)
78  {
79  controller_->enable();
80  ROS_INFO_STREAM("Controller will start enabled. [" << name_ <<"]");
81  }
82  else
83  {
84  controller_->disable();
85  ROS_INFO_STREAM("Controller will start disabled. [" << name_ <<"]");
86  }
88  NODELET_INFO_STREAM("Controller initialised. [" << name_ << "]");
89  }
90  else
91  {
92  NODELET_ERROR_STREAM("Couldn't initialise controller! Please restart. [" << name_ << "]");
93  }
94  }
95 private:
96  void update()
97  {
98  while (!shutdown_requested_ && ros::ok())
99  {
100  controller_->spinOnce();
101  spin_rate_.sleep();
102  }
103  }
104  std::string name_;
107  ecl::Thread update_thread_;
109 };
110 
111 } // namespace yocs
112 
#define NODELET_INFO_STREAM(...)
const std::string & getUnresolvedNamespace() const
A controller for driving a differential drive base to a pose goal or along a path specified by multip...
ros::NodeHandle & getPrivateNodeHandle() const
#define NODELET_ERROR_STREAM(...)
ROSCPP_DECL bool ok()
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
#define NODELET_DEBUG_STREAM(...)
bool sleep()
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
boost::shared_ptr< DiffDrivePoseControllerROS > controller_
Definition: nodelet.cpp:106
PLUGINLIB_EXPORT_CLASS(yocs::DiffDrivePoseControllerNodelet, nodelet::Nodelet)


yocs_diff_drive_pose_controller
Author(s): Marcus Liebhardt
autogenerated on Mon Jun 10 2019 15:53:50