Skip to content

Commit

Permalink
fix benchmark_rigid_body_tree (RobotLocomotion#8514)
Browse files Browse the repository at this point in the history
  • Loading branch information
RussTedrake authored and jwnimmer-tri committed Apr 4, 2018
1 parent 346448e commit a087ce5
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 1 deletion.
2 changes: 2 additions & 0 deletions multibody/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -339,8 +339,10 @@ drake_cc_binary(
name = "benchmark_rigid_body_tree",
testonly = 1,
srcs = ["test/benchmark_rigid_body_tree.cc"],
data = ["//examples/atlas:models"],
deps = [
":rigid_body_tree",
"//common:find_resource",
"//common/test_utilities:measure_execution",
"//multibody/parsers",
],
Expand Down
4 changes: 3 additions & 1 deletion multibody/test/benchmark_rigid_body_tree.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include <vector>

#include "drake/common/eigen_types.h"
#include "drake/common/find_resource.h"
#include "drake/common/test_utilities/measure_execution.h"
#include "drake/math/autodiff.h"
#include "drake/math/autodiff_gradient.h"
Expand Down Expand Up @@ -218,7 +219,8 @@ void TestScenario2(const RigidBodyTree<double>& model) {
int main() {
auto tree = std::make_unique<RigidBodyTree<double>>();
drake::parsers::urdf::AddModelInstanceFromUrdfFileToWorld(
"examples/atlas/urdf/atlas_minimal_contact.urdf",
drake::FindResourceOrThrow(
"drake/examples/atlas/urdf/atlas_minimal_contact.urdf"),
drake::multibody::joints::kRollPitchYaw, tree.get());

drake::multibody::TestScenario1(*tree);
Expand Down

0 comments on commit a087ce5

Please sign in to comment.