Skip to content

Commit 02b3f59

Browse files
mjcarrollNate Koenig
and
Nate Koenig
authored
Towards Green CI (#1771)
Apply fixes to get CI closer to green on all platforms. Signed-off-by: Michael Carroll <michael@openrobotics.org> Signed-off-by: Nate Koenig <nate@openrobotics.org> Co-authored-by: Nate Koenig <nate@openrobotics.org>
1 parent 6a326ac commit 02b3f59

33 files changed

+136
-97
lines changed

.gitignore

+5
Original file line numberDiff line numberDiff line change
@@ -15,3 +15,8 @@ build_*
1515

1616
# clangd index
1717
.cache
18+
19+
20+
# Python cache
21+
__pycache__
22+
*.pyc

python/CMakeLists.txt

+7-6
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@ else()
2828
set(GZ_PYTHON_INSTALL_PATH ${GZ_LIB_INSTALL_DIR}/python)
2929
endif()
3030

31+
set(GZ_PYTHON_EXECUTABLE ${Python3_EXECUTABLE})
3132
set(GZ_PYTHON_INSTALL_PATH "${GZ_PYTHON_INSTALL_PATH}/gz")
3233

3334
# Set the build location and install location for a CPython extension
@@ -88,7 +89,7 @@ if (BUILD_TESTING)
8889
testFixture_TEST
8990
)
9091

91-
execute_process(COMMAND "${PYTHON_EXECUTABLE}" -m pytest --version
92+
execute_process(COMMAND "${GZ_PYTHON_EXECUTABLE}" -m pytest --version
9293
OUTPUT_VARIABLE PYTEST_output
9394
ERROR_VARIABLE PYTEST_error
9495
RESULT_VARIABLE PYTEST_result)
@@ -101,17 +102,17 @@ if (BUILD_TESTING)
101102

102103
foreach (test ${python_tests})
103104
if (pytest_FOUND)
104-
add_test(NAME ${test}.py COMMAND
105-
"${PYTHON_EXECUTABLE}" -m pytest "${CMAKE_SOURCE_DIR}/python/test/${test}.py" --junitxml "${CMAKE_BINARY_DIR}/test_results/UNIT_${test}.xml")
105+
add_test(NAME ${test} COMMAND
106+
"${GZ_PYTHON_EXECUTABLE}" -m pytest "${CMAKE_SOURCE_DIR}/python/test/${test}.py" --junitxml "${CMAKE_BINARY_DIR}/test_results/UNIT_${test}.xml")
106107
else()
107-
add_test(NAME ${test}.py COMMAND
108-
"${PYTHON_EXECUTABLE}" "${CMAKE_SOURCE_DIR}/python/test/${test}.py")
108+
add_test(NAME ${test} COMMAND
109+
"${GZ_PYTHON_EXECUTABLE}" "${CMAKE_SOURCE_DIR}/python/test/${test}.py")
109110
endif()
110111

111112
set(_env_vars)
112113
list(APPEND _env_vars "PYTHONPATH=${CMAKE_INSTALL_PREFIX}/${CMAKE_INSTALL_LIBDIR}/python/")
113114
list(APPEND _env_vars "LD_LIBRARY_PATH=${CMAKE_INSTALL_PREFIX}/${CMAKE_INSTALL_LIBDIR}:$ENV{LD_LIBRARY_PATH}")
114-
set_tests_properties(${test}.py PROPERTIES
115+
set_tests_properties(${test} PROPERTIES
115116
ENVIRONMENT "${_env_vars}")
116117
endforeach()
117118
endif()

python/test/testFixture_TEST.py

100644100755
File mode changed.

src/Conversions_TEST.cc

+3-2
Original file line numberDiff line numberDiff line change
@@ -1032,9 +1032,10 @@ TEST(Conversions, ParticleEmitter)
10321032
EXPECT_NEAR(0.2, emitterMsg.max_velocity().data(), 1e-3);
10331033
EXPECT_EQ(math::Vector3d(1, 2, 3), msgs::Convert(emitterMsg.size()));
10341034
EXPECT_EQ(math::Vector3d(4, 5, 6), msgs::Convert(emitterMsg.particle_size()));
1035-
EXPECT_EQ(math::Color(0.1, 0.2, 0.3),
1035+
EXPECT_EQ(math::Color(0.1f, 0.2f, 0.3f),
10361036
msgs::Convert(emitterMsg.color_start()));
1037-
EXPECT_EQ(math::Color(0.4, 0.5, 0.6), msgs::Convert(emitterMsg.color_end()));
1037+
EXPECT_EQ(math::Color(0.4f, 0.5f, 0.6f),
1038+
msgs::Convert(emitterMsg.color_end()));
10381039
EXPECT_EQ("range_image", emitterMsg.color_range_image().data());
10391040

10401041
auto header = emitterMsg.header().data(0);

src/SdfGenerator_TEST.cc

+15-18
Original file line numberDiff line numberDiff line change
@@ -348,7 +348,7 @@ class ModelElementFixture : public ElementUpdateFixture
348348
/////////////////////////////////////////////////
349349
TEST_F(ModelElementFixture, ModelsInline)
350350
{
351-
this->LoadWorld("test/worlds/shapes.sdf");
351+
this->LoadWorld(common::joinPaths("test", "worlds", "shapes.sdf"));
352352
this->TestModel("box");
353353
this->TestModel("capsule");
354354
this->TestModel("cylinder");
@@ -359,15 +359,15 @@ TEST_F(ModelElementFixture, ModelsInline)
359359
/////////////////////////////////////////////////
360360
TEST_F(ModelElementFixture, ModelIncluded)
361361
{
362-
this->LoadWorld("test/worlds/save_world.sdf");
362+
this->LoadWorld(common::joinPaths("test", "worlds", "save_world.sdf"));
363363
this->TestModel("backpack1");
364364
this->TestModel("backpack2");
365365
}
366366

367367
/////////////////////////////////////////////////
368368
TEST_F(ModelElementFixture, ModelComponentUpdate)
369369
{
370-
this->LoadWorld("test/worlds/shapes.sdf");
370+
this->LoadWorld(common::joinPaths("test", "worlds", "shapes.sdf"));
371371
std::string modelName = "box";
372372
Entity modelEntity = this->ecm.EntityByComponents(
373373
components::Model(), components::Name(modelName));
@@ -461,8 +461,7 @@ TEST_F(ElementUpdateFixture, ConfigOverrideCopyOrMerge)
461461
/////////////////////////////////////////////////
462462
TEST_F(ElementUpdateFixture, ConfigOverride)
463463
{
464-
const std::string worldFile{"test/worlds/save_world.sdf"};
465-
this->LoadWorld(worldFile);
464+
this->LoadWorld(common::joinPaths("test", "worlds", "save_world.sdf"));
466465
Entity worldEntity = this->ecm.EntityByComponents(components::World());
467466
{
468467
this->sdfGenConfig.mutable_global_entity_gen_config()
@@ -522,8 +521,7 @@ TEST_F(ElementUpdateFixture, ConfigOverride)
522521
/////////////////////////////////////////////////
523522
TEST_F(ElementUpdateFixture, WorldWithModelsInline)
524523
{
525-
const std::string worldFile{"test/worlds/shapes.sdf"};
526-
this->LoadWorld(worldFile);
524+
this->LoadWorld(common::joinPaths("test", "worlds", "shapes.sdf"));
527525
Entity worldEntity = this->ecm.EntityByComponents(components::World());
528526
auto elem = std::make_shared<sdf::Element>();
529527
sdf::initFile("world.sdf", elem);
@@ -535,7 +533,7 @@ TEST_F(ElementUpdateFixture, WorldWithModelsInline)
535533
/////////////////////////////////////////////////
536534
TEST_F(ElementUpdateFixture, WorldWithModelsIncludedExpanded)
537535
{
538-
this->LoadWorld("test/worlds/save_world.sdf");
536+
this->LoadWorld(common::joinPaths("test", "worlds", "save_world.sdf"));
539537
Entity worldEntity = this->ecm.EntityByComponents(components::World());
540538
auto elem = std::make_shared<sdf::Element>();
541539
sdf::initFile("world.sdf", elem);
@@ -586,7 +584,7 @@ TEST_F(ElementUpdateFixture, WorldComponentUpdate)
586584
/////////////////////////////////////////////////
587585
TEST_F(ElementUpdateFixture, WorldWithModelsIncludedNotExpanded)
588586
{
589-
const std::string worldFile{"test/worlds/save_world.sdf"};
587+
const auto worldFile = common::joinPaths("test", "worlds", "save_world.sdf");
590588
this->LoadWorld(worldFile);
591589
Entity worldEntity = this->ecm.EntityByComponents(components::World());
592590
auto elem = std::make_shared<sdf::Element>();
@@ -644,17 +642,17 @@ TEST_F(ElementUpdateFixture, WorldWithModelsIncludedNotExpanded)
644642
TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithInvalidUris)
645643
{
646644
const std::string goodUri =
647-
"https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/2";
645+
"https://fuel.gazebosim.org/1.0/openroboticstest/models/backpack/2";
648646

649647
// These are URIs that are potentially problematic.
650648
const std::vector<std::string> fuelUris = {
651649
// Thes following two URIs are valid, but have a trailing '/'
652-
"https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/",
653-
"https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/2/",
650+
"https://fuel.gazebosim.org/1.0/openroboticstest/models/backpack/",
651+
"https://fuel.gazebosim.org/1.0/openroboticstest/models/backpack/2/",
654652
// Thes following two URIs are invalid, and will not be saved
655-
"https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/"
653+
"https://fuel.gazebosim.org/1.0/openroboticstest/models/backpack/"
656654
"notInt",
657-
"https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/"
655+
"https://fuel.gazebosim.org/1.0/openroboticstest/models/backpack/"
658656
"notInt/",
659657
};
660658

@@ -709,7 +707,7 @@ TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithInvalidUris)
709707
TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithNonFuelUris)
710708
{
711709
const std::vector<std::string> includeUris = {
712-
"https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack",
710+
"https://fuel.gazebosim.org/1.0/openroboticstest/models/backpack",
713711
std::string("file://") + PROJECT_SOURCE_PATH +
714712
"/test/worlds/models/sphere"};
715713

@@ -768,7 +766,7 @@ TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithNonFuelUris)
768766
/////////////////////////////////////////////////
769767
TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithOneExpanded)
770768
{
771-
const std::string worldFile{"test/worlds/save_world.sdf"};
769+
const auto worldFile = common::joinPaths("test", "worlds", "save_world.sdf");
772770
this->LoadWorld(worldFile);
773771
Entity worldEntity = this->ecm.EntityByComponents(components::World());
774772
auto elem = std::make_shared<sdf::Element>();
@@ -947,8 +945,7 @@ using GenerateWorldFixture = ElementUpdateFixture;
947945
/////////////////////////////////////////////////
948946
TEST_F(GenerateWorldFixture, ModelsInline)
949947
{
950-
const std::string worldFile{"test/worlds/save_world.sdf"};
951-
this->LoadWorld(worldFile);
948+
this->LoadWorld(common::joinPaths("test", "worlds", "save_world.sdf"));
952949
Entity worldEntity = this->ecm.EntityByComponents(components::World());
953950
// Check with expandIncludeTags = true
954951
{

src/Server.cc

+1-1
Original file line numberDiff line numberDiff line change
@@ -202,7 +202,7 @@ bool Server::Run(const bool _blocking, const uint64_t _iterations,
202202
// running variable gets updated before this function returns. With
203203
// a small number of iterations it is possible that the run thread
204204
// successfuly completes before this function returns.
205-
cond.wait(lock);
205+
cond.wait(lock, [this]() -> bool {return this->dataPtr->running;});
206206
return true;
207207
}
208208

src/ServerPrivate.cc

+1-2
Original file line numberDiff line numberDiff line change
@@ -227,9 +227,8 @@ void ServerPrivate::AddRecordPlugin(const ServerConfig &_config)
227227
{
228228
auto topic = recordTopicElem->Get<std::string>();
229229
sdfRecordTopics.push_back(topic);
230+
recordTopicElem = recordTopicElem->GetNextElement();
230231
}
231-
232-
recordTopicElem = recordTopicElem->GetNextElement();
233232
}
234233

235234
// Remove the plugin, which will be added back in by ServerConfig.

src/Server_TEST.cc

+18-1
Original file line numberDiff line numberDiff line change
@@ -1217,14 +1217,31 @@ TEST_P(ServerFixture, Stop)
12171217

12181218
sim::Server server(serverConfig);
12191219

1220+
std::mutex testMutex;
1221+
std::condition_variable testCv;
1222+
test::Relay testSystem;
1223+
unsigned int preUpdates{0};
1224+
testSystem.OnPreUpdate(
1225+
[&](const sim::UpdateInfo &,
1226+
sim::EntityComponentManager &)
1227+
{
1228+
std::scoped_lock localLock(testMutex);
1229+
++preUpdates;
1230+
testCv.notify_one();
1231+
return true;
1232+
});
1233+
1234+
server.AddSystem(testSystem.systemPtr);
12201235
// The simulation runner should not be running.
12211236
EXPECT_FALSE(*server.Running(0));
12221237
EXPECT_FALSE(server.Running());
12231238

12241239
// Run the server.
1240+
std::unique_lock<std::mutex> testLock(testMutex);
12251241
EXPECT_TRUE(server.Run(false, 0, false));
1226-
EXPECT_TRUE(*server.Running(0));
12271242
EXPECT_TRUE(server.Running());
1243+
testCv.wait(testLock, [&]() -> bool {return preUpdates > 0;});
1244+
EXPECT_TRUE(*server.Running(0));
12281245

12291246
// Stop the server
12301247
server.Stop();

src/SimulationRunner.cc

+2-1
Original file line numberDiff line numberDiff line change
@@ -502,7 +502,8 @@ void SimulationRunner::ProcessSystemQueue()
502502

503503
this->systemMgr->ActivatePendingSystems();
504504

505-
auto threadCount = this->systemMgr->SystemsPostUpdate().size() + 1u;
505+
unsigned int threadCount =
506+
static_cast<unsigned int>(this->systemMgr->SystemsPostUpdate().size() + 1u);
506507

507508
gzdbg << "Creating PostUpdate worker threads: "
508509
<< threadCount << std::endl;

src/gz_TEST.cc

+1-1
Original file line numberDiff line numberDiff line change
@@ -101,7 +101,7 @@ TEST(CmdLine, GZ_UTILS_TEST_DISABLED_ON_WIN32(CachedFuelWorld))
101101
std::string projectPath = std::string(PROJECT_SOURCE_PATH) + "/test/worlds";
102102
gz::common::setenv("GZ_FUEL_CACHE_PATH", projectPath.c_str());
103103
std::string cmd = kGzCommand + " -r -v 4 --iterations 5" +
104-
" https://fuel.ignitionrobotics.org/1.0/OpenRobotics/worlds/Test%20world";
104+
" https://fuel.gazebosim.org/1.0/openroboticstest/worlds/test%20world";
105105
std::cout << "Running command [" << cmd << "]" << std::endl;
106106

107107
std::string output = customExecStr(cmd);

src/systems/acoustic_comms/AcousticComms.cc

+3-3
Original file line numberDiff line numberDiff line change
@@ -57,10 +57,10 @@ AcousticComms::AcousticComms()
5757

5858
//////////////////////////////////////////////////
5959
void AcousticComms::Load(
60-
const Entity &_entity,
60+
const Entity &/*_entity*/,
6161
std::shared_ptr<const sdf::Element> _sdf,
62-
EntityComponentManager &_ecm,
63-
EventManager &_eventMgr)
62+
EntityComponentManager &/*_ecm*/,
63+
EventManager &/*_eventMgr*/)
6464
{
6565
if (_sdf->HasElement("max_range"))
6666
{

src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc

+8-9
Original file line numberDiff line numberDiff line change
@@ -767,8 +767,7 @@ void OpticalTactilePluginPrivate::ComputeNormalForces(
767767
normalsMsg.set_step(3 * sizeof(float) * _msg.width());
768768
normalsMsg.set_pixel_format_type(gz::msgs::PixelFormatType::R_FLOAT32);
769769

770-
uint32_t bufferSize = 3 * sizeof(float) * _msg.width() * _msg.height();
771-
std::shared_ptr<char> normalForcesBuffer(new char[bufferSize]);
770+
std::vector<float> normalForcesBuffer(3 * _msg.width() * _msg.height());
772771
uint32_t bufferIndex;
773772

774773
// Marker messages representing the normal forces
@@ -804,11 +803,10 @@ void OpticalTactilePluginPrivate::ComputeNormalForces(
804803
// Add force to buffer
805804
// Forces buffer is composed of XYZ coordinates, while _msg buffer is
806805
// made up of XYZRGB values
807-
bufferIndex = j * (_msg.row_step() / 2) + i * (_msg.point_step() / 2);
808-
normalForcesBuffer.get()[bufferIndex] = normalForce.X();
809-
normalForcesBuffer.get()[bufferIndex + sizeof(float)] = normalForce.Y();
810-
normalForcesBuffer.get()[bufferIndex + 2 * sizeof(float)] =
811-
normalForce.Z();
806+
bufferIndex = j * (_msg.width() * 3) + i * 3;
807+
normalForcesBuffer[bufferIndex] = normalForce.X();
808+
normalForcesBuffer[bufferIndex+1] = normalForce.Y();
809+
normalForcesBuffer[bufferIndex+2] = normalForce.Z();
812810

813811
if (!_visualizeForces)
814812
continue;
@@ -820,9 +818,10 @@ void OpticalTactilePluginPrivate::ComputeNormalForces(
820818
}
821819
}
822820

821+
std::string *dataStr = normalsMsg.mutable_data();
822+
dataStr->resize(sizeof(float) * normalForcesBuffer.size());
823+
memcpy(&((*dataStr)[0]), normalForcesBuffer.data(), dataStr->size());
823824
// Publish message
824-
normalsMsg.set_data(normalForcesBuffer.get(),
825-
3 * sizeof(float) * _msg.width() * _msg.height());
826825
this->normalForcesPub.Publish(normalsMsg);
827826

828827
if (_visualizeForces)

src/systems/rf_comms/RFComms.cc

+6-3
Original file line numberDiff line numberDiff line change
@@ -257,7 +257,8 @@ std::tuple<bool, double> RFComms::Implementation::AttemptSend(
257257

258258
// Compute prospective accumulated bits along with time window
259259
// (including this packet).
260-
double bitsSent = (_txState.bytesSentThisEpoch + _numBytes) * 8;
260+
auto bitsSent =
261+
static_cast<double>((_txState.bytesSentThisEpoch + _numBytes) * 8);
261262

262263
// Check current epoch bitrate vs capacity and fail to send accordingly
263264
if (bitsSent > this->radioConfig.capacity * this->epochDuration)
@@ -286,8 +287,9 @@ std::tuple<bool, double> RFComms::Implementation::AttemptSend(
286287
// error rate (BER).
287288
double ber = this->QPSKPowerToBER(
288289
this->DbmToPow(rxPower), this->DbmToPow(this->radioConfig.noiseFloor));
290+
double packetDropProb =
289291

290-
double packetDropProb = 1.0 - exp(_numBytes * log(1 - ber));
292+
1.0 - exp(static_cast<double>(_numBytes) * log(1 - ber));
291293

292294
// gzdbg << "TX power (dBm): " << this->radioConfig.txPower << "\n" <<
293295
// "RX power (dBm): " << rxPower << "\n" <<
@@ -315,7 +317,8 @@ std::tuple<bool, double> RFComms::Implementation::AttemptSend(
315317

316318
// Compute prospective accumulated bits along with time window
317319
// (including this packet).
318-
double bitsReceived = (_rxState.bytesReceivedThisEpoch + _numBytes) * 8;
320+
auto bitsReceived =
321+
static_cast<double>((_rxState.bytesReceivedThisEpoch + _numBytes) * 8);
319322

320323
// Check current epoch bitrate vs capacity and fail to send accordingly.
321324
if (bitsReceived > this->radioConfig.capacity * this->epochDuration)

src/systems/shader_param/ShaderParam.cc

+1-1
Original file line numberDiff line numberDiff line change
@@ -441,7 +441,7 @@ void ShaderParamPrivate::OnUpdate()
441441
if (!spv.type.empty() && spv.type == "int_array")
442442
{
443443
for (const auto &v : values)
444-
floatArrayValue.push_back(std::stoi(v));
444+
floatArrayValue.push_back(std::stof(v));
445445
paramType = rendering::ShaderParam::PARAM_INT_BUFFER;
446446
}
447447
// treat everything else as float_array

src/systems/track_controller/TrackController.cc

+1-1
Original file line numberDiff line numberDiff line change
@@ -533,7 +533,7 @@ void TrackControllerPrivate::ComputeSurfaceProperties(
533533
gz::msgs::Set(this->debugMarker.mutable_pose(), math::Pose3d(
534534
p.X(), p.Y(), p.Z(), rot.Roll(), rot.Pitch(), rot.Yaw()));
535535
this->debugMarker.mutable_material()->mutable_diffuse()->set_r(
536-
surfaceMotion >= 0 ? 0 : 1);
536+
surfaceMotion >= 0 ? 0.0f : 1.0f);
537537

538538
this->node.Request("/marker", this->debugMarker);
539539
}

src/systems/trajectory_follower/TrajectoryFollower.cc

+1-1
Original file line numberDiff line numberDiff line change
@@ -421,7 +421,7 @@ void TrajectoryFollower::PreUpdate(
421421
}
422422
}
423423

424-
int sign = std::abs(bearing.Degree()) / bearing.Degree();
424+
int sign = static_cast<int>(std::abs(bearing.Degree()) / bearing.Degree());
425425
torqueWorld = (*comPose).Rot().RotateVector(
426426
gz::math::Vector3d(0, 0, sign * this->dataPtr->torqueToApply));
427427
}

0 commit comments

Comments
 (0)