Skip to content

Commit

Permalink
Merge branch 'ign-gazebo6' into ports/6_to_7
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <michael@openrobotics.org>
  • Loading branch information
mjcarroll committed Jan 10, 2023
2 parents f49fb5a + 330eaf2 commit 0f09b82
Show file tree
Hide file tree
Showing 30 changed files with 1,087 additions and 77 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ set(GZ_PLUGIN_VER ${gz-plugin2_VERSION_MAJOR})

#--------------------------------------
# Find gz-transport
gz_find_package(gz-transport12 REQUIRED COMPONENTS log)
gz_find_package(gz-transport12 REQUIRED COMPONENTS log parameters)
set(GZ_TRANSPORT_VER ${gz-transport12_VERSION_MAJOR})

#--------------------------------------
Expand Down
54 changes: 54 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -433,6 +433,60 @@

## Gazebo Sim 6.x

### Gazebo Sim 6.14.0 (2022-12-29)

1. Fix Ackermann plugin zero linVel turningRadius bug
* [Pull request #1849](https://github.com/gazebosim/gz-sim/pull/1849)

1. Header guard fix for battery power load component
* [Pull request #1846](https://github.com/gazebosim/gz-sim/pull/1846)

1. Add interface to allow systems to declare parameters
* [Pull request #1431](https://github.com/gazebosim/gz-sim/pull/1431)

1. Adding battery consumers and extra fixes
* [Pull request #1811](https://github.com/gazebosim/gz-sim/pull/1811)

1. Disable tests that require dartsim on windows
* [Pull request #1840](https://github.com/gazebosim/gz-sim/pull/1840)

1. Added move camera to model service
* [Pull request #1823](https://github.com/gazebosim/gz-sim/pull/1823)

1. Add spin box to View Angle plugin for configuring view control sensitivity
* [Pull request #1799](https://github.com/gazebosim/gz-sim/pull/1799)

1. Sync View Angle GUI with view controller
* [Pull request #1825](https://github.com/gazebosim/gz-sim/pull/1825)

1. Hydrodynamics flags test strengthening
* [Pull request #1819](https://github.com/gazebosim/gz-sim/pull/1819)

1. Fixed Fortress tests related to lights
* [Pull request #1827](https://github.com/gazebosim/gz-sim/pull/1827)

1. Allow to move to model from Angle view plugin
* [Pull request #1810](https://github.com/gazebosim/gz-sim/pull/1810)

1. Fixed light entity number
* [Pull request #1818](https://github.com/gazebosim/gz-sim/pull/1818)

1. Check AddBvnAnimation return value
* [Pull request #1750](https://github.com/gazebosim/gz-sim/pull/1750)

1. Add checkbox in view angle plugin for toggling view control reference visual
* [Pull request #1788](https://github.com/gazebosim/gz-sim/pull/1788)

1. Adds support for hydrodynamic cross terms
* [Pull request #1784](https://github.com/gazebosim/gz-sim/pull/1784)

1. Addresses flakiness in `Hydrodynamics.VelocityTestInOil`.
* [Pull request #1787](https://github.com/gazebosim/gz-sim/pull/1787)

1. Fix minor bugs in RFComms plugin
* [Pull request #1743](https://github.com/gazebosim/gz-sim/pull/1743)


### Gazebo Sim 6.13.0 (2022-11-04)

1. Fix two tests on Windows
Expand Down
16 changes: 16 additions & 0 deletions include/gz/sim/System.hh
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@
#include <gz/sim/Export.hh>
#include <gz/sim/Types.hh>

#include <gz/transport/parameters/Registry.hh>

#include <sdf/Element.hh>

namespace gz
Expand Down Expand Up @@ -100,6 +102,20 @@ namespace gz
EventManager &_eventMgr) = 0;
};

/// \class ISystemConfigureParameters ISystem.hh ignition/gazebo/System.hh
/// \brief Interface for a system that declares parameters.
///
/// ISystemConfigureParameters::ConfigureParameters is called after
/// ISystemConfigure::Configure.
class ISystemConfigureParameters {
/// \brief Configure the parameters of the system.
/// \param[in] _registry The parameter registry.
public: virtual void ConfigureParameters(
gz::transport::parameters::ParametersRegistry &_registry,
EntityComponentManager &_ecm) = 0;
};


class ISystemReset {
public: virtual void Reset(const UpdateInfo &_info,
EntityComponentManager &_ecm) = 0;
Expand Down
49 changes: 49 additions & 0 deletions include/gz/sim/components/BatteryPowerLoad.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
/*
* Copyright (C) 2022 Open Source Robotics Foundation
*
* 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.
*
*/
#ifndef GZ_SIM_COMPONENTS_BATTERYPOWERLOAD_HH_
#define GZ_SIM_COMPONENTS_BATTERYPOWERLOAD_HH_

#include <gz/sim/components/Factory.hh>
#include <gz/sim/components/Component.hh>
#include <gz/sim/config.hh>

namespace gz::sim
{
// Inline bracket to help doxygen filtering.
inline namespace GZ_SIM_VERSION_NAMESPACE {
namespace components
{
/// \brief Data structure to hold the consumer power load
/// and the name of the battery it uses.
struct BatteryPowerLoadInfo
{
/// \brief Entity of the battery to use.
Entity batteryId;
/// \brief Battery power load (W) to add to the battery.
double batteryPowerLoad;
};

/// \brief A component that indicates the total consumption of a battery.
using BatteryPowerLoad =
Component<BatteryPowerLoadInfo, class BatteryPowerLoadTag>;
GZ_SIM_REGISTER_COMPONENT("gz_sim_components.BatteryPowerLoad",
BatteryPowerLoad)
}
}
} // namespace gz::sim

#endif // GZ_SIM_COMPONENTS_BATTERYPOWERLOAD_HH_
19 changes: 19 additions & 0 deletions include/ignition/gazebo/components/BatteryPowerLoad.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
/*
* Copyright (C) 2022 Open Source Robotics Foundation
*
* 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/sim/components/BatteryPowerLoad.hh>
#include <ignition/gazebo/config.hh>
1 change: 1 addition & 0 deletions src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -168,6 +168,7 @@ target_link_libraries(${PROJECT_LIBRARY_TARGET_NAME}
gz-fuel_tools${GZ_FUEL_TOOLS_VER}::gz-fuel_tools${GZ_FUEL_TOOLS_VER}
gz-gui${GZ_GUI_VER}::gz-gui${GZ_GUI_VER}
gz-transport${GZ_TRANSPORT_VER}::gz-transport${GZ_TRANSPORT_VER}
gz-transport${GZ_TRANSPORT_VER}::parameters
sdformat${SDF_VER}::sdformat${SDF_VER}
protobuf::libprotobuf
PRIVATE
Expand Down
9 changes: 7 additions & 2 deletions src/SimulationRunner.cc
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,10 @@ SimulationRunner::SimulationRunner(const sdf::World *_world,
// Keep world name
this->worldName = _world->Name();

this->parametersRegistry = std::make_unique<
gz::transport::parameters::ParametersRegistry>(
std::string{"world/"} + this->worldName);

// Get the physics profile
// TODO(luca): remove duplicated logic in SdfEntityCreator and LevelManager
auto physics = _world->PhysicsByIndex(0);
Expand Down Expand Up @@ -142,8 +146,9 @@ SimulationRunner::SimulationRunner(const sdf::World *_world,
this->node = std::make_unique<transport::Node>(opts);

// Create the system manager
this->systemMgr = std::make_unique<SystemManager>(_systemLoader,
&this->entityCompMgr, &this->eventMgr, validNs);
this->systemMgr = std::make_unique<SystemManager>(
_systemLoader, &this->entityCompMgr, &this->eventMgr, validNs,
this->parametersRegistry.get());

this->pauseConn = this->eventMgr.Connect<events::Pause>(
std::bind(&SimulationRunner::SetPaused, this, std::placeholders::_1));
Expand Down
5 changes: 5 additions & 0 deletions src/SimulationRunner.hh
Original file line number Diff line number Diff line change
Expand Up @@ -400,6 +400,11 @@ namespace gz
/// Note: must be before EntityComponentManager
private: EventManager eventMgr;

/// \brief Manager all parameters
private: std::unique_ptr<
gz::transport::parameters::ParametersRegistry
> parametersRegistry;

/// \brief Manager of all components.
private: EntityComponentManager entityCompMgr;

Expand Down
9 changes: 9 additions & 0 deletions src/SystemInternal.hh
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,8 @@ namespace gz
: systemPlugin(std::move(_systemPlugin)),
system(systemPlugin->QueryInterface<System>()),
configure(systemPlugin->QueryInterface<ISystemConfigure>()),
configureParameters(
systemPlugin->QueryInterface<ISystemConfigureParameters>()),
reset(systemPlugin->QueryInterface<ISystemReset>()),
preupdate(systemPlugin->QueryInterface<ISystemPreUpdate>()),
update(systemPlugin->QueryInterface<ISystemUpdate>()),
Expand All @@ -62,6 +64,8 @@ namespace gz
: systemShared(_system),
system(_system.get()),
configure(dynamic_cast<ISystemConfigure *>(_system.get())),
configureParameters(
dynamic_cast<ISystemConfigureParameters *>(_system.get())),
reset(dynamic_cast<ISystemReset *>(_system.get())),
preupdate(dynamic_cast<ISystemPreUpdate *>(_system.get())),
update(dynamic_cast<ISystemUpdate *>(_system.get())),
Expand All @@ -86,6 +90,11 @@ namespace gz
/// Will be nullptr if the System doesn't implement this interface.
public: ISystemConfigure *configure = nullptr;

/// \brief Access this system via the ISystemConfigureParameters
/// interface.
/// Will be nullptr if the System doesn't implement this interface.
public: ISystemConfigureParameters *configureParameters = nullptr;

/// \brief Access this system via the ISystemReset interface
/// Will be nullptr if the System doesn't implement this interface.
public: ISystemReset *reset = nullptr;
Expand Down
32 changes: 27 additions & 5 deletions src/SystemManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,13 +28,16 @@ using namespace gz;
using namespace sim;

//////////////////////////////////////////////////
SystemManager::SystemManager(const SystemLoaderPtr &_systemLoader,
EntityComponentManager *_entityCompMgr,
EventManager *_eventMgr,
const std::string &_namespace)
SystemManager::SystemManager(
const SystemLoaderPtr &_systemLoader,
EntityComponentManager *_entityCompMgr,
EventManager *_eventMgr,
const std::string &_namespace,
gz::transport::parameters::ParametersRegistry *_parametersRegistry)
: systemLoader(_systemLoader),
entityCompMgr(_entityCompMgr),
eventMgr(_eventMgr)
eventMgr(_eventMgr),
parametersRegistry(_parametersRegistry)
{
transport::NodeOptions opts;
opts.SetNameSpace(_namespace);
Expand Down Expand Up @@ -106,6 +109,9 @@ size_t SystemManager::ActivatePendingSystems()
if (system.configure)
this->systemsConfigure.push_back(system.configure);

if (system.configureParameters)
this->systemsConfigureParameters.push_back(system.configureParameters);

if (system.reset)
this->systemsReset.push_back(system.reset);

Expand Down Expand Up @@ -255,6 +261,16 @@ void SystemManager::AddSystemImpl(
*this->eventMgr);
}

// Configure the system parameters, if necessary
if (
_system.configureParameters && this->entityCompMgr &&
this->parametersRegistry)
{
_system.configureParameters->ConfigureParameters(
*this->parametersRegistry,
*this->entityCompMgr);
}

// Update callbacks will be handled later, add to queue
std::lock_guard<std::mutex> lock(this->pendingSystemsMutex);
this->pendingSystems.push_back(_system);
Expand All @@ -266,6 +282,12 @@ const std::vector<ISystemConfigure *>& SystemManager::SystemsConfigure()
return this->systemsConfigure;
}

const std::vector<ISystemConfigureParameters *>&
SystemManager::SystemsConfigureParameters()
{
return this->systemsConfigureParameters;
}

//////////////////////////////////////////////////
const std::vector<ISystemReset *> &SystemManager::SystemsReset()
{
Expand Down
25 changes: 21 additions & 4 deletions src/SystemManager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -52,10 +52,13 @@ namespace gz
/// \param[in] _eventMgr Pointer to the event manager to be used when
/// configuring new systems
/// \param[in] _namespace Namespace to use for the transport node
public: explicit SystemManager(const SystemLoaderPtr &_systemLoader,
EntityComponentManager *_entityCompMgr = nullptr,
EventManager *_eventMgr = nullptr,
const std::string &_namespace = std::string());
public: explicit SystemManager(
const SystemLoaderPtr &_systemLoader,
EntityComponentManager *_entityCompMgr = nullptr,
EventManager *_eventMgr = nullptr,
const std::string &_namespace = std::string(),
gz::transport::parameters::ParametersRegistry *
_parametersRegistry = nullptr);

/// \brief Load system plugin for a given entity.
/// \param[in] _entity Entity
Expand Down Expand Up @@ -113,6 +116,12 @@ namespace gz
/// \return Vector of systems' configure interfaces.
public: const std::vector<ISystemConfigure *>& SystemsConfigure();

/// \brief Get an vector of all active systems implementing
/// "ConfigureParameters"
/// \return Vector of systems's configure interfaces.
public: const std::vector<ISystemConfigureParameters *>&
SystemsConfigureParameters();

/// \brief Get an vector of all active systems implementing "Reset"
/// \return Vector of systems' reset interfaces.
public: const std::vector<ISystemReset *>& SystemsReset();
Expand Down Expand Up @@ -180,6 +189,10 @@ namespace gz
/// \brief Systems implementing Configure
private: std::vector<ISystemConfigure *> systemsConfigure;

/// \brief Systems implementing ConfigureParameters
private: std::vector<ISystemConfigureParameters *>
systemsConfigureParameters;

/// \brief Systems implementing Reset
private: std::vector<ISystemReset *> systemsReset;

Expand Down Expand Up @@ -212,6 +225,10 @@ namespace gz

/// \brief Node for communication.
private: std::unique_ptr<transport::Node> node{nullptr};

/// \brief Pointer to associated parameters registry
private: gz::transport::parameters::ParametersRegistry *
parametersRegistry;
};
}
} // namespace sim
Expand Down
Loading

0 comments on commit 0f09b82

Please sign in to comment.