Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Parse screw joints from SDFormat #18127

Merged
merged 2 commits into from
Oct 24, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
23 changes: 17 additions & 6 deletions multibody/parsing/detail_sdf_parser.cc
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@
#include "drake/multibody/tree/prismatic_joint.h"
#include "drake/multibody/tree/revolute_joint.h"
#include "drake/multibody/tree/revolute_spring.h"
#include "drake/multibody/tree/screw_joint.h"
#include "drake/multibody/tree/spatial_inertia.h"
#include "drake/multibody/tree/uniform_gravity_field_element.h"
#include "drake/multibody/tree/universal_joint.h"
Expand Down Expand Up @@ -311,6 +312,7 @@ Vector3d ExtractJointAxis(
const sdf::Joint& joint_spec) {
unused(model_spec);
DRAKE_DEMAND(joint_spec.Type() == sdf::JointType::REVOLUTE ||
joint_spec.Type() == sdf::JointType::SCREW ||
joint_spec.Type() == sdf::JointType::PRISMATIC ||
joint_spec.Type() == sdf::JointType::CONTINUOUS);

Expand Down Expand Up @@ -358,6 +360,7 @@ double ParseJointDamping(
const sdf::Joint& joint_spec) {
DRAKE_DEMAND(joint_spec.Type() == sdf::JointType::REVOLUTE ||
joint_spec.Type() == sdf::JointType::PRISMATIC ||
joint_spec.Type() == sdf::JointType::SCREW ||
joint_spec.Type() == sdf::JointType::UNIVERSAL ||
joint_spec.Type() == sdf::JointType::BALL ||
joint_spec.Type() == sdf::JointType::CONTINUOUS);
Expand Down Expand Up @@ -425,6 +428,7 @@ void AddJointActuatorFromSpecification(
MultibodyPlant<double>* plant) {
DRAKE_THROW_UNLESS(plant != nullptr);
DRAKE_DEMAND(joint_spec.Type() == sdf::JointType::BALL ||
joint_spec.Type() == sdf::JointType::SCREW ||
joint_spec.Type() == sdf::JointType::UNIVERSAL ||
joint_spec.Type() == sdf::JointType::PRISMATIC ||
joint_spec.Type() == sdf::JointType::REVOLUTE ||
Expand Down Expand Up @@ -463,7 +467,7 @@ void AddJointActuatorFromSpecification(
return;
}

// Prismatic, revolute, and continuous joints have a single axis.
// Prismatic, screw, revolute, and continuous joints have a single axis.
const double effort_limit = GetEffortLimit(diagnostic, joint_spec, 0);
if (effort_limit != 0) {
const JointActuator<double>& actuator =
Expand Down Expand Up @@ -602,7 +606,8 @@ void AddJointFromSpecification(
"drake:rotor_inertia",
"drake:gear_ratio",
"parent",
"pose"};
"pose",
"screw_thread_pitch"};
CheckSupportedElements(diagnostic, joint_spec.Element(),
supported_joint_elements);

Expand Down Expand Up @@ -762,10 +767,16 @@ void AddJointFromSpecification(
break;
}
case sdf::JointType::SCREW: {
// TODO(jwnimmer-tri) Use a multibody::ScrewJoint here.
diagnostic.Error(fmt::format(
"Joint type (screw) not supported for joint '{}'.",
joint_spec.Name()));
const double damping = ParseJointDamping(diagnostic, joint_spec);
// The ScrewThreadPitch() API uses the same representation as
// Drake's ScrewJoint class (meters / revolution, right-handed).
const double screw_thread_pitch = joint_spec.ScrewThreadPitch();
Vector3d axis_J = ExtractJointAxis(diagnostic, model_spec, joint_spec);
const auto& joint = plant->AddJoint<ScrewJoint>(
joint_spec.Name(),
parent_body, X_PJ,
child_body, X_CJ, axis_J, screw_thread_pitch, damping);
AddJointActuatorFromSpecification(diagnostic, joint_spec, joint, plant);
break;
}
case sdf::JointType::GEARBOX: {
Expand Down
38 changes: 23 additions & 15 deletions multibody/parsing/test/detail_sdf_parser_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
#include "drake/multibody/tree/revolute_joint.h"
#include "drake/multibody/tree/revolute_spring.h"
#include "drake/multibody/tree/rigid_body.h"
#include "drake/multibody/tree/screw_joint.h"
#include "drake/multibody/tree/universal_joint.h"
#include "drake/systems/framework/context.h"

Expand Down Expand Up @@ -986,6 +987,28 @@ TEST_F(SdfParserTest, JointParsingTest) {
CompareMatrices(continuous_joint.acceleration_lower_limits(), neg_inf));
EXPECT_TRUE(
CompareMatrices(continuous_joint.acceleration_upper_limits(), inf));

// Screw joint
DRAKE_EXPECT_NO_THROW(
plant_.GetJointByName<ScrewJoint>("screw_joint", instance1));
const ScrewJoint<double>& screw_joint =
plant_.GetJointByName<ScrewJoint>("screw_joint", instance1);
EXPECT_EQ(screw_joint.name(), "screw_joint");
EXPECT_EQ(screw_joint.parent_body().name(), "link8");
EXPECT_EQ(screw_joint.child_body().name(), "link9");
EXPECT_EQ(screw_joint.screw_axis(), Vector3d::UnitX());
EXPECT_EQ(screw_joint.screw_pitch(), 0.04);
EXPECT_EQ(screw_joint.damping(), 0.1);
EXPECT_TRUE(
CompareMatrices(screw_joint.position_lower_limits(), neg_inf));
EXPECT_TRUE(CompareMatrices(screw_joint.position_upper_limits(), inf));
EXPECT_TRUE(
CompareMatrices(screw_joint.velocity_lower_limits(), neg_inf));
EXPECT_TRUE(CompareMatrices(screw_joint.velocity_upper_limits(), inf));
EXPECT_TRUE(
CompareMatrices(screw_joint.acceleration_lower_limits(), neg_inf));
EXPECT_TRUE(
CompareMatrices(screw_joint.acceleration_upper_limits(), inf));
}

// Tests the error handling for an unsupported joint type (when actuated).
Expand Down Expand Up @@ -1116,21 +1139,6 @@ TEST_F(SdfParserTest, ActuatedBallJointParsingTest) {
ClearDiagnostics();
}

// Tests the error handling for an unsupported joint type.
TEST_F(SdfParserTest, ScrewJointParsingTest) {
ParseTestString(R"""(
<model name="molly">
<link name="larry" />
<joint name="jerry" type="screw">
<parent>world</parent>
<child>larry</child>
</joint>
</model>)""");
EXPECT_THAT(FormatFirstError(), ::testing::MatchesRegex(
".*screw.*not supported.*jerry.*"));
ClearDiagnostics();
}

// Tests the error handling for an unsupported joint type.
TEST_F(SdfParserTest, GearboxJointParsingTest) {
ParseTestString(R"""(
Expand Down
26 changes: 25 additions & 1 deletion multibody/parsing/test/sdf_parser_test/joint_parsing_test.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<!--
Defines an SDF model with various types of joints used for testing the parser.
-->
<sdf xmlns:drake="http://drake.mit.edu" version="1.7">
<sdf xmlns:drake="http://drake.mit.edu" version="1.10">
<world name="joint_parsing_test_world">
<model name="joint_parsing_test">
<link name="link1">
Expand Down Expand Up @@ -217,6 +217,30 @@ Defines an SDF model with various types of joints used for testing the parser.
</dynamics>
</axis>
</joint>
<link name="link9">
<inertial>
<mass>1</mass>
<inertia>
<ixx>0.1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1</iyy>
<iyz>0</iyz>
<izz>0.1</izz>
</inertia>
</inertial>
</link>
<joint name="screw_joint" type="screw">
<child>link9</child>
<parent>link8</parent>
<screw_thread_pitch>0.04</screw_thread_pitch>
<axis>
<xyz expressed_in="__model__">1 0 0</xyz>
<dynamics>
<damping>0.1</damping>
</dynamics>
</axis>
</joint>
</model>
<model name="joint_parsing_test2">
<link name="link6">
Expand Down
4 changes: 2 additions & 2 deletions tools/workspace/sdformat_internal/repository.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,9 @@ def sdformat_internal_repository(
github_archive(
name = name,
repository = "gazebosim/sdformat",
commit = "sdformat13_13.1.0",
commit = "sdformat13_13.2.0",
build_file = ":package.BUILD.bazel",
sha256 = "4b40bf64bc7d3f22c89a2395c2802d5315a3fd5e5dbaf29b087c5c806180a9db", # noqa
sha256 = "e1084091f65caf8aabd4cfca6df3a7bf3a9563de1715829810813840598d5de3", # noqa
patches = [
":patches/console.patch",
":patches/deprecation_unit_testing.patch",
Expand Down