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

Make joint store default value #13105

Merged
merged 4 commits into from
Apr 27, 2020
Merged
Show file tree
Hide file tree
Changes from 2 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
7 changes: 4 additions & 3 deletions multibody/tree/ball_rpy_joint.cc
Original file line number Diff line number Diff line change
Expand Up @@ -56,9 +56,10 @@ template <typename T>
std::unique_ptr<typename Joint<T>::BluePrint>
BallRpyJoint<T>::MakeImplementationBlueprint() const {
auto blue_print = std::make_unique<typename Joint<T>::BluePrint>();
blue_print->mobilizers_.push_back(
std::make_unique<internal::SpaceXYZMobilizer<T>>(this->frame_on_parent(),
this->frame_on_child()));
auto ballrpy_mobilizer = std::make_unique<internal::SpaceXYZMobilizer<T>>(
this->frame_on_parent(), this->frame_on_child());
ballrpy_mobilizer->set_default_position(this->default_positions());
blue_print->mobilizers_.push_back(std::move(ballrpy_mobilizer));
return std::move(blue_print);
}

Expand Down
25 changes: 19 additions & 6 deletions multibody/tree/ball_rpy_joint.h
Original file line number Diff line number Diff line change
Expand Up @@ -132,12 +132,6 @@ class BallRpyJoint final : public Joint<T> {
return *this;
}

/// Sets the default angles of this joint. See get_angles() for details on
/// the angle representation.
void set_default_angles(const Vector3<double>& angles) {
get_mutable_mobilizer()->set_default_position(angles);
}

/// Sets the random distribution that angles of this joint will be randomly
/// sampled from. See get_angles() for details on the angle representation.
void set_random_angles_distribution(
Expand Down Expand Up @@ -176,6 +170,25 @@ class BallRpyJoint final : public Joint<T> {

/// @}

/// Gets the default angles for `this` joint. Wrapper for the more general
/// `Joint::default_positions()`.
/// @returns The default angles of `this` stored in `default_positions_`
Vector3<double> get_default_angles() const {
return this->default_positions();
}

/// Sets the default angles of this joint.
/// If the parent tree has been finalized and the underlying mobilizer is
/// valid, this method sets the default positions of that mobilizer.
/// @param[in] angles
/// The desired default angles of the joint
void set_default_angles(const Vector3<double>& angles) {
this->set_default_positions(angles);
if (this->has_implementation()) {
get_mutable_mobilizer()->set_default_position(this->default_positions());
}
}

protected:
/// Joint<T> override called through public NVI, Joint::AddInForce().
/// Adding forces per-dof makes no physical sense. Therefore, this method
Expand Down
43 changes: 39 additions & 4 deletions multibody/tree/joint.h
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ namespace multibody {
///
/// @tparam_default_scalar
template <typename T>
class Joint : public MultibodyElement<Joint, T, JointIndex> {
class Joint : public MultibodyElement<Joint, T, JointIndex> {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(Joint)

Expand Down Expand Up @@ -118,7 +118,7 @@ class Joint : public MultibodyElement<Joint, T, JointIndex> {
const VectorX<double>& acc_lower_limits,
const VectorX<double>& acc_upper_limits)
: MultibodyElement<Joint, T, JointIndex>(
frame_on_child.model_instance()),
frame_on_child.model_instance()),
name_(name),
frame_on_parent_(frame_on_parent),
frame_on_child_(frame_on_child),
Expand All @@ -139,6 +139,12 @@ class Joint : public MultibodyElement<Joint, T, JointIndex> {

DRAKE_DEMAND(acc_lower_limits.size() == acc_upper_limits.size());
DRAKE_DEMAND((acc_lower_limits.array() <= acc_upper_limits.array()).all());

// N.B. We cannot use `num_positions()` here because it is virtual.
const int num_positions = pos_lower_limits.size();

// intialize the default positions.
default_positions_ = VectorX<double>::Zero(num_positions);
}

virtual ~Joint() {}
Expand Down Expand Up @@ -263,7 +269,7 @@ class Joint : public MultibodyElement<Joint, T, JointIndex> {
/// to which this joint belongs.
// NVI to DoAddInOneForce().
void AddInDamping(
const systems::Context<T> &context, MultibodyForces<T>* forces) const {
const systems::Context<T>& context, MultibodyForces<T>* forces) const {
DRAKE_DEMAND(forces != nullptr);
DRAKE_DEMAND(forces->CheckHasRightSizeForModel(this->get_parent_tree()));
DoAddInDamping(context, forces);
Expand Down Expand Up @@ -305,6 +311,11 @@ class Joint : public MultibodyElement<Joint, T, JointIndex> {
return acc_upper_limits_;
}

/// Returns the default positions.
const VectorX<double>& default_positions() const {
return default_positions_;
}

/// Sets the position limits to @p lower_limits and @p upper_limits.
/// @throws std::exception if the dimension of @p lower_limits or
/// @p upper_limits does not match num_positions().
Expand Down Expand Up @@ -346,6 +357,22 @@ class Joint : public MultibodyElement<Joint, T, JointIndex> {
acc_lower_limits_ = lower_limits;
acc_upper_limits_ = upper_limits;
}

/// Sets the default positions to @p default_positions.
/// @throws std::exception if the dimension of @p default_positions does not
/// match num_positions().
/// @throws std::exception if any of @p default_positions is smaller than
/// the corresponding term in `position_lower_limits()`.
/// @throws std::exception if any of @p default_positions is larger than
/// the corresponding term in `position_upper_limits()`.
void set_default_positions(const VectorX<double>& default_positions) {
DRAKE_THROW_UNLESS(default_positions.size() == num_positions());
DRAKE_THROW_UNLESS(
(position_lower_limits().array() <= default_positions.array()).all());
DRAKE_THROW_UNLESS(
(default_positions.array() <= position_upper_limits().array()).all());
default_positions_ = default_positions;
}
/// @}

// Hide the following section from Doxygen.
Expand Down Expand Up @@ -527,10 +554,15 @@ class Joint : public MultibodyElement<Joint, T, JointIndex> {
return *implementation_;
}

/// Returns whether `this` joint owns a particular implementation.
/// If the MultibodyTree has been finalized, this will return true.
bool has_implementation() const { return implementation_ != nullptr; }

private:
// Make all other Joint<U> objects a friend of Joint<T> so they can make
// Joint<ToScalar>::JointImplementation from CloneToScalar<ToScalar>().
template <typename> friend class Joint;
template <typename>
friend class Joint;

// JointImplementationBuilder is a friend so that it can access the
// Joint<T>::BluePrint and protected method MakeImplementationBlueprint().
Expand Down Expand Up @@ -562,6 +594,9 @@ class Joint : public MultibodyElement<Joint, T, JointIndex> {
VectorX<double> acc_lower_limits_;
VectorX<double> acc_upper_limits_;

// Joint default position. This vector has zero size for joints with no state.
VectorX<double> default_positions_;

// The Joint<T> implementation:
std::unique_ptr<JointImplementation> implementation_;
};
Expand Down
26 changes: 22 additions & 4 deletions multibody/tree/prismatic_joint.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ class PrismaticJoint final : public Joint<T> {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(PrismaticJoint)

template<typename Scalar>
template <typename Scalar>
using Context = systems::Context<Scalar>;

static const char kTypeName[];
Expand Down Expand Up @@ -187,8 +187,24 @@ class PrismaticJoint final : public Joint<T> {

/// @}

/// Gets the default translation. Wrapper for the more general
/// `Joint::default_positions()`.
/// @returns The default translation of `this` stored in `default_positions_`.
double get_default_translation() const {
return this->default_positions()[0];
}

/// Sets the `default_positions` of this joint (in this case a single
/// translation)
/// If the parent tree has been finalized and the underlying mobilizer is
/// valid, this method sets the default position of that mobilizer.
/// @param[in] translation
/// The desired default translation of the joint
void set_default_translation(double translation) {
get_mutable_mobilizer()->set_default_position(Vector1d{translation});
this->set_default_positions(Vector1d{translation});
if (this->has_implementation()) {
get_mutable_mobilizer()->set_default_position(this->default_positions());
}
}

void set_random_translation_distribution(
Expand Down Expand Up @@ -273,9 +289,11 @@ class PrismaticJoint final : public Joint<T> {
std::unique_ptr<typename Joint<T>::BluePrint>
MakeImplementationBlueprint() const final {
auto blue_print = std::make_unique<typename Joint<T>::BluePrint>();
blue_print->mobilizers_.push_back(
auto prismatic_mobilizer =
std::make_unique<internal::PrismaticMobilizer<T>>(
this->frame_on_parent(), this->frame_on_child(), axis_));
this->frame_on_parent(), this->frame_on_child(), axis_);
prismatic_mobilizer->set_default_position(this->default_positions());
blue_print->mobilizers_.push_back(std::move(prismatic_mobilizer));
return std::move(blue_print);
}

Expand Down
10 changes: 5 additions & 5 deletions multibody/tree/revolute_joint.cc
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,7 @@ namespace multibody {

template <typename T>
template <typename ToScalar>
std::unique_ptr<Joint<ToScalar>>
RevoluteJoint<T>::TemplatedDoCloneToScalar(
std::unique_ptr<Joint<ToScalar>> RevoluteJoint<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());
Expand Down Expand Up @@ -56,9 +55,10 @@ template <typename T>
std::unique_ptr<typename Joint<T>::BluePrint>
RevoluteJoint<T>::MakeImplementationBlueprint() const {
auto blue_print = std::make_unique<typename Joint<T>::BluePrint>();
blue_print->mobilizers_.push_back(
std::make_unique<internal::RevoluteMobilizer<T>>(
this->frame_on_parent(), this->frame_on_child(), axis_));
auto revolute_mobilizer = std::make_unique<internal::RevoluteMobilizer<T>>(
this->frame_on_parent(), this->frame_on_child(), axis_);
revolute_mobilizer->set_default_position(this->default_positions());
blue_print->mobilizers_.push_back(std::move(revolute_mobilizer));
return std::move(blue_print);
}

Expand Down
23 changes: 18 additions & 5 deletions multibody/tree/revolute_joint.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class RevoluteJoint final : public Joint<T> {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(RevoluteJoint)

template<typename Scalar>
template <typename Scalar>
using Context = systems::Context<Scalar>;

static const char kTypeName[];
Expand Down Expand Up @@ -191,10 +191,6 @@ class RevoluteJoint final : public Joint<T> {
return *this;
}

void set_default_angle(double angle) {
get_mutable_mobilizer()->set_default_position(Vector1d{angle});
}

void set_random_angle_distribution(const symbolic::Expression& angle) {
get_mutable_mobilizer()->set_random_position_distribution(
Vector1<symbolic::Expression>{angle});
Expand Down Expand Up @@ -227,6 +223,23 @@ class RevoluteJoint final : public Joint<T> {

/// @}

/// Gets the default rotation angle. Wrapper for the more general
/// `Joint::default_positions()`.
/// @returns The default angle of `this` stored in `default_positions_`
double get_default_angle() const { return this->default_positions()[0]; }

/// Sets the `default_positions` of this joint (in this case a single angle).
/// If the parent tree has been finalized and the underlying mobilizer is
/// valid, this method sets the default position of that mobilizer.
/// @param[in] angle
/// The desired default angle of the joint
void set_default_angle(double angle) {
this->set_default_positions(Vector1d{angle});
if (this->has_implementation()) {
get_mutable_mobilizer()->set_default_position(this->default_positions());
}
}

/// Adds into `forces` a given `torque` for `this` joint that is to be applied
/// about the joint's axis. The torque is defined to be positive according to
/// the right-hand-rule with the thumb aligned in the direction of `this`
Expand Down
32 changes: 32 additions & 0 deletions multibody/tree/test/ball_rpy_joint_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@ constexpr double kVelocityUpperLimit = 1.6;
constexpr double kAccelerationLowerLimit = -1.2;
constexpr double kAccelerationUpperLimit = 1.7;
constexpr double kDamping = 3;
constexpr double kPositionNonZeroDefault =
(kPositionLowerLimit + kPositionUpperLimit) / 2;

class BallRpyJointTest : public ::testing::Test {
public:
Expand Down Expand Up @@ -198,6 +200,36 @@ TEST_F(BallRpyJointTest, SetVelocityAndAccelerationLimits) {
std::runtime_error);
}

TEST_F(BallRpyJointTest, DefaultAngles) {
const Vector3d lower_limit_angles = Vector3d::Constant(kPositionLowerLimit);
const Vector3d upper_limit_angles = Vector3d::Constant(kPositionUpperLimit);

const Vector3d default_angles = Vector3d::Zero();

const Vector3d new_default_angles =
Vector3d::Constant(kPositionNonZeroDefault);

const Vector3d out_of_bounds_low_angles =
lower_limit_angles - Vector3d::Constant(1);
const Vector3d out_of_bounds_high_angles =
upper_limit_angles + Vector3d::Constant(1);

// Constructor should set the default angle to Vector3d::Zero()
EXPECT_EQ(joint_->get_default_angles(), default_angles);

// Setting a new default angle should propogate so that `get_default_angle()`
// remains correct.
mutable_joint_->set_default_angles(new_default_angles);
EXPECT_EQ(joint_->get_default_angles(), new_default_angles);

// Setting the default angle out of the bounds of the position limits
// should throw an exception
EXPECT_THROW(mutable_joint_->set_default_angles(out_of_bounds_low_angles),
std::runtime_error);
EXPECT_THROW(mutable_joint_->set_default_angles(out_of_bounds_high_angles),
std::runtime_error);
}

} // namespace
} // namespace multibody
} // namespace drake
27 changes: 27 additions & 0 deletions multibody/tree/test/prismatic_joint_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -186,6 +186,33 @@ TEST_F(PrismaticJointTest, RandomTranslationTest) {
EXPECT_GE(kPositionUpperLimit, joint1_->get_translation(*context_));
}

TEST_F(PrismaticJointTest, DefaultTranslation) {
const double default_translation = 0.0;

const double new_default_translation =
0.5 * kPositionLowerLimit + 0.5 * kPositionUpperLimit;

const double out_of_bounds_low_translation = kPositionLowerLimit - 1;
const double out_of_bounds_high_translation = kPositionUpperLimit + 1;

// Constructor should set the default tranlation to 0.0
EXPECT_EQ(joint1_->get_default_translation(), default_translation);

// Setting a new default translation should propogate so that
// `get_default_translation()` remains correct.
mutable_joint1_->set_default_translation(new_default_translation);
EXPECT_EQ(joint1_->get_default_translation(), new_default_translation);

// Setting the default angle out of the bounds of the position limits
// should throw an exception
EXPECT_THROW(
mutable_joint1_->set_default_translation(out_of_bounds_low_translation),
std::runtime_error);
EXPECT_THROW(
mutable_joint1_->set_default_translation(out_of_bounds_high_translation),
std::runtime_error);
}

} // namespace
} // namespace multibody
} // namespace drake
25 changes: 25 additions & 0 deletions multibody/tree/test/revolute_joint_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -211,6 +211,31 @@ TEST_F(RevoluteJointTest, SetVelocityAndAccelerationLimits) {
std::runtime_error);
}

TEST_F(RevoluteJointTest, DefaultAngle) {
const double default_angle = 0.0;

const double new_default_angle =
0.5 * kPositionLowerLimit + 0.5 * kPositionUpperLimit;

const double out_of_bounds_low_angle = kPositionLowerLimit - 1;
const double out_of_bounds_high_angle = kPositionUpperLimit + 1;

// Constructor should set the default angle to 0.0
EXPECT_EQ(joint1_->get_default_angle(), default_angle);

// Setting a new default angle should propogate so that `get_default_angle()`
// remains correct.
mutable_joint1_->set_default_angle(new_default_angle);
EXPECT_EQ(joint1_->get_default_angle(), new_default_angle);

// Setting the default angle out of the bounds of the position limits
// should throw an exception
EXPECT_THROW(mutable_joint1_->set_default_angle(out_of_bounds_low_angle),
std::runtime_error);
EXPECT_THROW(mutable_joint1_->set_default_angle(out_of_bounds_high_angle),
std::runtime_error);
}

} // namespace
} // namespace multibody
} // namespace drake