43 #ifndef ROBOT_ACTIVITY_ROBOT_ACTIVITY_H 44 #define ROBOT_ACTIVITY_ROBOT_ACTIVITY_H 50 #include <std_srvs/Empty.h> 51 #include <robot_activity_msgs/State.h> 52 #include <robot_activity_msgs/Error.h> 69 INVALID = robot_activity_msgs::State::INVALID,
70 LAUNCHING = robot_activity_msgs::State::LAUNCHING,
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,
110 const std::string& name_space = std::string(),
111 const std::string& name = std::string());
136 void run(uint8_t threads = 0);
145 void runAsync(uint8_t threads = 0);
174 void notifyError(uint8_t error_type,
175 const std::string&
function,
176 const std::string& description);
197 std::shared_ptr<IsolatedAsyncTimer>
199 const float& frequency,
200 bool stoppable =
true,
201 bool autostart =
false,
202 bool oneshot =
false);
234 bool wait_for_supervisor_ =
true;
240 bool autostart_ =
false;
245 bool autostart_after_reconfigure_ =
false;
316 virtual void onCreate() = 0;
322 virtual void onTerminate() = 0;
332 virtual bool onConfigure() = 0;
342 virtual bool onUnconfigure() = 0;
352 virtual bool onStart() = 0;
362 virtual bool onStop() = 0;
372 virtual bool onPause() = 0;
382 virtual bool onResume() = 0;
451 void notifyState()
const;
460 bool changeState(
const State& new_state);
470 bool transitionToState(
const State& new_state);
481 const std::string& service_name,
482 const std::vector<State>& states);
486 typedef boost::function < bool(
487 std_srvs::Empty::Request& req,
489 typedef MemberLambdaCallback StateTransitions
493 typedef State StateTransitionPaths
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.
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'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...