Skip to content

Commit

Permalink
Fix bug in create where command line arguments were truncated (#472)
Browse files Browse the repository at this point in the history
Signed-off-by: Addisu Z. Taddese <[email protected]>
  • Loading branch information
azeey authored Dec 20, 2023
1 parent a982161 commit 8fba3b4
Show file tree
Hide file tree
Showing 5 changed files with 118 additions and 2 deletions.
10 changes: 9 additions & 1 deletion ros_gz_sim/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -123,11 +123,15 @@ if(BUILD_TESTING)

# GTest
find_package(ament_cmake_gtest REQUIRED)
find_package(launch_testing_ament_cmake REQUIRED)
ament_find_gtest()

ament_add_gtest_executable(test_stopwatch
test/test_stopwatch.cpp
)
ament_add_gtest_executable(test_create
test/test_create.cpp
)

ament_target_dependencies(test_stopwatch rclcpp)

Expand All @@ -139,12 +143,16 @@ if(BUILD_TESTING)
target_link_libraries(test_stopwatch
${PROJECT_NAME}
)
target_link_libraries(test_create
${GZ_TARGET_PREFIX}-transport${GZ_TRANSPORT_VER}::core
)

install(
TARGETS test_stopwatch
TARGETS test_stopwatch test_create
DESTINATION lib/${PROJECT_NAME}
)
ament_add_gtest_test(test_stopwatch)
add_launch_test(test/test_create_node.launch.py TIMEOUT 200)
endif()

ament_package()
3 changes: 3 additions & 0 deletions ros_gz_sim/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,9 @@

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>launch_testing_ament_cmake</test_depend>
<test_depend>launch_ros</test_depend>
<test_depend>launch_testing</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
4 changes: 3 additions & 1 deletion ros_gz_sim/src/create.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,9 @@ int main(int _argc, char ** _argv)
char ** filtered_argv = new char *[(filtered_argc + 1)];
for (int ii = 0; ii < filtered_argc; ++ii) {
filtered_argv[ii] = new char[filtered_arguments[ii].size() + 1];
snprintf(filtered_argv[ii], sizeof(filtered_argv), "%s", filtered_arguments[ii].c_str());
snprintf(
filtered_argv[ii],
filtered_arguments[ii].size() + 1, "%s", filtered_arguments[ii].c_str());
}
filtered_argv[filtered_argc] = nullptr;

Expand Down
56 changes: 56 additions & 0 deletions ros_gz_sim/test/test_create.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
// Copyright 2023 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.


#include <gz/msgs/boolean.pb.h>
#include <gz/msgs/entity_factory.pb.h>
#include <csignal>
#include <chrono>
#include <condition_variable>
#include <functional>
#include <mutex>
#include <gz/transport/Node.hh>

// Simple application that provides a `/create` service and prints out the
// sdf_filename of the request. This works in conjection with
// test_create_node.launch.py
int main()
{
std::mutex m;
std::condition_variable cv;
bool test_complete = false;

gz::transport::Node node;
auto cb = std::function(
[&](
const gz::msgs::EntityFactory & _req,
gz::msgs::Boolean & _res) -> bool {
std::cout << _req.sdf_filename() << std::endl;
_res.set_data(true);

{
std::lock_guard<std::mutex> lk(m);
test_complete = true;
}
cv.notify_one();
return true;
});

node.Advertise("/world/default/create", cb);
// wait until we receive a message.
std::unique_lock<std::mutex> lk(m);
cv.wait(lk, [&] {return test_complete;});
// Sleep so that the service response can be sent before exiting.
std::this_thread::sleep_for(std::chrono::seconds(1));
}
47 changes: 47 additions & 0 deletions ros_gz_sim/test/test_create_node.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
# Copyright 2023 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import unittest

from launch import LaunchDescription

from launch_ros.actions import Node

import launch_testing


def generate_test_description():
expected_file_name = 'nonexistent/long/file_name'
create = Node(package='ros_gz_sim', executable='create',
arguments=['-world', 'default', '-file', expected_file_name], output='screen')
test_create = Node(package='ros_gz_sim', executable='test_create', output='screen')
return LaunchDescription([
create,
test_create,
launch_testing.util.KeepAliveProc(),
launch_testing.actions.ReadyToTest(),
]), locals()


class WaitForTests(unittest.TestCase):

def test_termination(self, test_create, proc_info):
proc_info.assertWaitForShutdown(process=test_create, timeout=200)


@launch_testing.post_shutdown_test()
class CreateTest(unittest.TestCase):

def test_output(self, expected_file_name, test_create, proc_output):
launch_testing.asserts.assertInStdout(proc_output, expected_file_name, test_create)

0 comments on commit 8fba3b4

Please sign in to comment.