Skip to content

Commit

Permalink
2 ➡️ 3 (plus fixes) (#296)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina authored Aug 20, 2020
2 parents 60e48fe + 408dd19 commit db6a467
Show file tree
Hide file tree
Showing 28 changed files with 1,101 additions and 23 deletions.
6 changes: 6 additions & 0 deletions .github/ci-bionic/after_make.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
#!/bin/sh -l

set -x

# Install
make install
13 changes: 13 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,19 @@

## Ignition Gazebo 2.x

### Ignition Gazebo 2.23.0 (2020-07-28)

1. Deactivate PerformerDetector if its parent model gets removed.
* [Pull Request 260](https://github.com/ignitionrobotics/ign-gazebo/pull/260)

1. Backport support for <uri>s from Fuel #255
* [Pull Request 255](https://github.com/ignitionrobotics/ign-gazebo/pull/255)

### Ignition Gazebo 2.22.0 (2020-07-22)

1. Allow zero or more key/value pairs to be added to detection header information.
* [Pull Request 257](https://github.com/ignitionrobotics/ign-gazebo/pull/257)

### Ignition Gazebo 2.21.0 (2020-07-16)

1. Added support for controlling which joints are published by the
Expand Down
9 changes: 9 additions & 0 deletions include/ignition/gazebo/Server.hh
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,12 @@ namespace ignition
/// 1. /world/<world_name>/scene/info(none) : ignition::msgs::Scene
/// + Returns the current scene information.
///
/// 2. /gazebo/resource_paths/get : ignition::msgs::StringMsg_V
/// + Get list of resource paths.
///
/// 3. /gazebo/resource_paths/add : ignition::msgs::Empty
/// + Add new resource paths.
///
/// ## Topics
///
/// The following are topics provided by the Server.
Expand All @@ -95,6 +101,9 @@ namespace ignition
/// 2. /world/<world_name>/stats : ignition::msgs::WorldStatistics
/// + This topic is throttled to 5Hz.
///
/// 3. /gazebo/resource_paths : ignition::msgs::StringMsg_V
/// + Updated list of resource paths.
///
class IGNITION_GAZEBO_VISIBLE Server
{
/// \brief Construct the server using the parameters specified in a
Expand Down
21 changes: 20 additions & 1 deletion include/ignition/gazebo/Util.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#define IGNITION_GAZEBO_UTIL_HH_

#include <string>
#include <vector>

#include <ignition/math/Pose3.hh>
#include "ignition/gazebo/config.hh"
Expand Down Expand Up @@ -66,8 +67,26 @@ namespace ignition
/// paths.
/// \param[in] _filePath The path to a file in disk.
/// \return The full path URI.
std::string asFullPath(const std::string &_uri,
std::string IGNITION_GAZEBO_VISIBLE asFullPath(const std::string &_uri,
const std::string &_filePath);

/// \brief Get resource paths based on latest environment variables.
/// \return All paths in the IGN_GAZEBO_RESOURCE_PATH variable.
std::vector<std::string> IGNITION_GAZEBO_VISIBLE resourcePaths();

/// \brief Add resource paths based on latest environment variables.
/// This will update the SDF and Ignition environment variables, and
/// optionally add more paths to the list.
/// \param[in] _paths Optional paths to add.
void IGNITION_GAZEBO_VISIBLE addResourcePaths(
const std::vector<std::string> &_paths = {});

/// \brief Environment variable holding resource paths.
const std::string kResourcePathEnv{"IGN_GAZEBO_RESOURCE_PATH"};

/// \brief Environment variable used by SDFormat to find URIs inside
/// `<include>`
const std::string kSdfPathEnv{"SDF_PATH"};
}
}
}
Expand Down
12 changes: 8 additions & 4 deletions src/SdfGenerator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -200,9 +200,11 @@ namespace sdf_generator
/// \brief Recursively go through the child elements of the input element and
/// update all relative URIs to absolute.
///
/// The resulting URI will have a "file://" scheme regardless of whether the
/// original URI had the scheme. i.e, absolute URIs without the "file://"
/// scheme will also be updated by this function.
/// URIs with http / https scheme won't be modified.
///
/// For all other URIs, the resulting URI will have a "file://" scheme
/// regardless of whether the original URI had the scheme. i.e, absolute URIs
/// without the "file://" scheme will also be updated by this function.
/// \param[in] _elem Input element to update
/// \param[in] _prefixPath Path to be prepended to relative URIs.
static void relativeToAbsoluteUri(const sdf::ElementPtr &_elem,
Expand All @@ -214,7 +216,9 @@ namespace sdf_generator
auto uriStr = uriElem->Get<std::string>();
// If the URI starts with "file://", it is assumed to be an
// absolute path, so there is no need to update it.
if (uriStr.find("file://") == std::string::npos)
if (uriStr.find("file://") == std::string::npos &&
uriStr.find("http://") == std::string::npos &&
uriStr.find("https://") == std::string::npos)
{
if (uriStr[0] != '/')
{
Expand Down
11 changes: 9 additions & 2 deletions src/SdfGenerator_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -52,19 +52,28 @@ static bool isSubset(const sdf::ElementPtr &_elemA,
const sdf::ElementPtr &_elemB)
{
if (_elemA->GetName() != _elemB->GetName())
{
return false;
}

if (_elemA->GetAttributeCount() != _elemB->GetAttributeCount())
{
return false;
}

// Compare attributes
for (std::size_t i = 0; i < _elemA->GetAttributeCount(); ++i)
{
sdf::ParamPtr attrA = _elemA->GetAttribute(i);
sdf::ParamPtr attrB = _elemB->GetAttribute(attrA->GetKey());
if (attrA->GetTypeName() != attrB->GetTypeName())
{
return false;
}
if (attrA->GetAsString() != attrB->GetAsString())
{
return false;
}
}
// Compare values
{
Expand Down Expand Up @@ -844,8 +853,6 @@ TEST_F(GenerateWorldFixture, ModelsInline)
const std::optional<std::string> worldStr = sdf_generator::generateWorld(
this->ecm, worldEntity, this->includeUriMap, this->sdfGenConfig);
ASSERT_TRUE(worldStr.has_value());
// std::cout << "Generated world:" << std::endl;
// std::cout << worldStr << std::endl;
sdf::Root newRoot;
newRoot.LoadSdfString(*worldStr);
EXPECT_TRUE(isSubset(newRoot.Element(), this->root.Element()));
Expand Down
8 changes: 6 additions & 2 deletions src/Server.cc
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@
* limitations under the License.
*
*/
#include "ignition/gazebo/Server.hh"

#include <ignition/common/SystemPaths.hh>
#include <ignition/fuel_tools/Interface.hh>
Expand All @@ -23,6 +22,9 @@
#include <sdf/Error.hh>

#include "ignition/gazebo/config.hh"
#include "ignition/gazebo/Server.hh"
#include "ignition/gazebo/Util.hh"

#include "ServerPrivate.hh"
#include "SimulationRunner.hh"

Expand Down Expand Up @@ -100,6 +102,8 @@ Server::Server(const ServerConfig &_config)
common::addFindFileURICallback(std::bind(&ServerPrivate::FetchResourceUri,
this->dataPtr.get(), std::placeholders::_1));

addResourcePaths();

sdf::Errors errors;

// Load a world if specified. Check SDF string first, then SDF file
Expand All @@ -120,7 +124,7 @@ Server::Server(const ServerConfig &_config)
else if (!_config.SdfFile().empty())
{
common::SystemPaths systemPaths;
systemPaths.SetFilePathEnv("IGN_GAZEBO_RESOURCE_PATH");
systemPaths.SetFilePathEnv(kResourcePathEnv);
systemPaths.AddFilePaths(IGN_GAZEBO_WORLD_INSTALL_DIR);
std::string filePath = systemPaths.FindFile(_config.SdfFile());
ignmsg << "Loading SDF world file[" << filePath << "].\n";
Expand Down
66 changes: 65 additions & 1 deletion src/ServerPrivate.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,11 +22,13 @@
#include <sdf/World.hh>

#include <ignition/common/Console.hh>
#include <ignition/common/Util.hh>

#include <ignition/fuel_tools/Interface.hh>

#include <ignition/gui/Application.hh>

#include "ignition/gazebo/Util.hh"
#include "SimulationRunner.hh"

using namespace ignition;
Expand Down Expand Up @@ -384,7 +386,26 @@ void ServerPrivate::CreateEntities()
void ServerPrivate::SetupTransport()
{
// Advertise available worlds.
this->node.Advertise("/gazebo/worlds", &ServerPrivate::WorldsService, this);
std::string worldsService{"/gazebo/worlds"};
this->node.Advertise(worldsService, &ServerPrivate::WorldsService, this);

ignmsg << "Serving world names on [" << worldsService << "]" << std::endl;

// Resource path management
std::string addPathService{"/gazebo/resource_paths/add"};
this->node.Advertise(addPathService,
&ServerPrivate::AddResourcePathsService, this);

std::string getPathService{"/gazebo/resource_paths/get"};
this->node.Advertise(getPathService,
&ServerPrivate::ResourcePathsService, this);

std::string pathTopic{"/gazebo/resource_paths"};
this->pathPub = this->node.Advertise<msgs::StringMsg_V>(pathTopic);

ignmsg << "Resource path interfaces on [" << addPathService
<< "], [" << getPathService << "], and [" << pathTopic << "]."
<< std::endl;
}

//////////////////////////////////////////////////
Expand All @@ -402,6 +423,49 @@ bool ServerPrivate::WorldsService(ignition::msgs::StringMsg_V &_res)
return true;
}

//////////////////////////////////////////////////
void ServerPrivate::AddResourcePathsService(
const ignition::msgs::StringMsg_V &_req)
{
std::vector<std::string> paths;
for (int i = 0; i < _req.data_size(); ++i)
{
paths.push_back(_req.data(i));
}
addResourcePaths(paths);

// Notify new paths
msgs::StringMsg_V msg;
auto gzPaths = resourcePaths();
for (const auto &path : gzPaths)
{
if (!path.empty())
msg.add_data(path);
}

this->pathPub.Publish(msg);
}

//////////////////////////////////////////////////
bool ServerPrivate::ResourcePathsService(
ignition::msgs::StringMsg_V &_res)
{
_res.Clear();

// Update paths
addResourcePaths();

// Get paths
auto gzPaths = resourcePaths();
for (const auto &path : gzPaths)
{
if (!path.empty())
_res.add_data(path);
}

return true;
}

//////////////////////////////////////////////////
std::string ServerPrivate::FetchResource(const std::string &_uri)
{
Expand Down
13 changes: 13 additions & 0 deletions src/ServerPrivate.hh
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,16 @@ namespace ignition
/// \return True if successful.
private: bool WorldsService(ignition::msgs::StringMsg_V &_res);

/// \brief Callback for add resource paths service.
/// \param[out] _req Request containing the paths to be added.
private: void AddResourcePathsService(
const ignition::msgs::StringMsg_V &_req);

/// \brief Callback for get resource paths service.
/// \param[out] _res Response filled with all current paths.
/// \return True if successful.
private: bool ResourcePathsService(ignition::msgs::StringMsg_V &_res);

/// \brief A pool of worker threads.
public: common::WorkerPool workerPool{2};

Expand Down Expand Up @@ -149,6 +159,9 @@ namespace ignition

/// \brief Node for transport.
private: transport::Node node;

/// \brief Publisher of resrouce paths.
private: transport::Node::Publisher pathPub;
};
}
}
Expand Down
Loading

0 comments on commit db6a467

Please sign in to comment.