SMACC2
Loading...
Searching...
No Matches
Public Member Functions | Private Member Functions | Private Attributes | List of all members
cl_nav2z::CbWaitNav2Nodes Class Reference

#include <cb_wait_nav2_nodes.hpp>

Inheritance diagram for cl_nav2z::CbWaitNav2Nodes:
Inheritance graph
Collaboration diagram for cl_nav2z::CbWaitNav2Nodes:
Collaboration graph

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
 
- Public Member Functions inherited from smacc2::SmaccAsyncClientBehavior
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
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 ()
 
ISmaccStateMachinegetStateMachine ()
 
std::string getName () const
 
template<typename SmaccClientType >
void requiresClient (SmaccClientType *&storage)
 
template<typename SmaccComponentType >
void requiresComponent (SmaccComponentType *&storage, bool throwExceptionIfNotExist=false)
 
virtual void onExit ()
 

Private Member Functions

void onMessageReceived (const bond::msg::Status &msg)
 

Private Attributes

std::string topicname_
 
rclcpp::Subscription< bond::msg::Status >::SharedPtr sub_
 
std::map< Nav2Nodes, boolreceivedAliveMsg_
 
std::vector< Nav2NodeswaitNodes_
 

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 ()
 
ISmaccStategetCurrentState ()
 
virtual rclcpp::Node::SharedPtr getNode () const
 
virtual rclcpp::Logger getLogger () const
 

Detailed Description

Definition at line 43 of file cb_wait_nav2_nodes.hpp.

Constructor & Destructor Documentation

◆ CbWaitNav2Nodes() [1/2]

cl_nav2z::CbWaitNav2Nodes::CbWaitNav2Nodes ( std::string  topicname,
std::vector< Nav2Nodes waitNodes = Nav2Nodes::PlannerServerNav2Nodes::ControllerServerNav2Nodes::BtNavigator} 
)

Definition at line 31 of file cb_wait_nav2_nodes.cpp.

32: topicname_(topic), waitNodes_(waitNodes)
33{
34}
std::vector< Nav2Nodes > waitNodes_

◆ CbWaitNav2Nodes() [2/2]

cl_nav2z::CbWaitNav2Nodes::CbWaitNav2Nodes ( std::vector< Nav2Nodes waitNodes = Nav2Nodes::PlannerServerNav2Nodes::ControllerServerNav2Nodes::BtNavigator})

Definition at line 26 of file cb_wait_nav2_nodes.cpp.

27: CbWaitNav2Nodes("/bond", waitNodes)
28{
29}
CbWaitNav2Nodes(std::string topicname, std::vector< Nav2Nodes > waitNodes={ Nav2Nodes::PlannerServer, Nav2Nodes::ControllerServer, Nav2Nodes::BtNavigator})

Member Function Documentation

◆ onEntry()

void cl_nav2z::CbWaitNav2Nodes::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 80 of file cb_wait_nav2_nodes.cpp.

81{
82 std::stringstream ss;
83 for (auto v : waitNodes_)
84 {
85 receivedAliveMsg_[v] = false;
86 ss << "[CbWaitNav2Nodes] - " << toString(v) << ": waiting" << std::endl;
87 }
88 RCLCPP_INFO(getLogger(), ss.str().c_str());
89
90 //rclcpp::SensorDataQoS qos;
91 rclcpp::SubscriptionOptions sub_option;
92
93 sub_ = getNode()->create_subscription<bond::msg::Status>(
94 topicname_, 20, std::bind(&CbWaitNav2Nodes::onMessageReceived, this, std::placeholders::_1),
95 sub_option);
96}
std::map< Nav2Nodes, bool > receivedAliveMsg_
void onMessageReceived(const bond::msg::Status &msg)
rclcpp::Subscription< bond::msg::Status >::SharedPtr sub_
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
std::string toString(Nav2Nodes value)

References smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getNode(), onMessageReceived(), receivedAliveMsg_, sub_, topicname_, cl_nav2z::toString(), and waitNodes_.

Here is the call graph for this function:

◆ onMessageReceived()

void cl_nav2z::CbWaitNav2Nodes::onMessageReceived ( const bond::msg::Status &  msg)
private

Definition at line 36 of file cb_wait_nav2_nodes.cpp.

37{
38 auto value = fromString(msg.id);
39 bool updated = false;
40 // RCLCPP_INFO(getLogger(), "[CbWaitNav2Nodes] received '%s'", msg.id.c_str());
41
42 if (receivedAliveMsg_.count(value) && !receivedAliveMsg_[value])
43 {
44 RCLCPP_INFO(getLogger(), "[CbWaitNav2Nodes] '%s' alive received", msg.id.c_str());
45 receivedAliveMsg_[value] = true;
46 updated = true;
47 }
48
49 if (updated)
50 {
51 bool success = true;
52 std::stringstream ss;
53 for (auto & pair : receivedAliveMsg_)
54 {
55 if (!pair.second)
56 {
57 success = false;
58 }
59 ss << "- " << toString(pair.first) << ": " << (pair.second ? "ALIVE" : "WAITING")
60 << std::endl;
61 }
62
63 RCLCPP_INFO_STREAM(
64 getLogger(), "[CbWaitNav2Nodes] waiting nodes status:" << std::endl
65 << ss.str().c_str());
66
67 if (success)
68 {
69 RCLCPP_INFO(getLogger(), "[CbWaitNav2Nodes] success event");
70 this->postSuccessEvent();
71 sub_ = nullptr;
72 }
73 else
74 {
75 RCLCPP_INFO(getLogger(), "[CbWaitNav2Nodes] still missing nodes");
76 }
77 }
78}
Nav2Nodes fromString(std::string str)

References cl_nav2z::fromString(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::SmaccAsyncClientBehavior::postSuccessEvent(), receivedAliveMsg_, sub_, and cl_nav2z::toString().

Referenced by onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ receivedAliveMsg_

std::map<Nav2Nodes, bool> cl_nav2z::CbWaitNav2Nodes::receivedAliveMsg_
private

Definition at line 63 of file cb_wait_nav2_nodes.hpp.

Referenced by onEntry(), and onMessageReceived().

◆ sub_

rclcpp::Subscription<bond::msg::Status>::SharedPtr cl_nav2z::CbWaitNav2Nodes::sub_
private

Definition at line 62 of file cb_wait_nav2_nodes.hpp.

Referenced by onEntry(), and onMessageReceived().

◆ topicname_

std::string cl_nav2z::CbWaitNav2Nodes::topicname_
private

Definition at line 60 of file cb_wait_nav2_nodes.hpp.

Referenced by onEntry().

◆ waitNodes_

std::vector<Nav2Nodes> cl_nav2z::CbWaitNav2Nodes::waitNodes_
private

Definition at line 65 of file cb_wait_nav2_nodes.hpp.

Referenced by onEntry().


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