Skip to content

Commit

Permalink
Merge branch 'ign-gazebo6' into marcoag/thrust_coefficient_for_thrust…
Browse files Browse the repository at this point in the history
…_plugin

Signed-off-by: Marco A. Gutierrez <[email protected]>
  • Loading branch information
Marco A. Gutierrez committed Sep 5, 2022
2 parents 0cd1d65 + 69e7757 commit 79abb52
Show file tree
Hide file tree
Showing 30 changed files with 654 additions and 54 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR)
#============================================================================
# Initialize the project
#============================================================================
project(ignition-gazebo6 VERSION 6.10.0)
project(ignition-gazebo6 VERSION 6.12.0)
set (GZ_DISTRIBUTION "Fortress")

#============================================================================
Expand Down
92 changes: 92 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,97 @@
## Ignition Gazebo 6.x

### Gazebo Sim 6.12.0 (2022-08-30)

1. Add topic parameter to thrust plugin
* [Pull request #1681](https://github.com/gazebosim/gz-sim/pull/1681)

1. Add information about `<topic>` system parameter
* [Pull request #1671](https://github.com/gazebosim/gz-sim/pull/1671)

1. Adding tests for hydrodynamics
* [Pull request #1617](https://github.com/gazebosim/gz-sim/pull/1617)

1. Fix Windows and Doxygen
* [Pull request #1643](https://github.com/gazebosim/gz-sim/pull/1643)

### Gazebo Sim 6.11.0 (2022-08-17)

1. Add support for specifying log record period
* [Pull request #1636](https://github.com/gazebosim/gz-sim/pull/1636)

1. Common widget GzColor replacement
* [Pull request #1530](https://github.com/gazebosim/gz-sim/pull/1530)

1. Replace plotIcon in ComponentInspector with GzPlotIcon
* [Pull request #1638](https://github.com/gazebosim/gz-sim/pull/1638)

1. Component Inspector with common widget pose plotting
* [Pull request #1607](https://github.com/gazebosim/gz-sim/pull/1607)

1. Change CODEOWNERS and maintainer to Michael
* [Pull request #1644](https://github.com/gazebosim/gz-sim/pull/1644)

1. Replace pose in ViewAngle with GzPose
* [Pull request #1641](https://github.com/gazebosim/gz-sim/pull/1641)

1. Add system to an entity through Component Inspector
* [Pull request #1549](https://github.com/gazebosim/gz-sim/pull/1549)

1. Quick start dialog
* [Pull request #1536](https://github.com/gazebosim/gz-sim/pull/1536)
* [Pull request #1627](https://github.com/gazebosim/gz-sim/pull/1627)

1. Quiet libSDFormat console on --verbose 0
* [Pull request #1621](https://github.com/gazebosim/gz-sim/pull/1621)

1. New Apply Link Wrench system
* [Pull request #1593](https://github.com/gazebosim/gz-sim/pull/1593)

1. Add Tf publishing to AckermannSteering system
* [Pull request #1576](https://github.com/gazebosim/gz-sim/pull/1576)

1. Fix component updates
* [Pull request #1580](https://github.com/gazebosim/gz-sim/pull/1580)

1. Implement vector3 with common widget vector3
* [Pull request #1569](https://github.com/gazebosim/gz-sim/pull/1569)

1. Fix to modelphotoshoot test
* [Pull request #1570](https://github.com/gazebosim/gz-sim/pull/1570)

1. Update log playback gui config
* [Pull request #1590](https://github.com/gazebosim/gz-sim/pull/1590)

1. Helper function to get an entity from an entity message
* [Pull request #1595](https://github.com/gazebosim/gz-sim/pull/1595)

1. Fix compilation of scene broadcaster test
* [Pull request #1599](https://github.com/gazebosim/gz-sim/pull/1599)

1. Ignition -> Gazebo
* [Pull request #1596](https://github.com/gazebosim/gz-sim/pull/1596)

1. Add Model::CanonicalLink getter
* [Pull request #1594](https://github.com/gazebosim/gz-sim/pull/1594)

1. Implement Pose3d with common widget pose
* [Pull request #1571](https://github.com/gazebosim/gz-sim/pull/1571)

1. Fix UNIT_Server_TEST on Windows
* [Pull request #1577](https://github.com/gazebosim/gz-sim/pull/1577)

1. Use pytest to generate junit xml files for python tests
* [Pull request #1562](https://github.com/gazebosim/gz-sim/pull/1562)

1. Refactor: Utilizes function to load animations
* [Pull request #1568](https://github.com/gazebosim/gz-sim/pull/1568)

1. Utilizes function to sequence trajectories
* [Pull request #1565](https://github.com/gazebosim/gz-sim/pull/1565)

1. Disable MacOS flakies Citadel
* [Pull request #1545](https://github.com/gazebosim/gz-sim/pull/1545)

### Gazebo Sim 6.10.0 (2022-06-24)

1. Expose the ability to stop a server from C++
Expand Down
6 changes: 6 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,12 @@ Deprecated code produces compile-time warnings. These warning serve as
notification to users that their code should be upgraded. The next major
release will remove the deprecated code.

## Ignition Gazebo 6.11.X to 6.12.X

* **Modified**:
+ In the Hydrodynamics plugin, inverted the added mass contribution to make it
act in the correct direction.

## Ignition Gazebo 6.1 to 6.2

* If no `<namespace>` is given to the `Thruster` plugin, the namespace now
Expand Down
6 changes: 3 additions & 3 deletions src/LevelManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -36,14 +36,14 @@
#include "ignition/gazebo/components/Geometry.hh"
#include "ignition/gazebo/components/Gravity.hh"
#include "ignition/gazebo/components/Level.hh"
#include "ignition/gazebo/components/Model.hh"
#include "ignition/gazebo/components/Light.hh"
#include "ignition/gazebo/components/Name.hh"
#include "ignition/gazebo/components/LevelBuffer.hh"
#include "ignition/gazebo/components/LevelEntityNames.hh"
#include "ignition/gazebo/components/Light.hh"
#include "ignition/gazebo/components/LinearVelocity.hh"
#include "ignition/gazebo/components/LinearVelocitySeed.hh"
#include "ignition/gazebo/components/MagneticField.hh"
#include "ignition/gazebo/components/Model.hh"
#include "ignition/gazebo/components/Name.hh"
#include "ignition/gazebo/components/ParentEntity.hh"
#include "ignition/gazebo/components/Performer.hh"
#include "ignition/gazebo/components/PerformerLevels.hh"
Expand Down
8 changes: 4 additions & 4 deletions src/gui/QuickStartHandler.hh
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,8 @@
#include <QtCore>
#include <string>

#include "ignition/gazebo/Export.hh"
#include "ignition/gazebo/config.hh"
#include "ignition/gazebo/gui/Export.hh"

namespace ignition
{
Expand All @@ -32,7 +32,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace gui
{
/// \brief Class for handling quick start dialog
class QuickStartHandler : public QObject
class IGNITION_GAZEBO_GUI_VISIBLE QuickStartHandler : public QObject
{
Q_OBJECT

Expand All @@ -44,8 +44,8 @@ class QuickStartHandler : public QObject
/// \return Distribution name, such as 'Citadel'
public: Q_INVOKABLE QString Distribution() const;

/// \brief Get Gazebo version
/// \return gazebo version
/// \brief Get Gazebo Sim version
/// \return Version
public: Q_INVOKABLE QString SimVersion() const;

/// \brief Set starting world
Expand Down
2 changes: 1 addition & 1 deletion src/systems/ackermann_steering/AckermannSteering.hh
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ namespace systems
/// right_steering_joint
///
/// References:
/// https://github.com/ignitionrobotics/ign-gazebo/tree/main/src/systems/diff_drive
/// https://github.com/gazebosim/gz-sim/tree/main/src/systems/ackermann_steering
/// https://www.auto.tuwien.ac.at/bib/pdf_TR/TR0183.pdf
/// https://github.com/froohoo/ackermansteer/blob/master/ackermansteer/

Expand Down
3 changes: 1 addition & 2 deletions src/systems/elevator/Elevator.hh
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,7 @@ namespace ignition
namespace gazebo
{
// Inline bracket to help doxygen filtering
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE
{
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace systems
{
// Data forward declaration
Expand Down
3 changes: 1 addition & 2 deletions src/systems/elevator/ElevatorCommonPrivate.hh
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,7 @@ namespace ignition
namespace gazebo
{
// Inline bracket to help doxygen filtering
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE
{
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace systems
{
class ElevatorCommonPrivate
Expand Down
3 changes: 1 addition & 2 deletions src/systems/elevator/ElevatorStateMachine.hh
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,7 @@ namespace ignition
namespace gazebo
{
// Inline bracket to help doxygen filtering
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE
{
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace systems
{
// Data forward declarations
Expand Down
3 changes: 1 addition & 2 deletions src/systems/elevator/state_machine/ActionsImpl.hh
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,7 @@ namespace ignition
namespace gazebo
{
// Inline bracket to help doxygen filtering
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE
{
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace systems
{
namespace actions
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,7 @@ namespace ignition
namespace gazebo
{
// Inline bracket to help doxygen filtering
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE
{
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace systems
{
class ElevatorStateMachinePrivate
Expand Down
3 changes: 1 addition & 2 deletions src/systems/elevator/state_machine/EventsImpl.hh
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,7 @@ namespace ignition
namespace gazebo
{
// Inline bracket to help doxygen filtering
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE
{
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace systems
{
namespace events
Expand Down
3 changes: 1 addition & 2 deletions src/systems/elevator/state_machine/GuardsImpl.hh
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,7 @@ namespace ignition
namespace gazebo
{
// Inline bracket to help doxygen filtering
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE
{
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace systems
{
namespace guards
Expand Down
3 changes: 1 addition & 2 deletions src/systems/elevator/state_machine/StatesImpl.hh
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,7 @@ namespace ignition
namespace gazebo
{
// Inline bracket to help doxygen filtering
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE
{
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace systems
{
/// \brief State at which the elevator is idling.
Expand Down
3 changes: 1 addition & 2 deletions src/systems/elevator/utils/DoorTimer.hh
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,7 @@ namespace ignition
namespace gazebo
{
// Inline bracket to help doxygen filtering
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE
{
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace systems
{
// Data forward declaration
Expand Down
3 changes: 1 addition & 2 deletions src/systems/elevator/utils/JointMonitor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,7 @@ namespace ignition
namespace gazebo
{
// Inline bracket to help doxygen filtering
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE
{
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace systems
{
// Data forward declaration
Expand Down
6 changes: 4 additions & 2 deletions src/systems/hydrodynamics/Hydrodynamics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -296,7 +296,7 @@ void Hydrodynamics::PreUpdate(

// These variables follow Fossen's scheme in "Guidance and Control
// of Ocean Vehicles." The `state` vector contains the ship's current velocity
// in the formate [x_vel, y_vel, z_vel, roll_vel, pitch_vel, yaw_vel].
// in the format [x_vel, y_vel, z_vel, roll_vel, pitch_vel, yaw_vel].
// `stateDot` consists of the first derivative in time of the state vector.
// `Cmat` corresponds to the Centripetal matrix
// `Dmat` is the drag matrix
Expand Down Expand Up @@ -340,13 +340,15 @@ void Hydrodynamics::PreUpdate(
state(4) = localRotationalVelocity.Y();
state(5) = localRotationalVelocity.Z();

// TODO(anyone) Make this configurable
auto dt = static_cast<double>(_info.dt.count())/1e9;
stateDot = (state - this->dataPtr->prevState)/dt;

this->dataPtr->prevState = state;

// The added mass
const Eigen::VectorXd kAmassVec = this->dataPtr->Ma * stateDot;
// Negative sign signifies the behaviour change
const Eigen::VectorXd kAmassVec = - this->dataPtr->Ma * stateDot;

// Coriolis and Centripetal forces for under water vehicles (Fossen P. 37)
// Note: this is significantly different from VRX because we need to account
Expand Down
5 changes: 4 additions & 1 deletion src/systems/joint_state_publisher/JointStatePublisher.hh
Original file line number Diff line number Diff line change
Expand Up @@ -35,14 +35,17 @@ namespace systems
{
/// \brief The JointStatePub system publishes state information for
/// a model. The published message type is ignition::msgs::Model, and the
/// publication topic is "/world/<world_name>/model/<model_name>/state".
/// publication topic is determined by the `<topic>` parameter.
///
/// By default the JointStatePublisher will publish all joints for
/// a model. Use the `<joint_name>` system parameter, described below, to
/// control which joints are published.
///
/// # System Parameters
///
/// `<topic>`: Name of the topic to publish to. This parameter is optional,
/// and if not provided, the joint state will be published to
/// "/world/<world_name>/model/<model_name>/state".
/// `<joint_name>`: Name of a joint to publish. This parameter can be
/// specified multiple times, and is optional. All joints in a model will
/// be published if joint names are not specified.
Expand Down
3 changes: 1 addition & 2 deletions src/systems/optical_tactile_plugin/OpticalTactilePlugin.hh
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,7 @@ namespace ignition
namespace gazebo
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE
{
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace systems
{
// Forward declaration
Expand Down
3 changes: 1 addition & 2 deletions src/systems/optical_tactile_plugin/Visualization.hh
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,7 @@ namespace ignition
namespace gazebo
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE
{
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace systems
{
namespace optical_tactile_sensor
Expand Down
4 changes: 2 additions & 2 deletions src/systems/particle_emitter2/ParticleEmitter2.cc
Original file line number Diff line number Diff line change
Expand Up @@ -158,7 +158,7 @@ void ParticleEmitter2::PreUpdate(const ignition::gazebo::UpdateInfo &_info,
// hack to avoid breaking the particle_emitter.proto message.
if (_emitter->Data().has_header())
{
for (const auto data : _emitter->Data().header().data())
for (const auto &data : _emitter->Data().header().data())
{
if (data.key() == "topic" && !data.value().empty())
{
Expand Down Expand Up @@ -218,7 +218,7 @@ void ParticleEmitter2::PreUpdate(const ignition::gazebo::UpdateInfo &_info,
return;

// Process each command
for (const auto cmd : this->dataPtr->userCmd)
for (const auto &cmd : this->dataPtr->userCmd)
{
// Create component.
auto emitterComp = _ecm.Component<components::ParticleEmitterCmd>(
Expand Down
Loading

0 comments on commit 79abb52

Please sign in to comment.