Skip to content

Commit

Permalink
Reduce lifecycle service client nodes (#2469)
Browse files Browse the repository at this point in the history
* remove LifecycleServiceClient's constructor which create internal node

Signed-off-by: zhenpeng ge <[email protected]>

* fix the linter

Signed-off-by: zhenpeng ge <[email protected]>
  • Loading branch information
gezp authored Jul 23, 2021
1 parent fd6fd61 commit a800b89
Show file tree
Hide file tree
Showing 7 changed files with 37 additions and 55 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -43,15 +43,6 @@ enum class SystemStatus {ACTIVE, INACTIVE, TIMEOUT};
class LifecycleManagerClient
{
public:
/**
* @brief A constructor for LifeCycleMangerClient
* @param name Managed node name
* @param ns Service node namespace
*/
explicit LifecycleManagerClient(
const std::string & name,
const std::string & ns = "");

/**
* @brief A constructor for LifeCycleMangerClient
* @param name Managed node name
Expand Down
17 changes: 0 additions & 17 deletions nav2_lifecycle_manager/src/lifecycle_manager_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,23 +26,6 @@ namespace nav2_lifecycle_manager
{
using nav2_util::geometry_utils::orientationAroundZAxis;

LifecycleManagerClient::LifecycleManagerClient(
const std::string & name,
const std::string & ns)
{
manage_service_name_ = name + std::string("/manage_nodes");
active_service_name_ = name + std::string("/is_active");

// Create the node to use for all of the service clients
node_ = std::make_shared<rclcpp::Node>(name + "_service_client", ns);

// Create the service clients
manager_client_ = std::make_shared<nav2_util::ServiceClient<ManageLifecycleNodes>>(
manage_service_name_, node_);
is_active_client_ = std::make_shared<nav2_util::ServiceClient<std_srvs::srv::Trigger>>(
active_service_name_, node_);
}

LifecycleManagerClient::LifecycleManagerClient(
const std::string & name,
std::shared_ptr<rclcpp::Node> parent_node)
Expand Down
6 changes: 4 additions & 2 deletions nav2_lifecycle_manager/test/test_bond.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,8 @@ TEST(LifecycleBondTest, POSITIVE)
// let the lifecycle server come up
rclcpp::Rate(1).sleep();

nav2_lifecycle_manager::LifecycleManagerClient client("lifecycle_manager_test");
auto node = std::make_shared<rclcpp::Node>("lifecycle_manager_test_service_client");
nav2_lifecycle_manager::LifecycleManagerClient client("lifecycle_manager_test", node);

// create node, should be up now
auto fixture = TestFixture(true, "bond_tester");
Expand Down Expand Up @@ -169,7 +170,8 @@ TEST(LifecycleBondTest, POSITIVE)

TEST(LifecycleBondTest, NEGATIVE)
{
nav2_lifecycle_manager::LifecycleManagerClient client("lifecycle_manager_test");
auto node = std::make_shared<rclcpp::Node>("lifecycle_manager_test_service_client");
nav2_lifecycle_manager::LifecycleManagerClient client("lifecycle_manager_test", node);

// create node, now without bond setup to connect to. Should fail because no bond
auto fixture = TestFixture(false, "bond_tester");
Expand Down
6 changes: 4 additions & 2 deletions nav2_lifecycle_manager/test/test_lifecycle_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,8 @@ class LifecycleClientTestFixture
TEST(LifecycleClientTest, BasicTest)
{
LifecycleClientTestFixture fix;
nav2_lifecycle_manager::LifecycleManagerClient client("lifecycle_manager_test");
auto node = std::make_shared<rclcpp::Node>("lifecycle_manager_test_service_client");
nav2_lifecycle_manager::LifecycleManagerClient client("lifecycle_manager_test", node);
EXPECT_EQ(
nav2_lifecycle_manager::SystemStatus::TIMEOUT,
client.is_active(std::chrono::nanoseconds(1000)));
Expand All @@ -104,7 +105,8 @@ TEST(LifecycleClientTest, BasicTest)

TEST(LifecycleClientTest, WithoutFixture)
{
nav2_lifecycle_manager::LifecycleManagerClient client("lifecycle_manager_test");
auto node = std::make_shared<rclcpp::Node>("lifecycle_manager_test_service_client");
nav2_lifecycle_manager::LifecycleManagerClient client("lifecycle_manager_test", node);
EXPECT_EQ(
nav2_lifecycle_manager::SystemStatus::TIMEOUT,
client.is_active(std::chrono::nanoseconds(1000)));
Expand Down
16 changes: 8 additions & 8 deletions nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,8 +121,8 @@ private Q_SLOTS:
NavThroughPosesGoalHandle::SharedPtr nav_through_poses_goal_handle_;

// The client used to control the nav2 stack
nav2_lifecycle_manager::LifecycleManagerClient client_nav_;
nav2_lifecycle_manager::LifecycleManagerClient client_loc_;
std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_nav_;
std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_loc_;

QPushButton * start_reset_button_{nullptr};
QPushButton * pause_resume_button_{nullptr};
Expand Down Expand Up @@ -193,8 +193,8 @@ class InitialThread : public QThread
using SystemStatus = nav2_lifecycle_manager::SystemStatus;

explicit InitialThread(
nav2_lifecycle_manager::LifecycleManagerClient & client_nav,
nav2_lifecycle_manager::LifecycleManagerClient & client_loc)
std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> & client_nav,
std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> & client_loc)
: client_nav_(client_nav), client_loc_(client_loc)
{}

Expand All @@ -205,14 +205,14 @@ class InitialThread : public QThread

while (status_nav == SystemStatus::TIMEOUT) {
if (status_nav == SystemStatus::TIMEOUT) {
status_nav = client_nav_.is_active(std::chrono::seconds(1));
status_nav = client_nav_->is_active(std::chrono::seconds(1));
}
}

// try to communicate twice, might not actually be up if in SLAM mode
bool tried_loc_bringup_once = false;
while (status_loc == SystemStatus::TIMEOUT) {
status_loc = client_loc_.is_active(std::chrono::seconds(1));
status_loc = client_loc_->is_active(std::chrono::seconds(1));
if (tried_loc_bringup_once) {
break;
}
Expand All @@ -239,8 +239,8 @@ class InitialThread : public QThread
void localizationInactive();

private:
nav2_lifecycle_manager::LifecycleManagerClient client_nav_;
nav2_lifecycle_manager::LifecycleManagerClient client_loc_;
std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_nav_;
std::shared_ptr<nav2_lifecycle_manager::LifecycleManagerClient> client_loc_;
};

} // namespace nav2_rviz_plugins
Expand Down
32 changes: 17 additions & 15 deletions nav2_rviz_plugins/src/nav2_panel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,9 +38,7 @@ GoalPoseUpdater GoalUpdater;

Nav2Panel::Nav2Panel(QWidget * parent)
: Panel(parent),
server_timeout_(100),
client_nav_("lifecycle_manager_navigation"),
client_loc_("lifecycle_manager_localization")
server_timeout_(100)
{
// Create the control button and its tooltip

Expand Down Expand Up @@ -276,6 +274,14 @@ Nav2Panel::Nav2Panel(QWidget * parent)
accumulatedNTPTransition->setTargetState(idle_);
accumulated_nav_through_poses_->addTransition(accumulatedNTPTransition);

auto options = rclcpp::NodeOptions().arguments(
{"--ros-args --remap __node:=navigation_dialog_action_client"});
client_node_ = std::make_shared<rclcpp::Node>("_", options);

client_nav_ = std::make_shared<nav2_lifecycle_manager::LifecycleManagerClient>(
"lifecycle_manager_navigation", client_node_);
client_loc_ = std::make_shared<nav2_lifecycle_manager::LifecycleManagerClient>(
"lifecycle_manager_localization", client_node_);
initial_thread_ = new InitialThread(client_nav_, client_loc_);
connect(initial_thread_, &InitialThread::finished, initial_thread_, &QObject::deleteLater);

Expand Down Expand Up @@ -345,10 +351,6 @@ Nav2Panel::Nav2Panel(QWidget * parent)
main_layout->setContentsMargins(10, 10, 10, 10);
setLayout(main_layout);

auto options = rclcpp::NodeOptions().arguments(
{"--ros-args --remap __node:=navigation_dialog_action_client"});
client_node_ = std::make_shared<rclcpp::Node>("_", options);

navigation_action_client_ =
rclcpp_action::create_client<nav2_msgs::action::NavigateToPose>(
client_node_,
Expand Down Expand Up @@ -437,12 +439,12 @@ Nav2Panel::onPause()
QtConcurrent::run(
std::bind(
&nav2_lifecycle_manager::LifecycleManagerClient::pause,
&client_nav_, std::placeholders::_1), server_timeout_);
client_nav_.get(), std::placeholders::_1), server_timeout_);
QFuture<void> futureLoc =
QtConcurrent::run(
std::bind(
&nav2_lifecycle_manager::LifecycleManagerClient::pause,
&client_loc_, std::placeholders::_1), server_timeout_);
client_loc_.get(), std::placeholders::_1), server_timeout_);
}

void
Expand All @@ -452,12 +454,12 @@ Nav2Panel::onResume()
QtConcurrent::run(
std::bind(
&nav2_lifecycle_manager::LifecycleManagerClient::resume,
&client_nav_, std::placeholders::_1), server_timeout_);
client_nav_.get(), std::placeholders::_1), server_timeout_);
QFuture<void> futureLoc =
QtConcurrent::run(
std::bind(
&nav2_lifecycle_manager::LifecycleManagerClient::resume,
&client_loc_, std::placeholders::_1), server_timeout_);
client_loc_.get(), std::placeholders::_1), server_timeout_);
}

void
Expand All @@ -467,12 +469,12 @@ Nav2Panel::onStartup()
QtConcurrent::run(
std::bind(
&nav2_lifecycle_manager::LifecycleManagerClient::startup,
&client_nav_, std::placeholders::_1), server_timeout_);
client_nav_.get(), std::placeholders::_1), server_timeout_);
QFuture<void> futureLoc =
QtConcurrent::run(
std::bind(
&nav2_lifecycle_manager::LifecycleManagerClient::startup,
&client_loc_, std::placeholders::_1), server_timeout_);
client_loc_.get(), std::placeholders::_1), server_timeout_);
}

void
Expand All @@ -482,12 +484,12 @@ Nav2Panel::onShutdown()
QtConcurrent::run(
std::bind(
&nav2_lifecycle_manager::LifecycleManagerClient::reset,
&client_nav_, std::placeholders::_1), server_timeout_);
client_nav_.get(), std::placeholders::_1), server_timeout_);
QFuture<void> futureLoc =
QtConcurrent::run(
std::bind(
&nav2_lifecycle_manager::LifecycleManagerClient::reset,
&client_loc_, std::placeholders::_1), server_timeout_);
client_loc_.get(), std::placeholders::_1), server_timeout_);
timer_.stop();
}

Expand Down
6 changes: 4 additions & 2 deletions nav2_system_tests/src/updown/test_updown.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include <random>
#include <string>
#include <vector>
#include <memory>

#include "geometry_msgs/msg/pose_stamped.hpp"
#include "nav2_lifecycle_manager/lifecycle_manager_client.hpp"
Expand All @@ -26,8 +27,9 @@ int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
RCLCPP_INFO(rclcpp::get_logger("test_updown"), "Initializing test");
nav2_lifecycle_manager::LifecycleManagerClient client_nav("lifecycle_manager_navigation");
nav2_lifecycle_manager::LifecycleManagerClient client_loc("lifecycle_manager_localization");
auto node = std::make_shared<rclcpp::Node>("lifecycle_manager_service_client");
nav2_lifecycle_manager::LifecycleManagerClient client_nav("lifecycle_manager_navigation", node);
nav2_lifecycle_manager::LifecycleManagerClient client_loc("lifecycle_manager_localization", node);
bool test_passed = true;

// Wait for a few seconds to let all of the nodes come up
Expand Down

0 comments on commit a800b89

Please sign in to comment.