diff --git a/src/systems/buoyancy/Buoyancy.cc b/src/systems/buoyancy/Buoyancy.cc index abbbd168749..8998c1f47ed 100644 --- a/src/systems/buoyancy/Buoyancy.cc +++ b/src/systems/buoyancy/Buoyancy.cc @@ -124,24 +124,22 @@ void BuoyancyPrivate::GradedFluidDensity( auto prevLayerFluidDensity = this->fluidDensity; auto volsum = 0; auto centerOfBuoyancy = math::Vector3d{0,0,0}; - ignerr << __FILE__ << ": " << __LINE__ < BuoyancyPrivate::resolveForces( const math::Pose3d &_pose) { auto force = math::Vector3d{0, 0, 0}; - ignerr << __FILE__ << ": " << __LINE__ <buoyancyForces) { @@ -197,10 +192,7 @@ std::pair BuoyancyPrivate::resolveForces( auto globalPoint = b.pose * localPoint; auto offset = globalPoint.Pos() - _pose.Pos(); torque += force.Cross(offset); - ignerr << __FILE__ << ": " << __LINE__ <Get("above_depth"); auto density = argument->Get("density"); this->dataPtr->layers[depth] = density; - ignerr << "Added layer " << std::endl; + igndbg << "Added layer at " << depth << std::endl; } argument = argument->GetNextElement(); } } - ignerr << "Finished parsing" << std::endl; - } ////////////////////////////////////////////////// @@ -281,7 +271,6 @@ void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info, return; } - ignerr << "was here" << std::endl; // Compute the volume and center of volume for each new link _ecm.EachNew( [&](const Entity &_entity, @@ -297,6 +286,9 @@ void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info, return true; } + enableComponent(_ecm, _entity); + enableComponent(_ecm, _entity); + Link link(_entity); std::vector collisions = _ecm.ChildrenByComponents( @@ -437,8 +429,6 @@ void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info, ignerr << "Invalid collision pointer. This shouldn't happen\n"; continue; } - ignerr << __FILE__ << ": " << __LINE__ <Data().Geom()->Type()) { @@ -446,7 +436,6 @@ void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info, //coll->Data().Geom()->BoxShape()->Shape().VolumeBelow(); break; case sdf::GeometryType::SPHERE: - ignerr << __FILE__ << ": " << __LINE__ <dataPtr->GradedFluidDensity( pose, coll->Data().Geom()->SphereShape()->Shape(), @@ -462,12 +451,11 @@ void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info, } } } - ignerr << __FILE__ << ": " << __LINE__ <dataPtr->resolveForces( link.WorldInertialPose(_ecm).value()); // Apply the wrench to the link. This wrench is applied in the // Physics System. + ignerr << "Force applied" << force << std::endl; link.AddWorldWrench(_ecm, force, torque); return true; });