diff --git a/dartsim/src/JointFeatures.cc b/dartsim/src/JointFeatures.cc index c15152d01..f1ea1b2cd 100644 --- a/dartsim/src/JointFeatures.cc +++ b/dartsim/src/JointFeatures.cc @@ -67,22 +67,57 @@ Pose3d JointFeatures::GetJointTransform(const Identity &_id) const void JointFeatures::SetJointPosition( const Identity &_id, const std::size_t _dof, const double _value) { - this->ReferenceInterface(_id)->joint->setPosition(_dof, _value); + auto joint = this->ReferenceInterface(_id)->joint; + + // 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 + if (!std::isfinite(_value)) + { + ignerr << "Invalid joint position value [" << _value << "] set on joint [" + << joint->getName() << " DOF " << _dof + << "]. The value will be ignored\n"; + return; + } + joint->setPosition(_dof, _value); } ///////////////////////////////////////////////// void JointFeatures::SetJointVelocity( const Identity &_id, const std::size_t _dof, const double _value) { - this->ReferenceInterface(_id)->joint->setVelocity(_dof, _value); + auto joint = this->ReferenceInterface(_id)->joint; + + // 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 + if (!std::isfinite(_value)) + { + ignerr << "Invalid joint velocity value [" << _value << "] set on joint [" + << joint->getName() << " DOF " << _dof + << "]. The value will be ignored\n"; + return; + } + joint->setVelocity(_dof, _value); } ///////////////////////////////////////////////// void JointFeatures::SetJointAcceleration( const Identity &_id, const std::size_t _dof, const double _value) { - this->ReferenceInterface(_id)->joint->setAcceleration(_dof, - _value); + auto joint = this->ReferenceInterface(_id)->joint; + + // 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 + if (!std::isfinite(_value)) + { + ignerr << "Invalid joint acceleration value [" << _value + << "] set on joint [" << joint->getName() << " DOF " << _dof + << "]. The value will be ignored\n"; + return; + } + joint->setAcceleration(_dof, _value); } ///////////////////////////////////////////////// @@ -90,6 +125,17 @@ void JointFeatures::SetJointForce( const Identity &_id, const std::size_t _dof, const double _value) { auto joint = this->ReferenceInterface(_id)->joint; + + // 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 + if (!std::isfinite(_value)) + { + ignerr << "Invalid joint force value [" << _value << "] set on joint [" + << joint->getName() << " DOF " << _dof + << "]. The value will be ignored\n"; + return; + } if (joint->getActuatorType() != dart::dynamics::Joint::FORCE) { joint->setActuatorType(dart::dynamics::Joint::FORCE); @@ -102,6 +148,17 @@ void JointFeatures::SetJointVelocityCommand( const Identity &_id, const std::size_t _dof, const double _value) { auto joint = this->ReferenceInterface(_id)->joint; + + // 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 + if (!std::isfinite(_value)) + { + ignerr << "Invalid joint velocity value [" << _value + << "] commanded on joint [" << joint->getName() << " DOF " << _dof + << "]. The command will be ignored\n"; + return; + } if (joint->getActuatorType() != dart::dynamics::Joint::SERVO) { joint->setActuatorType(dart::dynamics::Joint::SERVO); diff --git a/dartsim/src/JointFeatures_TEST.cc b/dartsim/src/JointFeatures_TEST.cc index f64e9aa7f..3d30b2429 100644 --- a/dartsim/src/JointFeatures_TEST.cc +++ b/dartsim/src/JointFeatures_TEST.cc @@ -40,6 +40,7 @@ #include #include +#include #include #include #include @@ -58,6 +59,7 @@ using TestFeatureList = ignition::physics::FeatureList< physics::GetBasicJointState, physics::GetEntities, physics::RevoluteJointCast, + physics::SetBasicJointState, physics::SetJointVelocityCommandFeature, physics::sdf::ConstructSdfModel, physics::sdf::ConstructSdfWorld @@ -105,6 +107,8 @@ TEST_F(JointFeaturesFixture, JointSetCommand) dartWorld->getSkeleton(modelName); ASSERT_NE(nullptr, skeleton); + const auto *dartBaseLink = skeleton->getBodyNode("base"); + ASSERT_NE(nullptr, dartBaseLink); const auto *dartJoint = skeleton->getJoint(jointName); // Default actuatore type @@ -119,6 +123,15 @@ TEST_F(JointFeaturesFixture, JointSetCommand) world->Step(output, state, input); EXPECT_LT(joint->GetVelocity(0), 0.0); + // Check that invalid velocity commands don't cause collisions to fail + for (std::size_t i = 0; i < 1000; ++i) + { + joint->SetForce(0, std::numeric_limits::quiet_NaN()); + // expect the position of the pendulum to stay aabove ground + world->Step(output, state, input); + EXPECT_NEAR(0.0, dartBaseLink->getWorldTransform().translation().z(), 1e-3); + } + joint->SetVelocityCommand(0, 1); world->Step(output, state, input); // Setting a velocity command changes the actuator type to SERVO @@ -139,6 +152,15 @@ TEST_F(JointFeaturesFixture, JointSetCommand) world->Step(output, state, input); EXPECT_NEAR(0.0, joint->GetVelocity(0), 1e-6); } + + // Check that invalid velocity commands don't cause collisions to fail + for (std::size_t i = 0; i < 1000; ++i) + { + joint->SetVelocityCommand(0, std::numeric_limits::quiet_NaN()); + // expect the position of the pendulum to stay aabove ground + world->Step(output, state, input); + EXPECT_NEAR(0.0, dartBaseLink->getWorldTransform().translation().z(), 1e-3); + } } // Test detaching joints.