Skip to content

Commit

Permalink
multibody: Update to new Value APIs
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri committed Mar 7, 2019
1 parent aaa1002 commit eb8a13f
Show file tree
Hide file tree
Showing 4 changed files with 19 additions and 19 deletions.
12 changes: 6 additions & 6 deletions multibody/plant/multibody_plant.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1720,7 +1720,7 @@ void MultibodyPlant<T>::DeclareCacheEntries() {
[this](const systems::ContextBase& context_base,
AbstractValue* cache_value) {
auto& context = dynamic_cast<const Context<T>&>(context_base);
auto& point_pairs_cache = cache_value->GetMutableValue<
auto& point_pairs_cache = cache_value->get_mutable_value<
std::vector<geometry::PenetrationAsPointPair<T>>>();
point_pairs_cache = this->CalcPointPairPenetrations(context);
},
Expand All @@ -1735,7 +1735,7 @@ void MultibodyPlant<T>::DeclareCacheEntries() {
AbstractValue* cache_value) {
auto& context = dynamic_cast<const Context<T>&>(context_base);
auto& contact_jacobians_cache =
cache_value->GetMutableValue<internal::ContactJacobians<T>>();
cache_value->get_mutable_value<internal::ContactJacobians<T>>();
this->CalcNormalAndTangentContactJacobians(
context, EvalPointPairPenetrations(context),
&contact_jacobians_cache.Jn, &contact_jacobians_cache.Jt,
Expand All @@ -1759,8 +1759,8 @@ void MultibodyPlant<T>::DeclareCacheEntries() {
AbstractValue* cache_value) {
auto& context = dynamic_cast<const Context<T>&>(context_base);
auto& implicit_stribeck_solver_cache =
cache_value
->GetMutableValue<internal::ImplicitStribeckSolverResults<T>>();
cache_value->get_mutable_value<
internal::ImplicitStribeckSolverResults<T>>();
this->CalcImplicitStribeckResults(context,
&implicit_stribeck_solver_cache);
},
Expand All @@ -1779,7 +1779,7 @@ void MultibodyPlant<T>::DeclareCacheEntries() {
AbstractValue* cache_value) {
auto& context = dynamic_cast<const Context<T>&>(context_base);
auto& contact_results_cache =
cache_value->GetMutableValue<ContactResults<T>>();
cache_value->get_mutable_value<ContactResults<T>>();
this->CalcContactResults(context, &contact_results_cache);
},
// We explicitly declare the dependence on the implicit Stribeck solver
Expand Down Expand Up @@ -1943,7 +1943,7 @@ void MultibodyPlant<T>::DeclareSceneGraphPorts() {
typename systems::LeafOutputPort<T>::CalcCallback pose_callback = [this](
const Context<T>& context, AbstractValue* value) {
this->CalcFramePoseOutput(
context, &value->GetMutableValue<FramePoseVector<T>>());
context, &value->get_mutable_value<FramePoseVector<T>>());
};
geometry_pose_port_ = this->DeclareAbstractOutputPort(
"geometry_pose", pose_alloc, pose_callback).get_index();
Expand Down
4 changes: 2 additions & 2 deletions multibody/plant/test/contact_results_to_lcm_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ GTEST_TEST(ContactResultToLcmSystem, EmptyMultibodyPlant) {
&lcm_message_value);

const lcmt_contact_results_for_viz& lcm_message =
lcm_message_value.GetValue<lcmt_contact_results_for_viz>();
lcm_message_value.get_value();

// We haven't stepped, so we should assume the time is the context's default
// value.
Expand Down Expand Up @@ -88,7 +88,7 @@ GTEST_TEST(ContactResultToLcmSystem, NonEmptyMultibodyPlantEmptyContact) {
lcm_system.get_lcm_message_output_port().Calc(*lcm_context,
&lcm_message_value);
const lcmt_contact_results_for_viz& lcm_message =
lcm_message_value.GetValue<lcmt_contact_results_for_viz>();
lcm_message_value.get_value();

// We haven't stepped, so we should assume the time is the context's default
// value.
Expand Down
16 changes: 8 additions & 8 deletions multibody/plant/test/multibody_plant_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -672,9 +672,9 @@ TEST_F(AcrobotPlantTests, VisualGeometryRegistration) {

unique_ptr<AbstractValue> poses_value =
plant_->get_geometry_poses_output_port().Allocate();
EXPECT_NO_THROW(poses_value->GetValueOrThrow<FramePoseVector<double>>());
EXPECT_NO_THROW(poses_value->get_value<FramePoseVector<double>>());
const FramePoseVector<double>& poses =
poses_value->GetValueOrThrow<FramePoseVector<double>>();
poses_value->get_value<FramePoseVector<double>>();
EXPECT_EQ(poses.source_id(), plant_->get_source_id());
EXPECT_EQ(poses.size(), 2); // Only two frames move.

Expand Down Expand Up @@ -1148,9 +1148,9 @@ GTEST_TEST(MultibodyPlantTest, CollisionGeometryRegistration) {

unique_ptr<AbstractValue> poses_value =
plant.get_geometry_poses_output_port().Allocate();
EXPECT_NO_THROW(poses_value->GetValueOrThrow<FramePoseVector<double>>());
EXPECT_NO_THROW(poses_value->get_value<FramePoseVector<double>>());
const FramePoseVector<double>& pose_data =
poses_value->GetValueOrThrow<FramePoseVector<double>>();
poses_value->get_value<FramePoseVector<double>>();
EXPECT_EQ(pose_data.source_id(), plant.get_source_id());
EXPECT_EQ(pose_data.size(), 2); // Only two frames move.

Expand Down Expand Up @@ -1220,9 +1220,9 @@ GTEST_TEST(MultibodyPlantTest, VisualGeometryRegistration) {
unique_ptr<Context<double>> context = scene_graph.CreateDefaultContext();
unique_ptr<AbstractValue> state_value =
scene_graph.get_query_output_port().Allocate();
EXPECT_NO_THROW(state_value->GetValueOrThrow<QueryObject<double>>());
EXPECT_NO_THROW(state_value->get_value<QueryObject<double>>());
const QueryObject<double>& query_object =
state_value->GetValueOrThrow<QueryObject<double>>();
state_value->get_value<QueryObject<double>>();
scene_graph.get_query_output_port().Calc(*context, state_value.get());

const SceneGraphInspector<double>& inspector = query_object.inspector();
Expand Down Expand Up @@ -1324,9 +1324,9 @@ TEST_F(AcrobotPlantTests, EvalContinuousStateOutputPort) {

unique_ptr<AbstractValue> state_value =
plant_->get_continuous_state_output_port().Allocate();
EXPECT_NO_THROW(state_value->GetValueOrThrow<BasicVector<double>>());
EXPECT_NO_THROW(state_value->get_value<BasicVector<double>>());
const BasicVector<double>& state_out =
state_value->GetValueOrThrow<BasicVector<double>>();
state_value->get_value<BasicVector<double>>();
EXPECT_EQ(state_out.size(), plant_->num_multibody_states());

// Compute the poses for each geometry in the model.
Expand Down
6 changes: 3 additions & 3 deletions multibody/tree/multibody_tree_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,7 @@ void MultibodyTreeSystem<T>::Finalize() {
AbstractValue* cache_value) {
auto& context = dynamic_cast<const Context<T>&>(context_base);
auto& position_cache =
cache_value->GetMutableValue<PositionKinematicsCache<T>>();
cache_value->get_mutable_value<PositionKinematicsCache<T>>();
tree->CalcPositionKinematicsCache(context, &position_cache);
},
{this->configuration_ticket()});
Expand All @@ -139,7 +139,7 @@ void MultibodyTreeSystem<T>::Finalize() {
AbstractValue* cache_value) {
auto& context = dynamic_cast<const Context<T>&>(context_base);
auto& velocity_cache =
cache_value->GetMutableValue<VelocityKinematicsCache<T>>();
cache_value->get_mutable_value<VelocityKinematicsCache<T>>();
tree->CalcVelocityKinematicsCache(
context, tree->EvalPositionKinematics(context), &velocity_cache);
},
Expand All @@ -159,7 +159,7 @@ void MultibodyTreeSystem<T>::Finalize() {
AbstractValue* cache_value) {
auto& context = dynamic_cast<const Context<T>&>(context_base);
auto& H_PB_W_cache =
cache_value->GetMutableValue<std::vector<Vector6<T>>>();
cache_value->get_mutable_value<std::vector<Vector6<T>>>();
tree->CalcAcrossNodeGeometricJacobianExpressedInWorld(
context, tree->EvalPositionKinematics(context), &H_PB_W_cache);
},
Expand Down

0 comments on commit eb8a13f

Please sign in to comment.