Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00043 #ifndef ROBOT_ACTIVITY_ROBOT_ACTIVITY_H
00044 #define ROBOT_ACTIVITY_ROBOT_ACTIVITY_H
00045
00046 #include <ros/ros.h>
00047 #include <ros/console.h>
00048 #include <ros/callback_queue.h>
00049
00050 #include <std_srvs/Empty.h>
00051 #include <robot_activity_msgs/State.h>
00052 #include <robot_activity_msgs/Error.h>
00053
00054 #include <robot_activity/isolated_async_timer.h>
00055
00056 #include <string>
00057 #include <vector>
00058
00059 namespace robot_activity
00060 {
00061
00067 enum class State : std::uint8_t
00068 {
00069 INVALID = robot_activity_msgs::State::INVALID,
00070 LAUNCHING = robot_activity_msgs::State::LAUNCHING,
00071 UNCONFIGURED = robot_activity_msgs::State::UNCONFIGURED,
00072 STOPPED = robot_activity_msgs::State::STOPPED,
00073 PAUSED = robot_activity_msgs::State::PAUSED,
00074 RUNNING = robot_activity_msgs::State::RUNNING,
00075 TERMINATED = robot_activity_msgs::State::TERMINATED,
00076 Count = 7
00077 };
00078
00085 std::ostream& operator<<(std::ostream& os, State state);
00086
00091 class RobotActivity
00092 {
00093 public:
00097 RobotActivity() = delete;
00098
00109 RobotActivity(int argc, char* argv[],
00110 const std::string& name_space = std::string(),
00111 const std::string& name = std::string());
00112
00116 virtual ~RobotActivity();
00117
00127 RobotActivity& init(bool autostart = false);
00128
00136 void run(uint8_t threads = 0);
00137
00145 void runAsync(uint8_t threads = 0);
00146
00151 State getState();
00152
00160 std::string getNamespace() const;
00161
00162 protected:
00163 ros::NodeHandlePtr node_handle_;
00164 ros::NodeHandlePtr node_handle_private_;
00165
00174 void notifyError(uint8_t error_type,
00175 const std::string& function,
00176 const std::string& description);
00177
00197 std::shared_ptr<IsolatedAsyncTimer>
00198 registerIsolatedTimer(const IsolatedAsyncTimer::LambdaCallback& callback,
00199 const float& frequency,
00200 bool stoppable = true,
00201 bool autostart = false,
00202 bool oneshot = false);
00203
00204 private:
00209 std::vector<std::shared_ptr<robot_activity::IsolatedAsyncTimer>> process_timers_;
00210
00214 std::shared_ptr<robot_activity::IsolatedAsyncTimer> heartbeat_timer_;
00215
00221 std::string node_namespace_;
00222
00226 std::string node_name_;
00227
00234 bool wait_for_supervisor_ = true;
00235
00240 bool autostart_ = false;
00241
00245 bool autostart_after_reconfigure_ = false;
00246
00250 ros::CallbackQueue state_request_callback_queue_;
00251
00255 std::shared_ptr<ros::AsyncSpinner> state_request_spinner_;
00256
00260 ros::ServiceServer terminate_server_;
00261
00265 ros::ServiceServer reconfigure_server_;
00266
00271 ros::ServiceServer restart_server_;
00272
00276 ros::ServiceServer start_server_;
00277
00278
00282 ros::ServiceServer stop_server_;
00283
00287 ros::ServiceServer pause_server_;
00288
00289
00293 ros::Publisher process_state_pub_;
00294
00298 ros::Publisher process_error_pub_;
00299
00300
00304 std::shared_ptr<ros::AsyncSpinner> global_callback_queue_spinner_;
00305
00306
00310 State current_state_ = State::LAUNCHING;
00311
00316 virtual void onCreate() = 0;
00317
00322 virtual void onTerminate() = 0;
00323
00332 virtual bool onConfigure() = 0;
00333
00342 virtual bool onUnconfigure() = 0;
00343
00352 virtual bool onStart() = 0;
00353
00362 virtual bool onStop() = 0;
00363
00372 virtual bool onPause() = 0;
00373
00382 virtual bool onResume() = 0;
00383
00390 bool create();
00391
00398 bool terminate();
00399
00406 bool configure();
00407
00414 bool unconfigure();
00415
00422 bool start();
00423
00430 bool stop();
00431
00438 bool resume();
00439
00446 bool pause();
00447
00451 void notifyState() const;
00452
00460 bool changeState(const State& new_state);
00461
00470 bool transitionToState(const State& new_state);
00471
00480 ros::ServiceServer registerStateChangeRequest(
00481 const std::string& service_name,
00482 const std::vector<State>& states);
00483
00484 typedef bool (RobotActivity::*MemberLambdaCallback)();
00485
00486 typedef boost::function < bool(
00487 std_srvs::Empty::Request& req,
00488 std_srvs::Empty::Response& res) > EmptyServiceCallback;
00489 typedef MemberLambdaCallback StateTransitions
00490 [static_cast<uint8_t>(State::Count)]
00491 [static_cast<uint8_t>(State::Count)];
00492
00493 typedef State StateTransitionPaths
00494 [static_cast<uint8_t>(State::Count)]
00495 [static_cast<uint8_t>(State::Count)];
00496
00503 const static StateTransitions STATE_TRANSITIONS;
00504
00508 const static StateTransitionPaths STATE_TRANSITIONS_PATHS;
00509 };
00510
00511 }
00512
00513 #endif // ROBOT_ACTIVITY_ROBOT_ACTIVITY_H