Skip to content

Commit

Permalink
Update old comments
Browse files Browse the repository at this point in the history
Signed-off-by: Jorge Perez <jjperez@ekumenlabs.com>
  • Loading branch information
Blast545 committed Mar 3, 2021
1 parent aa22784 commit 6c1dbd6
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 26 deletions.
4 changes: 1 addition & 3 deletions bullet/src/EntityManagementFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -112,9 +112,9 @@ bool EntityManagementFeatures::RemoveModelByIndex(
{
return false;
}

// Current implementation does not include joints
// Those should be removed here before removing the model

auto model = this->models.at(_modelIndex);
// Clean up collisions
std::unordered_map<std::size_t, CollisionInfoPtr>::iterator collision_it =
Expand Down Expand Up @@ -156,7 +156,6 @@ bool EntityManagementFeatures::RemoveModelByIndex(
bool EntityManagementFeatures::RemoveModelByName(
const Identity & _worldID, const std::string & _modelName )
{

// Check if there is a model with the requested name
bool found = false;
size_t index_id = 0;
Expand All @@ -174,7 +173,6 @@ bool EntityManagementFeatures::RemoveModelByName(

if (found)
{
// Use a not valid Identity, not used
return this->RemoveModelByIndex(_worldID, index_id);
}

Expand Down
9 changes: 3 additions & 6 deletions bullet/src/JointFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -318,9 +318,7 @@ void JointFeatures::SetJointVelocityCommand(
(void) _dof;
const auto &jointInfo = this->joints.at(_id.id);

// Take extra care that the value is finite. A nan can cause the DART
// constraint solver to fail, which will in turn either cause a crash or
// collisions to fail
// Take extra care that the value is finite
if (!std::isfinite(_value))
{
ignerr << "Invalid joint velocity value [" << _value << "] set on joint ["
Expand Down Expand Up @@ -348,9 +346,8 @@ void JointFeatures::SetJointVelocityCommand(
std::size_t JointFeatures::GetJointDegreesOfFreedom(const Identity &_id) const
{
(void) _id;
// TO-DO: Degrees of freedom may need to be saved in the JointInfo struct
// As bullet's constraints do not save this info
// igndbg << "Dummy GetJointDegreesOfFreedom\n";
// Degrees of freedom may need to be saved in the JointInfo struct
// Currently supporting 1DoF joints
return 1;
}

Expand Down
23 changes: 6 additions & 17 deletions bullet/src/SDFFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@ Identity SDFFeatures::ConstructSdfModel(
const std::string name = _sdfModel.Name();
const math::Pose3d pose = _sdfModel.RawPose();
const bool isStatic = _sdfModel.Static();
// Links within a model will collide unless these are chained with a joint
// const bool selfCollide = _sdfModel.SelfCollide();

const auto modelIdentity = this->AddModel({name, _worldID, isStatic, pose});
Expand Down Expand Up @@ -99,9 +100,7 @@ Identity SDFFeatures::ConstructSdfLink(
baseTransform.setOrigin(convertVec(poseTranslation));
baseTransform.setBasis(convertMat(poseLinear));

// Create link
// (TO-DO: do we want to use MotionState?)
// 2nd part: Do motion state use the same transformation?
// Fixed links have 0 mass and inertia
if (this->models.at(_modelID)->fixed)
{
mass = 0;
Expand Down Expand Up @@ -167,9 +166,8 @@ Identity SDFFeatures::ConstructSdfCollision(
shape = new btStaticPlaneShape(normal, 0);
}

// TODO(lobotuerk) find if there's a way to use friction and related
// info in bullet dynamics

// TODO(lobotuerk/blast545) Add additional friction parameters for bullet
// Currently supporting mu and mu2
const auto &surfaceElement = _collision.Element()->GetElement("surface");

// Get friction
Expand All @@ -178,7 +176,7 @@ Identity SDFFeatures::ConstructSdfCollision(
const auto mu = odeFriction->Get<btScalar>("mu");
const auto mu2 = odeFriction->Get<btScalar>("mu2");

// Get restitution
// Restitution coefficient not tested
// const auto restitution = surfaceElement->GetElement("bounce")
// ->Get<btScalar>("restitution_coefficient");
if (shape != nullptr)
Expand All @@ -187,11 +185,6 @@ Identity SDFFeatures::ConstructSdfCollision(
const auto &body = linkInfo->link;
const auto &modelID = linkInfo->model;

// TODO(LOBOTUERK) figure out why this was here
// if (!modelInfo->fixed){
// return this->GenerateInvalidId();
// }

const math::Pose3d pose = _collision.RawPose();
const Eigen::Isometry3d poseIsometry =
ignition::math::eigen3::convert(pose);
Expand All @@ -201,10 +194,9 @@ Identity SDFFeatures::ConstructSdfCollision(
baseTransform.setOrigin(convertVec(poseTranslation));
baseTransform.setBasis(convertMat(poseLinear));

// TODO(Blast545): Consider different approaches to set frictions
// shape->setMargin(btScalar(0.0001));
body->setFriction(1);
// body->setRollingFriction(0.25);
body->setFriction(1);
body->setAnisotropicFriction(btVector3(mu, mu2, 1),
btCollisionObject::CF_ANISOTROPIC_FRICTION);

Expand All @@ -223,9 +215,6 @@ Identity SDFFeatures::ConstructSdfJoint(
const Identity &_modelID,
const ::sdf::Joint &_sdfJoint)
{
// const auto &parentModelInfo =
// *this->ReferenceInterface<ModelInfo>(_modelID);

// Check supported Joints
const ::sdf::JointType type = _sdfJoint.Type();
if( type != ::sdf::JointType::REVOLUTE && type != ::sdf::JointType::FIXED )
Expand Down

0 comments on commit 6c1dbd6

Please sign in to comment.