Skip to content

Commit

Permalink
Merge ign-transport8 ➡️ ign-transport11 (#333)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <louise@openrobotics.org>
  • Loading branch information
chapulina committed Jul 23, 2022
2 parents 8fadc47 + c0c54bb commit 8191ef3
Show file tree
Hide file tree
Showing 8 changed files with 228 additions and 49 deletions.
7 changes: 5 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -94,8 +94,11 @@ else ()
endif()

#--------------------------------------
# Find ignition-tools
ign_find_package(ignition-tools QUIET)
# Find if command is available. This is used to enable tests.
# Note that CLI files are installed regardless of whether the dependency is
# available during build time
find_program(HAVE_IGN_TOOLS ign)
set (IGN_TOOLS_VER 1)

#--------------------------------------
# Find SQLite3
Expand Down
60 changes: 30 additions & 30 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,20 +1,20 @@
# Ignition Transport
# Gazebo Transport

**Maintainer:** caguero AT openrobotics DOT org

[![GitHub open issues](https://img.shields.io/github/issues-raw/ignitionrobotics/ign-transport.svg)](https://github.com/ignitionrobotics/ign-transport/issues)
[![GitHub open pull requests](https://img.shields.io/github/issues-pr-raw/ignitionrobotics/ign-transport.svg)](https://github.com/ignitionrobotics/ign-transport/pulls)
[![GitHub open issues](https://img.shields.io/github/issues-raw/gazebosim/gz-transport.svg)](https://github.com/gazebosim/gz-transport/issues)
[![GitHub open pull requests](https://img.shields.io/github/issues-pr-raw/gazebosim/gz-transport.svg)](https://github.com/gazebosim/gz-transport/pulls)
[![Discourse topics](https://img.shields.io/discourse/https/community.gazebosim.org/topics.svg)](https://community.gazebosim.org)
[![Hex.pm](https://img.shields.io/hexpm/l/plug.svg)](https://www.apache.org/licenses/LICENSE-2.0)

Build | Status
-- | --
Test coverage | [![codecov](https://codecov.io/gh/ignitionrobotics/ign-transport/branch/main/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/ign-transport)
Ubuntu Bionic | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_transport-ci-main-bionic-amd64)](https://build.osrfoundation.org/job/ignition_transport-ci-main-bionic-amd64)
Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_transport-ci-main-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_transport-ci-main-homebrew-amd64)
Windows | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ign_transport-ci-win)](https://build.osrfoundation.org/job/ign_transport-ci-win/)
Test coverage | [![codecov](https://codecov.io/gh/gazebosim/gz-transport/branch/ign-transport11/graph/badge.svg)](https://codecov.io/gh/gazebosim/gz-transport/branch/ign-transport11)
Ubuntu Focal | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_transport-ci-ign-transport11-focal-amd64)](https://build.osrfoundation.org/job/ignition_transport-ci-ign-transport11-focal-amd64)
Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_transport-ci-ign-transport11-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_transport-ci-ign-transport11-homebrew-amd64)
Windows | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ign_transport-ign-11-win)](https://build.osrfoundation.org/job/ign_transport-ign-11-win)

Ignition Transport, a component of [Ignition Robotics](https://ignitionrobotics.org), provides fast and efficient asyncronous message passing, services, and data logging.
Gazebo Transport, a component of [Gazebo](https://gazebosim.org), provides fast and efficient asynchronous message passing, services, and data logging.

# Table of Contents

Expand All @@ -40,81 +40,81 @@ Ignition Transport, a component of [Ignition Robotics](https://ignitionrobotics.

# Features

Ignition Transport is an open source communication library that allows
Gazebo Transport is an open source communication library that allows
exchanging data between clients. In our context, a client is called a node.
Nodes might be running within the same process in the same machine or in
machines located in different continents. Ignition Transport is multi-platform
machines located in different continents. Gazebo Transport is multi-platform
(Linux, Mac OS X, and Windows), so all the low level details, such as data
alignment or endianness are hidden for you.

Ignition Transport uses Google Protocol buffers as the data serialization format
Gazebo Transport uses Google Protocol buffers as the data serialization format
for communicating between nodes. Users can define their own messages using the
Protobuf utils, and then, exchange them between the nodes. Ignition Transport
Protobuf utils, and then, exchange them between the nodes. Gazebo Transport
discovers, serializes and delivers messages to the destinations using a
combination of custom code and ZeroMQ.

# Install

See the [installation tutorial](https://ignitionrobotics.org/api/transport/11.0/installation.html).
See the [installation tutorial](https://gazebosim.org/api/transport/11.0/installation.html).

# Usage

See [tutorials](https://ignitionrobotics.org/api/transport/11.0/tutorials.html)
and the [example directory](https://github.com/ignitionrobotics/ign-transport/blob/main/example/)
See [tutorials](https://gazebosim.org/api/transport/11.0/tutorials.html)
and the [example directory](https://github.com/gazebosim/gz-transport/blob/main/example/)
in the source code.

## Known issue of command line tools

In the event that the installation is a mix of Debian and from source, command
line tools from `ign-tools` may not work correctly.
line tools from `gz-tools` may not work correctly.

A workaround is to define the environment variable
`IGN_CONFIG_PATH` to point to the location of the Ignition library installation,
`IGN_CONFIG_PATH` to point to the location of the Gazebo library installation,
where the YAML file for the package is found, such as
```
export IGN_CONFIG_PATH=/usr/local/share/ignition
```

This issue is tracked [here](https://github.com/ignitionrobotics/ign-tools/issues/61).
This issue is tracked [here](https://github.com/gazebosim/gz-tools/issues/61).

# Documentation

Visit the [documentation page](https://ignitionrobotics.org/api/transport/11.0/index.html).
Visit the [documentation page](https://gazebosim.org/api/transport/11.0/index.html).

# Folder Structure

```
ign-transport
gz-transport
├── conf Configuration file for the integration with the `ign` CLI tool.
├── docker Dockerfile with ign-transport installed and scripts to build and run the code.
├── example Example programs that use most of the Ignition Transport API.
├── docker Dockerfile with gz-transport installed and scripts to build and run the code.
├── example Example programs that use most of the Gazebo Transport API.
├── include Header files that get installed.
├── log All the code related with Ignition Transport logging.
├── log All the code related with Gazebo Transport logging.
├── src Source code of the core library.
├── test A directory of integration, performance and regression tests.
└── tutorials A set of tutorials about Ignition Transport features.
└── tutorials A set of tutorials about Gazebo Transport features.
```

# Contributing

Please see
[CONTRIBUTING.md](https://github.com/ignitionrobotics/ign-gazebo/blob/main/CONTRIBUTING.md).
Please see the
[contributing gude](https://gazebosim.org/docs/all/contributing).

# Code of Conduct

Please see
[CODE_OF_CONDUCT.md](https://github.com/ignitionrobotics/ign-gazebo/blob/main/CODE_OF_CONDUCT.md).
[CODE_OF_CONDUCT.md](https://github.com/gazebosim/gz-sim/blob/main/CODE_OF_CONDUCT.md).

# Versioning

This library uses [Semantic Versioning](https://semver.org/). Additionally,
this library is part of the [Ignition Robotics project](https://ignitionrobotics.org)
this library is part of the [Gazebo project](https://gazebosim.org)
which periodically releases a versioned set of compatible and complimentary
libraries. See the [Ignition Robotics website](https://ignitionrobotics.org) for
libraries. See the [Gazebo website](https://gazebosim.org) for
version and release information.

# License

This library is licensed under [Apache 2.0](https://www.apache.org/licenses/LICENSE-2.0).
See also the [LICENSE](https://github.com/ignitionrobotics/ign-transport/raw/main/LICENSE)
See also the [LICENSE](https://github.com/gazebosim/gz-transport/raw/main/LICENSE)
file.
4 changes: 2 additions & 2 deletions log/test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -64,8 +64,8 @@ foreach(source_file ${aux})
PRIVATE IGN_TRANSPORT_LOG_BUILD_PATH="$<TARGET_FILE_DIR:${BINARY_NAME}>")
endforeach()

# ign log CLI test
if (IGNITION-TOOLS_BINARY_DIRS)
# CLI test
if (HAVE_IGN_TOOLS)
set(IGN_CONFIG_PATH "${CMAKE_BINARY_DIR}/log/test/lib/ruby/ignition")

add_test(ign_log_record_no_overwrite
Expand Down
1 change: 0 additions & 1 deletion src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,6 @@ foreach(test ${test_list})
target_compile_definitions(${test} PRIVATE
"DETAIL_IGN_TRANSPORT_TEST_DIR=\"$<TARGET_FILE_DIR:${test}>\""
"IGN_TEST_LIBRARY_PATH=\"$<TARGET_FILE_DIR:${PROJECT_LIBRARY_TARGET_NAME}>\"")

endforeach()

if(MSVC)
Expand Down
16 changes: 15 additions & 1 deletion src/cmd/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,8 @@ foreach(test ${test_list})
# multi-configuration generators, like Visual Studio.
target_compile_definitions(${test} PRIVATE
"DETAIL_IGN_TRANSPORT_TEST_DIR=\"$<TARGET_FILE_DIR:${test}>\""
"IGN_TEST_LIBRARY_PATH=\"$<TARGET_FILE_DIR:${PROJECT_LIBRARY_TARGET_NAME}>\"")
"IGN_TEST_LIBRARY_PATH=\"$<TARGET_FILE_DIR:${PROJECT_LIBRARY_TARGET_NAME}>\""
"PROJECT_SOURCE_DIR=\"${PROJECT_SOURCE_DIR}\"")

endforeach()

Expand Down Expand Up @@ -106,3 +107,16 @@ file(GENERATE

# Install the ruby command line library in an unversioned location.
install(FILES ${cmd_script_generated} DESTINATION lib/ruby/ignition)

#===============================================================================
# Bash completion

# Tack version onto and install the bash completion script
configure_file(
"transport.bash_completion.sh"
"${CMAKE_CURRENT_BINARY_DIR}/transport${PROJECT_VERSION_MAJOR}.bash_completion.sh" @ONLY)
install(
FILES
${CMAKE_CURRENT_BINARY_DIR}/transport${PROJECT_VERSION_MAJOR}.bash_completion.sh
DESTINATION
${CMAKE_INSTALL_PREFIX}/${CMAKE_INSTALL_DATAROOTDIR}/gz/gz${IGN_TOOLS_VER}.completion.d)
92 changes: 80 additions & 12 deletions src/cmd/ign_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
*
*/

#include <filesystem>
#include <fstream>
#include <iostream>
#include <string>
#include <ignition/msgs.hh>
Expand Down Expand Up @@ -86,7 +88,7 @@ TEST(ignTest, IGN_UTILS_TEST_DISABLED_ON_MAC(TopicList))
g_partition.c_str());

// Check the 'ign topic -l' command.
std::string ign = std::string(IGN_PATH) + "/ign";
std::string ign = std::string(IGN_PATH);

unsigned int retries = 0u;
bool topicFound = false;
Expand Down Expand Up @@ -117,7 +119,7 @@ TEST(ignTest, TopicInfo)
g_partition.c_str());

// Check the 'ign topic -i' command.
std::string ign = std::string(IGN_PATH) + "/ign";
std::string ign = std::string(IGN_PATH);

unsigned int retries = 0u;
bool infoFound = false;
Expand Down Expand Up @@ -153,7 +155,7 @@ TEST(ignTest, ServiceList)
g_partition.c_str());

// Check the 'ign service -l' command.
std::string ign = std::string(IGN_PATH) + "/ign";
std::string ign = std::string(IGN_PATH);

unsigned int retries = 0u;
bool serviceFound = false;
Expand Down Expand Up @@ -184,7 +186,7 @@ TEST(ignTest, ServiceInfo)
g_partition.c_str());

// Check the 'ign service -i' command.
std::string ign = std::string(IGN_PATH) + "/ign";
std::string ign = std::string(IGN_PATH);

unsigned int retries = 0u;
bool infoFound = false;
Expand Down Expand Up @@ -220,7 +222,7 @@ TEST(ignTest, TopicListSameProc)
EXPECT_TRUE(pub.Publish(msg));

// Check the 'ign topic -l' command.
std::string ign = std::string(IGN_PATH) + "/ign";
std::string ign = std::string(IGN_PATH);

unsigned int retries = 0u;
bool topicFound = false;
Expand Down Expand Up @@ -251,7 +253,7 @@ TEST(ignTest, TopicInfoSameProc)
EXPECT_TRUE(pub.Publish(msg));

// Check the 'ign topic -i' command.
std::string ign = std::string(IGN_PATH) + "/ign";
std::string ign = std::string(IGN_PATH);

unsigned int retries = 0u;
bool infoFound = false;
Expand All @@ -276,7 +278,7 @@ TEST(ignTest, ServiceListSameProc)
EXPECT_TRUE(node.Advertise("/foo", srvEcho));

// Check the 'ign service -l' command.
std::string ign = std::string(IGN_PATH) + "/ign";
std::string ign = std::string(IGN_PATH);

unsigned int retries = 0u;
bool serviceFound = false;
Expand All @@ -299,7 +301,7 @@ TEST(ignTest, ServiceInfoSameProc)
EXPECT_TRUE(node.Advertise("/foo", srvEcho));

// Check the 'ign service -i' command.
std::string ign = std::string(IGN_PATH) + "/ign";
std::string ign = std::string(IGN_PATH);

unsigned int retries = 0u;
bool infoFound = false;
Expand All @@ -326,7 +328,7 @@ TEST(ignTest, TopicPublish)
EXPECT_TRUE(node.Subscribe("/bar", topicCB));

// Check the 'ign topic -p' command.
std::string ign = std::string(IGN_PATH) + "/ign";
std::string ign = std::string(IGN_PATH);
std::string output;

unsigned int retries = 0;
Expand Down Expand Up @@ -381,7 +383,7 @@ TEST(ignTest, ServiceRequest)
msg.set_data(10);

// Check the 'ign service -r' command.
std::string ign = std::string(IGN_PATH) + "/ign";
std::string ign = std::string(IGN_PATH);
std::string output = custom_exec_str(ign +
" service -s " + service + " --reqtype ign_msgs.Int32 " +
"--reptype ign_msgs.Int32 --timeout 1000 " +
Expand All @@ -403,7 +405,7 @@ TEST(ignTest, TopicEcho)
g_partition.c_str());

// Check the 'ign topic -e' command.
std::string ign = std::string(IGN_PATH) + "/ign";
std::string ign = std::string(IGN_PATH);
std::string output = custom_exec_str(
ign + " topic -e -t /foo -d 1.5 " + g_ignVersion);

Expand All @@ -429,7 +431,7 @@ TEST(ignTest, TopicEchoNum)
g_partition.c_str());

// Check the 'ign topic -e -n' command.
std::string ign = std::string(IGN_PATH) + "/ign";
std::string ign = std::string(IGN_PATH);
std::string output = custom_exec_str(
ign + " topic -e -t /foo -n 2 " + g_ignVersion);

Expand Down Expand Up @@ -458,6 +460,72 @@ TEST(ignTest, TopicEchoNum)
testing::waitAndCleanupFork(pi);
}

//////////////////////////////////////////////////
/// \brief Check 'ign service --help' message and bash completion script for
/// consistent flags
TEST(ignTest, ServiceHelpVsCompletionFlags)
{
// Flags in help message
std::string helpOutput = custom_exec_str("ign service --help");

// Call the output function in the bash completion script
std::filesystem::path scriptPath = PROJECT_SOURCE_DIR;
scriptPath = scriptPath / "src" / "cmd" / "transport.bash_completion.sh";

// Equivalent to:
// sh -c "bash -c \". /path/to/transport.bash_completion.sh;
// _gz_service_flags\""
std::string cmd = "bash -c \". " + scriptPath.string() +
"; _gz_service_flags\"";
std::string scriptOutput = custom_exec_str(cmd);

// Tokenize script output
std::istringstream iss(scriptOutput);
std::vector<std::string> flags((std::istream_iterator<std::string>(iss)),
std::istream_iterator<std::string>());

EXPECT_GT(flags.size(), 0u);

// Match each flag in script output with help message
for (const auto &flag : flags)
{
EXPECT_NE(std::string::npos, helpOutput.find(flag)) << helpOutput;
}
}

//////////////////////////////////////////////////
/// \brief Check 'ign topic --help' message and bash completion script for
/// consistent flags
TEST(ignTest, TopicHelpVsCompletionFlags)
{
// Flags in help message
std::string helpOutput = custom_exec_str("ign topic --help");

// Call the output function in the bash completion script
std::filesystem::path scriptPath = PROJECT_SOURCE_DIR;
scriptPath = scriptPath / "src" / "cmd" / "transport.bash_completion.sh";

// Equivalent to:
// sh -c "bash -c \". /path/to/transport.bash_completion.sh;
// _gz_topic_flags\""
std::string cmd = "bash -c \". " + scriptPath.string() +
"; _gz_topic_flags\"";
std::string scriptOutput = custom_exec_str(cmd);

// Tokenize script output
std::istringstream iss(scriptOutput);
std::vector<std::string> flags((std::istream_iterator<std::string>(iss)),
std::istream_iterator<std::string>());

EXPECT_GT(flags.size(), 0u);

// Match each flag in script output with help message
for (const auto &flag : flags)
{
EXPECT_NE(std::string::npos, helpOutput.find(flag)) << helpOutput;
}
}

/////////////////////////////////////////////////
/// Main
int main(int argc, char **argv)
Expand Down
Loading

0 comments on commit 8191ef3

Please sign in to comment.