Skip to content

Commit

Permalink
Implement PlanarJoint (RobotLocomotion#13747)
Browse files Browse the repository at this point in the history
  • Loading branch information
mpetersen94 authored and Duy-Nguyen Ta committed Aug 7, 2020
1 parent 986532e commit e9dde19
Show file tree
Hide file tree
Showing 4 changed files with 714 additions and 0 deletions.
10 changes: 10 additions & 0 deletions multibody/tree/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -103,6 +103,7 @@ drake_cc_library(
"multibody_forces.cc",
"multibody_tree.cc",
"multibody_tree_system.cc",
"planar_joint.cc",
"planar_mobilizer.cc",
"prismatic_joint.cc",
"prismatic_mobilizer.cc",
Expand Down Expand Up @@ -140,6 +141,7 @@ drake_cc_library(
"multibody_tree.h",
"multibody_tree-inl.h",
"multibody_tree_system.h",
"planar_joint.h",
"planar_mobilizer.h",
"prismatic_joint.h",
"prismatic_mobilizer.h",
Expand Down Expand Up @@ -510,6 +512,14 @@ drake_cc_googletest(
],
)

drake_cc_googletest(
name = "planar_joint_test",
deps = [
":tree",
"//common/test_utilities:expect_throws_message",
],
)

drake_cc_googletest(
name = "prismatic_joint_test",
deps = [
Expand Down
69 changes: 69 additions & 0 deletions multibody/tree/planar_joint.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
#include "drake/multibody/tree/planar_joint.h"

#include <memory>

#include "drake/multibody/tree/multibody_tree.h"

namespace drake {
namespace multibody {

template <typename T>
template <typename ToScalar>
std::unique_ptr<Joint<ToScalar>> PlanarJoint<T>::TemplatedDoCloneToScalar(
const internal::MultibodyTree<ToScalar>& tree_clone) const {
const Frame<ToScalar>& frame_on_parent_body_clone =
tree_clone.get_variant(this->frame_on_parent());
const Frame<ToScalar>& frame_on_child_body_clone =
tree_clone.get_variant(this->frame_on_child());

// Make the Joint<T> clone.
auto joint_clone = std::make_unique<PlanarJoint<ToScalar>>(
this->name(), frame_on_parent_body_clone, frame_on_child_body_clone,
this->damping());
joint_clone->set_position_limits(this->position_lower_limits(),
this->position_upper_limits());
joint_clone->set_velocity_limits(this->velocity_lower_limits(),
this->velocity_upper_limits());
joint_clone->set_acceleration_limits(this->acceleration_lower_limits(),
this->acceleration_upper_limits());

return joint_clone;
}

template <typename T>
std::unique_ptr<Joint<double>> PlanarJoint<T>::DoCloneToScalar(
const internal::MultibodyTree<double>& tree_clone) const {
return TemplatedDoCloneToScalar(tree_clone);
}

template <typename T>
std::unique_ptr<Joint<AutoDiffXd>> PlanarJoint<T>::DoCloneToScalar(
const internal::MultibodyTree<AutoDiffXd>& tree_clone) const {
return TemplatedDoCloneToScalar(tree_clone);
}

template <typename T>
std::unique_ptr<Joint<symbolic::Expression>> PlanarJoint<T>::DoCloneToScalar(
const internal::MultibodyTree<symbolic::Expression>& tree_clone) const {
return TemplatedDoCloneToScalar(tree_clone);
}

// N.B. Due to esoteric linking errors on Mac (see #9345) involving
// `MobilizerImpl`, we must place this implementation in the source file, not
// in the header file.
template <typename T>
std::unique_ptr<typename Joint<T>::BluePrint>
PlanarJoint<T>::MakeImplementationBlueprint() const {
auto blue_print = std::make_unique<typename Joint<T>::BluePrint>();
auto planar_mobilizer = std::make_unique<internal::PlanarMobilizer<T>>(
this->frame_on_parent(), this->frame_on_child());
planar_mobilizer->set_default_position(this->default_positions());
blue_print->mobilizers_.push_back(std::move(planar_mobilizer));
return blue_print;
}

} // namespace multibody
} // namespace drake

DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS(
class ::drake::multibody::PlanarJoint)
Loading

0 comments on commit e9dde19

Please sign in to comment.