|
SMACC2
|
#include <cb_wait_nav2_nodes.hpp>


Public Member Functions | |
| CbWaitNav2Nodes (std::string topicname, std::vector< Nav2Nodes > waitNodes={ Nav2Nodes::PlannerServer, Nav2Nodes::ControllerServer, Nav2Nodes::BtNavigator}) | |
| CbWaitNav2Nodes (std::vector< Nav2Nodes > waitNodes={ Nav2Nodes::PlannerServer, Nav2Nodes::ControllerServer, Nav2Nodes::BtNavigator}) | |
| void | onEntry () override |
| CbWaitNav2Nodes (std::string topicname, std::vector< Nav2Nodes > waitNodes={ Nav2Nodes::PlannerServer, Nav2Nodes::ControllerServer, Nav2Nodes::BtNavigator}) | |
| CbWaitNav2Nodes (std::vector< Nav2Nodes > waitNodes={ Nav2Nodes::PlannerServer, Nav2Nodes::ControllerServer, Nav2Nodes::BtNavigator}) | |
| 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 () |
Private Member Functions | |
| void | onMessageReceived (const bond::msg::Status &msg) |
| void | onMessageReceived (const bond::msg::Status &msg) |
Private Attributes | |
| std::string | topicname_ |
| rclcpp::Subscription< bond::msg::Status >::SharedPtr | sub_ |
| std::map< Nav2Nodes, bool > | receivedAliveMsg_ |
| std::vector< Nav2Nodes > | waitNodes_ |
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 43 of file cb_wait_nav2_nodes.hpp.
| cl_nav2z::CbWaitNav2Nodes::CbWaitNav2Nodes | ( | std::string | topicname, |
| std::vector< Nav2Nodes > | waitNodes = { Nav2Nodes::PlannerServer, Nav2Nodes::ControllerServer, Nav2Nodes::BtNavigator} ) |
Definition at line 31 of file cb_wait_nav2_nodes.cpp.
| cl_nav2z::CbWaitNav2Nodes::CbWaitNav2Nodes | ( | std::vector< Nav2Nodes > | waitNodes = { Nav2Nodes::PlannerServer, Nav2Nodes::ControllerServer, Nav2Nodes::BtNavigator} | ) |
Definition at line 26 of file cb_wait_nav2_nodes.cpp.
| cl_nav2z::CbWaitNav2Nodes::CbWaitNav2Nodes | ( | std::string | topicname, |
| std::vector< Nav2Nodes > | waitNodes = { Nav2Nodes::PlannerServer, Nav2Nodes::ControllerServer, Nav2Nodes::BtNavigator} ) |
References cl_nav2z::BtNavigator, cl_nav2z::ControllerServer, and cl_nav2z::PlannerServer.
| cl_nav2z::CbWaitNav2Nodes::CbWaitNav2Nodes | ( | std::vector< Nav2Nodes > | waitNodes = { Nav2Nodes::PlannerServer, Nav2Nodes::ControllerServer, Nav2Nodes::BtNavigator} | ) |
References cl_nav2z::BtNavigator, cl_nav2z::ControllerServer, and cl_nav2z::PlannerServer.
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 80 of file cb_wait_nav2_nodes.cpp.
References smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getNode(), onMessageReceived(), receivedAliveMsg_, sub_, topicname_, cl_nav2z::toString(), and waitNodes_.

|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
|
private |
Definition at line 36 of file cb_wait_nav2_nodes.cpp.
References cl_nav2z::fromString(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::SmaccAsyncClientBehavior::postSuccessEvent(), receivedAliveMsg_, sub_, and cl_nav2z::toString().
Referenced by onEntry().


|
private |
|
private |
Definition at line 63 of file cb_wait_nav2_nodes.hpp.
Referenced by onEntry(), and onMessageReceived().
|
private |
Definition at line 62 of file cb_wait_nav2_nodes.hpp.
Referenced by onEntry(), and onMessageReceived().
|
private |
Definition at line 60 of file cb_wait_nav2_nodes.hpp.
Referenced by onEntry().
|
private |
Definition at line 65 of file cb_wait_nav2_nodes.hpp.
Referenced by onEntry().