Class for adding node lifecycle to ROS processes. More...
#include <robot_activity.h>
Public Member Functions | |
std::string | getNamespace () const |
Returns the full private namespace. | |
State | getState () |
Returns the current state. | |
RobotActivity & | init (bool autostart=false) |
Initializes the RobotActivity. | |
RobotActivity () | |
Default constructor is deleted. | |
RobotActivity (int argc, char *argv[], const std::string &name_space=std::string(), const std::string &name=std::string()) | |
Constructor. | |
void | run (uint8_t threads=0) |
Spins an amount of threads to serve the global callback queue. The call is blocking. | |
void | runAsync (uint8_t threads=0) |
Spins an amount of threads to serve the global callback queue. The call is non-blocking. | |
virtual | ~RobotActivity () |
Virtual destructor. | |
Protected Member Functions | |
void | notifyError (uint8_t error_type, const std::string &function, const std::string &description) |
Sends an error message to a global error topic "/error". | |
std::shared_ptr < IsolatedAsyncTimer > | registerIsolatedTimer (const IsolatedAsyncTimer::LambdaCallback &callback, const float &frequency, bool stoppable=true, bool autostart=false, bool oneshot=false) |
Register an isolated async timer. | |
Protected Attributes | |
ros::NodeHandlePtr | node_handle_ |
ros::NodeHandlePtr | node_handle_private_ |
Private Types | |
typedef boost::function< bool(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) > | EmptyServiceCallback |
typedef bool(RobotActivity::* | MemberLambdaCallback )() |
typedef State | StateTransitionPaths [static_cast< uint8_t >(State::Count)][static_cast< uint8_t >(State::Count)] |
typedef MemberLambdaCallback | StateTransitions [static_cast< uint8_t >(State::Count)][static_cast< uint8_t >(State::Count)] |
Private Member Functions | |
bool | changeState (const State &new_state) |
Changes state from current to new. Direct transition must exist. The appropriate function will be called during transition. | |
bool | configure () |
Called automatically, when transition from UNCONFIGURED to STOPPED. RobotActivity calls this function directly during transition, which internally calls the user-defined RobotActivity::onConfigure. | |
bool | create () |
Called automatically, when transition from LAUNCHING to UNCONFIGURED. RobotActivity calls this function directly during transition, which internally calls the user-defined RobotActivity::onCreate. | |
void | notifyState () const |
Sends a heartbeat message with the current state. | |
virtual bool | onConfigure ()=0 |
Function to be defined by the user. Called at the end of transition from UNCONFIGURED to STOPPED. User must return true or false depending whether transition should succeed or not. | |
virtual void | onCreate ()=0 |
Function to be defined by the user. Called at the end of transition from LAUNCHING to UNCONFIGURED. | |
virtual bool | onPause ()=0 |
Function to be defined by the user. Called at the end of transition from RUNNING to PAUSED. User must return true or false depending whether transition should succeed or not. | |
virtual bool | onResume ()=0 |
Function to be defined by the user. Called at the end of transition from PAUSED to RUNNING. User must return true or false depending whether transition should succeed or not. | |
virtual bool | onStart ()=0 |
Function to be defined by the user. Called at the end of transition from STOPPED to PAUSED. User must return true or false depending whether transition should succeed or not. | |
virtual bool | onStop ()=0 |
Function to be defined by the user. Called at the end of transition from PAUSED to STOPPED. User must return true or false depending whether transition should succeed or not. | |
virtual void | onTerminate ()=0 |
Function to be defined by the user. Called at the end of transition from UNCONFIGURED to TERMINATED. | |
virtual bool | onUnconfigure ()=0 |
Function to be defined by the user. Called at the end of transition from STOPPED to UNCONFIGURED. User must return true or false depending whether transition should succeed or not. | |
bool | pause () |
Called automatically, when transition from RUNNING to PAUSED. RobotActivity calls this function directly during transition, which internally calls the user-defined RobotActivity::onPause. | |
ros::ServiceServer | registerStateChangeRequest (const std::string &service_name, const std::vector< State > &states) |
Registers a ROS service server listening for state change requests. | |
bool | resume () |
Called automatically, when transition from PAUSED to RUNNING. RobotActivity calls this function directly during transition, which internally calls the user-defined RobotActivity::onResume. | |
bool | start () |
Called automatically, when transition from STOPPED to PAUSED. RobotActivity calls this function directly during transition, which internally calls the user-defined RobotActivity::onStart. | |
bool | stop () |
Called automatically, when transition from PAUSED to STOPPED. RobotActivity calls this function directly during transition, which internally calls the user-defined RobotActivity::onStop. | |
bool | terminate () |
Called automatically, when transition from UNCONFIGURED to TERMINATED. RobotActivity calls this function directly during transition, which internally calls the user-defined RobotActivity::onTerminate. | |
bool | transitionToState (const State &new_state) |
Transitions to a new state. Path must exists between the current and the new state. All appropriate function will be called when transition to the goal state. | |
bool | unconfigure () |
Called automatically, when transition from STOPPED to UNCONFIGURED. RobotActivity calls this function directly during transition, which internally calls the user-defined RobotActivity::onUnconfigure. | |
Private Attributes | |
bool | autostart_ = false |
Whether to automatically start (transition to RUNNING) at the end of init function if not the node will transition to STOPPED state. | |
bool | autostart_after_reconfigure_ = false |
Whether to autostart after reconfigure service is called. | |
State | current_state_ = State::LAUNCHING |
Current state of the RobotActivity. Initially, LAUNCHING state. | |
std::shared_ptr < ros::AsyncSpinner > | global_callback_queue_spinner_ |
Shared pointer to async spinner that serves the global callback queue. | |
std::shared_ptr < robot_activity::IsolatedAsyncTimer > | heartbeat_timer_ |
Shared pointer to the isolated timer that sends heartbeat messages. | |
std::string | node_name_ |
Name of the actual ROS node. | |
std::string | node_namespace_ |
Node's namespace, if empty then the private node handle resolves to ~ otheerwise private node handle resolves to ~node_namespace. | |
ros::ServiceServer | pause_server_ |
ServiceServer for serving pause service. | |
ros::Publisher | process_error_pub_ |
ROS Publisher of error messages. | |
ros::Publisher | process_state_pub_ |
ROS Publisher of heartbeat messages and state changes messages. | |
std::vector< std::shared_ptr < robot_activity::IsolatedAsyncTimer > > | process_timers_ |
Vector of shared pointers to isolated timers created by register isolated timer. | |
ros::ServiceServer | reconfigure_server_ |
ServiceServer for serving reconfigure 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::CallbackQueue | state_request_callback_queue_ |
Callback queue for state change request services. | |
std::shared_ptr < ros::AsyncSpinner > | state_request_spinner_ |
Async spinner for serving state change requests. | |
ros::ServiceServer | stop_server_ |
ServiceServer for serving stop service. | |
ros::ServiceServer | terminate_server_ |
ServiceServer for serving terminate service. | |
bool | wait_for_supervisor_ = true |
Whether to wait for the supervisor during the init function. Waiting means that there has to be at least one subscriber of the hearthbeat topic. | |
Static Private Attributes | |
static const StateTransitions | STATE_TRANSITIONS |
2D array of direct state transitions with values being the corresponding functions to be called during that transition. First index signifies the state we are transitioning from, while the second index signifies the state we are transitioning to. | |
static const StateTransitionPaths | STATE_TRANSITIONS_PATHS |
2D array of paths between states. |
Class for adding node lifecycle to ROS processes.
Definition at line 91 of file robot_activity.h.
typedef boost::function< bool( std_srvs::Empty::Request& req, std_srvs::Empty::Response& res) > robot_activity::RobotActivity::EmptyServiceCallback [private] |
Definition at line 488 of file robot_activity.h.
typedef bool(RobotActivity::* robot_activity::RobotActivity::MemberLambdaCallback)() [private] |
Definition at line 484 of file robot_activity.h.
typedef State robot_activity::RobotActivity::StateTransitionPaths[static_cast< uint8_t >(State::Count)][static_cast< uint8_t >(State::Count)] [private] |
Definition at line 495 of file robot_activity.h.
typedef MemberLambdaCallback robot_activity::RobotActivity::StateTransitions[static_cast< uint8_t >(State::Count)][static_cast< uint8_t >(State::Count)] [private] |
Definition at line 491 of file robot_activity.h.
Default constructor is deleted.
robot_activity::RobotActivity::RobotActivity | ( | int | argc, |
char * | argv[], | ||
const std::string & | name_space = std::string() , |
||
const std::string & | name = std::string() |
||
) |
Constructor.
UNIX process args are passed in due to ros::init being called inside. name_space allows for running multiple instances of the same class or multiple RobotActivity classes in the same UNIX process without name collisions. name argument is the name passed in to ros::init, which is usually remapped in roslaunch. If name is empty and name is not remapped, then anonymous name will be created.
Definition at line 48 of file robot_activity.cpp.
robot_activity::RobotActivity::~RobotActivity | ( | ) | [virtual] |
Virtual destructor.
Definition at line 70 of file robot_activity.cpp.
bool robot_activity::RobotActivity::changeState | ( | const State & | new_state | ) | [private] |
Changes state from current to new. Direct transition must exist. The appropriate function will be called during transition.
new_state | State to transition to. |
Definition at line 342 of file robot_activity.cpp.
bool robot_activity::RobotActivity::configure | ( | ) | [private] |
Called automatically, when transition from UNCONFIGURED to STOPPED. RobotActivity calls this function directly during transition, which internally calls the user-defined RobotActivity::onConfigure.
Definition at line 218 of file robot_activity.cpp.
bool robot_activity::RobotActivity::create | ( | ) | [private] |
Called automatically, when transition from LAUNCHING to UNCONFIGURED. RobotActivity calls this function directly during transition, which internally calls the user-defined RobotActivity::onCreate.
Definition at line 202 of file robot_activity.cpp.
std::string robot_activity::RobotActivity::getNamespace | ( | ) | const |
Returns the full private namespace.
Returns the full private namespace, meaning name of the actual ROS node together with the name_space argument passed during construction.
Definition at line 193 of file robot_activity.cpp.
Returns the current state.
Definition at line 154 of file robot_activity.cpp.
RobotActivity & robot_activity::RobotActivity::init | ( | bool | autostart = false | ) |
Initializes the RobotActivity.
Creates node handles, starts heartbeat thread, advertises state change request services, waits for the supervisor if requested
autostart | If true, transitions immediately to RUNNING state |
Definition at line 75 of file robot_activity.cpp.
void robot_activity::RobotActivity::notifyError | ( | uint8_t | error_type, |
const std::string & | function, | ||
const std::string & | description | ||
) | [protected] |
Sends an error message to a global error topic "/error".
Ideally the
error_type | Type of error |
function | Function, where the error was caused |
description | Detailed description of the error |
Definition at line 159 of file robot_activity.cpp.
void robot_activity::RobotActivity::notifyState | ( | ) | const [private] |
Sends a heartbeat message with the current state.
Definition at line 300 of file robot_activity.cpp.
virtual bool robot_activity::RobotActivity::onConfigure | ( | ) | [private, pure virtual] |
Function to be defined by the user. Called at the end of transition from UNCONFIGURED to STOPPED. User must return true or false depending whether transition should succeed or not.
Implemented in robot_activity::ManagedRobotActivity.
virtual void robot_activity::RobotActivity::onCreate | ( | ) | [private, pure virtual] |
Function to be defined by the user. Called at the end of transition from LAUNCHING to UNCONFIGURED.
Implemented in robot_activity::ManagedRobotActivity.
virtual bool robot_activity::RobotActivity::onPause | ( | ) | [private, pure virtual] |
Function to be defined by the user. Called at the end of transition from RUNNING to PAUSED. User must return true or false depending whether transition should succeed or not.
Implemented in robot_activity::ManagedRobotActivity.
virtual bool robot_activity::RobotActivity::onResume | ( | ) | [private, pure virtual] |
Function to be defined by the user. Called at the end of transition from PAUSED to RUNNING. User must return true or false depending whether transition should succeed or not.
Implemented in robot_activity::ManagedRobotActivity.
virtual bool robot_activity::RobotActivity::onStart | ( | ) | [private, pure virtual] |
Function to be defined by the user. Called at the end of transition from STOPPED to PAUSED. User must return true or false depending whether transition should succeed or not.
Implemented in robot_activity::ManagedRobotActivity.
virtual bool robot_activity::RobotActivity::onStop | ( | ) | [private, pure virtual] |
Function to be defined by the user. Called at the end of transition from PAUSED to STOPPED. User must return true or false depending whether transition should succeed or not.
Implemented in robot_activity::ManagedRobotActivity.
virtual void robot_activity::RobotActivity::onTerminate | ( | ) | [private, pure virtual] |
Function to be defined by the user. Called at the end of transition from UNCONFIGURED to TERMINATED.
Implemented in robot_activity::ManagedRobotActivity.
virtual bool robot_activity::RobotActivity::onUnconfigure | ( | ) | [private, pure virtual] |
Function to be defined by the user. Called at the end of transition from STOPPED to UNCONFIGURED. User must return true or false depending whether transition should succeed or not.
Implemented in robot_activity::ManagedRobotActivity.
bool robot_activity::RobotActivity::pause | ( | ) | [private] |
Called automatically, when transition from RUNNING to PAUSED. RobotActivity calls this function directly during transition, which internally calls the user-defined RobotActivity::onPause.
Definition at line 263 of file robot_activity.cpp.
std::shared_ptr< IsolatedAsyncTimer > robot_activity::RobotActivity::registerIsolatedTimer | ( | const IsolatedAsyncTimer::LambdaCallback & | callback, |
const float & | frequency, | ||
bool | stoppable = true , |
||
bool | autostart = false , |
||
bool | oneshot = false |
||
) | [protected] |
Register an isolated async timer.
Registers an isolated async timer, which runs on a separate callback queue and is served by a single separate thread. The timer is managed during the lifecycle and transitioning to PAUSED state will pause its execution, meaning that the callback still executes, but returns immediately. When RobotActivity transitions to STOPPED state, the timer is stopped completely and started again during transition from STOPPED to PAUSED. The function returns a reference to the newly created timer.
callback | Timer callback to be registered |
frequency | Frequency of the timer in Hz |
stoppable | If true, timer cannot be stopped when transitioning to PAUSED or STOPPED state |
autostart | |
oneshot |
Definition at line 175 of file robot_activity.cpp.
ros::ServiceServer robot_activity::RobotActivity::registerStateChangeRequest | ( | const std::string & | service_name, |
const std::vector< State > & | states | ||
) | [private] |
Registers a ROS service server listening for state change requests.
service_name | Name of the service |
states | States to transition to in order |
Definition at line 274 of file robot_activity.cpp.
bool robot_activity::RobotActivity::resume | ( | ) | [private] |
Called automatically, when transition from PAUSED to RUNNING. RobotActivity calls this function directly during transition, which internally calls the user-defined RobotActivity::onResume.
Definition at line 252 of file robot_activity.cpp.
void robot_activity::RobotActivity::run | ( | uint8_t | threads = 0 | ) |
Spins an amount of threads to serve the global callback queue. The call is blocking.
threads | Number of threads to use, 0 signifies the amount of CPU cores available to the OS |
Definition at line 142 of file robot_activity.cpp.
void robot_activity::RobotActivity::runAsync | ( | uint8_t | threads = 0 | ) |
Spins an amount of threads to serve the global callback queue. The call is non-blocking.
threads | Number of threads to use, 0 signifies the amount of CPU cores available to the OS |
Definition at line 148 of file robot_activity.cpp.
bool robot_activity::RobotActivity::start | ( | ) | [private] |
Called automatically, when transition from STOPPED to PAUSED. RobotActivity calls this function directly during transition, which internally calls the user-defined RobotActivity::onStart.
Definition at line 230 of file robot_activity.cpp.
bool robot_activity::RobotActivity::stop | ( | ) | [private] |
Called automatically, when transition from PAUSED to STOPPED. RobotActivity calls this function directly during transition, which internally calls the user-defined RobotActivity::onStop.
Definition at line 241 of file robot_activity.cpp.
bool robot_activity::RobotActivity::terminate | ( | ) | [private] |
Called automatically, when transition from UNCONFIGURED to TERMINATED. RobotActivity calls this function directly during transition, which internally calls the user-defined RobotActivity::onTerminate.
Definition at line 209 of file robot_activity.cpp.
bool robot_activity::RobotActivity::transitionToState | ( | const State & | new_state | ) | [private] |
Transitions to a new state. Path must exists between the current and the new state. All appropriate function will be called when transition to the goal state.
new_state | State to transition to. |
Definition at line 310 of file robot_activity.cpp.
bool robot_activity::RobotActivity::unconfigure | ( | ) | [private] |
Called automatically, when transition from STOPPED to UNCONFIGURED. RobotActivity calls this function directly during transition, which internally calls the user-defined RobotActivity::onUnconfigure.
Definition at line 224 of file robot_activity.cpp.
bool robot_activity::RobotActivity::autostart_ = false [private] |
Whether to automatically start (transition to RUNNING) at the end of init function if not the node will transition to STOPPED state.
Definition at line 240 of file robot_activity.h.
bool robot_activity::RobotActivity::autostart_after_reconfigure_ = false [private] |
Whether to autostart after reconfigure service is called.
Definition at line 245 of file robot_activity.h.
State robot_activity::RobotActivity::current_state_ = State::LAUNCHING [private] |
Current state of the RobotActivity. Initially, LAUNCHING state.
Definition at line 310 of file robot_activity.h.
std::shared_ptr<ros::AsyncSpinner> robot_activity::RobotActivity::global_callback_queue_spinner_ [private] |
Shared pointer to async spinner that serves the global callback queue.
Definition at line 304 of file robot_activity.h.
std::shared_ptr<robot_activity::IsolatedAsyncTimer> robot_activity::RobotActivity::heartbeat_timer_ [private] |
Shared pointer to the isolated timer that sends heartbeat messages.
Definition at line 214 of file robot_activity.h.
Definition at line 163 of file robot_activity.h.
Definition at line 164 of file robot_activity.h.
std::string robot_activity::RobotActivity::node_name_ [private] |
Name of the actual ROS node.
Definition at line 226 of file robot_activity.h.
std::string robot_activity::RobotActivity::node_namespace_ [private] |
Node's namespace, if empty then the private node handle resolves to ~ otheerwise private node handle resolves to ~node_namespace.
Definition at line 221 of file robot_activity.h.
ServiceServer for serving pause service.
Definition at line 287 of file robot_activity.h.
ROS Publisher of error messages.
Definition at line 298 of file robot_activity.h.
ROS Publisher of heartbeat messages and state changes messages.
Definition at line 293 of file robot_activity.h.
std::vector<std::shared_ptr<robot_activity::IsolatedAsyncTimer> > robot_activity::RobotActivity::process_timers_ [private] |
Vector of shared pointers to isolated timers created by register isolated timer.
Definition at line 209 of file robot_activity.h.
ServiceServer for serving reconfigure service.
Definition at line 265 of file robot_activity.h.
ServiceServer for serving restart service, where restart means transition to STOPPED and then RUNNING.
Definition at line 271 of file robot_activity.h.
ServiceServer for serving start service.
Definition at line 276 of file robot_activity.h.
Callback queue for state change request services.
Definition at line 250 of file robot_activity.h.
std::shared_ptr<ros::AsyncSpinner> robot_activity::RobotActivity::state_request_spinner_ [private] |
Async spinner for serving state change requests.
Definition at line 255 of file robot_activity.h.
const RobotActivity::StateTransitions robot_activity::RobotActivity::STATE_TRANSITIONS [static, private] |
{ {nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr}, {nullptr, nullptr, &RobotActivity::create, nullptr, nullptr, nullptr, nullptr}, {nullptr, nullptr, nullptr, &RobotActivity::configure, nullptr, nullptr, &RobotActivity::terminate}, {nullptr, nullptr, &RobotActivity::unconfigure, nullptr, &RobotActivity::start, nullptr, nullptr}, {nullptr, nullptr, nullptr, &RobotActivity::stop, nullptr, &RobotActivity::resume, nullptr}, {nullptr, nullptr, nullptr, nullptr, &RobotActivity::pause, nullptr, nullptr}, {nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr} }
2D array of direct state transitions with values being the corresponding functions to be called during that transition. First index signifies the state we are transitioning from, while the second index signifies the state we are transitioning to.
Definition at line 503 of file robot_activity.h.
const RobotActivity::StateTransitionPaths robot_activity::RobotActivity::STATE_TRANSITIONS_PATHS [static, private] |
2D array of paths between states.
Definition at line 508 of file robot_activity.h.
ServiceServer for serving stop service.
Definition at line 282 of file robot_activity.h.
ServiceServer for serving terminate service.
Definition at line 260 of file robot_activity.h.
bool robot_activity::RobotActivity::wait_for_supervisor_ = true [private] |
Whether to wait for the supervisor during the init function. Waiting means that there has to be at least one subscriber of the hearthbeat topic.
Definition at line 234 of file robot_activity.h.