Skip to content

Commit

Permalink
4 ➡️ 5 (#1259)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina authored Dec 21, 2021
2 parents a06198f + 3c4892b commit 1780d5f
Show file tree
Hide file tree
Showing 113 changed files with 549 additions and 79 deletions.
35 changes: 35 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -573,6 +573,41 @@

## Ignition Gazebo 4.x

### Ignition Gazebo 4.13.0 (2021-11-15)

1. Prevent creation of spurious `<plugin>` elements when saving worlds
* [Pull request #1192](https:/ignitionrobotics/ign-gazebo/pull/1192)

1. Add support for tracked vehicles
* [Pull request #869](https:/ignitionrobotics/ign-gazebo/pull/869)

1. Add components to dynamically set joint limits
* [Pull request #847](https:/ignitionrobotics/ign-gazebo/pull/847)

1. Fix updating component from state
* [Pull request #1181](https:/ignitionrobotics/ign-gazebo/pull/1181)

1. Fix updating a component's data via SerializedState msg
* [Pull request #1149](https:/ignitionrobotics/ign-gazebo/pull/1149)

1. Sensor systems work if loaded after sensors
* [Pull request #1104](https:/ignitionrobotics/ign-gazebo/pull/1104)

1. Fix generation of systems library symlinks in build directory
* [Pull request #1160](https:/ignitionrobotics/ign-gazebo/pull/1160)

1. Edit material colors in component inspector
* [Pull request #1123](https:/ignitionrobotics/ign-gazebo/pull/1123)

1. Support setting the background color for sensors
* [Pull request #1147](https:/ignitionrobotics/ign-gazebo/pull/1147)

1. Use uint64_t for ComponentInspector Entity IDs
* [Pull request #1144](https:/ignitionrobotics/ign-gazebo/pull/1144)

1. Fix integers and floats on component inspector
* [Pull request #1143](https:/ignitionrobotics/ign-gazebo/pull/1143)

### Ignition Gazebo 4.12.0 (2021-10-22)

1. Fix performance issue with contact data and AABB updates.
Expand Down
2 changes: 1 addition & 1 deletion src/SdfEntityCreator_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities)

EXPECT_EQ("default", _name->Data());
EXPECT_DOUBLE_EQ(0.001, _physics->Data().MaxStepSize());
EXPECT_DOUBLE_EQ(1.0, _physics->Data().RealTimeFactor());
EXPECT_DOUBLE_EQ(0.0, _physics->Data().RealTimeFactor());

worldCount++;

Expand Down
11 changes: 9 additions & 2 deletions src/SimulationRunner.cc
Original file line number Diff line number Diff line change
Expand Up @@ -103,8 +103,15 @@ SimulationRunner::SimulationRunner(const sdf::World *_world,
// So to get a given RTF, our desired period is:
//
// period = step_size / RTF
this->updatePeriod = std::chrono::nanoseconds(
static_cast<int>(this->stepSize.count() / this->desiredRtf));
if (this->desiredRtf < 1e-9)
{
this->updatePeriod = 0ms;
}
else
{
this->updatePeriod = std::chrono::nanoseconds(
static_cast<int>(this->stepSize.count() / this->desiredRtf));
}

this->pauseConn = this->eventMgr.Connect<events::Pause>(
std::bind(&SimulationRunner::SetPaused, this, std::placeholders::_1));
Expand Down
10 changes: 5 additions & 5 deletions src/SimulationRunner_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1073,7 +1073,7 @@ TEST_P(SimulationRunnerTest, Time)
EXPECT_EQ(0u, runner.CurrentInfo().iterations);
EXPECT_EQ(0ms, runner.CurrentInfo().simTime);
EXPECT_EQ(0ms, runner.CurrentInfo().dt);
EXPECT_EQ(1ms, runner.UpdatePeriod());
EXPECT_EQ(0ms, runner.UpdatePeriod());
EXPECT_EQ(1ms, runner.StepSize());

runner.SetPaused(false);
Expand All @@ -1086,7 +1086,7 @@ TEST_P(SimulationRunnerTest, Time)
EXPECT_EQ(100u, runner.CurrentInfo().iterations);
EXPECT_EQ(100ms, runner.CurrentInfo().simTime);
EXPECT_EQ(1ms, runner.CurrentInfo().dt);
EXPECT_EQ(1ms, runner.UpdatePeriod());
EXPECT_EQ(0ms, runner.UpdatePeriod());
EXPECT_EQ(1ms, runner.StepSize());

int sleep = 0;
Expand All @@ -1107,7 +1107,7 @@ TEST_P(SimulationRunnerTest, Time)
EXPECT_EQ(200u, runner.CurrentInfo().iterations);
EXPECT_EQ(300ms, runner.CurrentInfo().simTime);
EXPECT_EQ(2ms, runner.CurrentInfo().dt);
EXPECT_EQ(1ms, runner.UpdatePeriod());
EXPECT_EQ(0ms, runner.UpdatePeriod());
EXPECT_EQ(2ms, runner.StepSize());

sleep = 0;
Expand All @@ -1127,7 +1127,7 @@ TEST_P(SimulationRunnerTest, Time)
EXPECT_EQ(200u, runner.CurrentInfo().iterations);
EXPECT_EQ(300ms, runner.CurrentInfo().simTime);
EXPECT_EQ(2ms, runner.CurrentInfo().dt);
EXPECT_EQ(1ms, runner.UpdatePeriod());
EXPECT_EQ(0ms, runner.UpdatePeriod());
EXPECT_EQ(2ms, runner.StepSize());

// Verify info published to /clock topic
Expand All @@ -1145,7 +1145,7 @@ TEST_P(SimulationRunnerTest, Time)
EXPECT_EQ(500ms, runner.CurrentInfo().simTime)
<< runner.CurrentInfo().simTime.count();
EXPECT_EQ(2ms, runner.CurrentInfo().dt);
EXPECT_EQ(1ms, runner.UpdatePeriod());
EXPECT_EQ(0ms, runner.UpdatePeriod());
EXPECT_EQ(2ms, runner.StepSize());

sleep = 0;
Expand Down
7 changes: 6 additions & 1 deletion src/gui/plugins/visualize_lidar/VisualizeLidar.cc
Original file line number Diff line number Diff line change
Expand Up @@ -291,8 +291,13 @@ void VisualizeLidar::Update(const UpdateInfo &,
for (auto child : children)
{
std::string nextstring = lidarURIVec[i+1];
auto comp = _ecm.Component<components::Name>(child);
if (!comp)
{
continue;
}
std::string childname = std::string(
_ecm.Component<components::Name>(child)->Data());
comp->Data());
if (nextstring.compare(childname) == 0)
{
parent = child;
Expand Down
43 changes: 42 additions & 1 deletion src/systems/battery_plugin/LinearBatteryPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,15 @@ class ignition::gazebo::systems::LinearBatteryPluginPrivate
/// \param[in] _req This value should be true.
public: void OnDisableRecharge(const ignition::msgs::Boolean &_req);

/// \brief Callback connected to additional topics that can start battery
/// draining.
/// \param[in] _data Message data.
/// \param[in] _size Message data size.
/// \param[in] _info Information about the message.
public: void OnBatteryDrainingMsg(
const char *_data, const size_t _size,
const ignition::transport::MessageInfo &_info);

/// \brief Name of model, only used for printing warning when battery drains.
public: std::string modelName;

Expand Down Expand Up @@ -153,6 +162,9 @@ class ignition::gazebo::systems::LinearBatteryPluginPrivate

/// \brief Battery state of charge message publisher
public: transport::Node::Publisher statePub;

/// \brief Whether a topic has received any battery-draining command.
public: bool startDrainingFromTopics = false;
};

/////////////////////////////////////////////////
Expand Down Expand Up @@ -340,6 +352,23 @@ void LinearBatteryPlugin::Configure(const Entity &_entity,
<< "in LinearBatteryPlugin SDF" << std::endl;
}

// Subscribe to power draining topics, if any.
if (_sdf->HasElement("power_draining_topic"))
{
sdf::ElementConstPtr sdfElem = _sdf->FindElement("power_draining_topic");
while (sdfElem)
{
const auto &topic = sdfElem->Get<std::string>();
this->dataPtr->node.SubscribeRaw(topic,
std::bind(&LinearBatteryPluginPrivate::OnBatteryDrainingMsg,
this->dataPtr.get(), std::placeholders::_1, std::placeholders::_2,
std::placeholders::_3));
ignmsg << "LinearBatteryPlugin subscribes to power draining topic ["
<< topic << "]." << std::endl;
sdfElem = sdfElem->GetNextElement("power_draining_topic");
}
}

ignmsg << "LinearBatteryPlugin configured. Battery name: "
<< this->dataPtr->battery->Name() << std::endl;
igndbg << "Battery initial voltage: " << this->dataPtr->battery->InitVoltage()
Expand Down Expand Up @@ -371,6 +400,7 @@ void LinearBatteryPluginPrivate::Reset()
this->iraw = 0.0;
this->ismooth = 0.0;
this->q = this->q0;
this->startDrainingFromTopics = false;
}

/////////////////////////////////////////////////
Expand All @@ -395,13 +425,24 @@ void LinearBatteryPluginPrivate::OnDisableRecharge(
this->startCharging = false;
}

//////////////////////////////////////////////////
void LinearBatteryPluginPrivate::OnBatteryDrainingMsg(
const char *, const size_t, const ignition::transport::MessageInfo &)
{
this->startDrainingFromTopics = true;
}

//////////////////////////////////////////////////
void LinearBatteryPlugin::PreUpdate(
const ignition::gazebo::UpdateInfo &/*_info*/,
ignition::gazebo::EntityComponentManager &_ecm)
{
IGN_PROFILE("LinearBatteryPlugin::PreUpdate");
this->dataPtr->startDraining = false;

// \todo(anyone) Add in the ability to stop the battery from draining
// after it has been started by a topic. See this comment:
// https:/ignitionrobotics/ign-gazebo/pull/1255#discussion_r770223092
this->dataPtr->startDraining = this->dataPtr->startDrainingFromTopics;
// Start draining the battery if the robot has started moving
if (!this->dataPtr->startDraining)
{
Expand Down
5 changes: 5 additions & 0 deletions src/systems/battery_plugin/LinearBatteryPlugin.hh
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,11 @@ namespace systems
/// (Required if `<enable_recharge>` is set to true)
/// - `<fix_issue_225>` True to change the battery behavior to fix some issues
/// described in https:/ignitionrobotics/ign-gazebo/issues/225.
/// - `<power_draining_topic>` A topic that is used to start battery
/// discharge. Any message on the specified topic will cause the batter to
/// start draining. This element can be specified multiple times if
/// multiple topics should be monitored. Note that this mechanism will
/// start the battery draining, and once started will keep drainig.
class LinearBatteryPlugin
: public System,
public ISystemConfigure,
Expand Down
102 changes: 95 additions & 7 deletions test/integration/battery_plugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include <ignition/common/Console.hh>
#include <ignition/common/Util.hh>
#include <ignition/common/Filesystem.hh>
#include <ignition/transport/Node.hh>
#include <ignition/utilities/ExtraTestMacros.hh>

#include <sdf/Root.hh>
Expand Down Expand Up @@ -136,20 +137,107 @@ TEST_F(BatteryPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SingleBattery))
EXPECT_LT(batComp->Data(), 12.592);

// Check there is a single battery matching exactly the one specified
int batCount = 0;
int linearBatCount = 0;
int totalBatCount = 0;
ecm->Each<components::BatterySoC, components::Name>(
[&](const Entity &_batEntity, components::BatterySoC *_batComp,
components::Name *_nameComp) -> bool
{
batCount++;
totalBatCount++;
if (_nameComp->Data() == "linear_battery")
{
linearBatCount++;

EXPECT_NE(kNullEntity, _batEntity);
EXPECT_EQ(_nameComp->Data(), "linear_battery");
EXPECT_NE(kNullEntity, _batEntity);
EXPECT_EQ(_nameComp->Data(), "linear_battery");

// Check battery component voltage data is lower than initial voltage
EXPECT_LT(_batComp->Data(), 12.592);
// Check battery component voltage data is lower than initial voltage
EXPECT_LT(_batComp->Data(), 12.592);
}

return true;
});
EXPECT_EQ(batCount, 1);
EXPECT_EQ(linearBatCount, 1);
EXPECT_EQ(totalBatCount, 2);
}

/////////////////////////////////////////////////
// Battery with power draining topics
// See https:/ignitionrobotics/ign-gazebo/issues/1175
TEST_F(BatteryPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PowerDrainTopic))
{
const auto sdfPath = common::joinPaths(std::string(PROJECT_SOURCE_PATH),
"test", "worlds", "battery.sdf");
sdf::Root root;
EXPECT_EQ(root.Load(sdfPath).size(), 0lu);
EXPECT_GT(root.WorldCount(), 0lu);

ServerConfig serverConfig;
serverConfig.SetSdfFile(sdfPath);

// A pointer to the ecm. This will be valid once we run the mock system
gazebo::EntityComponentManager *ecm = nullptr;
this->mockSystem->preUpdateCallback =
[&ecm](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm)
{
ecm = &_ecm;

// Check a battery exists
EXPECT_TRUE(ecm->HasComponentType(components::BatterySoC::typeId));

// Find the battery entity
Entity batEntity = ecm->EntityByComponents(components::Name(
"linear_battery_topics"));
EXPECT_NE(kNullEntity, batEntity);

// Find the battery component
EXPECT_TRUE(ecm->EntityHasComponentType(batEntity,
components::BatterySoC::typeId));
auto batComp = ecm->Component<components::BatterySoC>(batEntity);

// Check voltage is never zero.
// This check is here to guarantee that components::BatterySoC in
// the LinearBatteryPlugin is not zero when created. If
// components::BatterySoC is zero on start, then the Physics plugin
// can disable a joint. This in turn can prevent the joint from
// rotating. See https:/ignitionrobotics/ign-gazebo/issues/55
EXPECT_GT(batComp->Data(), 0);
};

// Start server
Server server(serverConfig);
server.AddSystem(this->systemPtr);
server.Run(true, 100, false);
EXPECT_NE(nullptr, ecm);

// Check a battery exists
EXPECT_TRUE(ecm->HasComponentType(components::BatterySoC::typeId));

// Find the battery entity
Entity batEntity = ecm->EntityByComponents(components::Name(
"linear_battery_topics"));
EXPECT_NE(kNullEntity, batEntity);

// Find the battery component
EXPECT_TRUE(ecm->EntityHasComponentType(batEntity,
components::BatterySoC::typeId));
auto batComp = ecm->Component<components::BatterySoC>(batEntity);

// Check state of charge should be 1, since the batery has not drained
// and the <initial_charge> is equivalent ot the <capacity>.
EXPECT_DOUBLE_EQ(batComp->Data(), 1.0);

// Send a message on one of the <power_draining_topic> topics, which will
// start the battery draining when the server starts again.
ignition::transport::Node node;
auto pub = node.Advertise<msgs::StringMsg>("/battery/discharge2");
msgs::StringMsg msg;
pub.Publish(msg);

// Run the server again.
server.Run(true, 100, false);

// The state of charge should be <1, since the batery has started
// draining.
EXPECT_LT(batComp->Data(), 1.0);
}
2 changes: 0 additions & 2 deletions test/integration/imu_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -225,8 +225,6 @@ TEST_F(ImuTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(OrientationDisabled))
EXPECT_FALSE(server.Running());
EXPECT_FALSE(*server.Running(0));

const std::string sensorName = "imu_sensor";

auto topic =
"world/imu_sensor/model/imu_model/link/link/sensor/imu_sensor/imu";

Expand Down
2 changes: 1 addition & 1 deletion test/integration/scene_broadcaster_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -518,7 +518,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(StateStatic))
// Start server
ignition::gazebo::ServerConfig serverConfig;
serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) +
"/examples/worlds/empty.sdf");
"/test/worlds/empty.sdf");

gazebo::Server server(serverConfig);
EXPECT_FALSE(server.Running());
Expand Down
11 changes: 11 additions & 0 deletions test/integration/sensors_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,17 @@ void testDefaultTopics()
std::vector<transport::MessagePublisher> publishers;
transport::Node node;

// Sensors are created in a separate thread, so we sleep here to give them
// time
int sleep{0};
int maxSleep{30};
for (; sleep < maxSleep && !node.TopicInfo(topics.front(), publishers);
++sleep)
{
std::this_thread::sleep_for(std::chrono::milliseconds(100));
}
ASSERT_LT(sleep, maxSleep);

for (const std::string &topic : topics)
{
bool result = node.TopicInfo(topic, publishers);
Expand Down
2 changes: 1 addition & 1 deletion test/integration/touch_plugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -298,7 +298,7 @@ TEST_F(TouchPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SpawnedEntities))
auto testFunc = [&](const std::string &_box1, const std::string &_box2)
{
this->server.reset();
this->StartServer("/examples/worlds/empty.sdf");
this->StartServer("/test/worlds/empty.sdf");

whiteTouched = false;
req.set_sdf(_box1);
Expand Down
Loading

0 comments on commit 1780d5f

Please sign in to comment.