Skip to content

Commit

Permalink
Merge branch 'main' into feature/ign-gazebo7-metal-demo
Browse files Browse the repository at this point in the history
  • Loading branch information
srmainwaring authored Jan 3, 2022
2 parents 6800a8e + a95a584 commit 936a002
Show file tree
Hide file tree
Showing 18 changed files with 44 additions and 43 deletions.
8 changes: 4 additions & 4 deletions .github/ci/packages.apt
Original file line number Diff line number Diff line change
Expand Up @@ -2,12 +2,12 @@ freeglut3-dev
libfreeimage-dev
libglew-dev
libignition-cmake2-dev
libignition-common4-dev
libignition-common5-dev
libignition-gui7-dev
libignition-fuel-tools8-dev
libignition-math6-eigen3-dev
libignition-math7-eigen3-dev
libignition-msgs9-dev
libignition-physics5-dev
libignition-physics6-dev
libignition-plugin-dev
libignition-rendering7-dev
libignition-sensors7-dev
Expand All @@ -18,7 +18,7 @@ libogre-1.9-dev
libogre-2.1-dev
libprotobuf-dev
libprotoc-dev
libsdformat12-dev
libsdformat13-dev
libtinyxml2-dev
libxi-dev
libxmu-dev
Expand Down
16 changes: 8 additions & 8 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -50,8 +50,8 @@ set(CMAKE_POLICY_DEFAULT_CMP0077 NEW)
# as protobuf could be find transitively by any dependency
set(protobuf_MODULE_COMPATIBLE TRUE)

ign_find_package(sdformat12 REQUIRED VERSION 12.3)
set(SDF_VER ${sdformat12_VERSION_MAJOR})
ign_find_package(sdformat13 REQUIRED)
set(SDF_VER ${sdformat13_VERSION_MAJOR})

#--------------------------------------
# Find ignition-plugin
Expand All @@ -71,14 +71,14 @@ set(IGN_MSGS_VER ${ignition-msgs9_VERSION_MAJOR})
#--------------------------------------
# Find ignition-common
# Always use the profiler component to get the headers, regardless of status.
ign_find_package(ignition-common4 VERSION 4.4
ign_find_package(ignition-common5
COMPONENTS
profiler
events
av
REQUIRED
)
set(IGN_COMMON_VER ${ignition-common4_VERSION_MAJOR})
set(IGN_COMMON_VER ${ignition-common5_VERSION_MAJOR})

#--------------------------------------
# Find ignition-fuel_tools
Expand All @@ -99,14 +99,14 @@ ign_find_package (Qt5

#--------------------------------------
# Find ignition-physics
ign_find_package(ignition-physics5 VERSION 5.1
ign_find_package(ignition-physics6
COMPONENTS
heightmap
mesh
sdf
REQUIRED
)
set(IGN_PHYSICS_VER ${ignition-physics5_VERSION_MAJOR})
set(IGN_PHYSICS_VER ${ignition-physics6_VERSION_MAJOR})

#--------------------------------------
# Find ignition-sensors
Expand Down Expand Up @@ -142,8 +142,8 @@ set(IGN_RENDERING_VER ${ignition-rendering7_VERSION_MAJOR})

#--------------------------------------
# Find ignition-math
ign_find_package(ignition-math6 REQUIRED COMPONENTS eigen3 VERSION 6.9)
set(IGN_MATH_VER ${ignition-math6_VERSION_MAJOR})
ign_find_package(ignition-math7 REQUIRED COMPONENTS eigen3)
set(IGN_MATH_VER ${ignition-math7_VERSION_MAJOR})

#--------------------------------------
# Find ignition-tools
Expand Down
8 changes: 4 additions & 4 deletions docker/Dockerfile.nightly
Original file line number Diff line number Diff line change
Expand Up @@ -12,18 +12,18 @@ RUN scripts/enable_ign_nightly.sh
RUN apt-get update \
&& apt-get install -y \
libignition-cmake2-dev \
libignition-common4-dev \
libignition-common5-dev \
libignition-fuel-tools8-dev \
libignition-math6-eigen3-dev \
libignition-math7-eigen3-dev \
libignition-plugin-dev \
libignition-physics5-dev \
libignition-physics6-dev \
libignition-rendering7-dev \
libignition-tools-dev \
libignition-transport12-dev \
libignition-gui7-dev \
libignition-msgs9-dev \
libignition-sensors7-dev \
libsdformat12-dev
libsdformat13-dev

COPY . ign-gazebo
RUN cd ign-gazebo \
Expand Down
4 changes: 2 additions & 2 deletions examples/standalone/joy_to_twist/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@ cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR)
find_package(ignition-transport12 QUIET REQUIRED OPTIONAL_COMPONENTS log)
set(IGN_TRANSPORT_VER ${ignition-transport12_VERSION_MAJOR})

find_package(sdformat12 REQUIRED)
set(SDF_VER ${sdformat12_VERSION_MAJOR})
find_package(sdformat13 REQUIRED)
set(SDF_VER ${sdformat13_VERSION_MAJOR})

add_executable(joy_to_twist joy_to_twist.cc)
target_link_libraries(joy_to_twist
Expand Down
4 changes: 2 additions & 2 deletions examples/standalone/joystick/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@ if(${CMAKE_SYSTEM_NAME} STREQUAL "Linux")
find_package(ignition-transport12 QUIET REQUIRED OPTIONAL_COMPONENTS log)
set(IGN_TRANSPORT_VER ${ignition-transport12_VERSION_MAJOR})

find_package(sdformat12 REQUIRED)
set(SDF_VER ${sdformat12_VERSION_MAJOR})
find_package(sdformat13 REQUIRED)
set(SDF_VER ${sdformat13_VERSION_MAJOR})

add_executable(joystick joystick.cc)
target_link_libraries(joystick
Expand Down
8 changes: 4 additions & 4 deletions examples/standalone/keyboard/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,14 +4,14 @@ if(${CMAKE_SYSTEM_NAME} STREQUAL "Linux")
find_package(ignition-transport12 QUIET REQUIRED OPTIONAL_COMPONENTS log)
set(IGN_TRANSPORT_VER ${ignition-transport12_VERSION_MAJOR})

find_package(sdformat12 REQUIRED)
set(SDF_VER ${sdformat12_VERSION_MAJOR})
find_package(sdformat13 REQUIRED)
set(SDF_VER ${sdformat13_VERSION_MAJOR})

find_package(ignition-msgs9 REQUIRED)
set(IGN_MSGS_VER ${ignition-msgs9_VERSION_MAJOR})

find_package(ignition-common4 REQUIRED)
set(IGN_COMMON_VER ${ignition-common4_VERSION_MAJOR})
find_package(ignition-common5 REQUIRED)
set(IGN_COMMON_VER ${ignition-common5_VERSION_MAJOR})

add_executable(keyboard keyboard.cc)
target_link_libraries(keyboard
Expand Down
2 changes: 1 addition & 1 deletion include/ignition/gazebo/gui/GuiEvents.hh
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,7 @@ namespace events
};

/// \brief Event that notifies an entity is to be added to the model editor
class ModelEditorAddEntity : public QEvent
class IGNITION_GAZEBO_GUI_VISIBLE ModelEditorAddEntity : public QEvent
{
/// \brief Constructor
/// \param[in] _entity Entity added
Expand Down
2 changes: 1 addition & 1 deletion src/SdfGenerator_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -643,7 +643,7 @@ TEST_F(ElementUpdateFixture, WorldWithModelsIncludedNotExpanded)
TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithInvalidUris)
{
const std::string goodUri =
"https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/2/";
"https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/2";

// These are URIs that are potentially problematic.
const std::vector<std::string> fuelUris = {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1212,7 +1212,7 @@ rendering::GeometryPtr VisualizationCapabilitiesPrivate::CreateGeometry(
// The rotation is the angle between the +z(0,0,1) vector and the
// normal, which are both expressed in the local (Visual) frame.
math::Vector3d normal = _geom.PlaneShape()->Normal();
localPose.Rot().From2Axes(math::Vector3d::UnitZ, normal.Normalized());
localPose.Rot().SetFrom2Axes(math::Vector3d::UnitZ, normal.Normalized());
}
else if (_geom.Type() == sdf::GeometryType::SPHERE)
{
Expand Down
2 changes: 1 addition & 1 deletion src/rendering/SceneManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -651,7 +651,7 @@ rendering::GeometryPtr SceneManager::LoadGeometry(const sdf::Geometry &_geom,
// The rotation is the angle between the +z(0,0,1) vector and the
// normal, which are both expressed in the local (Visual) frame.
math::Vector3d normal = _geom.PlaneShape()->Normal();
localPose.Rot().From2Axes(math::Vector3d::UnitZ, normal.Normalized());
localPose.Rot().SetFrom2Axes(math::Vector3d::UnitZ, normal.Normalized());
}
else if (_geom.Type() == sdf::GeometryType::SPHERE)
{
Expand Down
2 changes: 1 addition & 1 deletion src/systems/collada_world_exporter/ColladaWorldExporter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,7 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate
// // normal, which are both expressed in the local (Visual) frame.
math::Vector3d normal = _geom->Data().PlaneShape()->Normal();
math::Quaterniond normalRot;
normalRot.From2Axes(math::Vector3d::UnitZ, normal.Normalized());
normalRot.SetFrom2Axes(math::Vector3d::UnitZ, normal.Normalized());
worldPose.Rot() = worldPose.Rot() * normalRot;

matrix = math::Matrix4d(worldPose);
Expand Down
2 changes: 1 addition & 1 deletion src/systems/multicopter_control/Common.cc
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ RotorConfiguration loadRotorConfiguration(const EntityComponentManager &_ecm,

rotor.armLength = rotorProj.Length();
math::Quaterniond rot;
rot.From2Axes(math::Vector3d::UnitX, rotorProj);
rot.SetFrom2Axes(math::Vector3d::UnitX, rotorProj);
rotor.angle = rot.Yaw();

if (!elem->HasElement("forceConstant"))
Expand Down
1 change: 0 additions & 1 deletion src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@
#include <ignition/common/Profiler.hh>
#include <ignition/plugin/Register.hh>
#include <ignition/transport/Node.hh>
#include <ignition/common/Time.hh>

#include <sdf/Element.hh>

Expand Down
2 changes: 1 addition & 1 deletion src/systems/optical_tactile_plugin/Visualization.cc
Original file line number Diff line number Diff line change
Expand Up @@ -203,7 +203,7 @@ void OpticalTactilePluginVisualization::AddNormalForceToMarkerMsgs(
_position.X(), _position.Y(), _position.Z());

ignition::math::Quaternionf normalForceOrientationFromSensor;
normalForceOrientationFromSensor.From2Axes(
normalForceOrientationFromSensor.SetFrom2Axes(
ignition::math::Vector3f(0, 0, 1), _normalForce);

ignition::math::Pose3f normalForcePoseFromSensor(
Expand Down
2 changes: 1 addition & 1 deletion src/systems/track_controller/TrackController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -525,7 +525,7 @@ void TrackControllerPrivate::ComputeSurfaceProperties(
this->debugMarker.set_id(++this->markerId);

math::Quaterniond rot;
rot.From2Axes(math::Vector3d::UnitX, frictionDirection);
rot.SetFrom2Axes(math::Vector3d::UnitX, frictionDirection);
math::Vector3d p = _point;
p += rot.RotateVector(
math::Vector3d::UnitX * this->debugMarker.scale().x() / 2);
Expand Down
4 changes: 3 additions & 1 deletion test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,9 @@ set(tests
thruster.cc
touch_plugin.cc
tracked_vehicle_system.cc
triggered_publisher.cc
# TODO(chapulina) Re-enable this test when parsing `type` attributes is fixed
# See https://github.com/ignitionrobotics/sdformat/pull/809
# triggered_publisher.cc
user_commands.cc
velocity_control_system.cc
log_system.cc
Expand Down
10 changes: 5 additions & 5 deletions test/integration/wheel_slip.cc
Original file line number Diff line number Diff line change
Expand Up @@ -304,15 +304,15 @@ TEST_F(WheelSlipTest, TireDrum)
{
WheelSlipState state = state0;
state.description = "Zero slip";
state.steer.Degree(0.0);
state.steer.SetDegree(0.0);
state.axelForceLateral = 0.0;
state.axelForceLongitudinal = 0.0;
states.push_back(state);
}
{
WheelSlipState state = state0;
state.description = "Lateral slip: low";
state.steer.Degree(3.0);
state.steer.SetDegree(3.0);
state.wheelSlipComplianceLateral = 0.1;
state.axelForceLateral = -state.suspForce *
sin(state.steer.Radian()) / state.wheelSlipComplianceLateral;
Expand All @@ -322,7 +322,7 @@ TEST_F(WheelSlipTest, TireDrum)
{
WheelSlipState state = state0;
state.description = "Lateral slip: high";
state.steer.Degree(10);
state.steer.SetDegree(10);
state.wheelSpeed *= cos(state.steer.Radian());
state.axelForceLateral = -state.suspForce;
state.axelForceLongitudinal = 0.0;
Expand All @@ -333,7 +333,7 @@ TEST_F(WheelSlipTest, TireDrum)
state.description = "Longitudinal torque control: low";
state.wheelSpeed = -1.055 * state.drumSpeed * drumRadius / wheelRadius;
state.wheelTorque = 0.25 * state.suspForce * wheelRadius;
state.steer.Degree(0.0);
state.steer.SetDegree(0.0);
state.wheelSlipComplianceLateral = 0.1;
state.axelForceLateral = 0.0;
state.axelForceLongitudinal = -250.0;
Expand All @@ -344,7 +344,7 @@ TEST_F(WheelSlipTest, TireDrum)
state.description = "Longitudinal torque control: moderate";
state.wheelSpeed = -1.12 * state.drumSpeed * drumRadius / wheelRadius;
state.wheelTorque = 0.5 * state.suspForce * wheelRadius;
state.steer.Degree(0.0);
state.steer.SetDegree(0.0);
state.wheelSlipComplianceLateral = 0.1;
state.axelForceLateral = 0.0;
state.axelForceLongitudinal = -600.0;
Expand Down
8 changes: 4 additions & 4 deletions tutorials/migrating_ardupilot_plugin.md
Original file line number Diff line number Diff line change
Expand Up @@ -751,12 +751,12 @@ In the new code we explicitly reference each Ignition package that we use:

```
# NEW
find_package(sdformat12 REQUIRED)
find_package(ignition-common4-all REQUIRED)
find_package(sdformat13 REQUIRED)
find_package(ignition-common5-all REQUIRED)
find_package(ignition-gazebo7-all REQUIRED)
find_package(ignition-math6-all REQUIRED)
find_package(ignition-math7-all REQUIRED)
find_package(ignition-msgs9-all REQUIRED)
find_package(ignition-physics5-all REQUIRED)
find_package(ignition-physics6-all REQUIRED)
find_package(ignition-sensors7-all REQUIRED)
find_package(ignition-transport12-all REQUIRED)
```
Expand Down

0 comments on commit 936a002

Please sign in to comment.