//============================================================================== TEST(SkelParser, JointDynamicsElements) { WorldPtr world = SkelParser::readWorld( DART_DATA_PATH"/skel/test/joint_dynamics_elements_test.skel"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel1 = world->getSkeleton("skeleton 1"); Joint* joint0 = skel1->getJoint("joint0"); EXPECT_EQ(joint0->getDampingCoefficient(0), 1.0); EXPECT_EQ(joint0->getCoulombFriction (0), 5.0); EXPECT_EQ(joint0->getRestPosition (0), 0.1); EXPECT_EQ(joint0->getSpringStiffness (0), 3.0); Joint* joint1 = skel1->getJoint("joint1"); EXPECT_EQ(joint1->getDampingCoefficient(0), 1.0); EXPECT_EQ(joint1->getCoulombFriction (0), 5.0); EXPECT_EQ(joint1->getRestPosition (0), 0.1); EXPECT_EQ(joint1->getSpringStiffness (0), 3.0); EXPECT_EQ(joint1->getDampingCoefficient(1), 2.0); EXPECT_EQ(joint1->getCoulombFriction (1), 4.0); EXPECT_EQ(joint1->getRestPosition (1), 0.2); EXPECT_EQ(joint1->getSpringStiffness (1), 2.0); EXPECT_EQ(joint1->getDampingCoefficient(2), 3.0); EXPECT_EQ(joint1->getCoulombFriction (2), 3.0); EXPECT_EQ(joint1->getRestPosition (2), 0.3); EXPECT_EQ(joint1->getSpringStiffness (2), 1.0); }
//============================================================================== TEST(SKEL_PARSER, JointActuatorType) { WorldPtr world = SkelParser::readWorld( DART_DATA_PATH"/skel/test/joint_actuator_type_test.skel"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel1 = world->getSkeleton("skeleton 1"); EXPECT_TRUE(skel1 != nullptr); // Test for no actuator type attribute being specified Joint* joint0 = skel1->getJoint("joint0"); EXPECT_EQ(joint0->getActuatorType(), Joint::DefaultActuatorType); EXPECT_EQ(joint0->getActuatorType(), Joint::FORCE); // Test for when actuator type attribute are specified Joint* joint1 = skel1->getJoint("joint1"); EXPECT_EQ(joint1->getActuatorType(), Joint::FORCE); // Test for only a dof name being changed Joint* joint2 = skel1->getJoint("joint2"); EXPECT_EQ(joint2->getActuatorType(), Joint::PASSIVE); joint2->setActuatorType(Joint::FORCE); EXPECT_EQ(joint2->getActuatorType(), Joint::FORCE); // Test for when actuator type attribute are specified Joint* joint3 = skel1->getJoint("joint3"); EXPECT_EQ(joint3->getActuatorType(), Joint::ACCELERATION); // Test for when actuator type attribute are specified Joint* joint4 = skel1->getJoint("joint4"); EXPECT_EQ(joint4->getActuatorType(), Joint::VELOCITY);}
SimulationWorld(WorldPtr world, const std::vector<Eigen::VectorXd>& trajectory) : osgDart::WorldNode(world), mTrajectory(trajectory) { mHubo = world->getSkeleton("drchubo"); double height = mHubo->getPosition(5); mHubo->setPositions(mTrajectory[0]); mHubo->setPosition(5, height); // index = 0; }
// Load a biped model and enable joint limits and self-collision SkeletonPtr loadBiped() { // Lesson 1 // Create the world with a skeleton WorldPtr world = SkelParser::readWorld("dart://sample/skel/biped.skel"); assert(world != nullptr); SkeletonPtr biped = world->getSkeleton("biped"); return biped; }
// Load a skateboard model and connect it to the biped model via an Euler joint // (Lesson 5 Answer) void modifyBipedWithSkateboard(SkeletonPtr biped) { // Load the Skeleton from a file WorldPtr world = SkelParser::readWorld("dart://sample/skel/skateboard.skel"); SkeletonPtr skateboard = world->getSkeleton(0); EulerJoint::Properties properties = EulerJoint::Properties(); properties.mT_ChildBodyToJoint.translation() = Eigen::Vector3d(0, 0.1, 0); skateboard->getRootBodyNode()->moveTo<EulerJoint> (biped->getBodyNode("h_heel_left"), properties); }
// Load a biped model and enable joint limits and self-collision // (Lesson 1 Answer) SkeletonPtr loadBiped() { // Create the world with a skeleton WorldPtr world = SkelParser::readWorld(DART_DATA_PATH"skel/biped.skel"); assert(world != nullptr); SkeletonPtr biped = world->getSkeleton("biped"); // Set joint limits for(size_t i = 0; i < biped->getNumJoints(); ++i) biped->getJoint(i)->setPositionLimitEnforced(true); // Enable self collision check but ignore adjacent bodies biped->enableSelfCollision(); return biped; }
//============================================================================== TEST(SkelParser, SerialChain) { WorldPtr world = SkelParser::readWorld( DART_DATA_PATH"skel/test/serial_chain_ball_joint.skel"); EXPECT_TRUE(world != nullptr); EXPECT_EQ(world->getTimeStep(), 0.001); EXPECT_EQ(world->getGravity()(0), 0); EXPECT_EQ(world->getGravity()(1), -9.81); EXPECT_EQ(world->getGravity()(2), 0); EXPECT_EQ(static_cast<int>(world->getNumSkeletons()), 1); SkeletonPtr skel1 = world->getSkeleton("skeleton 1"); EXPECT_EQ(static_cast<int>(skel1->getNumBodyNodes()), 10); world->step(); }
//============================================================================== TEST(SkelParser, SinglePendulum) { WorldPtr world = SkelParser::readWorld( DART_DATA_PATH"skel/test/single_pendulum.skel"); EXPECT_TRUE(world != nullptr); EXPECT_EQ(world->getTimeStep(), 0.001); EXPECT_EQ(world->getGravity()(0), 0); EXPECT_EQ(world->getGravity()(1), -9.81); EXPECT_EQ(world->getGravity()(2), 0); EXPECT_EQ(static_cast<int>(world->getNumSkeletons()), 1); SkeletonPtr skel1 = world->getSkeleton("single_pendulum"); EXPECT_EQ(static_cast<int>(skel1->getNumBodyNodes()), 1); world->step(); }
std::vector<SkeletonPtr> getSkeletons() { std::vector<std::string> fileList = getFileList(); std::vector<WorldPtr> worlds; for(size_t i=0; i<fileList.size(); ++i) worlds.push_back(utils::SkelParser::readWorld(fileList[i])); std::vector<SkeletonPtr> skeletons; for(size_t i=0; i<worlds.size(); ++i) { WorldPtr world = worlds[i]; for(size_t j=0; j<world->getNumSkeletons(); ++j) skeletons.push_back(world->getSkeleton(j)); } return skeletons; }
/// Constructor MyWindow(WorldPtr world) : mBallConstraint(nullptr), mPositiveSign(true), mBodyForce(false) { setWorld(world); // Find the Skeleton named "pendulum" within the World mPendulum = world->getSkeleton("pendulum"); // Make sure that the pendulum was found in the World assert(mPendulum != nullptr); mForceCountDown.resize(mPendulum->getNumDofs(), 0); ArrowShape::Properties arrow_properties; arrow_properties.mRadius = 0.05; mArrow = std::shared_ptr<ArrowShape>(new ArrowShape( Eigen::Vector3d(-default_height, 0.0, default_height / 2.0), Eigen::Vector3d(-default_width / 2.0, 0.0, default_height / 2.0), arrow_properties, dart::Color::Orange(1.0))); }
//============================================================================== TEST(SdfParser, SDFSingleBodyWithoutJoint) { // Regression test for #444 WorldPtr world = SdfParser::readSdfFile( DART_DATA_PATH"/sdf/test/single_bodynode_skeleton.world"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel = world->getSkeleton(0); EXPECT_TRUE(skel != nullptr); EXPECT_EQ(skel->getNumBodyNodes(), 1u); EXPECT_EQ(skel->getNumJoints(), 1u); BodyNodePtr bodyNode = skel->getBodyNode(0); EXPECT_TRUE(bodyNode != nullptr); EXPECT_EQ(bodyNode->getNumVisualizationShapes(), 1u); EXPECT_EQ(bodyNode->getNumCollisionShapes(), 1u); JointPtr joint = skel->getJoint(0); EXPECT_TRUE(joint != nullptr); EXPECT_EQ(joint->getType(), FreeJoint::getStaticType()); }
//============================================================================== TEST(SkelParser, RigidAndSoftBodies) { using namespace dart; using namespace math; using namespace dynamics; using namespace simulation; using namespace utils; WorldPtr world = SkelParser::readWorld( DART_DATA_PATH"skel/test/test_articulated_bodies.skel"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel1 = world->getSkeleton("skeleton 1"); EXPECT_TRUE(skel1 != nullptr); EXPECT_EQ(static_cast<int>(skel1->getNumBodyNodes()), 2); EXPECT_EQ(static_cast<int>(skel1->getNumRigidBodyNodes()), 1); EXPECT_EQ(static_cast<int>(skel1->getNumSoftBodyNodes()), 1); SoftBodyNode* sbn = skel1->getSoftBodyNode(0); EXPECT_TRUE(static_cast<int>(sbn->getNumPointMasses()) > 0); world->step(); }
//============================================================================== TEST(SkelParser, DofAttributes) { WorldPtr world = SkelParser::readWorld( DART_DATA_PATH"/skel/test/dof_attribute_test.skel"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel1 = world->getSkeleton("skeleton 1"); // Test for no dof elements being specified Joint* joint0 = skel1->getJoint("joint0"); EXPECT_EQ(joint0->getDof(0)->getPositionLowerLimit(), -DART_DBL_INF); EXPECT_EQ(joint0->getDof(0)->getPositionUpperLimit(), DART_DBL_INF); EXPECT_EQ(joint0->getDof(0)->getPosition(), 0); EXPECT_EQ(joint0->getDof(0)->getVelocityLowerLimit(), -DART_DBL_INF); EXPECT_EQ(joint0->getDof(0)->getVelocityUpperLimit(), DART_DBL_INF); EXPECT_EQ(joint0->getDof(0)->getVelocity(), 0); EXPECT_EQ(joint0->getDof(0)->getName(), joint0->getName()); // Test for only a dof name being changed Joint* joint1 = skel1->getJoint("joint1"); EXPECT_EQ(joint1->getDof(0)->getPositionLowerLimit(), -1.57); EXPECT_EQ(joint1->getDof(0)->getPositionUpperLimit(), 1.57); EXPECT_EQ(joint1->getDof(0)->getName(), "customJoint1"); // Test for when dof attributes (but not a name) are specified Joint* joint2 = skel1->getJoint("joint2"); EXPECT_EQ(joint2->getDof(0)->getName(), joint2->getName()); EXPECT_EQ(joint2->getDof(0)->getPositionLowerLimit(), -1); EXPECT_EQ(joint2->getDof(0)->getPositionUpperLimit(), 1); EXPECT_EQ(joint2->getDof(0)->getPosition(), 0); EXPECT_EQ(joint2->getDof(0)->getVelocityLowerLimit(), -2); EXPECT_EQ(joint2->getDof(0)->getVelocityUpperLimit(), 2); EXPECT_EQ(joint2->getDof(0)->getVelocity(), 0); EXPECT_EQ(joint2->getDof(0)->getAccelerationLowerLimit(), -3); EXPECT_EQ(joint2->getDof(0)->getAccelerationUpperLimit(), 3); EXPECT_EQ(joint2->getDof(0)->getAcceleration(), 0); EXPECT_EQ(joint2->getDof(0)->getForceLowerLimit(), -4); EXPECT_EQ(joint2->getDof(0)->getForceUpperLimit(), 4); EXPECT_EQ(joint2->getDof(0)->getForce(), 0); // Test for mixture of old method and new method // Note: If there is a conflict, the data given in the dof element will win Joint* joint3 = skel1->getJoint("joint3"); EXPECT_EQ(joint3->getDof(0)->getName(), joint3->getName() + "_1"); EXPECT_EQ(joint3->getDof(0)->getPositionLowerLimit(), -1); EXPECT_EQ(joint3->getDof(0)->getPositionUpperLimit(), 1); EXPECT_EQ(joint3->getDof(0)->getPosition(), 5); EXPECT_EQ(joint3->getDof(1)->getName(), joint3->getName() + "_2"); EXPECT_EQ(joint3->getDof(1)->getPositionLowerLimit(), -2); EXPECT_EQ(joint3->getDof(1)->getPositionUpperLimit(), 2); EXPECT_EQ(joint3->getDof(1)->getPosition(), -5); // Test for only some of the DOFs being specified Joint* joint4 = skel1->getJoint("joint4"); EXPECT_EQ(joint4->getDof(0)->getName(), "joint4_1"); EXPECT_EQ(joint4->getDof(0)->getPositionLowerLimit(), -1); EXPECT_EQ(joint4->getDof(0)->getPositionUpperLimit(), 1); EXPECT_EQ(joint4->getDof(0)->getVelocityLowerLimit(), -10); EXPECT_EQ(joint4->getDof(0)->getVelocityUpperLimit(), 10); EXPECT_EQ(joint4->getDof(1)->getName(), joint4->getName() + "_y"); EXPECT_EQ(joint4->getDof(2)->getName(), "joint4_3"); EXPECT_EQ(joint4->getDof(2)->getPositionLowerLimit(), -2); EXPECT_EQ(joint4->getDof(2)->getPositionUpperLimit(), 2); EXPECT_EQ(joint4->getDof(2)->getVelocityLowerLimit(), -20); EXPECT_EQ(joint4->getDof(2)->getVelocityUpperLimit(), 20); }
//============================================================================== TEST(SkelParser, PlanarJoint) { using namespace dart; using namespace math; using namespace dynamics; using namespace simulation; using namespace utils; WorldPtr world = SkelParser::readWorld( DART_DATA_PATH"skel/test/planar_joint.skel"); EXPECT_TRUE(world != nullptr); SkeletonPtr skel1 = world->getSkeleton("skeleton1"); EXPECT_TRUE(skel1 != nullptr); BodyNode* body1 = skel1->getBodyNode("link1"); BodyNode* body2 = skel1->getBodyNode("link2"); BodyNode* body3 = skel1->getBodyNode("link3"); BodyNode* body4 = skel1->getBodyNode("link4"); EXPECT_TRUE(body1 != nullptr); EXPECT_TRUE(body2 != nullptr); EXPECT_TRUE(body3 != nullptr); EXPECT_TRUE(body4 != nullptr); PlanarJoint* planarJoint1 = dynamic_cast<PlanarJoint*>(body1->getParentJoint()); PlanarJoint* planarJoint2 = dynamic_cast<PlanarJoint*>(body2->getParentJoint()); PlanarJoint* planarJoint3 = dynamic_cast<PlanarJoint*>(body3->getParentJoint()); PlanarJoint* planarJoint4 = dynamic_cast<PlanarJoint*>(body4->getParentJoint()); EXPECT_TRUE(planarJoint1 != nullptr); EXPECT_TRUE(planarJoint2 != nullptr); EXPECT_TRUE(planarJoint3 != nullptr); EXPECT_TRUE(planarJoint4 != nullptr); EXPECT_EQ(planarJoint1->getPlaneType(), PlanarJoint::PT_XY); EXPECT_EQ(planarJoint2->getPlaneType(), PlanarJoint::PT_YZ); EXPECT_EQ(planarJoint3->getPlaneType(), PlanarJoint::PT_ZX); EXPECT_EQ(planarJoint4->getPlaneType(), PlanarJoint::PT_ARBITRARY); EXPECT_EQ(planarJoint1->getTranslationalAxis1(), Eigen::Vector3d::UnitX()); EXPECT_EQ(planarJoint2->getTranslationalAxis1(), Eigen::Vector3d::UnitY()); EXPECT_EQ(planarJoint3->getTranslationalAxis1(), Eigen::Vector3d::UnitZ()); EXPECT_EQ(planarJoint4->getTranslationalAxis1(), Eigen::Vector3d::UnitX()); EXPECT_EQ(planarJoint1->getTranslationalAxis2(), Eigen::Vector3d::UnitY()); EXPECT_EQ(planarJoint2->getTranslationalAxis2(), Eigen::Vector3d::UnitZ()); EXPECT_EQ(planarJoint3->getTranslationalAxis2(), Eigen::Vector3d::UnitX()); EXPECT_EQ(planarJoint4->getTranslationalAxis2(), Eigen::Vector3d::UnitY()); EXPECT_EQ(planarJoint1->getRotationalAxis(), Eigen::Vector3d::UnitZ()); EXPECT_EQ(planarJoint2->getRotationalAxis(), Eigen::Vector3d::UnitX()); EXPECT_EQ(planarJoint3->getRotationalAxis(), Eigen::Vector3d::UnitY()); EXPECT_EQ(planarJoint4->getRotationalAxis(), Eigen::Vector3d::UnitZ()); EXPECT_EQ(planarJoint1->getPositions(), Eigen::Vector3d(1, 2, 3)); EXPECT_EQ(planarJoint2->getPositions(), Eigen::Vector3d(1, 2, 3)); EXPECT_EQ(planarJoint3->getPositions(), Eigen::Vector3d(1, 2, 3)); EXPECT_EQ(planarJoint4->getPositions(), Eigen::Vector3d(1, 2, 3)); EXPECT_EQ(planarJoint1->getVelocities(), Eigen::Vector3d(4, 5, 6)); EXPECT_EQ(planarJoint2->getVelocities(), Eigen::Vector3d(4, 5, 6)); EXPECT_EQ(planarJoint3->getVelocities(), Eigen::Vector3d(4, 5, 6)); EXPECT_EQ(planarJoint4->getVelocities(), Eigen::Vector3d(4, 5, 6)); EXPECT_EQ(planarJoint1->getDampingCoefficient(0), 1); EXPECT_EQ(planarJoint2->getDampingCoefficient(0), 1); EXPECT_EQ(planarJoint3->getDampingCoefficient(0), 1); EXPECT_EQ(planarJoint4->getDampingCoefficient(0), 1); EXPECT_EQ(planarJoint1->getDampingCoefficient(1), 2); EXPECT_EQ(planarJoint2->getDampingCoefficient(1), 2); EXPECT_EQ(planarJoint3->getDampingCoefficient(1), 2); EXPECT_EQ(planarJoint4->getDampingCoefficient(1), 2); EXPECT_EQ(planarJoint1->getDampingCoefficient(2), 3); EXPECT_EQ(planarJoint2->getDampingCoefficient(2), 3); EXPECT_EQ(planarJoint3->getDampingCoefficient(2), 3); EXPECT_EQ(planarJoint4->getDampingCoefficient(2), 3); EXPECT_EQ(planarJoint1->getPositionLowerLimit(0), -1.0); EXPECT_EQ(planarJoint2->getPositionLowerLimit(0), -1.0); EXPECT_EQ(planarJoint3->getPositionLowerLimit(0), -1.0); EXPECT_EQ(planarJoint4->getPositionLowerLimit(0), -1.0); EXPECT_EQ(planarJoint1->getPositionUpperLimit(0), +1.0); EXPECT_EQ(planarJoint2->getPositionUpperLimit(0), +1.0); EXPECT_EQ(planarJoint3->getPositionUpperLimit(0), +1.0); EXPECT_EQ(planarJoint4->getPositionUpperLimit(0), +1.0); EXPECT_EQ(planarJoint1->getPositionLowerLimit(1), -2.0); EXPECT_EQ(planarJoint2->getPositionLowerLimit(1), -2.0); EXPECT_EQ(planarJoint3->getPositionLowerLimit(1), -2.0); EXPECT_EQ(planarJoint4->getPositionLowerLimit(1), -2.0); EXPECT_EQ(planarJoint1->getPositionUpperLimit(1), +2.0); EXPECT_EQ(planarJoint2->getPositionUpperLimit(1), +2.0); EXPECT_EQ(planarJoint3->getPositionUpperLimit(1), +2.0); EXPECT_EQ(planarJoint4->getPositionUpperLimit(1), +2.0); EXPECT_EQ(planarJoint1->getPositionLowerLimit(2), -3.0); EXPECT_EQ(planarJoint2->getPositionLowerLimit(2), -3.0); EXPECT_EQ(planarJoint3->getPositionLowerLimit(2), -3.0); EXPECT_EQ(planarJoint4->getPositionLowerLimit(2), -3.0); EXPECT_EQ(planarJoint1->getPositionUpperLimit(2), +3.0); EXPECT_EQ(planarJoint2->getPositionUpperLimit(2), +3.0); EXPECT_EQ(planarJoint3->getPositionUpperLimit(2), +3.0); EXPECT_EQ(planarJoint4->getPositionUpperLimit(2), +3.0); world->step(); }