Skip to content

Commit

Permalink
[Backport #536 3 ⬅️ 4] Add service and GUI to configure physics param…
Browse files Browse the repository at this point in the history
…eters (#812)

* Add service and GUI to configure physics parameters (step size and real time factor) (#536)

Signed-off-by: Maganty Rushyendra <mrushyendra@yahoo.com.sg>
Signed-off-by: Luca Della Vedova <luca@openrobotics.org>
Signed-off-by: ahcorde <ahcorde@gmail.com>

Co-authored-by: mrushyendra <mrushyendra@yahoo.com.sg>
Co-authored-by: Louise Poubel <louise@openrobotics.org>
Co-authored-by: Luca Della Vedova <luca@openrobotics.org>
  • Loading branch information
4 people committed May 12, 2021
1 parent 4ee7d57 commit cceec4e
Show file tree
Hide file tree
Showing 18 changed files with 747 additions and 7 deletions.
39 changes: 38 additions & 1 deletion include/ignition/gazebo/Conversions.hh
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include <ignition/msgs/inertial.pb.h>
#include <ignition/msgs/light.pb.h>
#include <ignition/msgs/material.pb.h>
#include <ignition/msgs/physics.pb.h>
#include <ignition/msgs/scene.pb.h>
#include <ignition/msgs/sensor.pb.h>
#include <ignition/msgs/sensor_noise.pb.h>
Expand All @@ -46,6 +47,7 @@
#include <sdf/Light.hh>
#include <sdf/Material.hh>
#include <sdf/Noise.hh>
#include <sdf/Physics.hh>
#include <sdf/Scene.hh>
#include <sdf/Sensor.hh>

Expand Down Expand Up @@ -417,6 +419,41 @@ namespace ignition
sdf::Atmosphere convert(const msgs::Atmosphere &_in);


/// \brief Generic conversion from an SDF Physics to another type.
/// \param[in] _in SDF Physics.
/// \return Conversion result.
/// \tparam Out Output type.
template<class Out>
Out convert(const sdf::Physics &/*_in*/)
{
Out::ConversionNotImplemented;
}

/// \brief Specialized conversion from an SDF physics to a physics
/// message.
/// \param[in] _in SDF physics.
/// \return Physics message.
template<>
msgs::Physics convert(const sdf::Physics &_in);

/// \brief Generic conversion from a physics message to another type.
/// \param[in] _in Physics message.
/// \return Conversion result.
/// \tparam Out Output type.
template<class Out>
Out convert(const msgs::Physics &/*_in*/)
{
Out::ConversionNotImplemented;
}

/// \brief Specialized conversion from a physics message to a physics
/// SDF object.
/// \param[in] _in Physics message.
/// \return SDF physics.
template<>
sdf::Physics convert(const msgs::Physics &_in);


/// \brief Generic conversion from an SDF Sensor to another type.
/// \param[in] _in SDF Sensor.
/// \return Conversion result.
Expand All @@ -429,7 +466,7 @@ namespace ignition

/// \brief Specialized conversion from an SDF sensor to a sensor
/// message.
/// \param[in] _in SDF geometry.
/// \param[in] _in SDF sensor.
/// \return Sensor message.
template<>
msgs::Sensor convert(const sdf::Sensor &_in);
Expand Down
56 changes: 56 additions & 0 deletions include/ignition/gazebo/components/Physics.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
/*
* 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_COMPONENTS_PHYSICS_HH_
#define IGNITION_GAZEBO_COMPONENTS_PHYSICS_HH_

#include <ignition/msgs/physics.pb.h>

#include <sdf/Physics.hh>

#include <ignition/gazebo/config.hh>
#include <ignition/gazebo/Export.hh>

#include <ignition/gazebo/components/Factory.hh>
#include "ignition/gazebo/components/Component.hh"
#include <ignition/gazebo/components/Serialization.hh>
#include <ignition/gazebo/Conversions.hh>

namespace ignition
{
namespace gazebo
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace serializers
{
using PhysicsSerializer =
serializers::ComponentToMsgSerializer<sdf::Physics, msgs::Physics>;
}
namespace components
{
/// \brief A component type that contains the physics properties of
/// the World entity.
using Physics = Component<sdf::Physics, class PhysicsTag,
serializers::PhysicsSerializer>;
IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Physics",
Physics)
}
}
}
}

#endif
46 changes: 46 additions & 0 deletions include/ignition/gazebo/components/PhysicsCmd.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
/*
* 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_COMPONENTS_PHYSICSCMD_HH_
#define IGNITION_GAZEBO_COMPONENTS_PHYSICSCMD_HH_

#include <ignition/msgs/physics.pb.h>

#include <ignition/gazebo/config.hh>
#include <ignition/gazebo/Export.hh>

#include <ignition/gazebo/components/Factory.hh>
#include "ignition/gazebo/components/Component.hh"

namespace ignition
{
namespace gazebo
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace components
{
/// \brief A component type that contains the physics properties of
/// the World entity.
using PhysicsCmd = Component<msgs::Physics, class PhysicsCmdTag>;
IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.PhysicsCmd",
PhysicsCmd)
}
}
}
}

#endif
20 changes: 20 additions & 0 deletions src/Conversions.cc
Original file line number Diff line number Diff line change
Expand Up @@ -743,6 +743,26 @@ void ignition::gazebo::set(msgs::WorldStatistics *_msg,
_msg->set_paused(_in.paused);
}

//////////////////////////////////////////////////
template<>
msgs::Physics ignition::gazebo::convert(const sdf::Physics &_in)
{
msgs::Physics out;
out.set_max_step_size(_in.MaxStepSize());
out.set_real_time_factor(_in.RealTimeFactor());
return out;
}

//////////////////////////////////////////////////
template<>
sdf::Physics ignition::gazebo::convert(const msgs::Physics &_in)
{
sdf::Physics out;
out.SetRealTimeFactor(_in.real_time_factor());
out.SetMaxStepSize(_in.max_step_size());
return out;
}

//////////////////////////////////////////////////
void ignition::gazebo::set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf)
{
Expand Down
23 changes: 23 additions & 0 deletions src/Conversions_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
#include <sdf/Magnetometer.hh>
#include <sdf/Mesh.hh>
#include <sdf/Pbr.hh>
#include <sdf/Physics.hh>
#include <sdf/Plane.hh>
#include <sdf/Root.hh>
#include <sdf/Scene.hh>
Expand Down Expand Up @@ -157,6 +158,28 @@ TEST(Conversions, Entity)
EXPECT_EQ(msgs::Entity_Type_NONE, entityType2);
}

/////////////////////////////////////////////////
TEST(Conversions, Physics)
{
// Test conversion from msg to sdf
msgs::Physics msg;
msg.set_real_time_factor(1.23);
msg.set_max_step_size(0.12);

auto physics = convert<sdf::Physics>(msg);
EXPECT_DOUBLE_EQ(1.23, physics.RealTimeFactor());
EXPECT_DOUBLE_EQ(0.12, physics.MaxStepSize());

// Test conversion from sdf to msg
sdf::Physics physSdf;
physSdf.SetMaxStepSize(0.34);
physSdf.SetRealTimeFactor(2.34);

auto physMsg = convert<msgs::Physics>(physSdf);
EXPECT_DOUBLE_EQ(2.34, physMsg.real_time_factor());
EXPECT_DOUBLE_EQ(0.34, physMsg.max_step_size());
}

/////////////////////////////////////////////////
TEST(Conversions, Pose)
{
Expand Down
9 changes: 9 additions & 0 deletions src/LevelManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@
#include "ignition/gazebo/components/ParentEntity.hh"
#include "ignition/gazebo/components/Performer.hh"
#include "ignition/gazebo/components/PerformerLevels.hh"
#include "ignition/gazebo/components/Physics.hh"
#include "ignition/gazebo/components/PhysicsEnginePlugin.hh"
#include "ignition/gazebo/components/Pose.hh"
#include "ignition/gazebo/components/RenderEngineGuiPlugin.hh"
Expand Down Expand Up @@ -96,6 +97,14 @@ void LevelManager::ReadLevelPerformerInfo()
this->runner->entityCompMgr.CreateComponent(this->worldEntity,
components::Gravity(this->runner->sdfWorld->Gravity()));

auto physics = this->runner->sdfWorld->PhysicsByIndex(0);
if (!physics)
{
physics = this->runner->sdfWorld->PhysicsDefault();
}
this->runner->entityCompMgr.CreateComponent(this->worldEntity,
components::Physics(*physics));

this->runner->entityCompMgr.CreateComponent(this->worldEntity,
components::MagneticField(this->runner->sdfWorld->MagneticField()));

Expand Down
11 changes: 11 additions & 0 deletions src/SdfEntityCreator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@
#include "ignition/gazebo/components/Name.hh"
#include "ignition/gazebo/components/ParentLinkName.hh"
#include "ignition/gazebo/components/ParentEntity.hh"
#include "ignition/gazebo/components/Physics.hh"
#include "ignition/gazebo/components/Pose.hh"
#include "ignition/gazebo/components/RgbdCamera.hh"
#include "ignition/gazebo/components/Scene.hh"
Expand Down Expand Up @@ -202,6 +203,16 @@ Entity SdfEntityCreator::CreateEntities(const sdf::World *_world)
this->dataPtr->ecm->CreateComponent(worldEntity,
components::Gravity(_world->Gravity()));

// Physics
// \todo(anyone) Support picking a specific physics profile
auto physics = _world->PhysicsByIndex(0);
if (!physics)
{
physics = _world->PhysicsDefault();
}
this->dataPtr->ecm->CreateComponent(worldEntity,
components::Physics(*physics));

// MagneticField
this->dataPtr->ecm->CreateComponent(worldEntity,
components::MagneticField(_world->MagneticField()));
Expand Down
10 changes: 8 additions & 2 deletions src/SdfEntityCreator_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
#include "ignition/gazebo/components/Name.hh"
#include "ignition/gazebo/components/ParentEntity.hh"
#include "ignition/gazebo/components/ParentLinkName.hh"
#include "ignition/gazebo/components/Physics.hh"
#include "ignition/gazebo/components/Pose.hh"
#include "ignition/gazebo/components/Transparency.hh"
#include "ignition/gazebo/components/Visual.hh"
Expand Down Expand Up @@ -112,15 +113,20 @@ TEST_F(SdfEntityCreatorTest, CreateEntities)
unsigned int worldCount{0};
Entity worldEntity = kNullEntity;
this->ecm.Each<components::World,
components::Name>(
components::Name,
components::Physics>(
[&](const Entity &_entity,
const components::World *_world,
const components::Name *_name)->bool
const components::Name *_name,
const components::Physics *_physics)->bool
{
EXPECT_NE(nullptr, _world);
EXPECT_NE(nullptr, _name);
EXPECT_NE(nullptr, _physics);

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

worldCount++;

Expand Down
Loading

0 comments on commit cceec4e

Please sign in to comment.