Skip to content

Commit

Permalink
gz world: use gz-transport topic
Browse files Browse the repository at this point in the history
Publish to the new /world_control gz-transport topic
to avoid the issue with too many open files after
running `gz world` repeatedly.
Fixes #3341.

Signed-off-by: Steve Peters <scpeters@openrobotics.org>
  • Loading branch information
scpeters committed Feb 23, 2024
1 parent 299fdb2 commit 9e0ce8a
Show file tree
Hide file tree
Showing 4 changed files with 33 additions and 19 deletions.
2 changes: 1 addition & 1 deletion test/performance/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,5 +37,5 @@ if (NOT APPLE AND NOT WIN32)
set(tool_tests
gz_stress.cc
)
gz_build_tests(${tool_tests} EXTRA_LIBS gazebo_transport)
gz_build_tests(${tool_tests} EXTRA_LIBS gazebo_transport ${IGNITION-TRANSPORT_LIBRARIES})
endif()
11 changes: 5 additions & 6 deletions test/performance/gz_stress.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <boost/algorithm/string/trim.hpp>
#include <boost/thread/mutex.hpp>
#include <boost/filesystem.hpp>
#include <ignition/transport/Node.hh>

#include <gazebo/common/CommonIface.hh>
#include <gazebo/msgs/msgs.hh>
Expand All @@ -40,10 +41,10 @@ pid_t g_pid = -1;
boost::condition_variable g_msgCondition;

/////////////////////////////////////////////////
void WorldControlCB(ConstWorldControlPtr &_msg)
void WorldControlCB(const msgs::WorldControl &_msg)
{
boost::mutex::scoped_lock lock(g_mutex);
g_msgDebugOut = _msg->DebugString();
g_msgDebugOut = _msg.DebugString();
g_msgCondition.notify_all();
}

Expand Down Expand Up @@ -149,10 +150,8 @@ TEST_F(gzTest, Stress)
{
init();

gazebo::transport::NodePtr node(new gazebo::transport::Node());
node->Init();
gazebo::transport::SubscriberPtr sub =
node->Subscribe("~/world_control", &WorldControlCB, true);
ignition::transport::Node ignNode;
ignNode.Subscribe("/world_control", &WorldControlCB);

// Run the transport loop: starts a new thread
gazebo::transport::run();
Expand Down
29 changes: 23 additions & 6 deletions tools/gz.cc
Original file line number Diff line number Diff line change
Expand Up @@ -238,12 +238,25 @@ bool WorldCommand::RunImpl()
if (this->vm.count("world-name"))
worldName = this->vm["world-name"].as<std::string>();

transport::NodePtr node(new transport::Node());
node->Init(worldName);
ignition::transport::Node ignNode;

transport::PublisherPtr pub =
node->Advertise<msgs::WorldControl>("~/world_control");
pub->WaitForConnection();
const std::string topic{"/world_control"};
auto pub = ignNode.Advertise<msgs::WorldControl>(topic);

// Wait for subscribers
unsigned int maxSleep = 30;
unsigned int sleep = 0;
unsigned int mSleep = 100;
for (; sleep < maxSleep && !pub.HasConnections(); ++sleep)
{
common::Time::MSleep(mSleep);
}
if (sleep == maxSleep)
{
gzerr << "No subscribers to topic [" << topic <<"], timed out after " <<
maxSleep * mSleep << "ms." << std::endl;
return false;
}

msgs::WorldControl msg;
bool good = false;
Expand Down Expand Up @@ -285,9 +298,13 @@ bool WorldCommand::RunImpl()
}

if (good)
pub->Publish(msg, true);
{
pub.Publish(msg);
}
else
{
this->Help();
}

return true;
}
Expand Down
10 changes: 4 additions & 6 deletions tools/gz_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -190,10 +190,10 @@ void FactoryCB(ConstFactoryPtr &_msg)
}

/////////////////////////////////////////////////
void WorldControlCB(ConstWorldControlPtr &_msg)
void WorldControlCB(const msgs::WorldControl &_msg)
{
boost::mutex::scoped_lock lock(g_mutex);
g_msgDebugOut = _msg->DebugString();
g_msgDebugOut = _msg.DebugString();
g_msgCondition.notify_all();
}

Expand Down Expand Up @@ -503,10 +503,8 @@ TEST_F(gzTest, World)
std::string helpOutput = custom_exec_str("gz help world");
EXPECT_NE(helpOutput.find("gz world"), std::string::npos);

gazebo::transport::NodePtr node(new gazebo::transport::Node());
node->Init();
gazebo::transport::SubscriberPtr sub =
node->Subscribe("~/world_control", &WorldControlCB);
ignition::transport::Node ignNode;
ignNode.Subscribe("/world_control", &WorldControlCB);

// Test world pause
{
Expand Down

0 comments on commit 9e0ce8a

Please sign in to comment.