Skip to content

Commit

Permalink
Merge branch 'gz-physics7' into fix_ctad
Browse files Browse the repository at this point in the history
  • Loading branch information
iche033 authored Jul 8, 2024
2 parents 3ad355c + 707aa69 commit d4f7b41
Show file tree
Hide file tree
Showing 10 changed files with 270 additions and 35 deletions.
9 changes: 6 additions & 3 deletions bullet-featherstone/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

This component enables the use of this [Bullet Physics](https://github.com/bulletphysics/bullet3) `btMultiBody` Featherstone implementation.
The Featherstone uses minimal coordinates to represent articulated bodies and efficiently simulate them.

# Features

Originally tracked via: [Bullet featherstone meta-ticket](https://github.com/gazebosim/gz-physics/issues/423)
Expand All @@ -11,7 +11,7 @@ Originally tracked via: [Bullet featherstone meta-ticket](https://github.com/gaz

* Constructing SDF Models
* Constructing SDF Worlds
* Joint Types:
* Joint Types:
* Fixed
* Prismatic
* Revolute
Expand All @@ -25,7 +25,7 @@ Originally tracked via: [Bullet featherstone meta-ticket](https://github.com/gaz

These are the specific physics API features implemented.

* Entity Management Features
* Entity Management Features
* ConstructEmptyWorldFeature
* GetEngineInfo
* GetJointFromModel
Expand All @@ -47,6 +47,9 @@ These are the specific physics API features implemented.
* SetBasicJointState
* GetBasicJointProperties
* SetJointVelocityCommandFeature
* SetJointPositionLimitsFeature,
* SetJointVelocityLimitsFeature,
* SetJointEffortLimitsFeature,
* SetJointTransformFromParentFeature
* AttachFixedJointFeature
* DetachJointFeature
Expand Down
12 changes: 11 additions & 1 deletion bullet-featherstone/src/Base.hh
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,8 @@ struct WorldInfo
std::unordered_map<std::string, std::size_t> modelNameToEntityId;
int nextModelIndex = 0;

double stepSize = 0.001;

explicit WorldInfo(std::string name);
};

Expand Down Expand Up @@ -189,7 +191,15 @@ struct JointInfo
Identity model;
// This field gets set by AddJoint
std::size_t indexInGzModel = 0;
btScalar effort = 0;

// joint limits
// \todo(iche033) Extend to support joints with more than 1 dof
double minEffort = 0.0;
double maxEffort = 0.0;
double minVelocity = 0.0;
double maxVelocity = 0.0;
double axisLower = 0.0;
double axisUpper = 0.0;

std::shared_ptr<btMultiBodyJointMotor> motor = nullptr;
std::shared_ptr<btMultiBodyJointLimitConstraint> jointLimits = nullptr;
Expand Down
171 changes: 167 additions & 4 deletions bullet-featherstone/src/JointFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@
#include "JointFeatures.hh"

#include <algorithm>
#include <cmath>
#include <cstddef>
#include <memory>
#include <unordered_map>

Expand All @@ -28,6 +30,29 @@ namespace gz {
namespace physics {
namespace bullet_featherstone {

/////////////////////////////////////////////////
void recreateJointLimitConstraint(JointInfo *_jointInfo, ModelInfo *_modelInfo,
WorldInfo *_worldInfo)
{
const auto *identifier = std::get_if<InternalJoint>(&_jointInfo->identifier);
if (!identifier)
return;

if (_jointInfo->jointLimits)
{
_worldInfo->world->removeMultiBodyConstraint(_jointInfo->jointLimits.get());
_jointInfo->jointLimits.reset();
}

_jointInfo->jointLimits =
std::make_shared<btMultiBodyJointLimitConstraint>(
_modelInfo->body.get(), identifier->indexInBtModel,
static_cast<btScalar>(_jointInfo->axisLower),
static_cast<btScalar>(_jointInfo->axisUpper));

_worldInfo->world->addMultiBodyConstraint(_jointInfo->jointLimits.get());
}

/////////////////////////////////////////////////
void makeColliderStatic(LinkInfo *_linkInfo)
{
Expand Down Expand Up @@ -277,8 +302,13 @@ void JointFeatures::SetJointForce(
return;

const auto *model = this->ReferenceInterface<ModelInfo>(joint->model);

// clamp the values
double force = std::clamp(_value,
joint->minEffort, joint->maxEffort);

model->body->getJointTorqueMultiDof(
identifier->indexInBtModel)[_dof] = static_cast<btScalar>(_value);
identifier->indexInBtModel)[_dof] = static_cast<btScalar>(force);
model->body->wakeUp();
}

Expand Down Expand Up @@ -409,20 +439,153 @@ void JointFeatures::SetJointVelocityCommand(
auto modelInfo = this->ReferenceInterface<ModelInfo>(jointInfo->model);
if (!jointInfo->motor)
{
auto *world = this->ReferenceInterface<WorldInfo>(modelInfo->world);
// \todo(iche033) The motor constraint is created with a max impulse
// computed by maxEffort * stepsize. However, our API supports
// stepping sim with varying dt. We should recompute max impulse
// if stepSize changes.
jointInfo->motor = std::make_shared<btMultiBodyJointMotor>(
modelInfo->body.get(),
std::get<InternalJoint>(jointInfo->identifier).indexInBtModel,
0,
static_cast<btScalar>(0),
static_cast<btScalar>(jointInfo->effort));
auto *world = this->ReferenceInterface<WorldInfo>(modelInfo->world);
static_cast<btScalar>(jointInfo->maxEffort * world->stepSize));
world->world->addMultiBodyConstraint(jointInfo->motor.get());
}

jointInfo->motor->setVelocityTarget(static_cast<btScalar>(_value));
// clamp the values
double velocity = std::clamp(_value,
jointInfo->minVelocity, jointInfo->maxVelocity);

jointInfo->motor->setVelocityTarget(static_cast<btScalar>(velocity));
modelInfo->body->wakeUp();
}

/////////////////////////////////////////////////
void JointFeatures::SetJointMinPosition(
const Identity &_id, std::size_t _dof, double _value)
{
auto *jointInfo = this->ReferenceInterface<JointInfo>(_id);
if (std::isnan(_value))
{
gzerr << "Invalid minimum joint position value [" << _value
<< "] commanded on joint [" << jointInfo->name << " DOF " << _dof
<< "]. The command will be ignored\n";
return;
}
jointInfo->axisLower = _value;

auto *modelInfo = this->ReferenceInterface<ModelInfo>(jointInfo->model);
auto *worldInfo = this->ReferenceInterface<WorldInfo>(modelInfo->world);
recreateJointLimitConstraint(jointInfo, modelInfo, worldInfo);
}

/////////////////////////////////////////////////
void JointFeatures::SetJointMaxPosition(
const Identity &_id, std::size_t _dof, double _value)
{
auto *jointInfo = this->ReferenceInterface<JointInfo>(_id);
if (std::isnan(_value))
{
gzerr << "Invalid maximum joint position value [" << _value
<< "] commanded on joint [" << jointInfo->name << " DOF " << _dof
<< "]. The command will be ignored\n";
return;
}

jointInfo->axisUpper = _value;

auto *modelInfo = this->ReferenceInterface<ModelInfo>(jointInfo->model);
auto *worldInfo = this->ReferenceInterface<WorldInfo>(modelInfo->world);
recreateJointLimitConstraint(jointInfo, modelInfo, worldInfo);
}

/////////////////////////////////////////////////
void JointFeatures::SetJointMinVelocity(
const Identity &_id, std::size_t _dof, double _value)
{
auto *jointInfo = this->ReferenceInterface<JointInfo>(_id);
if (std::isnan(_value))
{
gzerr << "Invalid minimum joint velocity value [" << _value
<< "] commanded on joint [" << jointInfo->name << " DOF " << _dof
<< "]. The command will be ignored\n";
return;
}

jointInfo->minVelocity = _value;
}

/////////////////////////////////////////////////
void JointFeatures::SetJointMaxVelocity(
const Identity &_id, std::size_t _dof, double _value)
{
auto *jointInfo = this->ReferenceInterface<JointInfo>(_id);
if (std::isnan(_value))
{
gzerr << "Invalid maximum joint velocity value [" << _value
<< "] commanded on joint [" << jointInfo->name << " DOF " << _dof
<< "]. The command will be ignored\n";
return;
}

jointInfo->maxVelocity = _value;
}

/////////////////////////////////////////////////
void JointFeatures::SetJointMinEffort(
const Identity &_id, std::size_t _dof, double _value)
{
auto *jointInfo = this->ReferenceInterface<JointInfo>(_id);
if (std::isnan(_value))
{
gzerr << "Invalid minimum joint effort value [" << _value
<< "] commanded on joint [" << jointInfo->name << " DOF " << _dof
<< "]. The command will be ignored\n";

return;
}

jointInfo->minEffort = _value;
}

/////////////////////////////////////////////////
void JointFeatures::SetJointMaxEffort(
const Identity &_id, std::size_t _dof, double _value)
{
auto *jointInfo = this->ReferenceInterface<JointInfo>(_id);
if (std::isnan(_value))
{
gzerr << "Invalid maximum joint effort value [" << _value
<< "] commanded on joint [" << jointInfo->name << " DOF " << _dof
<< "]. The command will be ignored\n";
return;
}

const auto *identifier = std::get_if<InternalJoint>(&jointInfo->identifier);
if (!identifier)
return;

jointInfo->maxEffort = _value;

auto *modelInfo = this->ReferenceInterface<ModelInfo>(jointInfo->model);
auto *world = this->ReferenceInterface<WorldInfo>(modelInfo->world);

if (jointInfo->motor)
{
world->world->removeMultiBodyConstraint(jointInfo->motor.get());
jointInfo->motor.reset();
}

jointInfo->motor = std::make_shared<btMultiBodyJointMotor>(
modelInfo->body.get(),
std::get<InternalJoint>(jointInfo->identifier).indexInBtModel,
0,
static_cast<btScalar>(0),
static_cast<btScalar>(jointInfo->maxEffort * world->stepSize));
world->world->addMultiBodyConstraint(jointInfo->motor.get());
}

/////////////////////////////////////////////////
Identity JointFeatures::AttachFixedJoint(
const Identity &_childID,
Expand Down
27 changes: 27 additions & 0 deletions bullet-featherstone/src/JointFeatures.hh
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,9 @@ struct JointFeatureList : FeatureList<
GetBasicJointProperties,

SetJointVelocityCommandFeature,
SetJointPositionLimitsFeature,
SetJointVelocityLimitsFeature,
SetJointEffortLimitsFeature,

SetJointTransformFromParentFeature,
AttachFixedJointFeature,
Expand Down Expand Up @@ -127,6 +130,30 @@ class JointFeatures :
const Identity &_id, const std::size_t _dof,
const double _value) override;

public: void SetJointMinPosition(
const Identity &_id, std::size_t _dof,
double _value) override;

public: void SetJointMaxPosition(
const Identity &_id, std::size_t _dof,
double _value) override;

public: void SetJointMinVelocity(
const Identity &_id, std::size_t _dof,
double _value) override;

public: void SetJointMaxVelocity(
const Identity &_id, std::size_t _dof,
double _value) override;

public: void SetJointMinEffort(
const Identity &_id, std::size_t _dof,
double _value) override;

public: void SetJointMaxEffort(
const Identity &_id, std::size_t _dof,
double _value) override;

// ----- AttachFixedJointFeature -----
public: Identity AttachFixedJoint(
const Identity &_childID,
Expand Down
19 changes: 18 additions & 1 deletion bullet-featherstone/src/SDFFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
#include <sdf/JointAxis.hh>
#include <sdf/Link.hh>
#include <sdf/Mesh.hh>
#include <sdf/Physics.hh>
#include <sdf/Plane.hh>
#include <sdf/Sphere.hh>
#include <sdf/Surface.hh>
Expand Down Expand Up @@ -89,6 +90,12 @@ Identity SDFFeatures::ConstructSdfWorld(

worldInfo->world->setGravity(convertVec(_sdfWorld.Gravity()));

const ::sdf::Physics *physics = _sdfWorld.PhysicsByIndex(0);
if (physics)
worldInfo->stepSize = physics->MaxStepSize();
else
worldInfo->stepSize = 0.001;

for (std::size_t i = 0; i < _sdfWorld.ModelCount(); ++i)
{
const ::sdf::Model *model = _sdfWorld.ModelByIndex(i);
Expand Down Expand Up @@ -770,6 +777,10 @@ Identity SDFFeatures::ConstructSdfModelImpl(
if (::sdf::JointType::PRISMATIC == joint->Type() ||
::sdf::JointType::REVOLUTE == joint->Type())
{
// Note: These m_joint* properties below are currently not supported by
// bullet-featherstone and so setting them does not have any effect.
// The lower and uppper limit is supported via the
// btMultiBodyJointLimitConstraint.
model->body->getLink(i).m_jointLowerLimit =
static_cast<btScalar>(joint->Axis()->Lower());
model->body->getLink(i).m_jointUpperLimit =
Expand All @@ -782,7 +793,13 @@ Identity SDFFeatures::ConstructSdfModelImpl(
static_cast<btScalar>(joint->Axis()->MaxVelocity());
model->body->getLink(i).m_jointMaxForce =
static_cast<btScalar>(joint->Axis()->Effort());
jointInfo->effort = static_cast<btScalar>(joint->Axis()->Effort());

jointInfo->minEffort = -joint->Axis()->Effort();
jointInfo->maxEffort = joint->Axis()->Effort();
jointInfo->minVelocity = -joint->Axis()->MaxVelocity();
jointInfo->maxVelocity = joint->Axis()->MaxVelocity();
jointInfo->axisLower = joint->Axis()->Lower();
jointInfo->axisUpper = joint->Axis()->Upper();

jointInfo->jointLimits =
std::make_shared<btMultiBodyJointLimitConstraint>(
Expand Down
9 changes: 7 additions & 2 deletions bullet-featherstone/src/SimulationFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -37,14 +37,19 @@ void SimulationFeatures::WorldForwardStep(
const auto worldInfo = this->ReferenceInterface<WorldInfo>(_worldID);
auto *dtDur =
_u.Query<std::chrono::steady_clock::duration>();
double stepSize = 0.001;
if (dtDur)
{
std::chrono::duration<double> dt = *dtDur;
stepSize = dt.count();
}

worldInfo->world->stepSimulation(static_cast<btScalar>(this->stepSize), 1,
static_cast<btScalar>(this->stepSize));
// \todo(iche033) Stepping sim with varying dt may not work properly.
// One example is the motor constraint that's created in
// JointFeatures::SetJointVelocityCommand which assumes a fixed step
// size.
worldInfo->world->stepSimulation(static_cast<btScalar>(stepSize), 1,
static_cast<btScalar>(stepSize));

this->WriteRequiredData(_h);
this->Write(_h.Get<ChangedWorldPoses>());
Expand Down
2 changes: 0 additions & 2 deletions bullet-featherstone/src/SimulationFeatures.hh
Original file line number Diff line number Diff line change
Expand Up @@ -58,8 +58,6 @@ class SimulationFeatures :
public: std::vector<ContactInternal> GetContactsFromLastStep(
const Identity &_worldID) const override;

private: double stepSize = 0.001;

/// \brief link poses from the most recent pose change/update.
/// The key is the link's ID, and the value is the link's pose
private: mutable std::unordered_map<std::size_t, math::Pose3d> prevLinkPoses;
Expand Down
Loading

0 comments on commit d4f7b41

Please sign in to comment.