From b6c9a47877b20c6644928d6ef7bc685d962cc7bf Mon Sep 17 00:00:00 2001 From: Raphael Grimm <raphael.grimm@kit.edu> Date: Tue, 7 Apr 2020 18:32:14 +0200 Subject: [PATCH] Fix code formatting --- .../BulletEngine/BulletEngine.cpp | 46 +++-- .../BulletEngine/BulletRobot.cpp | 172 +++++++++--------- 2 files changed, 115 insertions(+), 103 deletions(-) diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp b/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp index 6eb52a3fe..af6436277 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp @@ -92,8 +92,8 @@ namespace SimDynamics dynamicsWorld = new btDiscreteDynamicsWorld(dispatcher, overlappingPairCache, constraintSolver, collision_config); dynamicsWorld->setGravity(btVector3(btScalar(config->gravity[0] * BulletObject::ScaleFactor), - btScalar(config->gravity[1] * BulletObject::ScaleFactor), - btScalar(config->gravity[2] * BulletObject::ScaleFactor))); + btScalar(config->gravity[1] * BulletObject::ScaleFactor), + btScalar(config->gravity[2] * BulletObject::ScaleFactor))); collisionFilterCallback = new BulletEngine::CustomCollisionCallback(this); dynamicsWorld->getPairCache()->setOverlapFilterCallback(collisionFilterCallback); @@ -116,7 +116,7 @@ namespace SimDynamics //only enable split impulse position correction when the penetration is deeper than this m_splitImpulsePenetrationThreshold, otherwise use the regular velocity/position constraint coupling (Baumgarte). solverInfo.m_splitImpulsePenetrationThreshold = config->bulletSolverSplitImpulsePenetrationThreshold; -// dynamicsWorld->setInternalTickCallback(externalCallbacks, this, true); + // dynamicsWorld->setInternalTickCallback(externalCallbacks, this, true); dynamicsWorld->addAction(this); return true; } @@ -166,8 +166,8 @@ namespace SimDynamics bulletConfig = newConfig; dynamicsWorld->setGravity(btVector3(btScalar(newConfig->gravity[0] * BulletObject::ScaleFactor), - btScalar(newConfig->gravity[1] * BulletObject::ScaleFactor), - btScalar(newConfig->gravity[2] * BulletObject::ScaleFactor))); + btScalar(newConfig->gravity[1] * BulletObject::ScaleFactor), + btScalar(newConfig->gravity[2] * BulletObject::ScaleFactor))); btContactSolverInfo& solverInfo = dynamicsWorld->getSolverInfo(); solverInfo.m_numIterations = newConfig->bulletSolverIterations; @@ -188,7 +188,7 @@ namespace SimDynamics auto friction = btObject->getSceneObject()->getPhysics().friction; btObject->getRigidBody()->setRestitution(bulletConfig->bulletObjectRestitution); - btObject->getRigidBody()->setFriction(friction>0.0?friction:bulletConfig->bulletObjectFriction); + btObject->getRigidBody()->setFriction(friction > 0.0 ? friction : bulletConfig->bulletObjectFriction); btObject->getRigidBody()->setFriction(bulletConfig->bulletObjectFriction); btObject->getRigidBody()->setDamping(bulletConfig->bulletObjectDampingLinear, bulletConfig->bulletObjectDampingAngular); btObject->getRigidBody()->setDeactivationTime(bulletConfig->bulletObjectDeactivation); @@ -233,7 +233,7 @@ namespace SimDynamics auto friction = o->getSceneObject()->getPhysics().friction; btObject->getRigidBody()->setCollisionFlags(btColFlag); btObject->getRigidBody()->setRestitution(bulletConfig->bulletObjectRestitution); - btObject->getRigidBody()->setFriction(friction>0.0?friction:bulletConfig->bulletObjectFriction); + btObject->getRigidBody()->setFriction(friction > 0.0 ? friction : bulletConfig->bulletObjectFriction); btObject->getRigidBody()->setDamping(bulletConfig->bulletObjectDampingLinear, bulletConfig->bulletObjectDampingAngular); btObject->getRigidBody()->setDeactivationTime(bulletConfig->bulletObjectDeactivation);//5.0f); btObject->getRigidBody()->setSleepingThresholds(bulletConfig->bulletObjectSleepingThresholdLinear, bulletConfig->bulletObjectSleepingThresholdAngular); //0.05f, 0.05f); @@ -284,7 +284,9 @@ namespace SimDynamics MutexLockPtr lock = getScopedLock(); if (friction <= 0) + { friction = bulletConfig->bulletObjectFriction; + } DynamicsEngine::createFloorPlane(pos, up); float size = float(floorExtendMM);//50000.0f; // mm float sizeSmall = float(floorDepthMM);// 500.0f; @@ -439,12 +441,12 @@ namespace SimDynamics std::vector<BulletRobot::LinkInfo> links = btRobot->getLinks(); std::vector<DynamicsObjectPtr> nodes = btRobot->getDynamicsRobotNodes(); - for (const auto & node : nodes) + for (const auto& node : nodes) { addObject(node); } - for (auto & link : links) + for (auto& link : links) { addLink(link); } @@ -473,7 +475,7 @@ namespace SimDynamics e->updateRobots(timeStep); - for (auto & callback : e->callbacks) + for (auto& callback : e->callbacks) { callback.first(callback.second, timeStep); } @@ -482,7 +484,7 @@ namespace SimDynamics void BulletEngine::updateRobots(btScalar timeStep) { - for (auto & robot : robots) + for (auto& robot : robots) { robot->actuateJoints(static_cast<double>(timeStep)); robot->updateSensors(static_cast<double>(timeStep)); @@ -504,12 +506,12 @@ namespace SimDynamics std::vector<DynamicsObjectPtr> nodes = btRobot->getDynamicsRobotNodes(); - for (auto & link : links) + for (auto& link : links) { removeLink(link); } - for (const auto & node : nodes) + for (const auto& node : nodes) { removeObject(node); } @@ -526,7 +528,7 @@ namespace SimDynamics dynamicsWorld->addConstraint(l.joint.get(), true); #endif - for (auto & disabledCollisionPair : l.disabledCollisionPairs) + for (auto& disabledCollisionPair : l.disabledCollisionPairs) { this->disableCollision(static_cast<DynamicsObject*>(disabledCollisionPair.first.get()), static_cast<DynamicsObject*>(disabledCollisionPair.second.get())); } @@ -621,9 +623,13 @@ namespace SimDynamics btManifoldPoint& pt = contactManifold->getContactPoint(j); DynamicsContactInfo i; if (dynObjA) + { i.objectAName = dynObjA->getName(); + } if (dynObjB) + { i.objectBName = dynObjB->getName(); + } const btVector3& ptA = pt.getPositionWorldOnA(); const btVector3& ptB = pt.getPositionWorldOnB(); const btVector3& normalOnB = pt.m_normalWorldOnB; @@ -724,7 +730,7 @@ namespace SimDynamics std::vector<BulletRobot::LinkInfo> links = br->getLinks(bo); - for (auto & link : links) + for (auto& link : links) { removeLink(link); } @@ -743,7 +749,7 @@ namespace SimDynamics } // namespace SimDynamics #include <chrono> -void SimDynamics::BulletEngine::updateAction(btCollisionWorld */*collisionWorld*/, btScalar deltaTimeStep) +void SimDynamics::BulletEngine::updateAction(btCollisionWorld* /*collisionWorld*/, btScalar deltaTimeStep) { auto start = std::chrono::system_clock::now(); // apply lock @@ -751,14 +757,14 @@ void SimDynamics::BulletEngine::updateAction(btCollisionWorld */*collisionWorld* updateRobots(deltaTimeStep); - for (auto & callback : callbacks) + for (auto& callback : callbacks) { callback.first(callback.second, deltaTimeStep); } - std::chrono::duration<double> diff = (std::chrono::system_clock::now()-start); -// cout << "duration: " << diff.count() << endl; + std::chrono::duration<double> diff = (std::chrono::system_clock::now() - start); + // cout << "duration: " << diff.count() << endl; } -void SimDynamics::BulletEngine::debugDraw(btIDebugDraw */*debugDrawer*/) +void SimDynamics::BulletEngine::debugDraw(btIDebugDraw* /*debugDrawer*/) { } diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp b/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp index e93f3af10..0fd1f45ad 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp @@ -25,7 +25,7 @@ namespace SimDynamics BulletRobot::BulletRobot(VirtualRobot::RobotPtr rob, bool enableJointMotors) : DynamicsRobot(rob) - // should be enough for up to 10ms/step + // should be enough for up to 10ms/step , bulletMaxMotorImulse(30 * BulletObject::ScaleFactor) { ignoreTranslationalJoints = false; @@ -47,7 +47,8 @@ namespace SimDynamics if (!hasLink(node)) { VR_WARNING << "Ignoring FT sensor " << ftSensor->getName() << ". Must be linked to a joint" << endl; - } else + } + else { const LinkInfo& link = getLink(node); enableForceTorqueFeedback(link); @@ -58,7 +59,7 @@ namespace SimDynamics } BulletRobot::~BulletRobot() - = default; + = default; @@ -88,7 +89,7 @@ namespace SimDynamics RobotNodePtr joint; //RobotNodePtr joint2; - if ( (rn->isTranslationalJoint() && !ignoreTranslationalJoints) || rn->isRotationalJoint()) + if ((rn->isTranslationalJoint() && !ignoreTranslationalJoints) || rn->isRotationalJoint()) { joint = rn; } @@ -97,12 +98,13 @@ namespace SimDynamics while (parent && !bodyA) { - if (!parent->getCollisionModel() && ( (parent->isTranslationalJoint() && !ignoreTranslationalJoints) || parent->isRotationalJoint())) + if (!parent->getCollisionModel() && ((parent->isTranslationalJoint() && !ignoreTranslationalJoints) || parent->isRotationalJoint())) { if (!joint) { joint = parent; - } else + } + else { VR_WARNING << "No body between " << parent->getName() << " and " << joint->getName() << ", skipping " << parent->getName() << endl; } @@ -172,7 +174,7 @@ namespace SimDynamics BulletObjectPtr drn1 = boost::dynamic_pointer_cast<BulletObject>(dynamicRobotNodes[rn]); VR_ASSERT(drn1); - for (const auto & i : ic) + for (const auto& i : ic) { RobotNodePtr rn2 = robot->getRobotNode(i); @@ -243,22 +245,22 @@ namespace SimDynamics tr2.getOrigin() = pivot2; boost::shared_ptr<btHingeConstraint> hinge(new btHingeConstraint(*btBody1, *btBody2, tr1, tr2, true)); -// hinge->setDbgDrawSize(0.15); + // hinge->setDbgDrawSize(0.15); // todo: check effects of parameters... -// hinge->setParam(BT_CONSTRAINT_STOP_ERP, 2.0f); -// hinge->setParam(BT_CONSTRAINT_ERP, 2.f); + // hinge->setParam(BT_CONSTRAINT_STOP_ERP, 2.0f); + // hinge->setParam(BT_CONSTRAINT_ERP, 2.f); -// hinge->setParam(BT_CONSTRAINT_CFM,0); -// hinge->setParam(BT_CONSTRAINT_STOP_CFM,0.f); + // hinge->setParam(BT_CONSTRAINT_CFM,0); + // hinge->setParam(BT_CONSTRAINT_STOP_CFM,0.f); //hinge->setLimit(limMin,limMax);//,btScalar(1.0f)); -// hinge->setParam(BT_CONSTRAINT_CFM,0.0f); + // hinge->setParam(BT_CONSTRAINT_CFM,0.0f); hinge->setLimit(btScalar(limMinBT), btScalar(limMaxBT)); return hinge; } - boost::shared_ptr<btTypedConstraint> BulletRobot::createTranslationalJoint(boost::shared_ptr<btRigidBody> btBody1, boost::shared_ptr<btRigidBody> btBody2, Eigen::Matrix4f &coordSystemNode1, Eigen::Matrix4f &coordSystemNode2, Eigen::Matrix4f& anchor_inNode1, Eigen::Matrix4f& anchor_inNode2, Eigen::Vector3f &directionLocal, Eigen::Matrix4f& coordSystemJoint, double limMinBT, double limMaxBT) + boost::shared_ptr<btTypedConstraint> BulletRobot::createTranslationalJoint(boost::shared_ptr<btRigidBody> btBody1, boost::shared_ptr<btRigidBody> btBody2, Eigen::Matrix4f& coordSystemNode1, Eigen::Matrix4f& coordSystemNode2, Eigen::Matrix4f& anchor_inNode1, Eigen::Matrix4f& anchor_inNode2, Eigen::Vector3f& directionLocal, Eigen::Matrix4f& coordSystemJoint, double limMinBT, double limMaxBT) { // we need to align coord system joint, so that z-axis is rotation axis @@ -336,9 +338,9 @@ namespace SimDynamics boost::shared_ptr<btRigidBody> btBody2 = drn2->getRigidBody(); VR_ASSERT(btBody1); VR_ASSERT(btBody2); - DynamicsWorld::GetWorld()->getEngine()->disableCollision(drn1.get(),drn2.get()); + DynamicsWorld::GetWorld()->getEngine()->disableCollision(drn1.get(), drn2.get()); - if (joint->getJointValue()!=0.0f) + if (joint->getJointValue() != 0.0f) { VR_WARNING << joint->getName() << ": joint values != 0 may produce a wrong setup, setting joint value to zero" << endl; joint->setJointValue(0); @@ -430,7 +432,9 @@ namespace SimDynamics // activate joint feedback for translational joints (somehow, the jumping positions issue seems sometimes to be solved with this?!) if (joint && joint->isTranslationalJoint() && !ignoreTranslationalJoints) + { enableForceTorqueFeedback(i); + } // disable col model i.disabledCollisionPairs.push_back( @@ -460,7 +464,7 @@ namespace SimDynamics { MutexLockPtr lock = getScopedLock(); - for (auto & link : links) + for (auto& link : links) { if (link.nodeA == node1 && link.nodeB == node2) { @@ -512,7 +516,9 @@ namespace SimDynamics VelocityMotorController& controller = actuationControllers[it->first]; if (!it->second.node->isRotationalJoint() && !it->second.node->isTranslationalJoint()) + { continue; + } LinkInfo link = getLink(it->second.node); @@ -533,64 +539,64 @@ namespace SimDynamics slider->setPoweredLinMotor(false); continue; } - } + } if (actuation.modes.torque) { // TORQUE MODES - if (it->second.node->isRotationalJoint()) - { - boost::shared_ptr<btHingeConstraint> hinge = boost::dynamic_pointer_cast<btHingeConstraint>(link.joint); - auto torque = it->second.jointTorqueTarget; - btVector3 hingeAxisLocalA = - hinge->getFrameOffsetA().getBasis().getColumn(2); - btVector3 hingeAxisLocalB = - hinge->getFrameOffsetB().getBasis().getColumn(2); - btVector3 hingeAxisWorldA = - hinge->getRigidBodyA().getWorldTransform().getBasis() * - hingeAxisLocalA; - btVector3 hingeAxisWorldB = - hinge->getRigidBodyB().getWorldTransform().getBasis() * - hingeAxisLocalB; - - - int sign = torque > 0?1:-1; - torque = std::min<double>(fabs(torque), it->first->getMaxTorque()) * sign; - - btVector3 hingeTorqueA = - torque * hingeAxisWorldA; - btVector3 hingeTorqueB = torque * hingeAxisWorldB; - hinge->enableMotor(false); - hinge->getRigidBodyA().applyTorque(hingeTorqueA); - hinge->getRigidBodyB().applyTorque(hingeTorqueB); - } - else - { - // not yet tested! - boost::shared_ptr<btSliderConstraint> slider = boost::dynamic_pointer_cast<btSliderConstraint>(link.joint); - auto torque = it->second.jointTorqueTarget; - btVector3 sliderAxisLocalA = - slider->getFrameOffsetA().getBasis().getColumn(2); - btVector3 sliderAxisLocalB = - slider->getFrameOffsetB().getBasis().getColumn(2); - btVector3 sliderAxisWorldA = - slider->getRigidBodyA().getWorldTransform().getBasis() * - sliderAxisLocalA; - btVector3 sliderAxisWorldB = - slider->getRigidBodyB().getWorldTransform().getBasis() * - sliderAxisLocalB; - - - int sign = torque > 0?1:-1; - torque = std::min<double>(fabs(torque), it->first->getMaxTorque()) * sign; - - btVector3 sliderTorqueA = - torque * sliderAxisWorldA; - btVector3 sliderTorqueB = torque * sliderAxisWorldB; - slider->setPoweredLinMotor(false); - slider->btTypedConstraint::getRigidBodyA().applyCentralForce(sliderTorqueA); - slider->btTypedConstraint::getRigidBodyB().applyCentralForce(sliderTorqueB); - } + if (it->second.node->isRotationalJoint()) + { + boost::shared_ptr<btHingeConstraint> hinge = boost::dynamic_pointer_cast<btHingeConstraint>(link.joint); + auto torque = it->second.jointTorqueTarget; + btVector3 hingeAxisLocalA = + hinge->getFrameOffsetA().getBasis().getColumn(2); + btVector3 hingeAxisLocalB = + hinge->getFrameOffsetB().getBasis().getColumn(2); + btVector3 hingeAxisWorldA = + hinge->getRigidBodyA().getWorldTransform().getBasis() * + hingeAxisLocalA; + btVector3 hingeAxisWorldB = + hinge->getRigidBodyB().getWorldTransform().getBasis() * + hingeAxisLocalB; + + + int sign = torque > 0 ? 1 : -1; + torque = std::min<double>(fabs(torque), it->first->getMaxTorque()) * sign; + + btVector3 hingeTorqueA = - torque * hingeAxisWorldA; + btVector3 hingeTorqueB = torque * hingeAxisWorldB; + hinge->enableMotor(false); + hinge->getRigidBodyA().applyTorque(hingeTorqueA); + hinge->getRigidBodyB().applyTorque(hingeTorqueB); + } + else + { + // not yet tested! + boost::shared_ptr<btSliderConstraint> slider = boost::dynamic_pointer_cast<btSliderConstraint>(link.joint); + auto torque = it->second.jointTorqueTarget; + btVector3 sliderAxisLocalA = + slider->getFrameOffsetA().getBasis().getColumn(2); + btVector3 sliderAxisLocalB = + slider->getFrameOffsetB().getBasis().getColumn(2); + btVector3 sliderAxisWorldA = + slider->getRigidBodyA().getWorldTransform().getBasis() * + sliderAxisLocalA; + btVector3 sliderAxisWorldB = + slider->getRigidBodyB().getWorldTransform().getBasis() * + sliderAxisLocalB; + + + int sign = torque > 0 ? 1 : -1; + torque = std::min<double>(fabs(torque), it->first->getMaxTorque()) * sign; + + btVector3 sliderTorqueA = - torque * sliderAxisWorldA; + btVector3 sliderTorqueB = torque * sliderAxisWorldB; + slider->setPoweredLinMotor(false); + slider->btTypedConstraint::getRigidBodyA().applyCentralForce(sliderTorqueA); + slider->btTypedConstraint::getRigidBodyB().applyCentralForce(sliderTorqueB); + } } else if (actuation.modes.position || actuation.modes.velocity) { @@ -636,13 +642,13 @@ namespace SimDynamics }*/ btScalar maxImpulse = bulletMaxMotorImulse; -// controller.setCurrentVelocity(velActual); + // controller.setCurrentVelocity(velActual); if (it->second.node->getMaxTorque() > 0) { maxImpulse = it->second.node->getMaxTorque() * btScalar(dt) * BulletObject::ScaleFactor * BulletObject::ScaleFactor * BulletObject::ScaleFactor; //cout << "node:" << it->second.node->getName() << ", max impulse: " << maxImpulse << ", dt:" << dt << ", maxImp:" << it->second.node->getMaxTorque() << endl; } - if(fabs(targetVelocity) > 0.00001) + if (fabs(targetVelocity) > 0.00001) { link.dynNode1->getRigidBody()->activate(); link.dynNode2->getRigidBody()->activate(); @@ -672,7 +678,7 @@ namespace SimDynamics boost::unordered_set<std::string> contactObjectNames; // this seems stupid and it is, but that is abstract interfaces for you. - for (auto & sensor : sensors) + for (auto& sensor : sensors) { ContactSensorPtr contactSensor = boost::dynamic_pointer_cast<ContactSensor>(sensor); @@ -686,7 +692,7 @@ namespace SimDynamics std::vector<SimDynamics::DynamicsEngine::DynamicsContactInfo> contacts = world->getEngine()->getContacts(); boost::unordered_map<std::string, VirtualRobot::ContactSensor::ContactFrame> frameMap; - for (auto & contact : contacts) + for (auto& contact : contacts) { if (contact.objectAName.empty() || contact.objectBName.empty()) { @@ -724,7 +730,7 @@ namespace SimDynamics } // Update forces and torques - for (auto & sensor : sensors) + for (auto& sensor : sensors) { ForceTorqueSensorPtr ftSensor = boost::dynamic_pointer_cast<ForceTorqueSensor>(sensor); @@ -759,7 +765,7 @@ namespace SimDynamics { MutexLockPtr lock = getScopedLock(); - for (auto & link : links) + for (auto& link : links) { if (link.nodeJoint == node /*|| links[i].nodeJoint2 == node*/) { @@ -775,7 +781,7 @@ namespace SimDynamics { MutexLockPtr lock = getScopedLock(); - for (auto & link : links) + for (auto& link : links) { if ((link.dynNode1 == object1 && link.dynNode2 == object2) || (link.dynNode1 == object2 && link.dynNode2 == object1)) { @@ -792,7 +798,7 @@ namespace SimDynamics MutexLockPtr lock = getScopedLock(); std::vector<BulletRobot::LinkInfo> result; - for (auto & link : links) + for (auto& link : links) { if (link.nodeJoint == node /*|| links[i].nodeJoint2 == node*/ || link.nodeA == node || link.nodeB == node) { @@ -808,7 +814,7 @@ namespace SimDynamics MutexLockPtr lock = getScopedLock(); std::vector<BulletRobot::LinkInfo> result; - for (auto & link : links) + for (auto& link : links) { if (link.dynNode1 == node || link.dynNode2 == node) { @@ -965,7 +971,7 @@ namespace SimDynamics return true; // not a failure, object is not attached } - for (const auto & l : ls) + for (const auto& l : ls) { res = res & removeLink(l); } @@ -978,7 +984,7 @@ namespace SimDynamics { MutexLockPtr lock = getScopedLock(); - for (auto & link : links) + for (auto& link : links) { if (link.nodeJoint == node /*|| links[i].nodeJoint2 == node*/) { @@ -1036,7 +1042,7 @@ namespace SimDynamics } else { - VR_ERROR << "Only Revolute and Prismatic joints implemented so far (node: " << node->getName() <<")..." << endl; + VR_ERROR << "Only Revolute and Prismatic joints implemented so far (node: " << node->getName() << ")..." << endl; } } @@ -1442,7 +1448,7 @@ namespace SimDynamics } } - void BulletRobot::enableForceTorqueFeedback(const LinkInfo& link , bool enable) + void BulletRobot::enableForceTorqueFeedback(const LinkInfo& link, bool enable) { MutexLockPtr lock = getScopedLock(); @@ -1534,7 +1540,7 @@ namespace SimDynamics void BulletRobot::setMaximumMotorImpulse(double maxImpulse) { - bulletMaxMotorImulse = (btScalar)maxImpulse; + bulletMaxMotorImulse = (btScalar)maxImpulse; } double BulletRobot::getMaximumMotorImpulse() const -- GitLab