Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

πŸ‘©β€πŸŒΎ Fix Windows build and some warnings #782

Merged
merged 10 commits into from
Apr 27, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions src/ComponentFactory_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ class ComponentFactoryTest : public ::testing::Test
protected: void SetUp() override
{
common::Console::SetVerbosity(4);
common::setenv("IGN_DEBUG_COMPONENT_FACTORY", "true");
}
};

Expand Down
1 change: 1 addition & 0 deletions src/Component_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ class ComponentTest : public ::testing::Test
protected: void SetUp() override
{
common::Console::SetVerbosity(4);
common::setenv("IGN_DEBUG_COMPONENT_FACTORY", "true");
}
};

Expand Down
4 changes: 2 additions & 2 deletions src/Conversions.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1263,8 +1263,8 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in)
if (_in.has_camera())
{
sensor.SetHorizontalFov(_in.camera().horizontal_fov());
sensor.SetImageWidth(_in.camera().image_size().x());
sensor.SetImageHeight(_in.camera().image_size().y());
sensor.SetImageWidth(static_cast<int>(_in.camera().image_size().x()));
sensor.SetImageHeight(static_cast<int>(_in.camera().image_size().y()));
sensor.SetPixelFormatStr(_in.camera().image_format());
sensor.SetNearClip(_in.camera().near_clip());
sensor.SetFarClip(_in.camera().far_clip());
Expand Down
44 changes: 22 additions & 22 deletions src/Conversions_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -80,15 +80,15 @@ TEST(Conversions, Light)
msgs::Convert(lightMsg.diffuse()));
EXPECT_EQ(math::Color(0.8f, 0.9f, 0.1f, 1),
msgs::Convert(lightMsg.specular()));
EXPECT_FLOAT_EQ(3.2, lightMsg.range());
EXPECT_FLOAT_EQ(0.5, lightMsg.attenuation_constant());
EXPECT_FLOAT_EQ(0.1, lightMsg.attenuation_linear());
EXPECT_FLOAT_EQ(0.01, lightMsg.attenuation_quadratic());
EXPECT_FLOAT_EQ(3.2f, lightMsg.range());
EXPECT_FLOAT_EQ(0.5f, lightMsg.attenuation_constant());
EXPECT_FLOAT_EQ(0.1f, lightMsg.attenuation_linear());
EXPECT_FLOAT_EQ(0.01f, lightMsg.attenuation_quadratic());
EXPECT_EQ(math::Vector3d(0.1, 0.2, 1), msgs::Convert(lightMsg.direction()));
EXPECT_EQ(math::Angle(1.9), lightMsg.spot_inner_angle());
EXPECT_EQ(math::Angle(3.3), lightMsg.spot_outer_angle());
EXPECT_FLOAT_EQ(0.9, lightMsg.spot_falloff());
EXPECT_FLOAT_EQ(1.7, lightMsg.intensity());
EXPECT_FLOAT_EQ(0.9f, lightMsg.spot_falloff());
EXPECT_FLOAT_EQ(1.7f, lightMsg.intensity());

auto newLight = convert<sdf::Light>(lightMsg);
EXPECT_EQ("test_convert_light", newLight.Name());
Expand All @@ -99,15 +99,15 @@ TEST(Conversions, Light)
EXPECT_TRUE(newLight.CastShadows());
EXPECT_EQ(math::Color(0.4f, 0.5f, 0.6f, 1.0f), newLight.Diffuse());
EXPECT_EQ(math::Color(0.8f, 0.9f, 0.1f, 1.0f), newLight.Specular());
EXPECT_FLOAT_EQ(3.2, newLight.AttenuationRange());
EXPECT_FLOAT_EQ(0.5, newLight.ConstantAttenuationFactor());
EXPECT_FLOAT_EQ(0.1, newLight.LinearAttenuationFactor());
EXPECT_FLOAT_EQ(0.01, newLight.QuadraticAttenuationFactor());
EXPECT_FLOAT_EQ(3.2f, newLight.AttenuationRange());
EXPECT_FLOAT_EQ(0.5f, newLight.ConstantAttenuationFactor());
EXPECT_FLOAT_EQ(0.1f, newLight.LinearAttenuationFactor());
EXPECT_FLOAT_EQ(0.01f, newLight.QuadraticAttenuationFactor());
EXPECT_EQ(math::Vector3d(0.1, 0.2, 1), newLight.Direction());
EXPECT_EQ(math::Angle(1.9), newLight.SpotInnerAngle());
EXPECT_EQ(math::Angle(3.3), newLight.SpotOuterAngle());
EXPECT_FLOAT_EQ(0.9, newLight.SpotFalloff());
EXPECT_FLOAT_EQ(1.7, newLight.Intensity());
EXPECT_FLOAT_EQ(0.9f, newLight.SpotFalloff());
EXPECT_FLOAT_EQ(1.7f, newLight.Intensity());

EXPECT_EQ("", convert(sdf::LightType::INVALID));
EXPECT_EQ("point", convert(sdf::LightType::POINT));
Expand Down Expand Up @@ -894,49 +894,49 @@ TEST(Conversions, Actor)
EXPECT_EQ(math::Pose3d(3, 2, 1, 0, 0, 0),
msgs::Convert(actorMsg.pose()));
EXPECT_EQ("walk.dae", actorMsg.skin_filename());
EXPECT_FLOAT_EQ(2.0, actorMsg.skin_scale());
EXPECT_FLOAT_EQ(2.0f, actorMsg.skin_scale());
EXPECT_TRUE(actorMsg.script_loop());
EXPECT_FLOAT_EQ(2.8, actorMsg.script_delay_start());
EXPECT_FLOAT_EQ(2.8f, actorMsg.script_delay_start());
EXPECT_TRUE(actorMsg.script_auto_start());

ASSERT_EQ(1, actorMsg.animations_size());
EXPECT_EQ("animation", actorMsg.animations(0).name());
EXPECT_EQ("animation_filename", actorMsg.animations(0).filename());
EXPECT_FLOAT_EQ(1.23, actorMsg.animations(0).scale());
EXPECT_FLOAT_EQ(1.23f, actorMsg.animations(0).scale());
EXPECT_TRUE(actorMsg.animations(0).interpolate_x());

ASSERT_EQ(1, actorMsg.trajectories_size());
EXPECT_EQ(456u, actorMsg.trajectories(0).id());
EXPECT_EQ("traj_type", actorMsg.trajectories(0).type());
EXPECT_FLOAT_EQ(7.89, actorMsg.trajectories(0).tension());
EXPECT_FLOAT_EQ(7.89f, actorMsg.trajectories(0).tension());

ASSERT_EQ(1, actorMsg.trajectories(0).waypoints_size());
EXPECT_FLOAT_EQ(0.123, actorMsg.trajectories(0).waypoints(0).time());
EXPECT_FLOAT_EQ(0.123f, actorMsg.trajectories(0).waypoints(0).time());
EXPECT_EQ(math::Pose3d(6, 5, 4, 0, 0, 0),
msgs::Convert(actorMsg.trajectories(0).waypoints(0).pose()));

auto newActor = convert<sdf::Actor>(actorMsg);
EXPECT_EQ("test_convert_actor", newActor.Name());
EXPECT_EQ(math::Pose3d(3, 2, 1, 0, 0, 0), newActor.RawPose());
EXPECT_EQ("walk.dae", newActor.SkinFilename());
EXPECT_FLOAT_EQ(2.0, newActor.SkinScale());
EXPECT_FLOAT_EQ(2.0f, newActor.SkinScale());
EXPECT_TRUE(newActor.ScriptLoop());
EXPECT_FLOAT_EQ(2.8, newActor.ScriptDelayStart());
EXPECT_FLOAT_EQ(2.8f, newActor.ScriptDelayStart());
EXPECT_TRUE(newActor.ScriptAutoStart());

ASSERT_EQ(1u, newActor.AnimationCount());
EXPECT_EQ("animation", newActor.AnimationByIndex(0)->Name());
EXPECT_EQ("animation_filename", newActor.AnimationByIndex(0)->Filename());
EXPECT_FLOAT_EQ(1.23, newActor.AnimationByIndex(0)->Scale());
EXPECT_FLOAT_EQ(1.23f, newActor.AnimationByIndex(0)->Scale());
EXPECT_TRUE(newActor.AnimationByIndex(0)->InterpolateX());

ASSERT_EQ(1u, newActor.TrajectoryCount());
EXPECT_EQ(456u, newActor.TrajectoryByIndex(0)->Id());
EXPECT_EQ("traj_type", newActor.TrajectoryByIndex(0)->Type());
EXPECT_FLOAT_EQ(7.89, newActor.TrajectoryByIndex(0)->Tension());
EXPECT_FLOAT_EQ(7.89f, newActor.TrajectoryByIndex(0)->Tension());

ASSERT_EQ(1u, newActor.TrajectoryByIndex(0)->WaypointCount());
EXPECT_FLOAT_EQ(0.123,
EXPECT_FLOAT_EQ(0.123f,
newActor.TrajectoryByIndex(0)->WaypointByIndex(0)->Time());
EXPECT_EQ(math::Pose3d(6, 5, 4, 0, 0, 0),
newActor.TrajectoryByIndex(0)->WaypointByIndex(0)->Pose());
Expand Down
4 changes: 2 additions & 2 deletions src/EntityComponentManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1063,8 +1063,8 @@ void EntityComponentManagerPrivate::CalculateStateThreadLoad()
int maxThreads = std::thread::hardware_concurrency();
uint64_t numThreads = std::min(numComponents, maxThreads);

int componentsPerThread = std::ceil(static_cast<double>(numComponents) /
numThreads);
int componentsPerThread = static_cast<int>(std::ceil(
static_cast<double>(numComponents) / numThreads));

igndbg << "Updated state thread iterators: " << numThreads
<< " threads processing around " << componentsPerThread
Expand Down
3 changes: 3 additions & 0 deletions src/EntityComponentManager_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <gtest/gtest.h>

#include <ignition/common/Console.hh>
#include <ignition/common/Util.hh>
#include <ignition/math/Pose3.hh>
#include <ignition/math/Rand.hh>

Expand Down Expand Up @@ -175,6 +176,8 @@ TEST_P(EntityComponentManagerFixture, AdjacentMemorySingleComponentType)
/////////////////////////////////////////////////
TEST_P(EntityComponentManagerFixture, AdjacentMemoryTwoComponentTypes)
{
common::setenv("IGN_DEBUG_COMPONENT_FACTORY", "true");

std::vector<components::Pose> poses;
std::vector<IntComponent> ints;
std::vector<ComponentKey> poseKeys;
Expand Down
6 changes: 3 additions & 3 deletions src/SdfEntityCreator_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -817,9 +817,9 @@ TEST_F(SdfEntityCreatorTest, CreateLights)
EXPECT_NE(nullptr, _geometry->Data().SphereShape());
EXPECT_DOUBLE_EQ(0.5, _geometry->Data().SphereShape()->Radius());

EXPECT_EQ(math::Color(0.3, 0.3, 0.3), _material->Data().Ambient());
EXPECT_EQ(math::Color(0.3, 0.3, 0.3), _material->Data().Diffuse());
EXPECT_EQ(math::Color(0.3, 0.3, 0.3), _material->Data().Specular());
EXPECT_EQ(math::Color(0.3f, 0.3f, 0.3f), _material->Data().Ambient());
EXPECT_EQ(math::Color(0.3f, 0.3f, 0.3f), _material->Data().Diffuse());
EXPECT_EQ(math::Color(0.3f, 0.3f, 0.3f), _material->Data().Specular());
return true;
});

Expand Down
4 changes: 2 additions & 2 deletions src/SimulationRunner.cc
Original file line number Diff line number Diff line change
Expand Up @@ -471,9 +471,9 @@ void SimulationRunner::ProcessSystemQueue()
<< this->systemsPostupdate.size() + 1 << std::endl;

this->postUpdateStartBarrier =
std::make_unique<Barrier>(this->systemsPostupdate.size() + 1);
std::make_unique<Barrier>(this->systemsPostupdate.size() + 1u);
this->postUpdateStopBarrier =
std::make_unique<Barrier>(this->systemsPostupdate.size() + 1);
std::make_unique<Barrier>(this->systemsPostupdate.size() + 1u);

this->postUpdateThreadsRunning = true;
int id = 0;
Expand Down
6 changes: 3 additions & 3 deletions src/SimulationRunner_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -785,9 +785,9 @@ TEST_P(SimulationRunnerTest, CreateLights)
EXPECT_NE(nullptr, _geometry->Data().SphereShape());
EXPECT_DOUBLE_EQ(0.5, _geometry->Data().SphereShape()->Radius());

EXPECT_EQ(math::Color(0.3, 0.3, 0.3), _material->Data().Ambient());
EXPECT_EQ(math::Color(0.3, 0.3, 0.3), _material->Data().Diffuse());
EXPECT_EQ(math::Color(0.3, 0.3, 0.3), _material->Data().Specular());
EXPECT_EQ(math::Color(0.3f, 0.3f, 0.3f), _material->Data().Ambient());
EXPECT_EQ(math::Color(0.3f, 0.3f, 0.3f), _material->Data().Diffuse());
EXPECT_EQ(math::Color(0.3f, 0.3f, 0.3f), _material->Data().Specular());
return true;
});

Expand Down
18 changes: 14 additions & 4 deletions src/gui/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,10 @@ set (gui_sources
TmpIface.cc
)

set (gtest_sources
Gui_TEST.cc
)

add_subdirectory(plugins)

if(POLICY CMP0100)
Expand All @@ -27,6 +31,16 @@ qt5_wrap_cpp(gui_sources
${PROJECT_SOURCE_DIR}/include/ignition/gazebo/gui/TmpIface.hh
)

if (MSVC)
# Warning #4251 is the "dll-interface" warning that tells you when types used
# by a class are not being exported. These generated source files have private
# members that don't get exported, so they trigger this warning. However, the
# warning is not important since those members do not need to be interfaced
# with.
set_source_files_properties(${gui_sources} ${gtest_sources}
COMPILE_FLAGS "/wd4251 /wd4146")
endif()

ign_add_component(gui
SOURCES ${gui_sources} resources/gazebo.qrc
GET_TARGET_NAME gui_target
Expand All @@ -51,10 +65,6 @@ install (FILES gui.config DESTINATION ${IGN_DATA_INSTALL_DIR}/gui)
install (FILES playback_gui.config DESTINATION ${IGN_DATA_INSTALL_DIR}/gui)

# Tests
set (gtest_sources
${gtest_sources}
Gui_TEST.cc
)
include_directories(${PROJECT_SOURCE_DIR}/test)

ign_build_tests(TYPE UNIT
Expand Down
9 changes: 9 additions & 0 deletions src/gui/plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,15 @@ function(gz_add_gui_plugin plugin_name)

cmake_parse_arguments(gz_add_gui_plugin "${options}" "${oneValueArgs}" "${multiValueArgs}" ${ARGN})

if(MSVC)
# Warning #4251 is the "dll-interface" warning that tells you when types
# used by a class are not being exported. These generated source files have
# private members that don't get exported, so they trigger this warning.
# However, the warning is not important since those members do not need to
# be interfaced with.
set_source_files_properties(${gz_add_gui_plugin_SOURCES} COMPILE_FLAGS "/wd4251")
endif()

gz_add_gui_library(${plugin_name}
SOURCES ${gz_add_gui_plugin_SOURCES}
QT_HEADERS ${gz_add_gui_plugin_QT_HEADERS}
Expand Down
2 changes: 1 addition & 1 deletion src/gui/plugins/grid_config/GridConfig.cc
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ namespace ignition::gazebo
math::Pose3d pose{math::Pose3d::Zero};

/// \brief Default color of grid
math::Color color{math::Color(0.7, 0.7, 0.7, 1.0)};
math::Color color{math::Color(0.7f, 0.7f, 0.7f, 1.0f)};

/// \brief Default visible state
bool visible{true};
Expand Down
4 changes: 2 additions & 2 deletions src/gui/plugins/tape_measure/TapeMeasure.cc
Original file line number Diff line number Diff line change
Expand Up @@ -70,12 +70,12 @@ namespace ignition::gazebo
/// \brief The color to set the marker when hovering the mouse over the
/// scene.
public: ignition::math::Color
hoverColor{ignition::math::Color(0.2, 0.2, 0.2, 0.5)};
hoverColor{ignition::math::Color(0.2f, 0.2f, 0.2f, 0.5f)};

/// \brief The color to draw the marker when the user clicks to confirm
/// its location.
public: ignition::math::Color
drawColor{ignition::math::Color(0.2, 0.2, 0.2, 1.0)};
drawColor{ignition::math::Color(0.2f, 0.2f, 0.2f, 1.0f)};

/// \brief A set of the currently placed markers. Used to make sure a
/// non-existent marker is not deleted.
Expand Down
10 changes: 10 additions & 0 deletions src/rendering/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,16 @@ set (rendering_comp_sources
SceneManager.cc
)

if (MSVC)
# Warning #4251 is the "dll-interface" warning that tells you when types used
# by a class are not being exported. These generated source files have private
# members that don't get exported, so they trigger this warning. However, the
# warning is not important since those members do not need to be interfaced
# with.
set_source_files_properties(${rendering_comp_sources}
COMPILE_FLAGS "/wd4251 /wd4146")
endif()

ign_add_component(rendering
SOURCES ${rendering_comp_sources}
GET_TARGET_NAME rendering_target
Expand Down
8 changes: 4 additions & 4 deletions src/rendering/SceneManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -329,8 +329,8 @@ rendering::VisualPtr SceneManager::CreateVisual(Entity _id,
material->SetAmbient(0.3, 0.3, 0.3);
material->SetDiffuse(0.7, 0.7, 0.7);
material->SetSpecular(1.0, 1.0, 1.0);
material->SetRoughness(0.2);
material->SetMetalness(1.0);
material->SetRoughness(0.2f);
material->SetMetalness(1.0f);
}
}
else
Expand Down Expand Up @@ -400,8 +400,8 @@ rendering::VisualPtr SceneManager::CreateCollision(Entity _id,
const sdf::Collision &_collision, Entity _parentId)
{
sdf::Material material;
material.SetAmbient(math::Color(1, 0.5088, 0.0468, 0.7));
material.SetDiffuse(math::Color(1, 0.5088, 0.0468, 0.7));
material.SetAmbient(math::Color(1.0f, 0.5088f, 0.0468f, 0.7f));
material.SetDiffuse(math::Color(1.0f, 0.5088f, 0.0468f, 0.7f));

sdf::Visual visual;
visual.SetGeom(*_collision.Geom());
Expand Down
2 changes: 1 addition & 1 deletion src/systems/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ add_subdirectory(imu)
add_subdirectory(joint_controller)
add_subdirectory(joint_position_controller)
add_subdirectory(joint_state_publisher)
add_subdirectory(joint_trajectory_controller)
add_subdirectory(joint_traj_control)
add_subdirectory(kinetic_energy_monitor)
add_subdirectory(lift_drag)
add_subdirectory(log)
Expand Down
4 changes: 2 additions & 2 deletions src/systems/optical_tactile_plugin/Visualization.cc
Original file line number Diff line number Diff line change
Expand Up @@ -115,14 +115,14 @@ void OpticalTactilePluginVisualization::InitializeNormalForcesMarkerMsgs(
ignition::msgs::Set(_positionMarkerMsg.mutable_material()->
mutable_diffuse(), math::Color(0, 0, 1, 1));
_positionMarkerMsg.mutable_lifetime()->set_nsec(
this->cameraUpdateRate * 1000000000);
static_cast<int>(this->cameraUpdateRate * 1000000000));

ignition::msgs::Set(_forceMarkerMsg.mutable_material()->
mutable_ambient(), math::Color(0, 1, 0, 1));
ignition::msgs::Set(_forceMarkerMsg.mutable_material()->
mutable_diffuse(), math::Color(0, 1, 0, 1));
_forceMarkerMsg.mutable_lifetime()->set_sec(
this->cameraUpdateRate * 1000000000);
static_cast<int>(this->cameraUpdateRate * 1000000000));
}

//////////////////////////////////////////////////
Expand Down
9 changes: 9 additions & 0 deletions test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,15 @@ else()
endforeach(test)
endif()

if (MSVC)
# Warning #4251 is the "dll-interface" warning that tells you when types used
# by a class are not being exported. These generated source files have private
# members that don't get exported, so they trigger this warning. However, the
# warning is not important since those members do not need to be interfaced
# with.
set_source_files_properties(${tests} COMPILE_FLAGS "/wd4251 /wd4146")
endif()

link_directories(${PROJECT_BINARY_DIR}/test)
include_directories(${PROJECT_SOURCE_DIR}/test)

Expand Down
7 changes: 4 additions & 3 deletions test/integration/altimeter_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -129,9 +129,10 @@ TEST_F(AltimeterTest, ModelFalling)
EXPECT_EQ(iters100, poses.size());

// Wait for messages to be received
double updateRate = 30;
size_t updateRate = 30;
double stepSize = 0.001;
size_t waitForMsgs = poses.size() * stepSize * updateRate + 1;
size_t waitForMsgs =
static_cast<size_t>(poses.size() * stepSize * updateRate + 1);
for (int sleep = 0; sleep < 30; ++sleep)
{
std::this_thread::sleep_for(std::chrono::milliseconds(100));
Expand Down Expand Up @@ -176,7 +177,7 @@ TEST_F(AltimeterTest, ModelFalling)
EXPECT_EQ(iters100 + iters1000, poses.size());

// Wait for messages to be received
waitForMsgs = poses.size() * stepSize * updateRate + 1;
waitForMsgs = static_cast<size_t>(poses.size() * stepSize * updateRate + 1);
for (int sleep = 0; sleep < 30; ++sleep)
{
std::this_thread::sleep_for(std::chrono::milliseconds(100));
Expand Down
Loading