robot_activity.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2018, University of Luxembourg
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of University of Luxembourg nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Maciej Zurad
36  *********************************************************************/
43 #ifndef ROBOT_ACTIVITY_ROBOT_ACTIVITY_H
44 #define ROBOT_ACTIVITY_ROBOT_ACTIVITY_H
45 
46 #include <ros/ros.h>
47 #include <ros/console.h>
48 #include <ros/callback_queue.h>
49 
50 #include <std_srvs/Empty.h>
51 #include <robot_activity_msgs/State.h>
52 #include <robot_activity_msgs/Error.h>
53 
55 
56 #include <string>
57 #include <vector>
58 
59 namespace robot_activity
60 {
61 
67 enum class State : std::uint8_t
68 {
69  INVALID = robot_activity_msgs::State::INVALID,
70  LAUNCHING = robot_activity_msgs::State::LAUNCHING,
71  UNCONFIGURED = robot_activity_msgs::State::UNCONFIGURED,
72  STOPPED = robot_activity_msgs::State::STOPPED,
73  PAUSED = robot_activity_msgs::State::PAUSED,
74  RUNNING = robot_activity_msgs::State::RUNNING,
75  TERMINATED = robot_activity_msgs::State::TERMINATED,
76  Count = 7
77 };
78 
85 std::ostream& operator<<(std::ostream& os, State state);
86 
92 {
93 public:
97  RobotActivity() = delete;
98 
109  RobotActivity(int argc, char* argv[],
110  const std::string& name_space = std::string(),
111  const std::string& name = std::string());
112 
116  virtual ~RobotActivity();
117 
127  RobotActivity& init(bool autostart = false);
128 
136  void run(uint8_t threads = 0);
137 
145  void runAsync(uint8_t threads = 0);
146 
151  State getState();
152 
160  std::string getNamespace() const;
161 
162 protected:
165 
174  void notifyError(uint8_t error_type,
175  const std::string& function,
176  const std::string& description);
177 
197  std::shared_ptr<IsolatedAsyncTimer>
198  registerIsolatedTimer(const IsolatedAsyncTimer::LambdaCallback& callback,
199  const float& frequency,
200  bool stoppable = true,
201  bool autostart = false,
202  bool oneshot = false);
203 
204 private:
209  std::vector<std::shared_ptr<robot_activity::IsolatedAsyncTimer>> process_timers_;
210 
214  std::shared_ptr<robot_activity::IsolatedAsyncTimer> heartbeat_timer_;
215 
221  std::string node_namespace_;
222 
226  std::string node_name_;
227 
234  bool wait_for_supervisor_ = true;
235 
240  bool autostart_ = false;
241 
245  bool autostart_after_reconfigure_ = false;
246 
251 
255  std::shared_ptr<ros::AsyncSpinner> state_request_spinner_;
256 
261 
266 
272 
277 
278 
283 
288 
289 
294 
299 
300 
304  std::shared_ptr<ros::AsyncSpinner> global_callback_queue_spinner_;
305 
306 
310  State current_state_ = State::LAUNCHING;
311 
316  virtual void onCreate() = 0;
317 
322  virtual void onTerminate() = 0;
323 
332  virtual bool onConfigure() = 0;
333 
342  virtual bool onUnconfigure() = 0;
343 
352  virtual bool onStart() = 0;
353 
362  virtual bool onStop() = 0;
363 
372  virtual bool onPause() = 0;
373 
382  virtual bool onResume() = 0;
383 
390  bool create();
391 
398  bool terminate();
399 
406  bool configure();
407 
414  bool unconfigure();
415 
422  bool start();
423 
430  bool stop();
431 
438  bool resume();
439 
446  bool pause();
447 
451  void notifyState() const;
452 
460  bool changeState(const State& new_state);
461 
470  bool transitionToState(const State& new_state);
471 
480  ros::ServiceServer registerStateChangeRequest(
481  const std::string& service_name,
482  const std::vector<State>& states);
483 
484  typedef bool (RobotActivity::*MemberLambdaCallback)();
485 
486  typedef boost::function < bool(
487  std_srvs::Empty::Request& req,
488  std_srvs::Empty::Response& res) > EmptyServiceCallback;
489  typedef MemberLambdaCallback StateTransitions
490  [static_cast<uint8_t>(State::Count)]
491  [static_cast<uint8_t>(State::Count)];
492 
493  typedef State StateTransitionPaths
494  [static_cast<uint8_t>(State::Count)]
495  [static_cast<uint8_t>(State::Count)];
496 
503  const static StateTransitions STATE_TRANSITIONS;
504 
508  const static StateTransitionPaths STATE_TRANSITIONS_PATHS;
509 };
510 
511 } // namespace robot_activity
512 
513 #endif // ROBOT_ACTIVITY_ROBOT_ACTIVITY_H
static const StateTransitions STATE_TRANSITIONS
2D array of direct state transitions with values being the corresponding functions to be called durin...
ros::ServiceServer stop_server_
ServiceServer for serving stop service.
ROSCPP_DECL void start()
static const StateTransitionPaths STATE_TRANSITIONS_PATHS
2D array of paths between states.
void init(const M_string &remappings)
std::vector< std::shared_ptr< robot_activity::IsolatedAsyncTimer > > process_timers_
Vector of shared pointers to isolated timers created by register isolated timer.
std::function< void(void)> LambdaCallback
std::shared_ptr< ros::AsyncSpinner > state_request_spinner_
Async spinner for serving state change requests.
ros::NodeHandlePtr node_handle_private_
std::shared_ptr< ros::AsyncSpinner > global_callback_queue_spinner_
Shared pointer to async spinner that serves the global callback queue.
boost::function< bool(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) > EmptyServiceCallback
ros::Publisher process_error_pub_
ROS Publisher of error messages.
ros::Publisher process_state_pub_
ROS Publisher of heartbeat messages and state changes messages.
Class for adding node lifecycle to ROS processes.
ROSCPP_DECL const std::string & getNamespace()
std::shared_ptr< robot_activity::IsolatedAsyncTimer > heartbeat_timer_
Shared pointer to the isolated timer that sends heartbeat messages.
ros::ServiceServer reconfigure_server_
ServiceServer for serving reconfigure service.
ros::ServiceServer pause_server_
ServiceServer for serving pause service.
ros::ServiceServer restart_server_
ServiceServer for serving restart service, where restart means transition to STOPPED and then RUNNING...
ros::ServiceServer start_server_
ServiceServer for serving start service.
ros::NodeHandlePtr node_handle_
State
RobotActivity state enum.
std::string node_name_
Name of the actual ROS node.
std::ostream & operator<<(std::ostream &os, State state)
Overridden operator<< for easy State enum printing.
std::string node_namespace_
Node&#39;s namespace, if empty then the private node handle resolves to ~ otheerwise private node handle ...
ros::ServiceServer terminate_server_
ServiceServer for serving terminate service.
ros::CallbackQueue state_request_callback_queue_
Callback queue for state change request services.
IsolatedAsyncTimer class implements ROS Timer served by a single-threaded async spinner on a separate...


robot_activity
Author(s): Maciej ZURAD
autogenerated on Mon Jun 10 2019 14:33:22