Public Member Functions | Protected Attributes | Private Member Functions | List of all members
robot_activity::ManagedRobotActivity Class Referenceabstract

Managed RobotActivity class, which adds further functionality to the RobotActivity class. More...

#include <managed_robot_activity.h>

Inheritance diagram for robot_activity::ManagedRobotActivity:
Inheritance graph
[legend]

Public Member Functions

virtual ~ManagedRobotActivity ()
 Virtual destructor. More...
 
- Public Member Functions inherited from robot_activity::RobotActivity
std::string getNamespace () const
 Returns the full private namespace. More...
 
State getState ()
 Returns the current state. More...
 
RobotActivityinit (bool autostart=false)
 Initializes the RobotActivity. More...
 
 RobotActivity ()=delete
 Default constructor is deleted. More...
 
 RobotActivity (int argc, char *argv[], const std::string &name_space=std::string(), const std::string &name=std::string())
 Constructor. More...
 
void run (uint8_t threads=0)
 Spins an amount of threads to serve the global callback queue. The call is blocking. More...
 
void runAsync (uint8_t threads=0)
 Spins an amount of threads to serve the global callback queue. The call is non-blocking. More...
 
virtual ~RobotActivity ()
 Virtual destructor. More...
 

Protected Attributes

resource::ServiceServerManager service_manager
 Manager for advertising ROS services. More...
 
resource::SubscriberManager subscriber_manager
 Manager for subscribing to ROS topics. More...
 
- Protected Attributes inherited from robot_activity::RobotActivity
ros::NodeHandlePtr node_handle_
 
ros::NodeHandlePtr node_handle_private_
 

Private Member Functions

bool onConfigure () final
 Overriden onConfigure, which calls onManagedConfigure. Cannot be overriden further by the child class of ManagedRobotActivity. More...
 
void onCreate () final
 Overriden onCreate, which calls onManagedCreate. Cannot be overriden further by the child class of ManagedRobotActivity. More...
 
virtual bool onManagedConfigure ()=0
 User-defined function that's called at the end of transition from UNCONFIGURED to STOPPED state User has to return true or false, indicating whether the transition has succeeded or not. In case of failure, the state remains unchanged. More...
 
virtual void onManagedCreate ()=0
 User-defined function that's called at the end of transition from LAUNCHING to UNCONFIGURED state. More...
 
virtual bool onManagedPause ()=0
 User-defined function that's called at the end of transition from RUNNING to PAUSED state User has to return true or false, indicating whether the transition has succeeded or not. In case of failure, the state remains unchanged. More...
 
virtual bool onManagedResume ()=0
 User-defined function that's called at the end of transition from PAUSED to RUNNING state User has to return true or false, indicating whether the transition has succeeded or not. In case of failure, the state remains unchanged. More...
 
virtual bool onManagedStart ()=0
 User-defined function that's called at the end of transition from STOPPED to PAUSED state User has to return true or false, indicating whether the transition has succeeded or not. In case of failure, the state remains unchanged. More...
 
virtual bool onManagedStop ()=0
 User-defined function that's called at the end of transition from PAUSED to STOPPED state User has to return true or false, indicating whether the transition has succeeded or not. In case of failure, the state remains unchanged. More...
 
virtual void onManagedTerminate ()=0
 User-defined function that's called at the end of transition from UNCONFIGURED to TERMINATED state. More...
 
virtual bool onManagedUnconfigure ()=0
 User-defined function that's called at the end of transition from STOPPED to UNCONFIGURED state User has to return true or false, indicating whether the transition has succeeded or not. In case of failure, the state remains unchanged. More...
 
bool onPause () final
 Overriden onPause, which calls onManagedPause. Cannot be overriden further by the child class of ManagedRobotActivity. It pauses all ROS topics and services that were subscribed and advertised with subscription_manager and service_manager before calling onManagedStart. More...
 
bool onResume () final
 Overriden onResume, which calls onManagedResume. Cannot be overriden further by the child class of ManagedRobotActivity. It resumes all ROS topics and services that were subscribed and advertised with subscription_manager and service_manager before calling onManagedStart. More...
 
bool onStart () final
 Overriden onStart, which calls onManagedStart. Cannot be overriden further by the child class of ManagedRobotActivity. It subscribes and adverties all ROS topics and services that were subscribed and advertised with subscription_manager and service_manager before calling onManagedStart. More...
 
bool onStop () final
 Overriden onStop, which calls onManagedStop. Cannot be overriden further by the child class of ManagedRobotActivity. It shutdowns all ROS topics and services that were subscribed and advertised with subscription_manager and service_manager before calling onManagedStart. More...
 
void onTerminate () final
 Overriden onTerminate, which calls onManagedTerminate. Cannot be overriden further by the child class of ManagedRobotActivity. More...
 
bool onUnconfigure () final
 Overriden onUnconfigure, which calls onManagedUnconfigure. Cannot be overriden further by the child class of ManagedRobotActivity. More...
 

Additional Inherited Members

- Protected Member Functions inherited from robot_activity::RobotActivity
void notifyError (uint8_t error_type, const std::string &function, const std::string &description)
 Sends an error message to a global error topic "/error". More...
 
std::shared_ptr< IsolatedAsyncTimerregisterIsolatedTimer (const IsolatedAsyncTimer::LambdaCallback &callback, const float &frequency, bool stoppable=true, bool autostart=false, bool oneshot=false)
 Register an isolated async timer. More...
 

Detailed Description

Managed RobotActivity class, which adds further functionality to the RobotActivity class.

ManagedRobotActivity manages ROS Subscribers and ServiceServers. It automatically pauses all Subscribers and ServiceServers during PAUSED state and resumes them when transitioning to the RUNNING state. It also shutdowns them in STOPPED state and re-acquires them (by re-subscribing or re-advertising) when transitioning from STOPPED to PAUSED.

Definition at line 71 of file managed_robot_activity.h.

Constructor & Destructor Documentation

robot_activity::ManagedRobotActivity::~ManagedRobotActivity ( )
virtual

Virtual destructor.

Definition at line 42 of file managed_robot_activity.cpp.

Member Function Documentation

bool robot_activity::ManagedRobotActivity::onConfigure ( )
finalprivatevirtual

Overriden onConfigure, which calls onManagedConfigure. Cannot be overriden further by the child class of ManagedRobotActivity.

Returns
Returns true if onManagedConfigure succeeded

Implements robot_activity::RobotActivity.

Definition at line 59 of file managed_robot_activity.cpp.

void robot_activity::ManagedRobotActivity::onCreate ( )
finalprivatevirtual

Overriden onCreate, which calls onManagedCreate. Cannot be overriden further by the child class of ManagedRobotActivity.

Implements robot_activity::RobotActivity.

Definition at line 47 of file managed_robot_activity.cpp.

virtual bool robot_activity::ManagedRobotActivity::onManagedConfigure ( )
privatepure virtual

User-defined function that's called at the end of transition from UNCONFIGURED to STOPPED state User has to return true or false, indicating whether the transition has succeeded or not. In case of failure, the state remains unchanged.

Returns
Returns true if transition succeeded
virtual void robot_activity::ManagedRobotActivity::onManagedCreate ( )
privatepure virtual

User-defined function that's called at the end of transition from LAUNCHING to UNCONFIGURED state.

virtual bool robot_activity::ManagedRobotActivity::onManagedPause ( )
privatepure virtual

User-defined function that's called at the end of transition from RUNNING to PAUSED state User has to return true or false, indicating whether the transition has succeeded or not. In case of failure, the state remains unchanged.

Returns
Returns true if transition succeeded
virtual bool robot_activity::ManagedRobotActivity::onManagedResume ( )
privatepure virtual

User-defined function that's called at the end of transition from PAUSED to RUNNING state User has to return true or false, indicating whether the transition has succeeded or not. In case of failure, the state remains unchanged.

Returns
Returns true if transition succeeded
virtual bool robot_activity::ManagedRobotActivity::onManagedStart ( )
privatepure virtual

User-defined function that's called at the end of transition from STOPPED to PAUSED state User has to return true or false, indicating whether the transition has succeeded or not. In case of failure, the state remains unchanged.

Returns
Returns true if transition succeeded
virtual bool robot_activity::ManagedRobotActivity::onManagedStop ( )
privatepure virtual

User-defined function that's called at the end of transition from PAUSED to STOPPED state User has to return true or false, indicating whether the transition has succeeded or not. In case of failure, the state remains unchanged.

Returns
Returns true if transition succeeded
virtual void robot_activity::ManagedRobotActivity::onManagedTerminate ( )
privatepure virtual

User-defined function that's called at the end of transition from UNCONFIGURED to TERMINATED state.

virtual bool robot_activity::ManagedRobotActivity::onManagedUnconfigure ( )
privatepure virtual

User-defined function that's called at the end of transition from STOPPED to UNCONFIGURED state User has to return true or false, indicating whether the transition has succeeded or not. In case of failure, the state remains unchanged.

Returns
Returns true if transition succeeded
bool robot_activity::ManagedRobotActivity::onPause ( )
finalprivatevirtual

Overriden onPause, which calls onManagedPause. Cannot be overriden further by the child class of ManagedRobotActivity. It pauses all ROS topics and services that were subscribed and advertised with subscription_manager and service_manager before calling onManagedStart.

Returns
Returns true if onManagedPause succeeded

Implements robot_activity::RobotActivity.

Definition at line 87 of file managed_robot_activity.cpp.

bool robot_activity::ManagedRobotActivity::onResume ( )
finalprivatevirtual

Overriden onResume, which calls onManagedResume. Cannot be overriden further by the child class of ManagedRobotActivity. It resumes all ROS topics and services that were subscribed and advertised with subscription_manager and service_manager before calling onManagedStart.

Returns
Returns true if onManagedResume succeeded

Implements robot_activity::RobotActivity.

Definition at line 95 of file managed_robot_activity.cpp.

bool robot_activity::ManagedRobotActivity::onStart ( )
finalprivatevirtual

Overriden onStart, which calls onManagedStart. Cannot be overriden further by the child class of ManagedRobotActivity. It subscribes and adverties all ROS topics and services that were subscribed and advertised with subscription_manager and service_manager before calling onManagedStart.

Returns
Returns true if onManagedStart succeeded

Implements robot_activity::RobotActivity.

Definition at line 71 of file managed_robot_activity.cpp.

bool robot_activity::ManagedRobotActivity::onStop ( )
finalprivatevirtual

Overriden onStop, which calls onManagedStop. Cannot be overriden further by the child class of ManagedRobotActivity. It shutdowns all ROS topics and services that were subscribed and advertised with subscription_manager and service_manager before calling onManagedStart.

Returns
Returns true if onManagedStop succeeded

Implements robot_activity::RobotActivity.

Definition at line 79 of file managed_robot_activity.cpp.

void robot_activity::ManagedRobotActivity::onTerminate ( )
finalprivatevirtual

Overriden onTerminate, which calls onManagedTerminate. Cannot be overriden further by the child class of ManagedRobotActivity.

Implements robot_activity::RobotActivity.

Definition at line 53 of file managed_robot_activity.cpp.

bool robot_activity::ManagedRobotActivity::onUnconfigure ( )
finalprivatevirtual

Overriden onUnconfigure, which calls onManagedUnconfigure. Cannot be overriden further by the child class of ManagedRobotActivity.

Returns
Returns true if onManagedUnconfigure succeeded

Implements robot_activity::RobotActivity.

Definition at line 65 of file managed_robot_activity.cpp.

Member Data Documentation

resource::ServiceServerManager robot_activity::ManagedRobotActivity::service_manager
protected

Manager for advertising ROS services.

Definition at line 93 of file managed_robot_activity.h.

resource::SubscriberManager robot_activity::ManagedRobotActivity::subscriber_manager
protected

Manager for subscribing to ROS topics.

Definition at line 88 of file managed_robot_activity.h.


The documentation for this class was generated from the following files:


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