Skip to content

Commit

Permalink
Fix build and codecheck
Browse files Browse the repository at this point in the history
Signed-off-by: Nate Koenig <[email protected]>
  • Loading branch information
Nate Koenig committed Jan 8, 2021
2 parents c70ee17 + 8ab2b7b commit e491a52
Show file tree
Hide file tree
Showing 100 changed files with 10,182 additions and 5,225 deletions.
33 changes: 19 additions & 14 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ set(IGN_FUEL_TOOLS_VER ${ignition-fuel_tools5_VERSION_MAJOR})

#--------------------------------------
# Find ignition-gui
ign_find_package(ignition-gui4 REQUIRED VERSION 4.1)
ign_find_package(ignition-gui4 REQUIRED VERSION 4.1.1)
set(IGN_GUI_VER ${ignition-gui4_VERSION_MAJOR})
ign_find_package (Qt5
COMPONENTS
Expand Down Expand Up @@ -158,19 +158,24 @@ ign_create_packages()
configure_file(${CMAKE_SOURCE_DIR}/api.md.in ${CMAKE_BINARY_DIR}/api.md)
configure_file(${CMAKE_SOURCE_DIR}/tutorials.md.in ${CMAKE_BINARY_DIR}/tutorials.md)

ign_create_docs(
API_MAINPAGE_MD "${CMAKE_BINARY_DIR}/api.md"
TUTORIALS_MAINPAGE_MD "${CMAKE_BINARY_DIR}/tutorials.md"
ADDITIONAL_INPUT_DIRS "${CMAKE_SOURCE_DIR}/src/systems ${CMAKE_SOURCE_DIR}/src/gui/plugins"
TAGFILES
"${IGNITION-MATH_DOXYGEN_TAGFILE} = ${IGNITION-MATH_API_URL}"
"${IGNITION-MSGS_DOXYGEN_TAGFILE} = ${IGNITION-MSGS_API_URL}"
"${IGNITION-PHYSICS_DOXYGEN_TAGFILE} = ${IGNITION-PHYSICS_API_URL}"
"${IGNITION-PLUGIN_DOXYGEN_TAGFILE} = ${IGNITION-PLUGIN_API_URL}"
"${IGNITION-TRANSPORT_DOXYGEN_TAGFILE} = ${IGNITION-TRANSPORT_API_URL}"
"${IGNITION-SENSORS_DOXYGEN_TAGFILE} = ${IGNITION-SENSORS_API_URL}"
"${IGNITION-COMMON_DOXYGEN_TAGFILE} = ${IGNITION-COMMON_API_URL}"
)
# disable doxygen on macOS due to issues with doxygen 1.9.0
# there is an unreleased fix; revert this when 1.9.1 is released
# https://github.com/ignitionrobotics/ign-gazebo/issues/520
if (NOT APPLE)
ign_create_docs(
API_MAINPAGE_MD "${CMAKE_BINARY_DIR}/api.md"
TUTORIALS_MAINPAGE_MD "${CMAKE_BINARY_DIR}/tutorials.md"
ADDITIONAL_INPUT_DIRS "${CMAKE_SOURCE_DIR}/src/systems ${CMAKE_SOURCE_DIR}/src/gui/plugins"
TAGFILES
"${IGNITION-MATH_DOXYGEN_TAGFILE} = ${IGNITION-MATH_API_URL}"
"${IGNITION-MSGS_DOXYGEN_TAGFILE} = ${IGNITION-MSGS_API_URL}"
"${IGNITION-PHYSICS_DOXYGEN_TAGFILE} = ${IGNITION-PHYSICS_API_URL}"
"${IGNITION-PLUGIN_DOXYGEN_TAGFILE} = ${IGNITION-PLUGIN_API_URL}"
"${IGNITION-TRANSPORT_DOXYGEN_TAGFILE} = ${IGNITION-TRANSPORT_API_URL}"
"${IGNITION-SENSORS_DOXYGEN_TAGFILE} = ${IGNITION-SENSORS_API_URL}"
"${IGNITION-COMMON_DOXYGEN_TAGFILE} = ${IGNITION-COMMON_API_URL}"
)
endif()

if(TARGET doc)
file(COPY ${CMAKE_SOURCE_DIR}/tutorials/files/ DESTINATION ${CMAKE_BINARY_DIR}/doxygen/html/files/)
Expand Down
62 changes: 62 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -157,6 +157,68 @@

### Ignition Gazebo 3.X.X (20XX-XX-XX)

### Ignition Gazebo 3.6.0 (2020-12-30)

1. Fix pose msg conversion when msg is missing orientation
* [Pull Request 450](https://github.com/ignitionrobotics/ign-gazebo/pull/450)

1. Address code checker warnings
* [Pull Request 443](https://github.com/ignitionrobotics/ign-gazebo/pull/443)
* [Pull Request 491](https://github.com/ignitionrobotics/ign-gazebo/pull/491)
* [Pull Request 499](https://github.com/ignitionrobotics/ign-gazebo/pull/499)
* [Pull Request 502](https://github.com/ignitionrobotics/ign-gazebo/pull/502)

1. Test fixes
* [Pull Request 455](https://github.com/ignitionrobotics/ign-gazebo/pull/455)
* [Pull Request 463](https://github.com/ignitionrobotics/ign-gazebo/pull/463)
* [Pull Request 452](https://github.com/ignitionrobotics/ign-gazebo/pull/452)
* [Pull Request 480](https://github.com/ignitionrobotics/ign-gazebo/pull/480)

1. Documentation updates
* [Pull Request 472](https://github.com/ignitionrobotics/ign-gazebo/pull/472)

1. Fix segfault in the Breadcrumb system when associated model is unloaded
* [Pull Request 454](https://github.com/ignitionrobotics/ign-gazebo/pull/454)

1. Added user commands to example thermal camera world
* [Pull Request 442](https://github.com/ignitionrobotics/ign-gazebo/pull/442)

1. Helper function to set component data
* [Pull Request 436](https://github.com/ignitionrobotics/ign-gazebo/pull/436)

1. Remove unneeded if statement in EntityComponentManager
* [Pull Request 432](https://github.com/ignitionrobotics/ign-gazebo/pull/432)

1. Clarify how time is represented in each phase of a System step
* [Pull Request 467](https://github.com/ignitionrobotics/ign-gazebo/pull/467)

1. Switch to async state service request
* [Pull Request 461](https://github.com/ignitionrobotics/ign-gazebo/pull/461)

1. Update key event handling
* [Pull Request 466](https://github.com/ignitionrobotics/ign-gazebo/pull/466)

1. Tape Measure Plugin
* [Pull Request 456](https://github.com/ignitionrobotics/ign-gazebo/pull/456)

1. Move deselect and preview termination to render thread
* [Pull Request 493](https://github.com/ignitionrobotics/ign-gazebo/pull/493)

1. Logical audio sensor plugin
* [Pull Request 401](https://github.com/ignitionrobotics/ign-gazebo/pull/401)

1. add frame_id and child_frame_id attribute support for DiffDrive
* [Pull Request 361](https://github.com/ignitionrobotics/ign-gazebo/pull/361)

1. Add ability to record video based on sim time
* [Pull Request 414](https://github.com/ignitionrobotics/ign-gazebo/pull/414)

1. Add lockstep mode to video recording
* [Pull Request 419](https://github.com/ignitionrobotics/ign-gazebo/pull/419)

1. Disable right click menu when using measuring tool
* [Pull Request 458](https://github.com/ignitionrobotics/ign-gazebo/pull/458)

### Ignition Gazebo 3.5.0 (2020-11-03)

1. Updated source build instructions
Expand Down
108 changes: 108 additions & 0 deletions examples/worlds/spaces.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,108 @@
<?xml version="1.0" ?>
<!--
This demo shows that it's possible to have entities with spaces in their names.
-->
<sdf version="1.6">
<world name="world with spaces">
<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="ignition-gazebo-physics-system"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="ignition-gazebo-user-commands-system"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin
filename="ignition-gazebo-scene-broadcaster-system"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>

<scene>
<ambient>1.0 1.0 1.0</ambient>
<background>0.8 0.8 0.8</background>
</scene>

<light type="directional" name="light with spaces">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>

<model name="ground plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>

<model name="model with spaces">
<pose>0 0 0.5 0 0 0</pose>
<link name="link with spaces">
<inertial>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="collision with spaces">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>

<visual name="visual with spaces">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>1 0 0 1</diffuse>
<specular>1 0 0 1</specular>
</material>
</visual>
</link>
</model>
</world>
</sdf>
27 changes: 19 additions & 8 deletions include/ignition/gazebo/System.hh
Original file line number Diff line number Diff line change
Expand Up @@ -44,21 +44,32 @@ namespace ignition
/// will only operate on an Entity if it has all of the required
/// Components.
///
/// Systems are executed in three phases:
/// Systems are executed in three phases, with each phase for a given step
/// corresponding to the entities at time UpdateInfo::simTime:
/// * PreUpdate
/// * Has read-write access to world entities and components
/// * Executed with simulation time at (t0)
/// * Has read-write access to world entities and components.
/// * This is where systems say what they'd like to happen at time
/// UpdateInfo::simTime.
/// * Can be used to modify state before physics runs, for example for
/// applying control signals or performing network syncronization.
/// * Update
/// * Has read-write access to world entities and components
/// * Responsible for propagating time from (t0) to (t0 + dt)
/// * Used for physics simulation step
/// * Has read-write access to world entities and components.
/// * Used for physics simulation step (i.e., simulates what happens at
/// time UpdateInfo::simTime).
/// * PostUpdate
/// * Has read-only access to world entities and components
/// * Executed with simulation time at (t0 + dt)
/// * Has read-only access to world entities and components.
/// * Captures everything that happened at time UpdateInfo::simTime.
/// * Used to read out results at the end of a simulation step to be used
/// for sensor or controller updates.
///
/// It's important to note that UpdateInfo::simTime does not refer to the
/// current time, but the time reached after the PreUpdate and Update calls
/// have finished. So, if any of the *Update functions are called with
/// simulation paused, time does not advance, which means the time reached
/// after PreUpdate and Update is the same as the starting time. This
/// explains why UpdateInfo::simTime is initially 0 if simulation is started
/// paused, while UpdateInfo::simTime is initially UpdateInfo::dt if
/// simulation is started un-paused.
class IGNITION_GAZEBO_VISIBLE System
{
/// \brief Constructor
Expand Down
15 changes: 15 additions & 0 deletions include/ignition/gazebo/Util.hh
Original file line number Diff line number Diff line change
Expand Up @@ -139,6 +139,21 @@ namespace ignition
const Entity &_entity,
const EntityComponentManager &_ecm);

/// \brief Helper function to generate a valid transport topic, given
/// a list of topics ordered by preference. The generated topic will be,
/// in this order:
///
/// 1. The first topic unchanged, if valid.
/// 2. A valid version of the first topic, if possible.
/// 3. The second topic unchanged, if valid.
/// 4. A valid version of the second topic, if possible.
/// 5. ...
/// 6. If no valid topics could be generated, return an empty string.
///
/// \param[in] _topics Topics ordered by preference.
std::string IGNITION_GAZEBO_VISIBLE validTopic(
const std::vector<std::string> &_topics);

/// \brief Environment variable holding resource paths.
const std::string kResourcePathEnv{"IGN_GAZEBO_RESOURCE_PATH"};

Expand Down
5 changes: 5 additions & 0 deletions include/ignition/gazebo/rendering/RenderUtil.hh
Original file line number Diff line number Diff line change
Expand Up @@ -124,6 +124,11 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// Returns reference to the marker manager.
public: class MarkerManager &MarkerManager();

/// \brief Get simulation time that the current rendering state corresponds
/// to
/// \returns Simulation time.
public: std::chrono::steady_clock::duration SimTime() const;

/// \brief Set the entity being selected
/// \param[in] _node Node representing the selected entity
public: void SetSelectedEntity(const rendering::NodePtr &_node);
Expand Down
2 changes: 1 addition & 1 deletion src/EntityComponentManager_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2362,5 +2362,5 @@ TEST_P(EntityComponentManagerFixture, RemovedComponentsSyncBetweenServerAndGUI)

// Run multiple times. We want to make sure that static globals don't cause
// problems.
INSTANTIATE_TEST_CASE_P(EntityComponentManagerRepeat,
INSTANTIATE_TEST_SUITE_P(EntityComponentManagerRepeat,
EntityComponentManagerFixture, ::testing::Range(1, 10));
10 changes: 8 additions & 2 deletions src/LevelManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -76,8 +76,14 @@ LevelManager::LevelManager(SimulationRunner *_runner, const bool _useLevels)
this->ReadLevelPerformerInfo();
this->CreatePerformers();

std::string service = "/world/";
service += this->runner->sdfWorld->Name() + "/level/set_performer";
std::string service = transport::TopicUtils::AsValidTopic("/world/" +
this->runner->sdfWorld->Name() + "/level/set_performer");
if (service.empty())
{
ignerr << "Failed to generate set_performer topic for world ["
<< this->runner->sdfWorld->Name() << "]" << std::endl;
return;
}
this->node.Advertise(service, &LevelManager::OnSetPerformer, this);
}

Expand Down
2 changes: 1 addition & 1 deletion src/Server_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -995,4 +995,4 @@ TEST_P(ServerFixture, AddResourcePaths)

// Run multiple times. We want to make sure that static globals don't cause
// problems.
INSTANTIATE_TEST_CASE_P(ServerRepeat, ServerFixture, ::testing::Range(1, 2));
INSTANTIATE_TEST_SUITE_P(ServerRepeat, ServerFixture, ::testing::Range(1, 2));
13 changes: 9 additions & 4 deletions src/SimulationRunner.cc
Original file line number Diff line number Diff line change
Expand Up @@ -157,15 +157,20 @@ SimulationRunner::SimulationRunner(const sdf::World *_world,

// World control
transport::NodeOptions opts;
std::string ns{"/world/" + this->worldName};
if (this->networkMgr)
{
opts.SetNameSpace(this->networkMgr->Namespace() +
"/world/" + this->worldName);
ns = this->networkMgr->Namespace() + ns;
}
else

auto validNs = transport::TopicUtils::AsValidTopic(ns);
if (validNs.empty())
{
opts.SetNameSpace("/world/" + this->worldName);
ignerr << "Invalid namespace [" << ns
<< "], not initializing runner transport." << std::endl;
return;
}
opts.SetNameSpace(validNs);

this->node = std::make_unique<transport::Node>(opts);

Expand Down
2 changes: 1 addition & 1 deletion src/SimulationRunner_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1294,5 +1294,5 @@ TEST_P(SimulationRunnerTest, GenerateWorldSdf)

// Run multiple times. We want to make sure that static globals don't cause
// problems.
INSTANTIATE_TEST_CASE_P(ServerRepeat, SimulationRunnerTest,
INSTANTIATE_TEST_SUITE_P(ServerRepeat, SimulationRunnerTest,
::testing::Range(1, 2));
22 changes: 22 additions & 0 deletions src/Util.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#endif
#include <ignition/common/Filesystem.hh>
#include <ignition/common/StringUtils.hh>
#include <ignition/transport/TopicUtils.hh>

#include "ignition/gazebo/components/Actor.hh"
#include "ignition/gazebo/components/Collision.hh"
Expand Down Expand Up @@ -416,6 +417,27 @@ ignition::gazebo::Entity topLevelModel(const Entity &_entity,
}
return entity;
}

//////////////////////////////////////////////////
std::string validTopic(const std::vector<std::string> &_topics)
{
for (const auto &topic : _topics)
{
auto validTopic = transport::TopicUtils::AsValidTopic(topic);
if (validTopic.empty())
{
ignerr << "Topic [" << topic << "] is invalid, ignoring." << std::endl;
continue;
}
if (validTopic != topic)
{
igndbg << "Topic [" << topic << "] changed to valid topic ["
<< validTopic << "]" << std::endl;
}
return validTopic;
}
return std::string();
}
}
}
}
Expand Down
Loading

0 comments on commit e491a52

Please sign in to comment.