nodelet_class.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2010, Willow Garage, Inc.
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 the Willow Garage, Inc. 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 #include <nodelet/nodelet.h>
33 
34 #include <ros/ros.h>
35 #include <ros/callback_queue.h>
36 
37 namespace nodelet
38 {
39 
41 : inited_(false)
42 , nodelet_name_("uninitialized")
43 {
44 }
45 
47 {
48 }
49 
51 {
52  if (!inited_)
53  {
54  throw UninitializedException("getSTCallbackQueue");
55  }
56 
57  return *nh_->getCallbackQueue();
58 }
59 
61 {
62  if (!inited_)
63  {
64  throw UninitializedException("getMTCallbackQueue");
65  }
66 
67  return *mt_nh_->getCallbackQueue();
68 }
69 
71 {
72  if (!inited_)
73  {
74  throw UninitializedException("getNodeHandle");
75  }
76 
77  return *nh_;
78 }
80 {
81  if (!inited_)
82  {
83  throw UninitializedException("getPrivateNodeHandle");
84  }
85 
86  return *private_nh_;
87 }
89 {
90  if (!inited_)
91  {
92  throw UninitializedException("getMTNodeHandle");
93  }
94 
95  return *mt_nh_;
96 }
98 {
99  if (!inited_)
100  {
101  throw UninitializedException("getMTPrivateNodeHandle");
102  }
103 
104  return *mt_private_nh_;
105 }
106 
107 void Nodelet::init(const std::string& name, const M_string& remapping_args, const V_string& my_argv,
109 {
110  if (inited_)
111  {
113  }
114 
115  nodelet_name_ = name;
116  remapping_args_ = remapping_args;
117  my_argv_ = my_argv;
118 
119  // Set up NodeHandles with correct namespaces
120  private_nh_.reset(new ros::NodeHandle(name, remapping_args));
121  nh_.reset(new ros::NodeHandle(ros::names::parentNamespace(name), remapping_args));
122  mt_private_nh_.reset(new ros::NodeHandle(name, remapping_args));
123  mt_nh_.reset(new ros::NodeHandle(ros::names::parentNamespace(name), remapping_args));
124 
125  // Use the provided callback queues (or the global queue if they're NULL).
126  // This allows Loader and CallbackQueueManager to spread nodelets over multiple threads.
127  private_nh_->setCallbackQueue(st_queue);
128  nh_->setCallbackQueue(st_queue);
129  mt_private_nh_->setCallbackQueue(mt_queue);
130  mt_nh_->setCallbackQueue(mt_queue);
131 
132  NODELET_DEBUG ("Nodelet initializing");
133  inited_ = true;
134  this->onInit ();
135 }
136 
137 } // namespace nodelet
NodeHandlePtr mt_nh_
Definition: nodelet.h:215
ROSCPP_DECL std::string parentNamespace(const std::string &name)
NodeHandlePtr private_nh_
Definition: nodelet.h:214
ros::NodeHandle & getMTNodeHandle() const
ros::CallbackQueueInterface & getMTCallbackQueue() const
void init(const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
Init function called at startup.
ros::NodeHandle & getPrivateNodeHandle() const
M_string remapping_args_
Definition: nodelet.h:218
std::string nodelet_name_
Definition: nodelet.h:211
ros::NodeHandle & getMTPrivateNodeHandle() const
ros::CallbackQueueInterface & getSTCallbackQueue() const
V_string my_argv_
Definition: nodelet.h:217
Nodelet()
Empty constructor required for dynamic loading.
ros::NodeHandle & getNodeHandle() const
virtual void onInit()=0
#define NODELET_DEBUG(...)
Definition: nodelet.h:49
std::vector< std::string > V_string
Definition: loader.h:57
NodeHandlePtr nh_
Definition: nodelet.h:213
std::map< std::string, std::string > M_string
Definition: loader.h:55
NodeHandlePtr mt_private_nh_
Definition: nodelet.h:216


nodelet
Author(s): Tully Foote, Radu Bogdan Rusu
autogenerated on Sat Jul 18 2020 03:17:53