diff --git a/.github/workflows/cicd.yml b/.github/workflows/cicd.yml index e2ff819ec..11ec19dd4 100644 --- a/.github/workflows/cicd.yml +++ b/.github/workflows/cicd.yml @@ -20,9 +20,9 @@ jobs: - User - Developer ignition: - - edifice - - dome # - citadel + # - dome + - edifice env: CCACHE_DIR: ${{ github.workspace }}/.ccache diff --git a/cpp/scenario/CMakeLists.txt b/cpp/scenario/CMakeLists.txt index 1f1cffe53..7721c9f77 100644 --- a/cpp/scenario/CMakeLists.txt +++ b/cpp/scenario/CMakeLists.txt @@ -9,6 +9,9 @@ set(SCENARIO_PRIVATE_DEPENDENCIES "") if(SCENARIO_USE_IGNITION) + option(ENABLE_PROFILER "Enable Ignition Profiler" OFF) + mark_as_advanced(ENABLE_PROFILER) + add_subdirectory(gazebo) add_subdirectory(plugins) add_subdirectory(controllers) diff --git a/cpp/scenario/gazebo/CMakeLists.txt b/cpp/scenario/gazebo/CMakeLists.txt index 06a84761a..545f6f1a7 100644 --- a/cpp/scenario/gazebo/CMakeLists.txt +++ b/cpp/scenario/gazebo/CMakeLists.txt @@ -34,7 +34,6 @@ set(EXTRA_COMPONENTS_PUBLIC_HEADERS include/scenario/gazebo/components/BaseWorldAccelerationTarget.h include/scenario/gazebo/components/JointControlMode.h include/scenario/gazebo/components/JointController.h - include/scenario/gazebo/components/WorldVelocityCmd.h include/scenario/gazebo/components/JointPositionTarget.h include/scenario/gazebo/components/JointVelocityTarget.h include/scenario/gazebo/components/JointAccelerationTarget.h diff --git a/cpp/scenario/gazebo/include/scenario/gazebo/components/WorldVelocityCmd.h b/cpp/scenario/gazebo/include/scenario/gazebo/components/WorldVelocityCmd.h deleted file mode 100644 index 13a8d7490..000000000 --- a/cpp/scenario/gazebo/include/scenario/gazebo/components/WorldVelocityCmd.h +++ /dev/null @@ -1,65 +0,0 @@ -/* - * Copyright (C) 2020 Istituto Italiano di Tecnologia (IIT) - * All rights reserved. - * - * This project is dual licensed under LGPL v2.1+ or Apache License. - * - * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * - * - * This software may be modified and distributed under the terms of the - * GNU Lesser General Public License v2.1 or any later version. - * - * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#ifndef IGNITION_GAZEBO_COMPONENTS_WORLDVELOCITYCMD_H -#define IGNITION_GAZEBO_COMPONENTS_WORLDVELOCITYCMD_H - -#include - -#include -#include - -#include "ignition/gazebo/components/Component.hh" -#include - -namespace ignition::gazebo { - // Inline bracket to help doxygen filtering. - inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { - struct WorldVelocity - { - math::Vector3d linear; - math::Vector3d angular; - - bool operator==(const WorldVelocity& other) const - { - return this->linear == other.linear - && this->angular == other.angular; - } - }; - - namespace components { - /// \brief A component type that contains commanded velocity of - /// an entity in the world frame represented by - /// ignition::math::Vector3d. - using WorldVelocityCmd = - Component; - IGN_GAZEBO_REGISTER_COMPONENT( - "ign_gazebo_components.WorldVelocityCmdTag", - WorldVelocityCmd) - } // namespace components - } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE -} // namespace ignition::gazebo -#endif // IGNITION_GAZEBO_COMPONENTS_WORLDVELOCITYCMD_H diff --git a/cpp/scenario/gazebo/include/scenario/gazebo/helpers.h b/cpp/scenario/gazebo/include/scenario/gazebo/helpers.h index 138d63def..6c8958001 100644 --- a/cpp/scenario/gazebo/include/scenario/gazebo/helpers.h +++ b/cpp/scenario/gazebo/include/scenario/gazebo/helpers.h @@ -165,17 +165,17 @@ namespace scenario::gazebo::utils { sdf::JointType toSdf(const scenario::core::JointType type); scenario::core::JointType fromSdf(const sdf::JointType sdfType); - std::pair - fromModelToBaseVelocity(const ignition::math::Vector3d& linModelVelocity, - const ignition::math::Vector3d& angModelVelocity, - const ignition::math::Pose3d& M_H_B, - const ignition::math::Quaterniond& W_R_B); - - std::pair - fromBaseToModelVelocity(const ignition::math::Vector3d& linBaseVelocity, - const ignition::math::Vector3d& angBaseVelocity, - const ignition::math::Pose3d& M_H_B, - const ignition::math::Quaterniond& W_R_B); + ignition::math::Vector3d fromModelToBaseLinearVelocity( + const ignition::math::Vector3d& linModelVelocity, + const ignition::math::Vector3d& angModelVelocity, + const ignition::math::Pose3d& M_H_B, + const ignition::math::Quaterniond& W_R_B); + + ignition::math::Vector3d fromBaseToModelLinearVelocity( + const ignition::math::Vector3d& linBaseVelocity, + const ignition::math::Vector3d& angBaseVelocity, + const ignition::math::Pose3d& M_H_B, + const ignition::math::Quaterniond& W_R_B); std::shared_ptr getParentWorld(const GazeboEntity& gazeboEntity); diff --git a/cpp/scenario/gazebo/src/GazeboSimulator.cpp b/cpp/scenario/gazebo/src/GazeboSimulator.cpp index 05049143f..4b08d9d67 100644 --- a/cpp/scenario/gazebo/src/GazeboSimulator.cpp +++ b/cpp/scenario/gazebo/src/GazeboSimulator.cpp @@ -39,6 +39,7 @@ #include #include #include +#include #include #include #include @@ -233,12 +234,45 @@ bool GazeboSimulator::run(const bool paused) iterations = 1; } + // Recent versions of Ignition Gazebo optimize the streaming of pose updates + // in order to reduce the bandwidth between server and client. + // However, it does not take into account paused steps. + // Here below we force all the Pose components to be streamed by manually + // setting them as changed. + if (paused) { + // Get the singleton + auto& ecmSingleton = + scenario::plugins::gazebo::ECMSingleton::Instance(); + + // Process all worlds + for (const auto& worldName : this->worldNames()) { + assert(ecmSingleton.hasWorld(worldName)); + assert(ecmSingleton.valid(worldName)); + assert(ecmSingleton.getECM(worldName)); + + // Get the ECM + auto* ecm = ecmSingleton.getECM(worldName); + + // Mark all all entities with Pose component as Changed + ecm->Each( + [&](const ignition::gazebo::Entity& entity, + ignition::gazebo::components::Pose*) -> bool { + ecm->SetChanged( + entity, + ignition::gazebo::components::Pose::typeId, + ignition::gazebo::ComponentState::OneTimeChange); + return true; + }); + } + } + + // Paused simulation run if (paused && !server->RunOnce(/*paused=*/true)) { sError << "The server couldn't execute the paused step" << std::endl; return false; } - // Run the simulation + // Unpaused simulation run if (!paused && !server->Run(/*blocking=*/deterministic, /*iterations=*/iterations, diff --git a/cpp/scenario/gazebo/src/Model.cpp b/cpp/scenario/gazebo/src/Model.cpp index 7f1101713..6d9c7b545 100644 --- a/cpp/scenario/gazebo/src/Model.cpp +++ b/cpp/scenario/gazebo/src/Model.cpp @@ -34,15 +34,16 @@ #include "scenario/gazebo/components/BaseWorldVelocityTarget.h" #include "scenario/gazebo/components/JointControllerPeriod.h" #include "scenario/gazebo/components/Timestamp.h" -#include "scenario/gazebo/components/WorldVelocityCmd.h" #include "scenario/gazebo/exceptions.h" #include "scenario/gazebo/helpers.h" #include #include #include +#include #include #include +#include #include #include #include @@ -300,49 +301,13 @@ bool Model::resetBaseOrientation(const std::array& orientation) bool Model::resetBaseWorldLinearVelocity(const std::array& linear) { - // Check if the velocity was not already reset in this simulation run, - // otherwise the previous target would get overridden - if (!this->m_ecm->EntityHasComponentType( - this->m_entity, - ignition::gazebo::components::WorldVelocityCmd::typeId)) { + // Note: there could be a rigid transformation between the base frame and + // the canonical frame. The Physics system processes velocity commands + // in the canonical frame, but this method receives velocity commands + // of in the base frame (all expressed in world coordinates). + // Therefore, we need to compute the base linear velocity from the + // base frame to the canonical frame. - return this->resetBaseWorldVelocity(linear, - this->baseWorldAngularVelocity()); - } - - // Get the existing cmd - const auto& velocityCmd = utils::getExistingComponentData< - ignition::gazebo::components::WorldVelocityCmd>(m_ecm, m_entity); - - // Override only the linear velocity - return this->resetBaseWorldVelocity( - linear, utils::fromIgnitionVector(velocityCmd.angular)); -} - -bool Model::resetBaseWorldAngularVelocity(const std::array& angular) -{ - // Check if the velocity was not already reset in this simulation run, - // otherwise the previous target would get overridden - if (!this->m_ecm->EntityHasComponentType( - this->m_entity, - ignition::gazebo::components::WorldVelocityCmd::typeId)) { - - return this->resetBaseWorldVelocity(this->baseWorldLinearVelocity(), - angular); - } - - // Get the existing cmd - const auto& velocityCmd = utils::getExistingComponentData< - ignition::gazebo::components::WorldVelocityCmd>(m_ecm, m_entity); - - // Override only the angular velocity - return this->resetBaseWorldVelocity( - utils::fromIgnitionVector(velocityCmd.linear), angular); -} - -bool Model::resetBaseWorldVelocity(const std::array& linear, - const std::array& angular) -{ // Get the entity of the canonical (base) link const auto canonicalLinkEntity = m_ecm->EntityByComponents( ignition::gazebo::components::Link(), @@ -359,23 +324,40 @@ bool Model::resetBaseWorldVelocity(const std::array& linear, const auto& W_R_B = utils::toIgnitionQuaternion( this->getLink(this->baseFrame())->orientation()); - // Create the new model velocity - ignition::gazebo::WorldVelocity baseWorldVelocity; - - // Compute the mixed velocity of the base link - std::tie(baseWorldVelocity.linear, baseWorldVelocity.angular) = - utils::fromModelToBaseVelocity(utils::toIgnitionVector3(linear), - utils::toIgnitionVector3(angular), - M_H_B, - W_R_B); + // Compute the linear part of the base link mixed velocity + const ignition::math::Vector3d baseLinearWorldVelocity = + utils::fromModelToBaseLinearVelocity( + utils::toIgnitionVector3(linear), + utils::toIgnitionVector3(this->baseWorldAngularVelocity()), + M_H_B, + W_R_B); // Store the new velocity - utils::setComponentData( - m_ecm, m_entity, baseWorldVelocity); + utils::setComponentData( + m_ecm, m_entity, baseLinearWorldVelocity); + + return true; +} + +bool Model::resetBaseWorldAngularVelocity(const std::array& angular) +{ + // Note: the angular part of the velocity does not change between the base + // link and the canonical link (as the linear part). + // In fact, the angular velocity is invariant if there's a rigid + // transformation between the two frames, like in this case. + utils::setComponentData( + m_ecm, m_entity, utils::toIgnitionVector3(angular)); return true; } +bool Model::resetBaseWorldVelocity(const std::array& linear, + const std::array& angular) +{ + return this->resetBaseWorldLinearVelocity(linear) + && this->resetBaseWorldAngularVelocity(angular); +} + bool Model::valid() const { return this->validEntity() && pImpl->model.Valid(*m_ecm); @@ -1050,7 +1032,7 @@ std::array Model::baseWorldLinearVelocity() const this->getLink(this->baseFrame())->worldAngularVelocity()); // Convert the base velocity to the model mixed velocity - auto [modelLinearVelocity, _] = utils::fromBaseToModelVelocity( // + const auto& modelLinearVelocity = utils::fromBaseToModelLinearVelocity( // canonicalLinkLinearVelocity, canonicalLinkAngularVelocity, M_H_B, diff --git a/cpp/scenario/gazebo/src/helpers.cpp b/cpp/scenario/gazebo/src/helpers.cpp index 5ef22dea2..22ea23b27 100644 --- a/cpp/scenario/gazebo/src/helpers.cpp +++ b/cpp/scenario/gazebo/src/helpers.cpp @@ -504,46 +504,41 @@ scenario::core::JointType utils::fromSdf(const sdf::JointType sdfType) return type; } -std::pair -utils::fromModelToBaseVelocity(const ignition::math::Vector3d& linModelVelocity, - const ignition::math::Vector3d& angModelVelocity, - const ignition::math::Pose3d& M_H_B, - const ignition::math::Quaterniond& W_R_B) +ignition::math::Vector3d utils::fromModelToBaseLinearVelocity( + const ignition::math::Vector3d& linModelVelocity, + const ignition::math::Vector3d& angModelVelocity, + const ignition::math::Pose3d& M_H_B, + const ignition::math::Quaterniond& W_R_B) { - ignition::math::Vector3d linBaseVelocity; - const ignition::math::Vector3d& angBaseVelocity = angModelVelocity; - // Extract the rotation and the position of the model wrt to the base auto B_R_M = M_H_B.Rot().Inverse(); auto M_o_B = M_H_B.Pos(); auto B_o_M = -B_R_M * M_o_B; // Compute the base linear velocity - linBaseVelocity = linModelVelocity - angModelVelocity.Cross(W_R_B * B_o_M); + const ignition::math::Vector3d linBaseVelocity = + linModelVelocity - angModelVelocity.Cross(W_R_B * B_o_M); - // Return the mixed velocity of the base - return {linBaseVelocity, angBaseVelocity}; + // Return the linear part of the mixed velocity of the base + return linBaseVelocity; } -std::pair -utils::fromBaseToModelVelocity(const ignition::math::Vector3d& linBaseVelocity, - const ignition::math::Vector3d& angBaseVelocity, - const ignition::math::Pose3d& M_H_B, - const ignition::math::Quaterniond& W_R_B) +ignition::math::Vector3d utils::fromBaseToModelLinearVelocity( + const ignition::math::Vector3d& linBaseVelocity, + const ignition::math::Vector3d& angBaseVelocity, + const ignition::math::Pose3d& M_H_B, + const ignition::math::Quaterniond& W_R_B) { - ignition::math::Vector3d linModelVelocity; - const ignition::math::Vector3d& angModelVelocity = angBaseVelocity; - // Extract the rotation and the position of the model wrt to the base auto B_R_M = M_H_B.Rot().Inverse(); auto M_o_B = M_H_B.Pos(); // Compute the model linear velocity - linModelVelocity = + const ignition::math::Vector3d linModelVelocity = linBaseVelocity - angBaseVelocity.Cross(W_R_B * B_R_M * M_o_B); - // Return the mixed velocity of the model - return {linModelVelocity, angModelVelocity}; + // Return the linear part of the mixed velocity of the model + return linModelVelocity; } std::shared_ptr utils::getParentWorld(const GazeboEntity& gazeboEntity) diff --git a/cpp/scenario/plugins/Physics/CMakeLists.txt b/cpp/scenario/plugins/Physics/CMakeLists.txt index 80fca4065..0ca0be299 100644 --- a/cpp/scenario/plugins/Physics/CMakeLists.txt +++ b/cpp/scenario/plugins/Physics/CMakeLists.txt @@ -27,8 +27,8 @@ # ============= add_library(PhysicsSystem SHARED - Physics.h - Physics.cpp) + Physics.hh + Physics.cc) target_link_libraries(PhysicsSystem PUBLIC @@ -41,6 +41,10 @@ target_link_libraries(PhysicsSystem target_include_directories(PhysicsSystem PRIVATE $) +if(ENABLE_PROFILER) + target_compile_definitions(PhysicsSystem PRIVATE "IGN_PROFILER_ENABLE=1") +endif() + # =================== # Install the targets # =================== diff --git a/cpp/scenario/plugins/Physics/EntityFeatureMap.hh b/cpp/scenario/plugins/Physics/EntityFeatureMap.hh new file mode 100644 index 000000000..8008f478d --- /dev/null +++ b/cpp/scenario/plugins/Physics/EntityFeatureMap.hh @@ -0,0 +1,313 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#ifndef IGNITION_GAZEBO_SYSTEMS_PHYSICS_ENTITY_FEATURE_MAP_HH_ +#define IGNITION_GAZEBO_SYSTEMS_PHYSICS_ENTITY_FEATURE_MAP_HH_ + +#include +#include +#include + +#include +#include +#include +#include + +#include "ignition/gazebo/Entity.hh" + +namespace ignition::gazebo +{ +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace systems::physics_system +{ + // \brief Helper class that associates Gazebo entities with Physics entities + // with required and optional features. It can be used to cast a physics + // entity with the required features to another physics entity with one of + // the optional features. This class was created to keep all physics entities + // in one place so that when a gazebo entity is removed, all the mapped + // physics entitities can be removed at the same time. This ensures that + // reference counts are properly zeroed out in the underlying physics engines + // and the memory associated with the physics entities can be freed. + // + // DEV WARNING: There is an implicit conversion between physics EntityPtr and + // std::size_t in ign-physics. This seems also implicitly convert between + // EntityPtr and gazebo Entity. Therefore, any member function that takes a + // gazebo Entity can accidentally take an EntityPtr. To prevent this, for + // every function that takes a gazebo Entity, we should always have an + // overload that also takes an EntityPtr with required features. We can do + // this because there's a 1:1 mapping between the two in maps contained in + // this class. + // + // \tparam PhysicsEntityT Type of entity, such as World, Model, or Link + // \tparam PolicyT Policy of the physics engine (2D, 3D) + // \tparam RequiredFeatureList Required features of the physics entity + // \tparam OptionalFeatureLists One or more optional feature lists of the + // physics entity. + template