@@ -47,22 +47,22 @@ namespace fuse_core
4747{
4848
4949/* *
50- * @brief A sensor model base class that provides node handles and a private callback queue.
50+ * @brief A sensor model base class that provides an internal node and an internal callback queue.
5151 *
5252 * A sensor model plugin is responsible for generating new constraints, packaging them in a
5353 * fuse_core::Transaction object, and passing them along to the optimizer. The asynchronous
54- * sensor model plugin is designed similar to the nodelet plugin, attempting to be as generic and
54+ * sensor model plugin is designed similar to a nodelet plugin, attempting to be as generic and
5555 * easy to use as a standard ROS node.
5656 *
5757 * There are a few notable differences between the asynchronous sensor model plugin and a
5858 * standard ROS node. First and most obvious, the sensor model is designed as a plugin, with all
5959 * of the stipulations and requirements that come with all ROS plugins (must be derived from a
6060 * known base class, will be default constructed). Second, the base AsyncSensorModel class
61- * provides a global and private node handle, both hooked to a local callback queue and local
62- * spinner . This makes it act like a full ROS node -- subscriptions trigger message callbacks,
61+ * provides an internal node that is hooked to a local callback queue and local executor on
62+ * init . This makes it act like a full ROS node -- subscriptions trigger message callbacks,
6363 * callbacks will fire sequentially, etc. However, authors of derived sensor models should be
64- * aware of this fact and avoid creating additional node handles , or at least take care when
65- * creating new node handles and additional callback queues. Finally, instead of publishing the
64+ * aware of this fact and avoid creating additional sub-nodes , or at least take care when
65+ * creating new sub-nodes and additional callback queues. Finally, instead of publishing the
6666 * generated constraints using a ROS publisher, the asynchronous sensor model provides a
6767 * "sendTransaction()" method that should be called whenever the sensor is ready to send a
6868 * fuse_core::Transaction object to the Optimizer. Under the hood, this executes the
@@ -103,9 +103,9 @@ class AsyncSensorModel : public SensorModel
103103 * This method will be called by the optimizer, in the optimizer's thread, after each Graph
104104 * update is complete. This implementation repackages the provided \p graph, and inserts a
105105 * call to onGraphUpdate() into this sensor's callback queue. This is meant to simplify
106- * thread synchronization. If this sensor uses a single-threaded spinner , then all callbacks
106+ * thread synchronization. If this sensor uses a single-threaded executor , then all callbacks
107107 * will fire sequentially and no semaphores are needed. If this sensor uses a multi-threaded
108- * spinner , then normal multithreading rules apply and data accessed in more than one place
108+ * executor , then normal multithreading rules apply and data accessed in more than one place
109109 * should be guarded.
110110 *
111111 * @param[in] graph A read-only pointer to the graph object, allowing queries to be performed
@@ -118,9 +118,9 @@ class AsyncSensorModel : public SensorModel
118118 * reading from the parameter server.
119119 *
120120 * This will be called for each plugin after construction and after the ROS node has been
121- * initialized. The provided private node handle will be in a namespace based on the plugin's
122- * name. This should prevent conflicts and allow the same plugin to be used multiple times
123- * with different settings and topics.
121+ * initialized. The provided node will be in a namespace based on the plugin's name. This should
122+ * prevent conflicts and allow the same plugin to be used multiple times with different settings
123+ * and topics.
124124 *
125125 * @param[in] name A unique name to give this plugin instance
126126 * @param[in] transaction_callback The function to call every time a transaction is published
@@ -162,9 +162,9 @@ class AsyncSensorModel : public SensorModel
162162 *
163163 * This implementation inserts a call to onStart() into this sensor model's callback queue.
164164 * This method then blocks until the call to onStart() has completed. This is meant to
165- * simplify thread synchronization. If this sensor model uses a single-threaded spinner , then
165+ * simplify thread synchronization. If this sensor model uses a single-threaded executor , then
166166 * all callbacks will fire sequentially and no semaphores are needed. If this sensor model
167- * uses a multithreaded spinner , then normal multithreading rules apply and data accessed in
167+ * uses a multithreaded executor , then normal multithreading rules apply and data accessed in
168168 * more than one place should be guarded.
169169 */
170170 void start () override ;
@@ -180,9 +180,9 @@ class AsyncSensorModel : public SensorModel
180180 *
181181 * This implementation inserts a call to onStop() into this sensor model's callback queue.
182182 * This method then blocks until the call to onStop() has completed. This is meant to
183- * simplify thread synchronization. If this sensor model uses a single-threaded spinner , then
183+ * simplify thread synchronization. If this sensor model uses a single-threaded executor , then
184184 * all callbacks will fire sequentially and no semaphores are needed. If this sensor model
185- * uses a multithreaded spinner , then normal multithreading rules apply and data accessed in
185+ * uses a multithreaded executor , then normal multithreading rules apply and data accessed in
186186 * more than one place should be guarded.
187187 */
188188 void stop () override ;
@@ -194,18 +194,19 @@ class AsyncSensorModel : public SensorModel
194194 std::string name_; // !< The unique name for this sensor model instance
195195 rclcpp::Node::SharedPtr node_; // !< The node for this sensor model
196196
197- // ! A single/multi-threaded spinner assigned to the local callback queue
197+ // ! A single/multi-threaded executor assigned to the local callback queue
198198 rclcpp::executors::MultiThreadedExecutor::SharedPtr executor_;
199199
200200 // ! The function to be executed every time a Transaction is "published"
201201 TransactionCallback transaction_callback_;
202202 size_t executor_thread_count_;
203203 std::thread spinner_; // !< Internal thread for spinning the executor
204+ std::atomic<bool > initialized_ = false ; // !< True if instance has been fully initialized
204205
205206 /* *
206207 * @brief Constructor
207208 *
208- * Construct a new sensor model and create a local callback queue and thread spinner .
209+ * Construct a new sensor model and create a local callback queue and internal executor .
209210 *
210211 * @param[in] thread_count The number of threads used to service the local callback queue
211212 */
@@ -234,7 +235,7 @@ class AsyncSensorModel : public SensorModel
234235 * @brief Perform any required initialization for the sensor model
235236 *
236237 * This could include things like reading from the parameter server or subscribing to topics.
237- * The class's node handles will be properly initialized before onInit() is called. Spinning
238+ * The class's node will be properly initialized before onInit() is called. Spinning
238239 * of the callback queue will not begin until after the call to onInit() completes.
239240 *
240241 * Derived sensor models classes must implement this function, because otherwise I'm not sure
0 commit comments