Skip to content

Commit

Permalink
Several minor fixes (#2027)
Browse files Browse the repository at this point in the history
Signed-off-by: Shameek Ganguly <shameekarcanesphinx@gmail.com>
  • Loading branch information
shameekganguly authored Jul 3, 2023
1 parent 001dd9b commit b8a8a18
Show file tree
Hide file tree
Showing 18 changed files with 63 additions and 57 deletions.
5 changes: 4 additions & 1 deletion src/ServerConfig.cc
Original file line number Diff line number Diff line change
Expand Up @@ -265,7 +265,8 @@ class gz::sim::ServerConfigPrivate
networkSecondaries(_cfg->networkSecondaries),
seed(_cfg->seed),
logRecordTopics(_cfg->logRecordTopics),
isHeadlessRendering(_cfg->isHeadlessRendering) { }
isHeadlessRendering(_cfg->isHeadlessRendering),
source(_cfg->source){ }

// \brief The SDF file that the server should load
public: std::string sdfFile = "";
Expand Down Expand Up @@ -811,6 +812,7 @@ ServerConfig::SourceType ServerConfig::Source() const
}

/////////////////////////////////////////////////
namespace {
void copyElement(sdf::ElementPtr _sdf, const tinyxml2::XMLElement *_xml)
{
_sdf->SetName(_xml->Value());
Expand Down Expand Up @@ -917,6 +919,7 @@ parsePluginsFromDoc(const tinyxml2::XMLDocument &_doc)
}
return ret;
}
} // namespace

/////////////////////////////////////////////////
std::list<ServerConfig::PluginInfo>
Expand Down
5 changes: 2 additions & 3 deletions src/SystemLoader_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -97,9 +97,8 @@ TEST(SystemLoader, PluginPaths)
for (const auto &s : paths)
{
// the returned path string may not be exact match due to extra '/'
// appended at the end of the string. So use absPath to generate
// a path string that matches the format returned by joinPaths
if (common::absPath(s) == testBuildPath)
// appended at the end of the string. So use absPath to compare paths
if (common::absPath(s) == common::absPath(testBuildPath))
{
hasPath = true;
break;
Expand Down
18 changes: 9 additions & 9 deletions src/gui/plugins/component_inspector/ComponentInspector.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1215,7 +1215,7 @@ void ComponentInspector::QuerySystems()
"/system/info"};
if (!this->dataPtr->node.Request(service, req, timeout, res, result))
{
ignerr << "Unable to query available systems." << std::endl;
gzerr << "Unable to query available systems." << std::endl;
return;
}

Expand All @@ -1225,8 +1225,8 @@ void ComponentInspector::QuerySystems()
{
if (plugin.filename().empty())
{
ignerr << "Received empty plugin name. This shouldn't happen."
<< std::endl;
gzerr << "Received empty plugin name. This shouldn't happen."
<< std::endl;
continue;
}

Expand Down Expand Up @@ -1273,7 +1273,7 @@ void ComponentInspector::OnAddSystem(const QString &_name,
auto it = this->dataPtr->systemMap.find(filenameStr);
if (it == this->dataPtr->systemMap.end())
{
ignerr << "Internal error: failed to find [" << filenameStr
gzerr << "Internal error: failed to find [" << filenameStr
<< "] in system map." << std::endl;
return;
}
Expand All @@ -1296,11 +1296,11 @@ void ComponentInspector::OnAddSystem(const QString &_name,
"/entity/system/add"};
if (!this->dataPtr->node.Request(service, req, timeout, res, result))
{
ignerr << "Error adding new system to entity: "
<< this->dataPtr->entity << "\n"
<< "Name: " << name << "\n"
<< "Filename: " << filename << "\n"
<< "Inner XML: " << innerxml << std::endl;
gzerr << "Error adding new system to entity: "
<< this->dataPtr->entity << "\n"
<< "Name: " << name << "\n"
<< "Filename: " << filename << "\n"
<< "Inner XML: " << innerxml << std::endl;
}
}

Expand Down
2 changes: 1 addition & 1 deletion src/rendering/RenderUtil.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1266,7 +1266,7 @@ void RenderUtil::Update()
}
else
{
ignerr << "Failed to create light" << std::endl;
gzerr << "Failed to create light" << std::endl;
}
}

Expand Down
16 changes: 8 additions & 8 deletions src/rendering/SceneManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1191,7 +1191,7 @@ rendering::LightPtr SceneManager::CreateLight(Entity _id,

if (this->HasEntity(_id))
{
ignerr << "Light with Id: [" << _id << "] can not be create there is "
gzerr << "Light with Id: [" << _id << "] can not be create there is "
"another entity with the same entity number" << std::endl;
return nullptr;
}
Expand Down Expand Up @@ -2376,8 +2376,8 @@ SceneManager::LoadAnimations(const sdf::Actor &_actor)
{
if (!meshSkel->AddBvhAnimation(animFilename, animScale))
{
ignerr << "Bvh animation in file " << animFilename
<< " failed to load during actor creation" << std::endl;
gzerr << "Bvh animation in file " << animFilename
<< " failed to load during actor creation" << std::endl;
continue;
}
}
Expand Down Expand Up @@ -2473,8 +2473,8 @@ SceneManagerPrivate::LoadTrajectories(const sdf::Actor &_actor,
const sdf::Trajectory *trajSdf = _actor.TrajectoryByIndex(i);
if (nullptr == trajSdf)
{
ignerr << "Null trajectory SDF for [" << _actor.Name() << "]"
<< std::endl;
gzerr << "Null trajectory SDF for [" << _actor.Name() << "]"
<< std::endl;
continue;
}
common::TrajectoryInfo trajInfo;
Expand Down Expand Up @@ -2517,9 +2517,9 @@ SceneManagerPrivate::LoadTrajectories(const sdf::Actor &_actor,
}
else
{
ignwarn << "Animation has no x displacement. "
<< "Ignoring <interpolate_x> for the animation in '"
<< animation->Filename() << "'." << std::endl;
gzwarn << "Animation has no x displacement. "
<< "Ignoring <interpolate_x> for the animation in '"
<< animation->Filename() << "'." << std::endl;
}
animInterpolateCheck.insert(animation->Filename());
}
Expand Down
6 changes: 3 additions & 3 deletions src/systems/battery_plugin/LinearBatteryPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -394,8 +394,8 @@ void LinearBatteryPlugin::Configure(const Entity &_entity,
std::bind(&LinearBatteryPluginPrivate::OnBatteryStopDrainingMsg,
this->dataPtr.get(), std::placeholders::_1, std::placeholders::_2,
std::placeholders::_3));
ignmsg << "LinearBatteryPlugin subscribes to stop power draining topic ["
<< topic << "]." << std::endl;
gzmsg << "LinearBatteryPlugin subscribes to stop power draining topic ["
<< topic << "]." << std::endl;
sdfElem = sdfElem->GetNextElement("power_draining_topic");
}
}
Expand Down Expand Up @@ -498,7 +498,7 @@ void LinearBatteryPlugin::PreUpdate(
bool success = this->dataPtr->battery->SetPowerLoad(
this->dataPtr->consumerId, total_power_load);
if (!success)
ignerr << "Failed to set consumer power load." << std::endl;
gzerr << "Failed to set consumer power load." << std::endl;

// Start draining the battery if the robot has started moving
if (!this->dataPtr->startDraining)
Expand Down
2 changes: 1 addition & 1 deletion src/systems/buoyancy/Buoyancy.cc
Original file line number Diff line number Diff line change
Expand Up @@ -643,7 +643,7 @@ void Buoyancy::PostUpdate(
bool Buoyancy::IsEnabled(Entity _entity,
const EntityComponentManager &_ecm) const
{
return this->IsEnabled(_entity, _ecm);
return this->dataPtr->IsEnabled(_entity, _ecm);
}

GZ_ADD_PLUGIN(Buoyancy,
Expand Down
2 changes: 1 addition & 1 deletion src/systems/environment_preload/EnvironmentPreload.cc
Original file line number Diff line number Diff line change
Expand Up @@ -134,7 +134,7 @@ void EnvironmentPreload::PreUpdate(
}
else if (unitName != "radians")
{
ignerr << "Unrecognized unit " << unitName << "\n";
gzerr << "Unrecognized unit " << unitName << "\n";
}
}
}
Expand Down
4 changes: 2 additions & 2 deletions src/systems/hydrodynamics/Hydrodynamics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -295,7 +295,7 @@ void Hydrodynamics::Configure(
{
if (_sdf->HasElement("waterDensity"))
{
ignwarn <<
gzwarn <<
"<waterDensity> parameter is deprecated and will be removed Ignition G.\n"
<< "\tPlease update your SDF to use <water_density> instead.";
}
Expand Down Expand Up @@ -342,7 +342,7 @@ void Hydrodynamics::Configure(

if (warnBehaviourChange)
{
ignwarn << "You are using parameters that may cause instabilities "
gzwarn << "You are using parameters that may cause instabilities "
<< "in your simulation. If your simulation crashes we recommend "
<< "renaming <xUU> -> <xUabsU> and likewise for other axis "
<< "for more information see:" << std::endl
Expand Down
3 changes: 3 additions & 0 deletions src/systems/multicopter_control/MulticopterVelocityControl.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,9 @@
#include <memory>
#include <string>

#include <gz/msgs/actuators.pb.h>
#include <gz/msgs/boolean.pb.h>
#include <gz/msgs/twist.pb.h>
#include <gz/transport/Node.hh>

#include <gz/sim/System.hh>
Expand Down
1 change: 1 addition & 0 deletions src/systems/performer_detector/PerformerDetector.hh
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include <string>
#include <unordered_set>

#include <gz/math/AxisAlignedBox.hh>
#include <gz/transport/Node.hh>

#include "gz/sim/Model.hh"
Expand Down
3 changes: 1 addition & 2 deletions src/systems/physics/Physics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3763,8 +3763,7 @@ void PhysicsPrivate::UpdateCollisions(EntityComponentManager &_ecm)
// Note that we are temporarily storing pointers to elements in this
// ("allContacts") container. Thus, we must make sure it doesn't get destroyed
// until the end of this function.
auto allContacts =
std::move(worldCollisionFeature->GetContactsFromLastStep());
auto allContacts = worldCollisionFeature->GetContactsFromLastStep();

for (const auto &contactComposite : allContacts)
{
Expand Down
2 changes: 1 addition & 1 deletion src/systems/sensors/Sensors.cc
Original file line number Diff line number Diff line change
Expand Up @@ -621,7 +621,7 @@ void Sensors::Update(const UpdateInfo &_info,
_ecm.HasComponentType(components::WideAngleCamera::typeId)))
{
std::unique_lock<std::mutex> lock(this->dataPtr->renderMutex);
igndbg << "Initialization needed" << std::endl;
gzdbg << "Initialization needed" << std::endl;
this->dataPtr->renderUtil.Init();
this->dataPtr->nextUpdateTime = _info.simTime;
}
Expand Down
16 changes: 8 additions & 8 deletions src/systems/thruster/Thruster.cc
Original file line number Diff line number Diff line change
Expand Up @@ -451,7 +451,7 @@ void Thruster::Configure(
{
if (!_sdf->HasElement("battery_name"))
{
ignerr << "Specified a <power_load> but missing <battery_name>."
gzerr << "Specified a <power_load> but missing <battery_name>."
"Specify a battery name so the power load can be assigned to it."
<< std::endl;
}
Expand Down Expand Up @@ -586,17 +586,17 @@ void Thruster::PreUpdate(
});
if (numBatteriesWithName == 0)
{
ignerr << "Can't assign battery consumption to battery: ["
<< this->dataPtr->batteryName << "]. No batteries"
"were found with the given name." << std::endl;
gzerr << "Can't assign battery consumption to battery: ["
<< this->dataPtr->batteryName << "]. No batteries"
"were found with the given name." << std::endl;
return;
}
if (numBatteriesWithName > 1)
{
ignerr << "More than one battery found with name: ["
<< this->dataPtr->batteryName << "]. Please make"
"sure battery names are unique within the system."
<< std::endl;
gzerr << "More than one battery found with name: ["
<< this->dataPtr->batteryName << "]. Please make"
"sure battery names are unique within the system."
<< std::endl;
return;
}

Expand Down
26 changes: 13 additions & 13 deletions src/systems/triggered_publisher/TriggeredPublisher.cc
Original file line number Diff line number Diff line change
Expand Up @@ -605,31 +605,31 @@ void TriggeredPublisher::Configure(const Entity &,
serviceInfo.srvName = serviceElem->Get<std::string>("name");
if (serviceInfo.srvName.empty())
{
ignerr << "Service name cannot be empty\n";
gzerr << "Service name cannot be empty\n";
return;
}
serviceInfo.reqType = serviceElem->Get<std::string>("reqType");
if (serviceInfo.reqType.empty())
{
ignerr << "Service request type cannot be empty\n";
gzerr << "Service request type cannot be empty\n";
return;
}
serviceInfo.repType = serviceElem->Get<std::string>("repType");
if (serviceInfo.repType.empty())
{
ignerr << "Service reply type cannot be empty\n";
gzerr << "Service reply type cannot be empty\n";
return;
}
serviceInfo.reqMsg = serviceElem->Get<std::string>("reqMsg");
if (serviceInfo.reqMsg.empty())
{
ignerr << "Service request message cannot be empty\n";
gzerr << "Service request message cannot be empty\n";
return;
}
std::string timeoutInfo = serviceElem->Get<std::string>("timeout");
if (timeoutInfo.empty())
{
ignerr << "Timeout value cannot be empty\n";
gzerr << "Timeout value cannot be empty\n";
return;
}

Expand All @@ -639,7 +639,7 @@ void TriggeredPublisher::Configure(const Entity &,
}
if (!sdfClone->HasElement("service") && !sdfClone->HasElement("output"))
{
ignerr << "No output and service specified. Make sure to specify at least"
gzerr << "No output and service specified. Make sure to specify at least"
"one of them." << std::endl;
return;
}
Expand Down Expand Up @@ -715,16 +715,16 @@ void TriggeredPublisher::CallService(std::size_t pendingSrv)
auto req = msgs::Factory::New(serviceInfo.reqType, serviceInfo.reqMsg);
if (!req)
{
ignerr << "Unable to create request for type ["
<< serviceInfo.reqType << "].\n";
gzerr << "Unable to create request for type ["
<< serviceInfo.reqType << "].\n";
return;
}

auto rep = msgs::Factory::New(serviceInfo.repType);
if (!rep)
{
ignerr << "Unable to create response for type ["
<< serviceInfo.repType << "].\n";
gzerr << "Unable to create response for type ["
<< serviceInfo.repType << "].\n";
return;
}

Expand All @@ -734,16 +734,16 @@ void TriggeredPublisher::CallService(std::size_t pendingSrv)
{
if (!result)
{
ignerr << "Service call [" << serviceInfo.srvName << "] failed\n";
gzerr << "Service call [" << serviceInfo.srvName << "] failed\n";
}
else
{
ignmsg << "Service call [" << serviceInfo.srvName << "] succeeded\n";
gzmsg << "Service call [" << serviceInfo.srvName << "] succeeded\n";
}
}
else
{
ignerr << "Service call [" << serviceInfo.srvName << "] timed out\n";
gzerr << "Service call [" << serviceInfo.srvName << "] timed out\n";
}
}
}
Expand Down
2 changes: 1 addition & 1 deletion test/integration/log_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1669,7 +1669,7 @@ TEST_F(LogSystemTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(RecordPeriod))
#ifndef __APPLE__
// Log from command line
{
// Command line triggers ign.cc, which handles initializing ignLogDirectory
// Command line triggers gz.cc, which handles initializing gzlogDirectory
std::string cmd = kGzCommand + " -r -v 4 --iterations "
+ std::to_string(numIterations) + " "
+ "--record-period 0.002 "
Expand Down
1 change: 1 addition & 0 deletions test/test_config.hh.in
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#define GZ_SIM_TEST_CONFIG_HH_

#include <stdlib.h>
#include <string>
#include <gz/sim/config.hh>

#define PROJECT_SOURCE_PATH "${PROJECT_SOURCE_DIR}"
Expand Down
6 changes: 3 additions & 3 deletions tutorials/battery.md
Original file line number Diff line number Diff line change
Expand Up @@ -187,7 +187,7 @@ At the configure step the parameters are read and saved:
{
if (!_sdf->HasElement("battery_name"))
{
ignerr << "Specified a <power_load> but missing <battery_name>."
gzerr << "Specified a <power_load> but missing <battery_name>."
"Specify a battery name so the power load can be assigned to it."
<< std::endl;
}
Expand Down Expand Up @@ -246,14 +246,14 @@ are found with the specified name.
```
if (numBatteriesWithName == 0)
{
ignerr << "Can't assign battery consumption to battery: ["
gzerr << "Can't assign battery consumption to battery: ["
<< this->dataPtr->batteryName << "]. No batteries"
"were found with the given name." << std::endl;
return;
}
if (numBatteriesWithName > 1)
{
ignerr << "More than one battery found with name: ["
gzerr << "More than one battery found with name: ["
<< this->dataPtr->batteryName << "]. Please make"
"sure battery names are unique within the system."
<< std::endl;
Expand Down

0 comments on commit b8a8a18

Please sign in to comment.