32: topicname_(topic), waitNodes_(waitNodes)
44 RCLCPP_INFO(
getLogger(),
"[CbWaitNav2Nodes] '%s' alive received", msg.id.c_str());
59 ss <<
"- " <<
toString(pair.first) <<
": " << (pair.second ?
"ALIVE" :
"WAITING")
64 getLogger(),
"[CbWaitNav2Nodes] waiting nodes status:" << std::endl
69 RCLCPP_INFO(
getLogger(),
"[CbWaitNav2Nodes] success event");
75 RCLCPP_INFO(
getLogger(),
"[CbWaitNav2Nodes] still missing nodes");
86 ss <<
"[CbWaitNav2Nodes] - " <<
toString(v) <<
": waiting" << std::endl;
88 RCLCPP_INFO(
getLogger(), ss.str().c_str());
91 rclcpp::SubscriptionOptions sub_option;
93 sub_ =
getNode()->create_subscription<bond::msg::Status>(
103 return "planner_server";
105 return "controller_server";
107 return "recoveries_server";
109 return "bt_navigator";
119 if (
id ==
"planner_server")
121 else if (
id ==
"controller_server")
123 else if (
id ==
"recoveries_server")
125 else if (
id ==
"bt_navigator")
127 else if (
id ==
"map_server")
std::map< Nav2Nodes, bool > receivedAliveMsg_
std::vector< Nav2Nodes > waitNodes_
void onMessageReceived(const bond::msg::Status &msg)
rclcpp::Subscription< bond::msg::Status >::SharedPtr sub_
CbWaitNav2Nodes(std::string topicname, std::vector< Nav2Nodes > waitNodes={ Nav2Nodes::PlannerServer, Nav2Nodes::ControllerServer, Nav2Nodes::BtNavigator})
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
std::string toString(Nav2Nodes value)
Nav2Nodes fromString(std::string str)