|
SMACC2
|
#include <cb_ros_launch_2.hpp>


Public Member Functions | |
| CbRosLaunch2 () | |
| CbRosLaunch2 (std::string package, std::string launchfile, RosLaunchMode) | |
| virtual | ~CbRosLaunch2 () |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onOrthogonalAllocation () |
| void | onEntry () override |
Public Member Functions inherited from smacc2::SmaccAsyncClientBehavior | |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onOrthogonalAllocation () |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onStateOrthogonalAllocation () |
| virtual | ~SmaccAsyncClientBehavior () |
| template<typename TCallback , typename T > | |
| boost::signals2::connection | onSuccess (TCallback callback, T *object) |
| template<typename TCallback , typename T > | |
| boost::signals2::connection | onFinished (TCallback callback, T *object) |
| template<typename TCallback , typename T > | |
| boost::signals2::connection | onFailure (TCallback callback, T *object) |
| void | requestForceFinish () |
| void | executeOnEntry () override |
| void | executeOnExit () override |
| void | waitOnEntryThread (bool requestFinish) |
| template<typename TCallbackMethod , typename T > | |
| boost::signals2::connection | onSuccess (TCallbackMethod callback, T *object) |
| template<typename TCallbackMethod , typename T > | |
| boost::signals2::connection | onFinished (TCallbackMethod callback, T *object) |
| template<typename TCallbackMethod , typename T > | |
| boost::signals2::connection | onFailure (TCallbackMethod callback, T *object) |
Public Member Functions inherited from smacc2::ISmaccClientBehavior | |
| ISmaccClientBehavior () | |
| virtual | ~ISmaccClientBehavior () |
| ISmaccStateMachine * | getStateMachine () |
| std::string | getName () const |
| template<typename SmaccClientType > | |
| void | requiresClient (SmaccClientType *&storage) |
| template<typename SmaccComponentType > | |
| void | requiresComponent (SmaccComponentType *&storage, bool throwExceptionIfNotExist) |
| template<typename SmaccComponentType > | |
| void | requiresComponent (SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT) |
| virtual void | onExit () |
Public Attributes | |
| std::optional< std::string > | packageName_ |
| std::optional< std::string > | launchFileName_ |
| RosLaunchMode | launchMode_ |
Protected Attributes | |
| std::future< std::string > | result_ |
| smacc2::client_bases::ClRosLaunch2 * | client_ |
| std::future< std::string > | future_ |
Static Private Attributes | |
| static std::vector< std::future< std::string > > | detached_futures_ |
Additional Inherited Members | |
Protected Member Functions inherited from smacc2::SmaccAsyncClientBehavior | |
| void | postSuccessEvent () |
| void | postFailureEvent () |
| virtual void | dispose () override |
| bool | isShutdownRequested () |
| onEntry is executed in a new thread. However the current state cannot be left until the onEntry thread finishes. This flag can be checked from the onEntry thread to force finishing the thread. | |
Protected Member Functions inherited from smacc2::ISmaccClientBehavior | |
| virtual void | runtimeConfigure () |
| template<typename EventType > | |
| void | postEvent (const EventType &ev) |
| template<typename EventType > | |
| void | postEvent () |
| ISmaccState * | getCurrentState () |
| virtual rclcpp::Node::SharedPtr | getNode () const |
| virtual rclcpp::Logger | getLogger () const |
Definition at line 35 of file cb_ros_launch_2.hpp.
| smacc2::client_behaviors::CbRosLaunch2::CbRosLaunch2 | ( | ) |
Definition at line 28 of file cb_ros_launch_2.cpp.
| smacc2::client_behaviors::CbRosLaunch2::CbRosLaunch2 | ( | std::string | package, |
| std::string | launchfile, | ||
| RosLaunchMode | launchmode ) |
Definition at line 36 of file cb_ros_launch_2.cpp.
|
virtual |
Definition at line 41 of file cb_ros_launch_2.cpp.
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 49 of file cb_ros_launch_2.cpp.
References client_, smacc2::client_bases::ClRosLaunch2::executeRosLaunch(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::SmaccAsyncClientBehavior::isShutdownRequested(), smacc2::client_bases::ClRosLaunch2::launch(), smacc2::client_behaviors::LAUNCH_CLIENT_BEHAVIOR_LIFETIME, smacc2::client_behaviors::LAUNCH_DETTACHED, smacc2::client_bases::ClRosLaunch2::launchFileName_, launchFileName_, launchMode_, smacc2::client_bases::ClRosLaunch2::packageName_, packageName_, smacc2::ISmaccClientBehavior::requiresClient(), and result_.

|
inline |
Definition at line 50 of file cb_ros_launch_2.hpp.
References smacc2::SmaccAsyncClientBehavior::onOrthogonalAllocation().

|
protected |
Definition at line 65 of file cb_ros_launch_2.hpp.
Referenced by onEntry().
|
staticprivate |
Definition at line 38 of file cb_ros_launch_2.hpp.
|
protected |
Definition at line 67 of file cb_ros_launch_2.hpp.
| std::optional<std::string> smacc2::client_behaviors::CbRosLaunch2::launchFileName_ |
Definition at line 58 of file cb_ros_launch_2.hpp.
Referenced by onEntry().
| RosLaunchMode smacc2::client_behaviors::CbRosLaunch2::launchMode_ |
Definition at line 60 of file cb_ros_launch_2.hpp.
Referenced by onEntry().
| std::optional<std::string> smacc2::client_behaviors::CbRosLaunch2::packageName_ |
Definition at line 57 of file cb_ros_launch_2.hpp.
Referenced by onEntry().
|
protected |
Definition at line 63 of file cb_ros_launch_2.hpp.
Referenced by onEntry().