From bafbec00c9e47d42e3c0e5c481c6fe628dba2713 Mon Sep 17 00:00:00 2001 From: Kunimatsu Hashimoto Date: Thu, 29 Jun 2017 20:53:12 -0400 Subject: [PATCH] Port drake/examples to FindResource (#6446) --- drake/examples/Acrobot/BUILD | 8 +++--- drake/examples/Acrobot/acrobot_plant_w_lcm.cc | 4 +-- drake/examples/Acrobot/acrobot_run_lqr.cc | 4 +-- .../Acrobot/acrobot_run_lqr_w_estimator.cc | 4 +-- drake/examples/Acrobot/acrobot_run_passive.cc | 4 +-- .../examples/Acrobot/acrobot_run_swing_up.cc | 4 +-- .../acrobot_run_swing_up_traj_optimization.cc | 4 +-- .../test/acrobot_urdf_dynamics_test.cc | 4 +-- drake/examples/Pendulum/BUILD | 8 +++--- .../Pendulum/pendulum_run_dynamics.cc | 4 +-- .../Pendulum/pendulum_run_energy_shaping.cc | 4 +-- drake/examples/Pendulum/pendulum_run_lqr.cc | 4 +-- .../Pendulum/pendulum_run_swing_up.cc | 4 +-- .../test/pendulum_urdf_dynamics_test.cc | 4 +-- .../QPInverseDynamicsForHumanoids/BUILD | 3 +++ .../param_parsers/BUILD | 2 ++ .../param_parsers/test/param_parser_test.cc | 23 +++++++--------- .../test/rigid_body_tree_alias_groups_test.cc | 11 ++++---- .../plan_eval/BUILD | 4 +-- .../plan_eval/test/generic_plan_test.cc | 26 +++++++++--------- .../plan_eval/test/manipulator_plan_test.cc | 26 +++++++++--------- .../system/BUILD | 6 ++++- .../system/humanoid_plan_eval_system.cc | 1 - .../system/plan_eval_base_system.cc | 1 - .../test/humanoid_plan_eval_system_test.cc | 27 +++++++++---------- .../joint_level_controller_system_test.cc | 8 +++--- ...ulator_inverse_dynamics_controller_test.cc | 26 +++++++++--------- .../system/test/qp_controller_system_test.cc | 27 +++++++++---------- .../valkyrie_balancing_controller_system.cc | 22 +++++++-------- .../test/iiwa_inverse_dynamics_test.cc | 20 +++++++------- .../test/lcm_utils_test.cc | 8 +++--- .../test/valkyrie_balancing_test.cc | 19 ++++++------- drake/examples/Quadrotor/BUILD | 6 ++--- .../Quadrotor/run_quadrotor_dynamics.cc | 6 ++--- drake/examples/Quadrotor/run_quadrotor_lqr.cc | 4 +-- .../Quadrotor/test/quadrotor_dynamics_test.cc | 4 +-- drake/examples/Valkyrie/BUILD | 9 ++++--- ...ommand_to_desired_effort_converter_test.cc | 13 +++++---- .../test/robot_state_encoder_decoder_test.cc | 8 +++--- .../Valkyrie/test/valkyrie_ik_test.cc | 7 ++--- .../Valkyrie/valkyrie_pd_ff_controller.cc | 8 +++--- drake/examples/Valkyrie/valkyrie_simulator.h | 8 +++--- drake/examples/contact_model/BUILD | 6 ++--- drake/examples/contact_model/bowling_ball.cc | 8 +++--- drake/examples/contact_model/rigid_gripper.cc | 6 ++--- .../examples/contact_model/sliding_bricks.cc | 11 +++++--- drake/examples/kinova_jaco_arm/BUILD | 3 +++ .../run_controlled_jaco_demo.cc | 16 +++++------ .../kinova_jaco_arm/run_passive_jaco_demo.cc | 10 +++---- .../kinova_jaco_arm/run_setpose_jaco_demo.cc | 10 +++---- drake/examples/kuka_iiwa_arm/BUILD | 5 ++++ .../kuka_iiwa_arm/controlled_kuka/BUILD | 1 + .../controlled_kuka/controlled_kuka_demo.cc | 8 +++--- .../dev/monolithic_pick_and_place/BUILD | 1 + .../monolithic_pick_and_place_demo.cc | 18 ++++++------- .../state_machine_system.cc | 2 -- .../kuka_iiwa_arm/dev/pick_and_place/BUILD | 1 + .../dev/pick_and_place/pick_and_place_demo.cc | 8 +++--- drake/examples/kuka_iiwa_arm/dev/tools/BUILD | 1 + .../dev/tools/simple_tree_visualizer_demo.cc | 6 ++--- drake/examples/kuka_iiwa_arm/iiwa_common.cc | 4 +-- .../examples/kuka_iiwa_arm/iiwa_controller.cc | 6 ++--- drake/examples/kuka_iiwa_arm/iiwa_world/BUILD | 1 + .../iiwa_world/multi_arm_with_gripper_demo.cc | 4 +-- .../iiwa_world/world_sim_tree_builder.cc | 8 +++--- .../kuka_iiwa_arm/iiwa_wsg_simulation.cc | 13 +++++---- .../kuka_iiwa_arm/kuka_plan_runner.cc | 6 ++--- .../examples/kuka_iiwa_arm/kuka_simulation.cc | 8 +++--- .../kuka_iiwa_arm/pick_and_place/BUILD | 2 ++ .../test/pick_and_place_state_machine_test.cc | 8 +++--- .../pick_and_place/test/world_state_test.cc | 8 +++--- .../test/robot_plan_interpolator_test.cc | 12 ++++----- .../test/sim_diagram_builder_test.cc | 7 +++-- drake/examples/particles/BUILD | 1 + .../uniformly_accelerated_particle.cc | 6 ++--- drake/examples/schunk_wsg/BUILD | 4 +-- .../schunk_wsg/simulated_schunk_wsg_system.cc | 6 ++--- .../schunk_wsg/test/schunk_wsg_lift_test.cc | 12 ++++----- 78 files changed, 319 insertions(+), 315 deletions(-) diff --git a/drake/examples/Acrobot/BUILD b/drake/examples/Acrobot/BUILD index faefae881e04..d71d56f9efba 100644 --- a/drake/examples/Acrobot/BUILD +++ b/drake/examples/Acrobot/BUILD @@ -92,7 +92,7 @@ drake_cc_binary( test_rule_args = ["-realtime_factor=0.0"], deps = [ ":acrobot_plant", - "//drake/common:drake_path", + "//drake/common:find_resource", "//drake/lcm", "//drake/multibody:rigid_body_tree", "//drake/multibody/parsers", @@ -112,7 +112,7 @@ drake_cc_binary( deps = [ ":acrobot_plant", "//drake/common:call_matlab", - "//drake/common:drake_path", + "//drake/common:find_resource", "//drake/lcm", "//drake/multibody:rigid_body_tree", "//drake/multibody/joints", @@ -136,7 +136,7 @@ drake_cc_binary( test_rule_args = ["-realtime_factor=0.0"], deps = [ ":acrobot_plant", - "//drake/common:drake_path", + "//drake/common:find_resource", "//drake/lcm", "//drake/multibody:rigid_body_tree", "//drake/multibody/joints", @@ -226,8 +226,8 @@ drake_cc_googletest( data = [":models"], deps = [ ":acrobot_plant", - "//drake/common:drake_path", "//drake/common:eigen_matrix_compare", + "//drake/common:find_resource", "//drake/multibody/joints", "//drake/multibody/parsers", "//drake/multibody/rigid_body_plant", diff --git a/drake/examples/Acrobot/acrobot_plant_w_lcm.cc b/drake/examples/Acrobot/acrobot_plant_w_lcm.cc index 47e22dfd89a2..6ee648eec87b 100644 --- a/drake/examples/Acrobot/acrobot_plant_w_lcm.cc +++ b/drake/examples/Acrobot/acrobot_plant_w_lcm.cc @@ -15,7 +15,7 @@ #include -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/examples/Acrobot/acrobot_lcm.h" #include "drake/lcm/drake_lcm.h" #include "drake/lcmt_acrobot_u.hpp" @@ -52,7 +52,7 @@ int DoMain() { lcm::DrakeLcm lcm; auto tree = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( - GetDrakePath() + "/examples/Acrobot/Acrobot.urdf", + FindResourceOrThrow("drake/examples/Acrobot/Acrobot.urdf"), multibody::joints::kFixed, tree.get()); auto publisher = builder.AddSystem(*tree, &lcm); auto acrobot = builder.AddSystem(); diff --git a/drake/examples/Acrobot/acrobot_run_lqr.cc b/drake/examples/Acrobot/acrobot_run_lqr.cc index 95fb04e9b493..b24ed80410b0 100644 --- a/drake/examples/Acrobot/acrobot_run_lqr.cc +++ b/drake/examples/Acrobot/acrobot_run_lqr.cc @@ -2,7 +2,7 @@ #include -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/examples/Acrobot/acrobot_plant.h" #include "drake/examples/Acrobot/gen/acrobot_state_vector.h" #include "drake/lcm/drake_lcm.h" @@ -33,7 +33,7 @@ int do_main(int argc, char* argv[]) { lcm::DrakeLcm lcm; auto tree = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( - GetDrakePath() + "/examples/Acrobot/Acrobot.urdf", + FindResourceOrThrow("drake/examples/Acrobot/Acrobot.urdf"), multibody::joints::kFixed, tree.get()); systems::DiagramBuilder builder; diff --git a/drake/examples/Acrobot/acrobot_run_lqr_w_estimator.cc b/drake/examples/Acrobot/acrobot_run_lqr_w_estimator.cc index 6d9ef2fa9d2e..6f5eb133d553 100644 --- a/drake/examples/Acrobot/acrobot_run_lqr_w_estimator.cc +++ b/drake/examples/Acrobot/acrobot_run_lqr_w_estimator.cc @@ -4,7 +4,7 @@ #include #include "drake/common/call_matlab.h" -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/examples/Acrobot/acrobot_plant.h" #include "drake/examples/Acrobot/gen/acrobot_state_vector.h" #include "drake/lcm/drake_lcm.h" @@ -49,7 +49,7 @@ int do_main(int argc, char* argv[]) { lcm::DrakeLcm lcm; auto tree = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( - GetDrakePath() + "/examples/Acrobot/Acrobot.urdf", + FindResourceOrThrow("drake/examples/Acrobot/Acrobot.urdf"), multibody::joints::kFixed, tree.get()); auto publisher = builder.AddSystem(*tree, &lcm); publisher->set_name("publisher"); diff --git a/drake/examples/Acrobot/acrobot_run_passive.cc b/drake/examples/Acrobot/acrobot_run_passive.cc index bdaf3489e06e..31e4c1128b56 100644 --- a/drake/examples/Acrobot/acrobot_run_passive.cc +++ b/drake/examples/Acrobot/acrobot_run_passive.cc @@ -2,7 +2,7 @@ #include -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/examples/Acrobot/acrobot_plant.h" #include "drake/examples/Acrobot/gen/acrobot_state_vector.h" #include "drake/lcm/drake_lcm.h" @@ -32,7 +32,7 @@ int do_main(int argc, char* argv[]) { lcm::DrakeLcm lcm; auto tree = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( - GetDrakePath() + "/examples/Acrobot/Acrobot.urdf", + FindResourceOrThrow("drake/examples/Acrobot/Acrobot.urdf"), multibody::joints::kFixed, tree.get()); systems::DiagramBuilder builder; diff --git a/drake/examples/Acrobot/acrobot_run_swing_up.cc b/drake/examples/Acrobot/acrobot_run_swing_up.cc index 8b06e00a1da6..d32ca0c127df 100644 --- a/drake/examples/Acrobot/acrobot_run_swing_up.cc +++ b/drake/examples/Acrobot/acrobot_run_swing_up.cc @@ -2,7 +2,7 @@ #include -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/examples/Acrobot/acrobot_plant.h" #include "drake/examples/Acrobot/acrobot_spong_controller.h" #include "drake/examples/Acrobot/gen/acrobot_state_vector.h" @@ -36,7 +36,7 @@ int do_main(int argc, char* argv[]) { lcm::DrakeLcm lcm; auto tree = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( - GetDrakePath() + "/examples/Acrobot/Acrobot.urdf", + FindResourceOrThrow("drake/examples/Acrobot/Acrobot.urdf"), multibody::joints::kFixed, tree.get()); systems::DiagramBuilder builder; diff --git a/drake/examples/Acrobot/acrobot_run_swing_up_traj_optimization.cc b/drake/examples/Acrobot/acrobot_run_swing_up_traj_optimization.cc index df8778cf1934..f37cddee3d4c 100644 --- a/drake/examples/Acrobot/acrobot_run_swing_up_traj_optimization.cc +++ b/drake/examples/Acrobot/acrobot_run_swing_up_traj_optimization.cc @@ -7,7 +7,7 @@ #include -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/examples/Acrobot/acrobot_plant.h" #include "drake/examples/Acrobot/acrobot_swing_up.h" #include "drake/lcm/drake_lcm.h" @@ -69,7 +69,7 @@ int do_main() { lcm::DrakeLcm lcm; auto tree = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( - GetDrakePath() + "/examples/Acrobot/Acrobot.urdf", + FindResourceOrThrow("drake/examples/Acrobot/Acrobot.urdf"), multibody::joints::kFixed, tree.get()); auto publisher = builder.AddSystem(*tree, &lcm); diff --git a/drake/examples/Acrobot/test/acrobot_urdf_dynamics_test.cc b/drake/examples/Acrobot/test/acrobot_urdf_dynamics_test.cc index 4d1450b2a0dd..10bbbe88f246 100644 --- a/drake/examples/Acrobot/test/acrobot_urdf_dynamics_test.cc +++ b/drake/examples/Acrobot/test/acrobot_urdf_dynamics_test.cc @@ -2,8 +2,8 @@ #include -#include "drake/common/drake_path.h" #include "drake/common/eigen_matrix_compare.h" +#include "drake/common/find_resource.h" #include "drake/examples/Acrobot/acrobot_plant.h" #include "drake/multibody/joints/floating_base_types.h" #include "drake/multibody/parsers/urdf_parser.h" @@ -19,7 +19,7 @@ namespace { GTEST_TEST(UrdfDynamicsTest, AllTests) { auto tree = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( - GetDrakePath() + "/examples/Acrobot/Acrobot.urdf", + FindResourceOrThrow("drake/examples/Acrobot/Acrobot.urdf"), multibody::joints::kFixed, tree.get()); systems::RigidBodyPlant rbp(std::move(tree)); diff --git a/drake/examples/Pendulum/BUILD b/drake/examples/Pendulum/BUILD index f24e043cc0db..a102d18ba784 100644 --- a/drake/examples/Pendulum/BUILD +++ b/drake/examples/Pendulum/BUILD @@ -40,7 +40,7 @@ drake_cc_binary( data = [":models"], deps = [ ":pendulum_plant", - "//drake/common:drake_path", + "//drake/common:find_resource", "//drake/lcm", "//drake/multibody:rigid_body_tree", "//drake/multibody/joints", @@ -59,7 +59,7 @@ drake_cc_binary( data = [":models"], deps = [ ":pendulum_plant", - "//drake/common:drake_path", + "//drake/common:find_resource", "//drake/lcm", "//drake/multibody/joints", "//drake/multibody/parsers", @@ -77,7 +77,7 @@ drake_cc_binary( data = [":models"], deps = [ ":pendulum_plant", - "//drake/common:drake_path", + "//drake/common:find_resource", "//drake/lcm", "//drake/multibody/joints", "//drake/multibody/parsers", @@ -97,7 +97,7 @@ drake_cc_binary( test_rule_args = ["--target_realtime_rate=0.0"], deps = [ "pendulum_swing_up", - "//drake/common:drake_path", + "//drake/common:find_resource", "//drake/common:is_approx_equal_abstol", "//drake/lcm", "//drake/multibody/joints", diff --git a/drake/examples/Pendulum/pendulum_run_dynamics.cc b/drake/examples/Pendulum/pendulum_run_dynamics.cc index 0d073e8894f3..2e539cc4e6d7 100644 --- a/drake/examples/Pendulum/pendulum_run_dynamics.cc +++ b/drake/examples/Pendulum/pendulum_run_dynamics.cc @@ -1,6 +1,6 @@ #include -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/examples/Pendulum/pendulum_plant.h" #include "drake/lcm/drake_lcm.h" #include "drake/multibody/joints/floating_base_types.h" @@ -21,7 +21,7 @@ int do_main() { lcm::DrakeLcm lcm; auto tree = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( - GetDrakePath() + "/examples/Pendulum/Pendulum.urdf", + FindResourceOrThrow("drake/examples/Pendulum/Pendulum.urdf"), multibody::joints::kFixed, tree.get()); Eigen::VectorXd tau = Eigen::VectorXd::Zero(1); diff --git a/drake/examples/Pendulum/pendulum_run_energy_shaping.cc b/drake/examples/Pendulum/pendulum_run_energy_shaping.cc index 857a9f524af1..37e9857769e6 100644 --- a/drake/examples/Pendulum/pendulum_run_energy_shaping.cc +++ b/drake/examples/Pendulum/pendulum_run_energy_shaping.cc @@ -2,7 +2,7 @@ #include #include "drake/common/drake_assert.h" -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/examples/Pendulum/pendulum_plant.h" #include "drake/lcm/drake_lcm.h" #include "drake/multibody/joints/floating_base_types.h" @@ -61,7 +61,7 @@ int do_main() { lcm::DrakeLcm lcm; auto tree = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( - GetDrakePath() + "/examples/Pendulum/Pendulum.urdf", + FindResourceOrThrow("drake/examples/Pendulum/Pendulum.urdf"), multibody::joints::kFixed, tree.get()); systems::DiagramBuilder builder; diff --git a/drake/examples/Pendulum/pendulum_run_lqr.cc b/drake/examples/Pendulum/pendulum_run_lqr.cc index f5edd6d86d01..3e56779730a3 100644 --- a/drake/examples/Pendulum/pendulum_run_lqr.cc +++ b/drake/examples/Pendulum/pendulum_run_lqr.cc @@ -2,7 +2,7 @@ #include #include "drake/common/drake_assert.h" -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/examples/Pendulum/pendulum_plant.h" #include "drake/lcm/drake_lcm.h" #include "drake/multibody/joints/floating_base_types.h" @@ -26,7 +26,7 @@ int do_main() { auto tree = std::make_unique>(); drake::parsers::urdf::AddModelInstanceFromUrdfFileToWorld( - GetDrakePath() + "/examples/Pendulum/Pendulum.urdf", + FindResourceOrThrow("drake/examples/Pendulum/Pendulum.urdf"), multibody::joints::kFixed, tree.get()); systems::DiagramBuilder builder; diff --git a/drake/examples/Pendulum/pendulum_run_swing_up.cc b/drake/examples/Pendulum/pendulum_run_swing_up.cc index 48918f9d2167..b23e65485b47 100644 --- a/drake/examples/Pendulum/pendulum_run_swing_up.cc +++ b/drake/examples/Pendulum/pendulum_run_swing_up.cc @@ -3,7 +3,7 @@ #include -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/common/is_approx_equal_abstol.h" #include "drake/examples/Pendulum/pendulum_plant.h" #include "drake/examples/Pendulum/pendulum_swing_up.h" @@ -90,7 +90,7 @@ int do_main() { lcm::DrakeLcm lcm; auto tree = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( - GetDrakePath() + "/examples/Pendulum/Pendulum.urdf", + FindResourceOrThrow("drake/examples/Pendulum/Pendulum.urdf"), multibody::joints::kFixed, tree.get()); auto publisher = builder.AddSystem(*tree, &lcm); diff --git a/drake/examples/Pendulum/test/pendulum_urdf_dynamics_test.cc b/drake/examples/Pendulum/test/pendulum_urdf_dynamics_test.cc index e02ea4e101c7..f7b435fbd731 100644 --- a/drake/examples/Pendulum/test/pendulum_urdf_dynamics_test.cc +++ b/drake/examples/Pendulum/test/pendulum_urdf_dynamics_test.cc @@ -2,8 +2,8 @@ #include -#include "drake/common/drake_path.h" #include "drake/common/eigen_matrix_compare.h" +#include "drake/common/find_resource.h" #include "drake/examples/Pendulum/pendulum_plant.h" #include "drake/multibody/joints/floating_base_types.h" #include "drake/multibody/parsers/urdf_parser.h" @@ -17,7 +17,7 @@ namespace { GTEST_TEST(UrdfDynamicsTest, AllTests) { auto tree = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( - GetDrakePath() + "/examples/Pendulum/Pendulum.urdf", + FindResourceOrThrow("drake/examples/Pendulum/Pendulum.urdf"), multibody::joints::kFixed, tree.get()); systems::RigidBodyPlant rbp(std::move(tree)); diff --git a/drake/examples/QPInverseDynamicsForHumanoids/BUILD b/drake/examples/QPInverseDynamicsForHumanoids/BUILD index 988f8c42cdd3..a458938750d1 100644 --- a/drake/examples/QPInverseDynamicsForHumanoids/BUILD +++ b/drake/examples/QPInverseDynamicsForHumanoids/BUILD @@ -98,6 +98,7 @@ drake_cc_googletest( deps = [ ":lcm_utils", "//drake/common:eigen_matrix_compare", + "//drake/common:find_resource", "//drake/multibody/parsers", ], ) @@ -124,6 +125,7 @@ drake_cc_googletest( ":control_utils", ":qp_controller", "//drake/common:eigen_matrix_compare", + "//drake/common:find_resource", "//drake/examples/QPInverseDynamicsForHumanoids/param_parsers:param_parser", "//drake/examples/Valkyrie:valkyrie_constants", "//drake/multibody/parsers", @@ -143,6 +145,7 @@ drake_cc_googletest( ":control_utils", ":qp_controller", "//drake/common:eigen_matrix_compare", + "//drake/common:find_resource", "//drake/examples/QPInverseDynamicsForHumanoids/param_parsers:param_parser", "//drake/multibody/parsers", ], diff --git a/drake/examples/QPInverseDynamicsForHumanoids/param_parsers/BUILD b/drake/examples/QPInverseDynamicsForHumanoids/param_parsers/BUILD index 75096c49de41..1761858f8d08 100644 --- a/drake/examples/QPInverseDynamicsForHumanoids/param_parsers/BUILD +++ b/drake/examples/QPInverseDynamicsForHumanoids/param_parsers/BUILD @@ -64,6 +64,7 @@ drake_cc_googletest( deps = [ ":rigid_body_tree_alias_groups", "//drake/common:eigen_matrix_compare", + "//drake/common:find_resource", "//drake/multibody/parsers", ], ) @@ -80,6 +81,7 @@ drake_cc_googletest( ":param_parser", ":rigid_body_tree_alias_groups", "//drake/common:eigen_matrix_compare", + "//drake/common:find_resource", "//drake/multibody/parsers", ], ) diff --git a/drake/examples/QPInverseDynamicsForHumanoids/param_parsers/test/param_parser_test.cc b/drake/examples/QPInverseDynamicsForHumanoids/param_parsers/test/param_parser_test.cc index 711c6fe1dd33..80d3808dbf90 100644 --- a/drake/examples/QPInverseDynamicsForHumanoids/param_parsers/test/param_parser_test.cc +++ b/drake/examples/QPInverseDynamicsForHumanoids/param_parsers/test/param_parser_test.cc @@ -4,8 +4,8 @@ #include -#include "drake/common/drake_path.h" #include "drake/common/eigen_matrix_compare.h" +#include "drake/common/find_resource.h" #include "drake/multibody/joints/floating_base_types.h" #include "drake/multibody/parsers/urdf_parser.h" @@ -18,18 +18,15 @@ namespace { class ParamParserTests : public ::testing::Test { protected: virtual void SetUp() { - const std::string urdf_name = - drake::GetDrakePath() + - "/examples/Valkyrie/urdf/urdf/" - "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf"; - const std::string alias_groups_config_name = - drake::GetDrakePath() + - "/examples/QPInverseDynamicsForHumanoids/" - "param_parsers/test/params.alias_groups"; - const std::string controller_config_name = - drake::GetDrakePath() + - "/examples/QPInverseDynamicsForHumanoids/" - "param_parsers/test/params.id_controller_config"; + const std::string urdf_name = FindResourceOrThrow( + "drake/examples/Valkyrie/urdf/urdf/" + "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf"); + const std::string alias_groups_config_name = FindResourceOrThrow( + "drake/examples/QPInverseDynamicsForHumanoids/" + "param_parsers/test/params.alias_groups"); + const std::string controller_config_name = FindResourceOrThrow( + "drake/examples/QPInverseDynamicsForHumanoids/" + "param_parsers/test/params.id_controller_config"); robot_ = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( diff --git a/drake/examples/QPInverseDynamicsForHumanoids/param_parsers/test/rigid_body_tree_alias_groups_test.cc b/drake/examples/QPInverseDynamicsForHumanoids/param_parsers/test/rigid_body_tree_alias_groups_test.cc index b167964b9785..c06bccd19ad8 100644 --- a/drake/examples/QPInverseDynamicsForHumanoids/param_parsers/test/rigid_body_tree_alias_groups_test.cc +++ b/drake/examples/QPInverseDynamicsForHumanoids/param_parsers/test/rigid_body_tree_alias_groups_test.cc @@ -2,7 +2,7 @@ #include -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/multibody/parsers/urdf_parser.h" namespace drake { @@ -11,7 +11,7 @@ namespace qp_inverse_dynamics { namespace param_parsers { const char* const kTestDir = - "/examples/QPInverseDynamicsForHumanoids/param_parsers/test/"; + "drake/examples/QPInverseDynamicsForHumanoids/param_parsers/test/"; // The test YAML config looks like this: // @@ -37,9 +37,10 @@ const char* const kTestDir = // // Please refer to the full config file for more details. void TestFullConfig(multibody::joints::FloatingBaseType type) { - std::string urdf = drake::GetDrakePath() - + "/multibody/test/rigid_body_tree/two_dof_robot.urdf"; - std::string config = drake::GetDrakePath() + kTestDir + "test.alias_groups"; + std::string urdf = FindResourceOrThrow( + "drake/multibody/test/rigid_body_tree/two_dof_robot.urdf"); + std::string config = FindResourceOrThrow( + std::string(kTestDir) + "test.alias_groups"); auto robot = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld(urdf, type, robot.get()); diff --git a/drake/examples/QPInverseDynamicsForHumanoids/plan_eval/BUILD b/drake/examples/QPInverseDynamicsForHumanoids/plan_eval/BUILD index c797c6be7688..828c6a297245 100644 --- a/drake/examples/QPInverseDynamicsForHumanoids/plan_eval/BUILD +++ b/drake/examples/QPInverseDynamicsForHumanoids/plan_eval/BUILD @@ -60,8 +60,8 @@ drake_cc_googletest( deps = [ ":manipulator_plans", ":test_common", - "//drake/common:drake_path", "//drake/common:eigen_matrix_compare", + "//drake/common:find_resource", "//drake/multibody:rigid_body_tree", "//drake/multibody/parsers", ], @@ -78,8 +78,8 @@ drake_cc_googletest( deps = [ ":generic_plan", ":test_common", - "//drake/common:drake_path", "//drake/common:eigen_matrix_compare", + "//drake/common:find_resource", "//drake/multibody:rigid_body_tree", "//drake/multibody/parsers", ], diff --git a/drake/examples/QPInverseDynamicsForHumanoids/plan_eval/test/generic_plan_test.cc b/drake/examples/QPInverseDynamicsForHumanoids/plan_eval/test/generic_plan_test.cc index c172c3371f15..86fe83a41e07 100644 --- a/drake/examples/QPInverseDynamicsForHumanoids/plan_eval/test/generic_plan_test.cc +++ b/drake/examples/QPInverseDynamicsForHumanoids/plan_eval/test/generic_plan_test.cc @@ -1,7 +1,7 @@ #include -#include "drake/common/drake_path.h" #include "drake/common/eigen_matrix_compare.h" +#include "drake/common/find_resource.h" #include "drake/examples/QPInverseDynamicsForHumanoids/plan_eval/test/test_common.h" namespace drake { @@ -50,19 +50,17 @@ class DummyPlan : public GenericPlan { class DummyPlanTest : public GenericPlanTest { protected: void SetUp() override { - const std::string kModelPath = drake::GetDrakePath() + - "/manipulation/models/iiwa_description/urdf/" - "iiwa14_polytope_collision.urdf"; - - const std::string kAliasGroupsPath = - drake::GetDrakePath() + - "/examples/QPInverseDynamicsForHumanoids/" - "config/iiwa.alias_groups"; - - const std::string kControlConfigPath = - drake::GetDrakePath() + - "/examples/QPInverseDynamicsForHumanoids/" - "config/iiwa.id_controller_config"; + const std::string kModelPath = FindResourceOrThrow( + "drake/manipulation/models/iiwa_description/urdf/" + "iiwa14_polytope_collision.urdf"); + + const std::string kAliasGroupsPath = FindResourceOrThrow( + "drake/examples/QPInverseDynamicsForHumanoids/" + "config/iiwa.alias_groups"); + + const std::string kControlConfigPath = FindResourceOrThrow( + "drake/examples/QPInverseDynamicsForHumanoids/" + "config/iiwa.id_controller_config"); std::default_random_engine generator(123); AllocateResources(kModelPath, kAliasGroupsPath, kControlConfigPath); diff --git a/drake/examples/QPInverseDynamicsForHumanoids/plan_eval/test/manipulator_plan_test.cc b/drake/examples/QPInverseDynamicsForHumanoids/plan_eval/test/manipulator_plan_test.cc index 57f1d55a3724..f098edd8acef 100644 --- a/drake/examples/QPInverseDynamicsForHumanoids/plan_eval/test/manipulator_plan_test.cc +++ b/drake/examples/QPInverseDynamicsForHumanoids/plan_eval/test/manipulator_plan_test.cc @@ -1,7 +1,7 @@ #include -#include "drake/common/drake_path.h" #include "drake/common/eigen_matrix_compare.h" +#include "drake/common/find_resource.h" #include "drake/examples/QPInverseDynamicsForHumanoids/plan_eval/manipulator_move_end_effector_plan.h" #include "drake/examples/QPInverseDynamicsForHumanoids/plan_eval/test/test_common.h" #include "drake/lcmt_manipulator_plan_move_end_effector.hpp" @@ -39,19 +39,17 @@ lcmt_manipulator_plan_move_end_effector make_move_end_effector_message( class ManipPlanTest : public GenericPlanTest { protected: void SetUp() override { - const std::string kModelPath = drake::GetDrakePath() + - "/manipulation/models/iiwa_description/urdf/" - "iiwa14_polytope_collision.urdf"; - - const std::string kAliasGroupsPath = - drake::GetDrakePath() + - "/examples/QPInverseDynamicsForHumanoids/" - "config/iiwa.alias_groups"; - - const std::string kControlConfigPath = - drake::GetDrakePath() + - "/examples/QPInverseDynamicsForHumanoids/" - "config/iiwa.id_controller_config"; + const std::string kModelPath = FindResourceOrThrow( + "drake/manipulation/models/iiwa_description/urdf/" + "iiwa14_polytope_collision.urdf"); + + const std::string kAliasGroupsPath = FindResourceOrThrow( + "drake/examples/QPInverseDynamicsForHumanoids/" + "config/iiwa.alias_groups"); + + const std::string kControlConfigPath = FindResourceOrThrow( + "drake/examples/QPInverseDynamicsForHumanoids/" + "config/iiwa.id_controller_config"); std::default_random_engine generator(123); AllocateResources(kModelPath, kAliasGroupsPath, kControlConfigPath); diff --git a/drake/examples/QPInverseDynamicsForHumanoids/system/BUILD b/drake/examples/QPInverseDynamicsForHumanoids/system/BUILD index 510e63244997..db54edb47c66 100644 --- a/drake/examples/QPInverseDynamicsForHumanoids/system/BUILD +++ b/drake/examples/QPInverseDynamicsForHumanoids/system/BUILD @@ -49,7 +49,6 @@ drake_cc_library( srcs = ["plan_eval_base_system.cc"], hdrs = ["plan_eval_base_system.h"], deps = [ - "//drake/common:drake_path", "//drake/examples/QPInverseDynamicsForHumanoids:control_utils", "//drake/examples/QPInverseDynamicsForHumanoids:humanoid_status", "//drake/examples/QPInverseDynamicsForHumanoids/param_parsers:param_parser", @@ -133,6 +132,7 @@ drake_cc_binary( tags = gurobi_test_tags(), deps = [ ":valkyrie_controller", + "//drake/common:find_resource", "//drake/examples/Valkyrie:valkyrie_constants", "//drake/systems/lcm:lcm_driven_loop", ], @@ -151,6 +151,7 @@ drake_cc_googletest( ":humanoid_plan_eval_system", ":qp_controller_system", "//drake/common:eigen_matrix_compare", + "//drake/common:find_resource", "//drake/examples/QPInverseDynamicsForHumanoids:control_utils", "//drake/examples/QPInverseDynamicsForHumanoids:qp_controller", "//drake/examples/QPInverseDynamicsForHumanoids/param_parsers:param_parser", @@ -174,6 +175,7 @@ drake_cc_googletest( deps = [ ":manipulator_inverse_dynamics_controller", "//drake/common:eigen_matrix_compare", + "//drake/common:find_resource", "//drake/multibody/parsers", "//drake/systems/analysis:simulator", "//drake/systems/controllers:inverse_dynamics_controller", @@ -194,6 +196,7 @@ drake_cc_googletest( deps = [ ":qp_controller_system", "//drake/common:eigen_matrix_compare", + "//drake/common:find_resource", "//drake/examples/QPInverseDynamicsForHumanoids:control_utils", "//drake/examples/QPInverseDynamicsForHumanoids/param_parsers:param_parser", "//drake/multibody/parsers", @@ -212,6 +215,7 @@ drake_cc_googletest( deps = [ ":atlas_joint_level_controller_system", "//drake/common:eigen_matrix_compare", + "//drake/common:find_resource", "//drake/multibody/parsers", "//drake/systems/framework", ], diff --git a/drake/examples/QPInverseDynamicsForHumanoids/system/humanoid_plan_eval_system.cc b/drake/examples/QPInverseDynamicsForHumanoids/system/humanoid_plan_eval_system.cc index f3b940e4a668..570af29da17e 100644 --- a/drake/examples/QPInverseDynamicsForHumanoids/system/humanoid_plan_eval_system.cc +++ b/drake/examples/QPInverseDynamicsForHumanoids/system/humanoid_plan_eval_system.cc @@ -5,7 +5,6 @@ #include #include -#include "drake/common/drake_path.h" #include "drake/examples/QPInverseDynamicsForHumanoids/control_utils.h" #include "drake/examples/QPInverseDynamicsForHumanoids/humanoid_status.h" diff --git a/drake/examples/QPInverseDynamicsForHumanoids/system/plan_eval_base_system.cc b/drake/examples/QPInverseDynamicsForHumanoids/system/plan_eval_base_system.cc index 95381b356d96..5b56d605b5fa 100644 --- a/drake/examples/QPInverseDynamicsForHumanoids/system/plan_eval_base_system.cc +++ b/drake/examples/QPInverseDynamicsForHumanoids/system/plan_eval_base_system.cc @@ -4,7 +4,6 @@ #include #include -#include "drake/common/drake_path.h" #include "drake/examples/QPInverseDynamicsForHumanoids/control_utils.h" #include "drake/examples/QPInverseDynamicsForHumanoids/humanoid_status.h" diff --git a/drake/examples/QPInverseDynamicsForHumanoids/system/test/humanoid_plan_eval_system_test.cc b/drake/examples/QPInverseDynamicsForHumanoids/system/test/humanoid_plan_eval_system_test.cc index a289fbb614e6..5d719490fa46 100644 --- a/drake/examples/QPInverseDynamicsForHumanoids/system/test/humanoid_plan_eval_system_test.cc +++ b/drake/examples/QPInverseDynamicsForHumanoids/system/test/humanoid_plan_eval_system_test.cc @@ -2,8 +2,8 @@ #include -#include "drake/common/drake_path.h" #include "drake/common/eigen_matrix_compare.h" +#include "drake/common/find_resource.h" #include "drake/examples/QPInverseDynamicsForHumanoids/control_utils.h" #include "drake/examples/QPInverseDynamicsForHumanoids/humanoid_status.h" #include "drake/examples/QPInverseDynamicsForHumanoids/system/qp_controller_system.h" @@ -31,20 +31,17 @@ namespace { class HumanoidPlanEvalAndQpInverseDynamicsTest : public ::testing::Test { protected: void SetUp() override { - const std::string kModelPath = - drake::GetDrakePath() + - "/examples/Valkyrie/urdf/urdf/" - "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf"; - - const std::string kAliasGroupsPath = - drake::GetDrakePath() + - "/examples/QPInverseDynamicsForHumanoids/" - "config/valkyrie.alias_groups"; - - const std::string kControlConfigPath = - drake::GetDrakePath() + - "/examples/QPInverseDynamicsForHumanoids/" - "config/valkyrie.id_controller_config"; + const std::string kModelPath = FindResourceOrThrow( + "drake/examples/Valkyrie/urdf/urdf/" + "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf"); + + const std::string kAliasGroupsPath = FindResourceOrThrow( + "drake/examples/QPInverseDynamicsForHumanoids/" + "config/valkyrie.alias_groups"); + + const std::string kControlConfigPath = FindResourceOrThrow( + "drake/examples/QPInverseDynamicsForHumanoids/" + "config/valkyrie.id_controller_config"); auto robot = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( diff --git a/drake/examples/QPInverseDynamicsForHumanoids/system/test/joint_level_controller_system_test.cc b/drake/examples/QPInverseDynamicsForHumanoids/system/test/joint_level_controller_system_test.cc index a00ac77262ce..a97b6192baf8 100644 --- a/drake/examples/QPInverseDynamicsForHumanoids/system/test/joint_level_controller_system_test.cc +++ b/drake/examples/QPInverseDynamicsForHumanoids/system/test/joint_level_controller_system_test.cc @@ -5,8 +5,8 @@ #include #include "bot_core/atlas_command_t.hpp" -#include "drake/common/drake_path.h" #include "drake/common/eigen_matrix_compare.h" +#include "drake/common/find_resource.h" #include "drake/examples/QPInverseDynamicsForHumanoids/qp_controller_common.h" #include "drake/examples/QPInverseDynamicsForHumanoids/system/atlas_joint_level_controller_system.h" #include "drake/multibody/joints/floating_base_types.h" @@ -24,9 +24,9 @@ class JointLevelControllerTest : public ::testing::Test { robot_ = std::make_unique>(); // Use this model because the dof order and actuator order are different. parsers::urdf::AddModelInstanceFromUrdfFile( - GetDrakePath() + - "/examples/Valkyrie/urdf/urdf/" - "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf", + FindResourceOrThrow( + "drake/examples/Valkyrie/urdf/urdf/" + "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf"), drake::multibody::joints::kQuaternion, nullptr /* weld to frame */, robot_.get()); diff --git a/drake/examples/QPInverseDynamicsForHumanoids/system/test/manipulator_inverse_dynamics_controller_test.cc b/drake/examples/QPInverseDynamicsForHumanoids/system/test/manipulator_inverse_dynamics_controller_test.cc index a216daa8d58d..a9f7755261a9 100644 --- a/drake/examples/QPInverseDynamicsForHumanoids/system/test/manipulator_inverse_dynamics_controller_test.cc +++ b/drake/examples/QPInverseDynamicsForHumanoids/system/test/manipulator_inverse_dynamics_controller_test.cc @@ -2,8 +2,8 @@ #include -#include "drake/common/drake_path.h" #include "drake/common/eigen_matrix_compare.h" +#include "drake/common/find_resource.h" #include "drake/examples/QPInverseDynamicsForHumanoids/control_utils.h" #include "drake/examples/QPInverseDynamicsForHumanoids/humanoid_status.h" #include "drake/examples/QPInverseDynamicsForHumanoids/system/qp_controller_system.h" @@ -25,19 +25,17 @@ namespace { class ManipulatorInverseDynamicsControllerTest : public ::testing::Test { protected: void SetUp() override { - const std::string kModelPath = drake::GetDrakePath() + - "/manipulation/models/iiwa_description/urdf/" - "iiwa14_polytope_collision.urdf"; - - const std::string kAliasGroupsPath = - drake::GetDrakePath() + - "/examples/QPInverseDynamicsForHumanoids/" - "config/iiwa.alias_groups"; - - const std::string kControlConfigPath = - drake::GetDrakePath() + - "/examples/QPInverseDynamicsForHumanoids/" - "config/iiwa.id_controller_config"; + const std::string kModelPath = FindResourceOrThrow( + "drake/manipulation/models/iiwa_description/urdf/" + "iiwa14_polytope_collision.urdf"); + + const std::string kAliasGroupsPath = FindResourceOrThrow( + "drake/examples/QPInverseDynamicsForHumanoids/" + "config/iiwa.alias_groups"); + + const std::string kControlConfigPath = FindResourceOrThrow( + "drake/examples/QPInverseDynamicsForHumanoids/" + "config/iiwa.id_controller_config"); auto robot = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( diff --git a/drake/examples/QPInverseDynamicsForHumanoids/system/test/qp_controller_system_test.cc b/drake/examples/QPInverseDynamicsForHumanoids/system/test/qp_controller_system_test.cc index 57082f90920c..b51797cbd3b0 100644 --- a/drake/examples/QPInverseDynamicsForHumanoids/system/test/qp_controller_system_test.cc +++ b/drake/examples/QPInverseDynamicsForHumanoids/system/test/qp_controller_system_test.cc @@ -2,8 +2,8 @@ #include -#include "drake/common/drake_path.h" #include "drake/common/eigen_matrix_compare.h" +#include "drake/common/find_resource.h" #include "drake/examples/QPInverseDynamicsForHumanoids/control_utils.h" #include "drake/examples/QPInverseDynamicsForHumanoids/humanoid_status.h" #include "drake/examples/QPInverseDynamicsForHumanoids/param_parsers/param_parser.h" @@ -22,20 +22,17 @@ namespace qp_inverse_dynamics { // constraints, the inverse dynamics controller should track the desired // acceleration almost perfectly. GTEST_TEST(testQpControllerSystem, IiwaInverseDynamics) { - const std::string kModelPath = - drake::GetDrakePath() + - "/manipulation/models/iiwa_description/urdf/" - "iiwa14_polytope_collision.urdf"; - - const std::string kAliasGroupsPath = - drake::GetDrakePath() + - "/examples/QPInverseDynamicsForHumanoids/config/" - "iiwa.alias_groups"; - - const std::string kControlConfigPath = - drake::GetDrakePath() + - "/examples/QPInverseDynamicsForHumanoids/config/" - "iiwa.id_controller_config"; + const std::string kModelPath = FindResourceOrThrow( + "drake/manipulation/models/iiwa_description/urdf/" + "iiwa14_polytope_collision.urdf"); + + const std::string kAliasGroupsPath = FindResourceOrThrow( + "drake/examples/QPInverseDynamicsForHumanoids/config/" + "iiwa.alias_groups"); + + const std::string kControlConfigPath = FindResourceOrThrow( + "drake/examples/QPInverseDynamicsForHumanoids/config/" + "iiwa.id_controller_config"); auto robot = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( diff --git a/drake/examples/QPInverseDynamicsForHumanoids/system/valkyrie_balancing_controller_system.cc b/drake/examples/QPInverseDynamicsForHumanoids/system/valkyrie_balancing_controller_system.cc index ea957197754d..2601ef40ea25 100644 --- a/drake/examples/QPInverseDynamicsForHumanoids/system/valkyrie_balancing_controller_system.cc +++ b/drake/examples/QPInverseDynamicsForHumanoids/system/valkyrie_balancing_controller_system.cc @@ -1,4 +1,4 @@ -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/examples/QPInverseDynamicsForHumanoids/system/valkyrie_controller.h" #include "drake/examples/Valkyrie/valkyrie_constants.h" #include "drake/systems/lcm/lcm_driven_loop.h" @@ -13,17 +13,15 @@ namespace qp_inverse_dynamics { // The overall input and output is a LCM message of type // bot_core::robot_state_t and bot_core::atlas_command_t. void controller_loop() { - const std::string kModelFileName = - drake::GetDrakePath() + - "/examples/Valkyrie/urdf/urdf/" - "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf"; - const std::string kAliasGroupPath = drake::GetDrakePath() + - "/examples/QPInverseDynamicsForHumanoids/" - "config/valkyrie.alias_groups"; - const std::string kControlConfigPath = - drake::GetDrakePath() + - "/examples/QPInverseDynamicsForHumanoids/" - "config/valkyrie.id_controller_config"; + const std::string kModelFileName = FindResourceOrThrow( + "drake/examples/Valkyrie/urdf/urdf/" + "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf"); + const std::string kAliasGroupPath = FindResourceOrThrow( + "drake/examples/QPInverseDynamicsForHumanoids/" + "config/valkyrie.alias_groups"); + const std::string kControlConfigPath = FindResourceOrThrow( + "drake/examples/QPInverseDynamicsForHumanoids/" + "config/valkyrie.id_controller_config"); drake::lcm::DrakeLcm lcm; ValkyrieController valkyrie_controller(kModelFileName, kControlConfigPath, diff --git a/drake/examples/QPInverseDynamicsForHumanoids/test/iiwa_inverse_dynamics_test.cc b/drake/examples/QPInverseDynamicsForHumanoids/test/iiwa_inverse_dynamics_test.cc index 35cf5a83b609..7cc946240a3c 100644 --- a/drake/examples/QPInverseDynamicsForHumanoids/test/iiwa_inverse_dynamics_test.cc +++ b/drake/examples/QPInverseDynamicsForHumanoids/test/iiwa_inverse_dynamics_test.cc @@ -1,7 +1,7 @@ #include -#include "drake/common/drake_path.h" #include "drake/common/eigen_matrix_compare.h" +#include "drake/common/find_resource.h" #include "drake/common/text_logging.h" #include "drake/examples/QPInverseDynamicsForHumanoids/control_utils.h" #include "drake/examples/QPInverseDynamicsForHumanoids/param_parsers/param_parser.h" @@ -19,15 +19,15 @@ namespace qp_inverse_dynamics { // dynamics should return a generalized acceleration very close to the desired // one. GTEST_TEST(testQPInverseDynamicsController, testForIiwa) { - std::string urdf = drake::GetDrakePath() + - "/manipulation/models/iiwa_description/urdf/" - "iiwa14_polytope_collision.urdf"; - std::string alias_groups_config = drake::GetDrakePath() + - "/examples/QPInverseDynamicsForHumanoids/" - "config/iiwa.alias_groups"; - std::string controller_config = drake::GetDrakePath() + - "/examples/QPInverseDynamicsForHumanoids/" - "config/iiwa.id_controller_config"; + std::string urdf = FindResourceOrThrow( + "drake/manipulation/models/iiwa_description/urdf/" + "iiwa14_polytope_collision.urdf"); + std::string alias_groups_config = FindResourceOrThrow( + "drake/examples/QPInverseDynamicsForHumanoids/" + "config/iiwa.alias_groups"); + std::string controller_config = FindResourceOrThrow( + "drake/examples/QPInverseDynamicsForHumanoids/" + "config/iiwa.id_controller_config"); auto robot = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( diff --git a/drake/examples/QPInverseDynamicsForHumanoids/test/lcm_utils_test.cc b/drake/examples/QPInverseDynamicsForHumanoids/test/lcm_utils_test.cc index 349298296646..cf2206e44303 100644 --- a/drake/examples/QPInverseDynamicsForHumanoids/test/lcm_utils_test.cc +++ b/drake/examples/QPInverseDynamicsForHumanoids/test/lcm_utils_test.cc @@ -5,8 +5,8 @@ #include -#include "drake/common/drake_path.h" #include "drake/common/eigen_matrix_compare.h" +#include "drake/common/find_resource.h" #include "drake/multibody/joints/floating_base_types.h" #include "drake/multibody/parsers/urdf_parser.h" #include "drake/multibody/rigid_body_tree.h" @@ -199,9 +199,9 @@ class LcmUtilsTests : public ::testing::Test { virtual void SetUp() { tree_ = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( - GetDrakePath() + - "/examples/Valkyrie/urdf/urdf/" - "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf", + FindResourceOrThrow( + "drake/examples/Valkyrie/urdf/urdf/" + "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf"), multibody::joints::kRollPitchYaw, tree_.get()); } diff --git a/drake/examples/QPInverseDynamicsForHumanoids/test/valkyrie_balancing_test.cc b/drake/examples/QPInverseDynamicsForHumanoids/test/valkyrie_balancing_test.cc index c2102b3ce60e..bd553894aa10 100644 --- a/drake/examples/QPInverseDynamicsForHumanoids/test/valkyrie_balancing_test.cc +++ b/drake/examples/QPInverseDynamicsForHumanoids/test/valkyrie_balancing_test.cc @@ -1,7 +1,7 @@ #include -#include "drake/common/drake_path.h" #include "drake/common/eigen_matrix_compare.h" +#include "drake/common/find_resource.h" #include "drake/common/text_logging.h" #include "drake/examples/QPInverseDynamicsForHumanoids/control_utils.h" #include "drake/examples/QPInverseDynamicsForHumanoids/param_parsers/param_parser.h" @@ -25,14 +25,15 @@ namespace qp_inverse_dynamics { // seconds. GTEST_TEST(testQPInverseDynamicsController, testBalancingStanding) { // Loads model. - std::string urdf = drake::GetDrakePath() + "/examples/Valkyrie/urdf/urdf/" - "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf"; - std::string alias_groups_config = - drake::GetDrakePath() + "/examples/QPInverseDynamicsForHumanoids/" - "config/valkyrie.alias_groups"; - std::string controller_config = - drake::GetDrakePath() + "/examples/QPInverseDynamicsForHumanoids/" - "config/valkyrie.id_controller_config"; + std::string urdf = FindResourceOrThrow( + "drake/examples/Valkyrie/urdf/urdf/" + "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf"); + std::string alias_groups_config = FindResourceOrThrow( + "drake/examples/QPInverseDynamicsForHumanoids/" + "config/valkyrie.alias_groups"); + std::string controller_config = FindResourceOrThrow( + "drake/examples/QPInverseDynamicsForHumanoids/" + "config/valkyrie.id_controller_config"); auto robot = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( diff --git a/drake/examples/Quadrotor/BUILD b/drake/examples/Quadrotor/BUILD index 2098bca4c7d7..d82fc6447f0b 100644 --- a/drake/examples/Quadrotor/BUILD +++ b/drake/examples/Quadrotor/BUILD @@ -43,7 +43,7 @@ drake_cc_binary( test_rule_size = "medium", deps = [ ":quadrotor_plant", - "//drake/common:drake_path", + "//drake/common:find_resource", "//drake/lcm", "//drake/multibody:rigid_body_tree", "//drake/multibody:rigid_body_tree_construction", @@ -68,7 +68,7 @@ drake_cc_binary( ], deps = [ ":quadrotor_plant", - "//drake/common:drake_path", + "//drake/common:find_resource", "//drake/common:is_approx_equal_abstol", "//drake/lcm", "//drake/multibody:rigid_body_tree", @@ -87,8 +87,8 @@ drake_cc_googletest( data = [":models"], deps = [ ":quadrotor_plant", - "//drake/common:drake_path", "//drake/common:eigen_matrix_compare", + "//drake/common:find_resource", "//drake/multibody:rigid_body_tree_construction", "//drake/multibody/parsers", "//drake/multibody/rigid_body_plant", diff --git a/drake/examples/Quadrotor/run_quadrotor_dynamics.cc b/drake/examples/Quadrotor/run_quadrotor_dynamics.cc index 500b501dee72..0abab5b28285 100644 --- a/drake/examples/Quadrotor/run_quadrotor_dynamics.cc +++ b/drake/examples/Quadrotor/run_quadrotor_dynamics.cc @@ -6,7 +6,7 @@ #include -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/common/text_logging.h" #include "drake/lcm/drake_lcm.h" #include "drake/multibody/parsers/model_instance_id_table.h" @@ -43,11 +43,11 @@ class Quadrotor : public systems::Diagram { auto tree = std::make_unique>(); ModelInstanceIdTable model_id_table = AddModelInstanceFromUrdfFileToWorld( - drake::GetDrakePath() + "/examples/Quadrotor/quadrotor.urdf", + FindResourceOrThrow("drake/examples/Quadrotor/quadrotor.urdf"), kRollPitchYaw, tree.get()); const int quadrotor_id = model_id_table.at("quadrotor"); AddModelInstancesFromSdfFile( - drake::GetDrakePath() + "/examples/Quadrotor/warehouse.sdf", + FindResourceOrThrow("drake/examples/Quadrotor/warehouse.sdf"), kFixed, nullptr /* weld to frame */, tree.get()); drake::multibody::AddFlatTerrainToWorld(tree.get()); diff --git a/drake/examples/Quadrotor/run_quadrotor_lqr.cc b/drake/examples/Quadrotor/run_quadrotor_lqr.cc index 1d393403bd28..e4e0a15aa6a6 100644 --- a/drake/examples/Quadrotor/run_quadrotor_lqr.cc +++ b/drake/examples/Quadrotor/run_quadrotor_lqr.cc @@ -7,7 +7,7 @@ #include -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/common/is_approx_equal_abstol.h" #include "drake/examples/Quadrotor/quadrotor_plant.h" #include "drake/lcm/drake_lcm.h" @@ -42,7 +42,7 @@ int do_main() { auto tree = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( - GetDrakePath() + "/examples/Quadrotor/quadrotor.urdf", + FindResourceOrThrow("drake/examples/Quadrotor/quadrotor.urdf"), multibody::joints::kRollPitchYaw, tree.get()); // The nominal hover position is at (0, 0, 1.0) in world coordinates. diff --git a/drake/examples/Quadrotor/test/quadrotor_dynamics_test.cc b/drake/examples/Quadrotor/test/quadrotor_dynamics_test.cc index 01ca9be5f002..ef4b832c6de2 100644 --- a/drake/examples/Quadrotor/test/quadrotor_dynamics_test.cc +++ b/drake/examples/Quadrotor/test/quadrotor_dynamics_test.cc @@ -2,8 +2,8 @@ #include -#include "drake/common/drake_path.h" #include "drake/common/eigen_matrix_compare.h" +#include "drake/common/find_resource.h" #include "drake/examples/Quadrotor/quadrotor_plant.h" #include "drake/multibody/parsers/urdf_parser.h" #include "drake/multibody/rigid_body_plant/rigid_body_plant.h" @@ -76,7 +76,7 @@ class RigidBodyQuadrotor: public systems::Diagram { auto tree = std::make_unique>(); drake::parsers::urdf::AddModelInstanceFromUrdfFile( - drake::GetDrakePath() + "/examples/Quadrotor/quadrotor.urdf", + FindResourceOrThrow("drake/examples/Quadrotor/quadrotor.urdf"), multibody::joints::kRollPitchYaw, nullptr, tree.get()); systems::DiagramBuilder builder; diff --git a/drake/examples/Valkyrie/BUILD b/drake/examples/Valkyrie/BUILD index 6eeb50f7e4a3..c736cf7dbe43 100644 --- a/drake/examples/Valkyrie/BUILD +++ b/drake/examples/Valkyrie/BUILD @@ -75,7 +75,7 @@ drake_cc_library( ":robot_state_decoder", ":valkyrie_constants", "//drake/common", - "//drake/common:drake_path", + "//drake/common:find_resource", "//drake/lcm", "//drake/multibody:kinematics_cache", "//drake/multibody:rigid_body_tree", @@ -110,6 +110,7 @@ drake_cc_library( ":robot_command_to_desired_effort_converter", ":robot_state_encoder", ":valkyrie_constants", + "//drake/common:find_resource", "//drake/lcm", "//drake/lcmtypes:contact_info_for_viz", "//drake/lcmtypes:contact_results_for_viz", @@ -142,8 +143,8 @@ drake_cc_googletest( deps = [ ":robot_state_decoder", ":robot_state_encoder", - "//drake/common:drake_path", "//drake/common:eigen_matrix_compare", + "//drake/common:find_resource", "//drake/math:geometric_transform", "//drake/multibody:rigid_body_tree_construction", "//drake/multibody/parsers", @@ -160,8 +161,8 @@ drake_cc_googletest( data = [":models"], deps = [ ":robot_command_to_desired_effort_converter", - "//drake/common:drake_path", "//drake/common:eigen_matrix_compare", + "//drake/common:find_resource", "//drake/multibody/parsers", "//drake/systems/framework:diagram", "//drake/systems/primitives:constant_value_source", @@ -179,7 +180,7 @@ drake_cc_googletest( name = "valkyrie_ik_test", data = [":models"], deps = [ - "//drake/common:drake_path", + "//drake/common:find_resource", "//drake/lcm", "//drake/multibody:inverse_kinematics", "//drake/multibody:rigid_body_constraint", diff --git a/drake/examples/Valkyrie/test/robot_command_to_desired_effort_converter_test.cc b/drake/examples/Valkyrie/test/robot_command_to_desired_effort_converter_test.cc index 49a8f6d25147..dd16869d2990 100644 --- a/drake/examples/Valkyrie/test/robot_command_to_desired_effort_converter_test.cc +++ b/drake/examples/Valkyrie/test/robot_command_to_desired_effort_converter_test.cc @@ -3,8 +3,8 @@ #include #include "lcmtypes/bot_core/atlas_command_t.hpp" -#include "drake/common/drake_path.h" #include "drake/common/eigen_matrix_compare.h" +#include "drake/common/find_resource.h" #include "drake/multibody/parsers/urdf_parser.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/primitives/constant_value_source.h" @@ -18,6 +18,9 @@ using std::move; using multibody::joints::FloatingBaseType; +const char* kValkyrieUrdf = "drake/examples/Valkyrie/urdf/urdf/" + "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf"; + void TestCommandToDesiredEffortConverter( const RigidBodyTree& tree, const bot_core::atlas_command_t& message, const std::map& expected_efforts) { @@ -65,9 +68,7 @@ GTEST_TEST(EffortToInputConverterTest, TestEmptyMessage) { RigidBodyTree tree; drake::parsers::urdf::AddModelInstanceFromUrdfFile( - drake::GetDrakePath() + - "/examples/Valkyrie/urdf/urdf/" - "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf", + FindResourceOrThrow(kValkyrieUrdf), FloatingBaseType::kRollPitchYaw, nullptr /* weld to frame */, &tree); std::map expected_efforts; @@ -83,9 +84,7 @@ GTEST_TEST(EffortToInputConverterTest, TestNonEmptyMessage) { RigidBodyTree tree; drake::parsers::urdf::AddModelInstanceFromUrdfFile( - drake::GetDrakePath() + - "/examples/Valkyrie/urdf/urdf/" - "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf", + FindResourceOrThrow(kValkyrieUrdf), FloatingBaseType::kRollPitchYaw, nullptr /* weld to frame */, &tree); std::map expected_efforts; diff --git a/drake/examples/Valkyrie/test/robot_state_encoder_decoder_test.cc b/drake/examples/Valkyrie/test/robot_state_encoder_decoder_test.cc index 21a99ea8e260..0dfb009e1320 100644 --- a/drake/examples/Valkyrie/test/robot_state_encoder_decoder_test.cc +++ b/drake/examples/Valkyrie/test/robot_state_encoder_decoder_test.cc @@ -5,8 +5,8 @@ #include -#include "drake/common/drake_path.h" #include "drake/common/eigen_matrix_compare.h" +#include "drake/common/find_resource.h" #include "drake/math/quaternion.h" #include "drake/multibody/parsers/urdf_parser.h" #include "drake/multibody/rigid_body_plant/contact_results.h" @@ -59,9 +59,9 @@ static ContactForce TransformContactWrench( void TestEncodeThenDecode(FloatingBaseType floating_base_type) { RigidBodyTree tree; drake::parsers::urdf::AddModelInstanceFromUrdfFile( - drake::GetDrakePath() + - "/examples/Valkyrie/urdf/urdf/" - "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf", + FindResourceOrThrow( + "drake/examples/Valkyrie/urdf/urdf/" + "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf"), floating_base_type, nullptr /* weld to frame */, &tree); // Add a collision geom for the world. multibody::AddFlatTerrainToWorld(&tree, 100., 10.); diff --git a/drake/examples/Valkyrie/test/valkyrie_ik_test.cc b/drake/examples/Valkyrie/test/valkyrie_ik_test.cc index cf63ec078ce6..9a813bf3f237 100644 --- a/drake/examples/Valkyrie/test/valkyrie_ik_test.cc +++ b/drake/examples/Valkyrie/test/valkyrie_ik_test.cc @@ -7,7 +7,7 @@ #include -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/lcm/drake_lcm.h" #include "drake/multibody/constraint/rigid_body_constraint.h" #include "drake/multibody/ik_options.h" @@ -64,8 +64,9 @@ void FindJointAndInsert(const RigidBodyTreed* model, const std::string& name, GTEST_TEST(ValkyrieIK_Test, ValkyrieIK_Test_StandingPose_Test) { auto tree = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( - GetDrakePath() + "/examples/Valkyrie/urdf/urdf/" - "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf", + FindResourceOrThrow( + "drake/examples/Valkyrie/urdf/urdf/" + "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf"), multibody::joints::kRollPitchYaw, tree.get()); // Setting up constraints, based on testIKMoreConstraints.cpp and diff --git a/drake/examples/Valkyrie/valkyrie_pd_ff_controller.cc b/drake/examples/Valkyrie/valkyrie_pd_ff_controller.cc index 2b51875e3c99..1fc6a9b71232 100644 --- a/drake/examples/Valkyrie/valkyrie_pd_ff_controller.cc +++ b/drake/examples/Valkyrie/valkyrie_pd_ff_controller.cc @@ -8,7 +8,7 @@ #include "lcmtypes/bot_core/atlas_command_t.hpp" #include "lcmtypes/bot_core/robot_state_t.hpp" -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/examples/Valkyrie/robot_state_decoder.h" #include "drake/examples/Valkyrie/valkyrie_constants.h" #include "drake/lcm/drake_lcm.h" @@ -126,10 +126,8 @@ void ValkyriePDAndFeedForwardController::OutputCommand( void run_valkyrie_pd_ff_controller() { - std::string urdf = - drake::GetDrakePath() + - std::string( - "/examples/Valkyrie/urdf/urdf/" + std::string urdf = FindResourceOrThrow( + "drake/examples/Valkyrie/urdf/urdf/" "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf"); auto robot = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( diff --git a/drake/examples/Valkyrie/valkyrie_simulator.h b/drake/examples/Valkyrie/valkyrie_simulator.h index 21b81882658c..347f4ffaf511 100644 --- a/drake/examples/Valkyrie/valkyrie_simulator.h +++ b/drake/examples/Valkyrie/valkyrie_simulator.h @@ -8,7 +8,7 @@ #include "lcmtypes/bot_core/atlas_command_t.hpp" #include "lcmtypes/bot_core/robot_state_t.hpp" -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/common/text_logging.h" #include "drake/examples/Valkyrie/actuator_effort_to_rigid_body_plant_input_converter.h" #include "drake/examples/Valkyrie/robot_command_to_desired_effort_converter.h" @@ -42,9 +42,9 @@ class ValkyrieSimulationDiagram : public systems::Diagram { // Create RigidBodyTree. auto tree_ptr = std::make_unique>(); drake::parsers::urdf::AddModelInstanceFromUrdfFile( - drake::GetDrakePath() + - "/examples/Valkyrie/urdf/urdf/" - "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf", + FindResourceOrThrow( + "drake/examples/Valkyrie/urdf/urdf/" + "valkyrie_A_sim_drake_one_neck_dof_wide_ankle_rom.urdf"), multibody::joints::kRollPitchYaw, nullptr /* weld to frame */, tree_ptr.get()); multibody::AddFlatTerrainToWorld(tree_ptr.get(), 100., 10.); diff --git a/drake/examples/contact_model/BUILD b/drake/examples/contact_model/BUILD index bbcd4849fd15..dd270a608393 100644 --- a/drake/examples/contact_model/BUILD +++ b/drake/examples/contact_model/BUILD @@ -19,7 +19,7 @@ drake_cc_binary( " --playback=false", ], deps = [ - "//drake/common:drake_path", + "//drake/common:find_resource", "//drake/lcm", "//drake/multibody:rigid_body_tree_construction", "//drake/multibody/parsers", @@ -44,7 +44,7 @@ drake_cc_binary( " --playback=false", ], deps = [ - "//drake/common:drake_path", + "//drake/common:find_resource", "//drake/lcm", "//drake/multibody:rigid_body_tree_construction", "//drake/multibody/parsers", @@ -68,7 +68,7 @@ drake_cc_binary( " --playback=false", ], deps = [ - "//drake/common:drake_path", + "//drake/common:find_resource", "//drake/lcm", "//drake/multibody:rigid_body_tree_construction", "//drake/multibody/parsers", diff --git a/drake/examples/contact_model/bowling_ball.cc b/drake/examples/contact_model/bowling_ball.cc index 13ec7ee3cadf..edd1cd295228 100644 --- a/drake/examples/contact_model/bowling_ball.cc +++ b/drake/examples/contact_model/bowling_ball.cc @@ -28,8 +28,8 @@ #include -#include "drake/common/drake_path.h" #include "drake/common/eigen_types.h" +#include "drake/common/find_resource.h" #include "drake/lcm/drake_lcm.h" #include "drake/multibody/parsers/urdf_parser.h" #include "drake/multibody/rigid_body_plant/drake_visualizer.h" @@ -87,13 +87,13 @@ int main() { // Create RigidBodyTree. auto tree_ptr = make_unique>(); drake::parsers::urdf::AddModelInstanceFromUrdfFile( - drake::GetDrakePath() + "/examples/contact_model/bowling_ball.urdf", + FindResourceOrThrow("drake/examples/contact_model/bowling_ball.urdf"), kQuaternion, nullptr /* weld to frame */, tree_ptr.get()); for (int i = 0; i < FLAGS_pin_count; ++i) { drake::parsers::urdf::AddModelInstanceFromUrdfFile( - drake::GetDrakePath() + "/examples/contact_model/pin.urdf", kQuaternion, - nullptr /* weld to frame */, tree_ptr.get()); + FindResourceOrThrow("drake/examples/contact_model/pin.urdf"), + kQuaternion, nullptr /* weld to frame */, tree_ptr.get()); } multibody::AddFlatTerrainToWorld(tree_ptr.get(), 100., 10.); diff --git a/drake/examples/contact_model/rigid_gripper.cc b/drake/examples/contact_model/rigid_gripper.cc index 68e5b015ed8c..c3504899bea6 100644 --- a/drake/examples/contact_model/rigid_gripper.cc +++ b/drake/examples/contact_model/rigid_gripper.cc @@ -20,7 +20,7 @@ during stiction). #include -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/lcm/drake_lcm.h" #include "drake/lcmt_contact_results_for_viz.hpp" #include "drake/multibody/parsers/urdf_parser.h" @@ -63,7 +63,7 @@ std::unique_ptr BuildTestTree() { &tree->world(), Eigen::Vector3d(0, -0.065, 0.05), Eigen::Vector3d::Zero()); parsers::urdf::AddModelInstanceFromUrdfFile( - GetDrakePath() + "/examples/contact_model/rigid_gripper.urdf", + FindResourceOrThrow("drake/examples/contact_model/rigid_gripper.urdf"), multibody::joints::kFixed, gripper_frame, tree.get()); // Add a box to grip. Position it such that if there *were* a plane at z = 0, @@ -73,7 +73,7 @@ std::unique_ptr BuildTestTree() { Eigen::aligned_allocator>(), "box_offset", &tree->world(), Eigen::Vector3d(0, 0, 0.075), Eigen::Vector3d::Zero()); parsers::urdf::AddModelInstanceFromUrdfFile( - GetDrakePath() + "/multibody/models/box_small.urdf", + FindResourceOrThrow("drake/multibody/models/box_small.urdf"), multibody::joints::kQuaternion, box_frame, tree.get()); return tree; diff --git a/drake/examples/contact_model/sliding_bricks.cc b/drake/examples/contact_model/sliding_bricks.cc index b2aa351586bf..944ce68f7e47 100644 --- a/drake/examples/contact_model/sliding_bricks.cc +++ b/drake/examples/contact_model/sliding_bricks.cc @@ -4,8 +4,8 @@ #include -#include "drake/common/drake_path.h" #include "drake/common/eigen_types.h" +#include "drake/common/find_resource.h" #include "drake/lcm/drake_lcm.h" #include "drake/multibody/parsers/urdf_parser.h" #include "drake/multibody/rigid_body_plant/drake_visualizer.h" @@ -47,6 +47,11 @@ DEFINE_double(sim_duration, 3, "The simulation duration"); DEFINE_bool(playback, true, "If true, enters looping playback after sim finished"); +namespace { +const char* kSlidingBrickUrdf = + "drake/examples/contact_model/sliding_brick.urdf"; +} // namespace + // Simple scenario of two blocks being pushed across a plane. The first block // has zero initial velocity. The second has a small initial velocity in the // pushing direction. @@ -66,10 +71,10 @@ int main() { // Create RigidBodyTree. auto tree_ptr = make_unique>(); drake::parsers::urdf::AddModelInstanceFromUrdfFile( - drake::GetDrakePath() + "/examples/contact_model/sliding_brick.urdf", + FindResourceOrThrow(kSlidingBrickUrdf), kFixed, nullptr /* weld to frame */, tree_ptr.get()); drake::parsers::urdf::AddModelInstanceFromUrdfFile( - drake::GetDrakePath() + "/examples/contact_model/sliding_brick.urdf", + FindResourceOrThrow(kSlidingBrickUrdf), kFixed, nullptr /* weld to frame */, tree_ptr.get()); multibody::AddFlatTerrainToWorld(tree_ptr.get(), 100., 10.); diff --git a/drake/examples/kinova_jaco_arm/BUILD b/drake/examples/kinova_jaco_arm/BUILD index 53ec36d61e6e..4af49a3c93f9 100644 --- a/drake/examples/kinova_jaco_arm/BUILD +++ b/drake/examples/kinova_jaco_arm/BUILD @@ -36,6 +36,7 @@ drake_cc_binary( test_rule_args = ["--simulation_sec=0.1"], deps = [ ":jaco_common", + "//drake/common:find_resource", "//drake/common:text_logging_gflags", "//drake/lcm", "//drake/multibody:rigid_body_tree_construction", @@ -58,6 +59,7 @@ drake_cc_binary( test_rule_args = ["--simulation_sec=0.1"], deps = [ ":jaco_common", + "//drake/common:find_resource", "//drake/lcm", "//drake/multibody:rigid_body_tree_construction", "//drake/multibody/rigid_body_plant", @@ -80,6 +82,7 @@ drake_cc_binary( test_rule_args = ["--simulation_sec=0.1"], deps = [ ":jaco_common", + "//drake/common:find_resource", "//drake/common/trajectories:piecewise_polynomial_trajectory", "//drake/lcm", "//drake/multibody:inverse_kinematics", diff --git a/drake/examples/kinova_jaco_arm/run_controlled_jaco_demo.cc b/drake/examples/kinova_jaco_arm/run_controlled_jaco_demo.cc index 9c217208c536..6a83cd45207b 100644 --- a/drake/examples/kinova_jaco_arm/run_controlled_jaco_demo.cc +++ b/drake/examples/kinova_jaco_arm/run_controlled_jaco_demo.cc @@ -11,7 +11,7 @@ #include -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/common/trajectories/piecewise_polynomial_trajectory.h" #include "drake/examples/kinova_jaco_arm/jaco_common.h" #include "drake/lcm/drake_lcm.h" @@ -39,15 +39,13 @@ namespace examples { namespace kinova_jaco_arm { namespace { -const char kRelUrdfPath[] = - "/manipulation/models/jaco_description/urdf/j2n6s300.urdf"; +const char* kRelUrdfPath = + "drake/manipulation/models/jaco_description/urdf/j2n6s300.urdf"; std::unique_ptr MakePlan() { - const std::string kUrdfPath = - drake::GetDrakePath() + std::string(kRelUrdfPath); auto tree = make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( - kUrdfPath, multibody::joints::kFixed, tree.get()); + FindResourceOrThrow(kRelUrdfPath), multibody::joints::kFixed, tree.get()); // Create a basic point-wise IK trajectory for moving the Jaco arm. // It starts in the zero configuration (straight up). @@ -155,9 +153,6 @@ std::unique_ptr MakePlan() { int DoMain() { DRAKE_DEMAND(FLAGS_simulation_sec > 0); - const std::string kUrdfPath = - drake::GetDrakePath() + std::string(kRelUrdfPath); - drake::lcm::DrakeLcm lcm; systems::DiagramBuilder builder; systems::RigidBodyPlant* plant = nullptr; @@ -166,7 +161,8 @@ int DoMain() { { auto tree = make_unique>(); drake::multibody::AddFlatTerrainToWorld(tree.get()); - CreateTreeFromFixedModelAtPose(kUrdfPath, tree.get()); + CreateTreeFromFixedModelAtPose(FindResourceOrThrow(kRelUrdfPath), + tree.get()); auto tree_sys = std::make_unique>(std::move(tree)); diff --git a/drake/examples/kinova_jaco_arm/run_passive_jaco_demo.cc b/drake/examples/kinova_jaco_arm/run_passive_jaco_demo.cc index 9559edcf1de3..beff2a780f8f 100644 --- a/drake/examples/kinova_jaco_arm/run_passive_jaco_demo.cc +++ b/drake/examples/kinova_jaco_arm/run_passive_jaco_demo.cc @@ -6,7 +6,7 @@ #include -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/common/text_logging_gflags.h" #include "drake/examples/kinova_jaco_arm/jaco_common.h" #include "drake/lcm/drake_lcm.h" @@ -40,13 +40,13 @@ int DoMain() { // Adds a plant. RigidBodyPlant* plant = nullptr; - const std::string kModelPath = drake::GetDrakePath() + - "/manipulation/models/jaco_description/urdf/" - "j2n6s300.urdf"; { auto tree = std::make_unique>(); drake::multibody::AddFlatTerrainToWorld(tree.get()); - CreateTreeFromFixedModelAtPose(kModelPath, tree.get()); + CreateTreeFromFixedModelAtPose( + FindResourceOrThrow( + "drake/manipulation/models/jaco_description/urdf/j2n6s300.urdf"), + tree.get()); auto tree_sys = std::make_unique>(std::move(tree)); diff --git a/drake/examples/kinova_jaco_arm/run_setpose_jaco_demo.cc b/drake/examples/kinova_jaco_arm/run_setpose_jaco_demo.cc index 5134e2a216e7..c052fcaddb1a 100644 --- a/drake/examples/kinova_jaco_arm/run_setpose_jaco_demo.cc +++ b/drake/examples/kinova_jaco_arm/run_setpose_jaco_demo.cc @@ -7,7 +7,7 @@ #include -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/examples/kinova_jaco_arm/jaco_common.h" #include "drake/lcm/drake_lcm.h" #include "drake/multibody/rigid_body_plant/drake_visualizer.h" @@ -32,14 +32,14 @@ int DoMain() { systems::DiagramBuilder builder; systems::RigidBodyPlant* plant = nullptr; - const std::string kUrdfPath = drake::GetDrakePath() + - "/manipulation/models/jaco_description/urdf/" - "j2n6s300.urdf"; { auto tree = std::make_unique>(); drake::multibody::AddFlatTerrainToWorld(tree.get()); - CreateTreeFromFixedModelAtPose(kUrdfPath, tree.get()); + CreateTreeFromFixedModelAtPose( + FindResourceOrThrow( + "drake/manipulation/models/jaco_description/urdf/j2n6s300.urdf"), + tree.get()); auto tree_sys = std::make_unique>(std::move(tree)); diff --git a/drake/examples/kuka_iiwa_arm/BUILD b/drake/examples/kuka_iiwa_arm/BUILD index a9ee1546b692..a80f2c0b505c 100644 --- a/drake/examples/kuka_iiwa_arm/BUILD +++ b/drake/examples/kuka_iiwa_arm/BUILD @@ -33,6 +33,7 @@ drake_cc_library( "iiwa_common.h", ], deps = [ + "//drake/common:find_resource", "//drake/common/trajectories:piecewise_polynomial_trajectory", "//drake/multibody:inverse_kinematics", "//drake/multibody:rigid_body_tree", @@ -105,6 +106,7 @@ drake_cc_binary( ":iiwa_common", ":iiwa_lcm", ":robot_plan_interpolator", + "//drake/common:find_resource", "//drake/common:text_logging_gflags", "//drake/lcm", "//drake/systems/analysis:simulator", @@ -160,6 +162,7 @@ drake_cc_binary( ":iiwa_common", ":iiwa_lcm", ":sim_diagram_builder", + "//drake/common:find_resource", "//drake/examples/kuka_iiwa_arm/iiwa_world:world_sim_tree_builder", "//drake/lcm", "//drake/multibody/rigid_body_plant", @@ -180,6 +183,7 @@ drake_cc_binary( deps = [ ":iiwa_common", ":iiwa_lcm", + "//drake/common:find_resource", "@lcmtypes_bot2_core", "@lcmtypes_robotlocomotion", ], @@ -205,6 +209,7 @@ drake_cc_googletest( deps = [ ":iiwa_common", ":robot_plan_interpolator", + "//drake/common:find_resource", "//drake/systems/framework", ], ) diff --git a/drake/examples/kuka_iiwa_arm/controlled_kuka/BUILD b/drake/examples/kuka_iiwa_arm/controlled_kuka/BUILD index 2e8c4449d2ae..4683d75d919a 100644 --- a/drake/examples/kuka_iiwa_arm/controlled_kuka/BUILD +++ b/drake/examples/kuka_iiwa_arm/controlled_kuka/BUILD @@ -19,6 +19,7 @@ drake_cc_binary( ], tags = ["snopt"], deps = [ + "//drake/common:find_resource", "//drake/examples/kuka_iiwa_arm:iiwa_common", "//drake/examples/kuka_iiwa_arm:sim_diagram_builder", "//drake/lcm", diff --git a/drake/examples/kuka_iiwa_arm/controlled_kuka/controlled_kuka_demo.cc b/drake/examples/kuka_iiwa_arm/controlled_kuka/controlled_kuka_demo.cc index 30532a10a512..92242bc04c87 100644 --- a/drake/examples/kuka_iiwa_arm/controlled_kuka/controlled_kuka_demo.cc +++ b/drake/examples/kuka_iiwa_arm/controlled_kuka/controlled_kuka_demo.cc @@ -12,7 +12,7 @@ #include -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/common/trajectories/piecewise_polynomial_trajectory.h" #include "drake/examples/kuka_iiwa_arm/iiwa_common.h" #include "drake/examples/kuka_iiwa_arm/sim_diagram_builder.h" @@ -43,13 +43,13 @@ namespace examples { namespace kuka_iiwa_arm { namespace { -const char kUrdfPath[] = "/manipulation/models/iiwa_description/urdf/" +const char kUrdfPath[] = "drake/manipulation/models/iiwa_description/urdf/" "iiwa14_polytope_collision.urdf"; unique_ptr MakePlan() { auto tree = make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( - GetDrakePath() + kUrdfPath, multibody::joints::kFixed, tree.get()); + FindResourceOrThrow(kUrdfPath), multibody::joints::kFixed, tree.get()); // Creates a basic pointwise IK trajectory for moving the iiwa arm. // It starts in the zero configuration (straight up). @@ -142,7 +142,7 @@ int DoMain() { DRAKE_DEMAND(FLAGS_simulation_sec > 0); auto tree = std::make_unique>(); - CreateTreedFromFixedModelAtPose(kUrdfPath, tree.get()); + CreateTreedFromFixedModelAtPose(FindResourceOrThrow(kUrdfPath), tree.get()); std::unique_ptr traj = MakePlan(); diff --git a/drake/examples/kuka_iiwa_arm/dev/monolithic_pick_and_place/BUILD b/drake/examples/kuka_iiwa_arm/dev/monolithic_pick_and_place/BUILD index 8221c879147a..8b8aef098eae 100644 --- a/drake/examples/kuka_iiwa_arm/dev/monolithic_pick_and_place/BUILD +++ b/drake/examples/kuka_iiwa_arm/dev/monolithic_pick_and_place/BUILD @@ -35,6 +35,7 @@ drake_cc_binary( ], deps = [ ":kuka_pick_and_place_monolithic", + "//drake/common:find_resource", "//drake/examples/kuka_iiwa_arm:iiwa_common", "//drake/examples/kuka_iiwa_arm:iiwa_lcm", "//drake/examples/kuka_iiwa_arm:robot_plan_interpolator", diff --git a/drake/examples/kuka_iiwa_arm/dev/monolithic_pick_and_place/monolithic_pick_and_place_demo.cc b/drake/examples/kuka_iiwa_arm/dev/monolithic_pick_and_place/monolithic_pick_and_place_demo.cc index 3cd24dbf62df..27fe9123c1c7 100644 --- a/drake/examples/kuka_iiwa_arm/dev/monolithic_pick_and_place/monolithic_pick_and_place_demo.cc +++ b/drake/examples/kuka_iiwa_arm/dev/monolithic_pick_and_place/monolithic_pick_and_place_demo.cc @@ -6,7 +6,7 @@ #include "bot_core/robot_state_t.hpp" #include "robotlocomotion/robot_plan_t.hpp" -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/examples/kuka_iiwa_arm/dev/monolithic_pick_and_place/state_machine_system.h" #include "drake/examples/kuka_iiwa_arm/iiwa_common.h" #include "drake/examples/kuka_iiwa_arm/iiwa_world/iiwa_wsg_diagram_factory.h" @@ -43,7 +43,7 @@ namespace monolithic_pick_and_place { namespace { const char kIiwaUrdf[] = - "/manipulation/models/iiwa_description/urdf/" + "drake/manipulation/models/iiwa_description/urdf/" "iiwa14_polytope_collision.urdf"; const char kIiwaEndEffectorName[] = "iiwa_link_ee"; @@ -92,18 +92,18 @@ std::unique_ptr> BuildCombinedPlant( // Adds models to the simulation builder. Instances of these models can be // subsequently added to the world. - tree_builder->StoreModel("iiwa", kIiwaUrdf); + tree_builder->StoreModel("iiwa", FindResourceOrThrow(kIiwaUrdf)); tree_builder->StoreModel("table", - "/examples/kuka_iiwa_arm/models/table/" + "drake/examples/kuka_iiwa_arm/models/table/" "extra_heavy_duty_table_surface_only_collision.sdf"); tree_builder->StoreModel( - "target", "/examples/kuka_iiwa_arm/models/objects/" + target_model); + "target", "drake/examples/kuka_iiwa_arm/models/objects/" + target_model); tree_builder->StoreModel("yellow_post", - "/examples/kuka_iiwa_arm/models/objects/" + "drake/examples/kuka_iiwa_arm/models/objects/" "yellow_post.urdf"); tree_builder->StoreModel( "wsg", - "/manipulation/models/wsg_50_description" + "drake/manipulation/models/wsg_50_description" "/sdf/schunk_wsg_50_ball_contact.sdf"); // The main table which the arm sits on. @@ -217,7 +217,7 @@ int DoMain(void) { drake_visualizer->get_input_port(0)); auto iiwa_trajectory_generator = builder.AddSystem( - drake::GetDrakePath() + kIiwaUrdf); + FindResourceOrThrow(kIiwaUrdf)); builder.Connect(plant->get_output_port_iiwa_state(), iiwa_trajectory_generator->get_state_input_port()); builder.Connect( @@ -255,7 +255,7 @@ int DoMain(void) { auto state_machine = builder.template AddSystem( - drake::GetDrakePath() + kIiwaUrdf, kIiwaEndEffectorName, + FindResourceOrThrow(kIiwaUrdf), kIiwaEndEffectorName, iiwa_base, place_locations); builder.Connect(plant->get_output_port_box_robot_state_msg(), diff --git a/drake/examples/kuka_iiwa_arm/dev/monolithic_pick_and_place/state_machine_system.cc b/drake/examples/kuka_iiwa_arm/dev/monolithic_pick_and_place/state_machine_system.cc index 9e1881fe95e1..798b23b22add 100644 --- a/drake/examples/kuka_iiwa_arm/dev/monolithic_pick_and_place/state_machine_system.cc +++ b/drake/examples/kuka_iiwa_arm/dev/monolithic_pick_and_place/state_machine_system.cc @@ -6,8 +6,6 @@ #include "bot_core/robot_state_t.hpp" #include "robotlocomotion/robot_plan_t.hpp" -#include "drake/common/drake_path.h" - using bot_core::robot_state_t; namespace drake { diff --git a/drake/examples/kuka_iiwa_arm/dev/pick_and_place/BUILD b/drake/examples/kuka_iiwa_arm/dev/pick_and_place/BUILD index 85b95674b255..cb3c9a58e1e5 100644 --- a/drake/examples/kuka_iiwa_arm/dev/pick_and_place/BUILD +++ b/drake/examples/kuka_iiwa_arm/dev/pick_and_place/BUILD @@ -13,6 +13,7 @@ drake_cc_binary( "pick_and_place_demo.cc", ], deps = [ + "//drake/common:find_resource", "//drake/examples/kuka_iiwa_arm:iiwa_common", "//drake/examples/kuka_iiwa_arm:iiwa_lcm", "//drake/examples/kuka_iiwa_arm/pick_and_place", diff --git a/drake/examples/kuka_iiwa_arm/dev/pick_and_place/pick_and_place_demo.cc b/drake/examples/kuka_iiwa_arm/dev/pick_and_place/pick_and_place_demo.cc index f8b40af442da..893510b1eac9 100644 --- a/drake/examples/kuka_iiwa_arm/dev/pick_and_place/pick_and_place_demo.cc +++ b/drake/examples/kuka_iiwa_arm/dev/pick_and_place/pick_and_place_demo.cc @@ -12,7 +12,7 @@ #include "drake/common/drake_assert.h" #include "drake/common/drake_copyable.h" -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/examples/kuka_iiwa_arm/pick_and_place/pick_and_place_state_machine.h" #include "drake/examples/kuka_iiwa_arm/pick_and_place/world_state.h" #include "drake/lcmt_iiwa_status.hpp" @@ -92,9 +92,9 @@ using manipulation::planner::ConstraintRelaxingIk; void RunPickAndPlaceDemo() { lcm::LCM lcm; - const std::string iiwa_path = GetDrakePath() + - "/manipulation/models/iiwa_description/urdf/" - "iiwa14_primitive_collision.urdf"; + const std::string iiwa_path = FindResourceOrThrow( + "drake/manipulation/models/iiwa_description/urdf/" + "iiwa14_primitive_collision.urdf"); const std::string iiwa_end_effector_name = "iiwa_link_ee"; // Makes a WorldState, and sets up LCM subscriptions. diff --git a/drake/examples/kuka_iiwa_arm/dev/tools/BUILD b/drake/examples/kuka_iiwa_arm/dev/tools/BUILD index 34705a7e3d48..a03d9274fa8a 100644 --- a/drake/examples/kuka_iiwa_arm/dev/tools/BUILD +++ b/drake/examples/kuka_iiwa_arm/dev/tools/BUILD @@ -37,6 +37,7 @@ drake_cc_binary( deps = [ ":simple_tree_visualizer", "//drake/common", + "//drake/common:find_resource", "//drake/lcm", "//drake/multibody/parsers", "//drake/systems/framework", diff --git a/drake/examples/kuka_iiwa_arm/dev/tools/simple_tree_visualizer_demo.cc b/drake/examples/kuka_iiwa_arm/dev/tools/simple_tree_visualizer_demo.cc index a87dd7a49245..9728196fd075 100644 --- a/drake/examples/kuka_iiwa_arm/dev/tools/simple_tree_visualizer_demo.cc +++ b/drake/examples/kuka_iiwa_arm/dev/tools/simple_tree_visualizer_demo.cc @@ -8,8 +8,8 @@ #include -#include "drake/common/drake_path.h" #include "drake/common/eigen_types.h" +#include "drake/common/find_resource.h" #include "drake/lcm/drake_lcm.h" #include "drake/multibody/parsers/urdf_parser.h" #include "drake/multibody/rigid_body_tree.h" @@ -28,7 +28,7 @@ int DoMain() { // Adds a demo tree. const std::string kModelPath = - "/manipulation/models/iiwa_description/urdf/" + "drake/manipulation/models/iiwa_description/urdf/" "iiwa14_polytope_collision.urdf"; auto tree = std::make_unique>(); @@ -39,7 +39,7 @@ int DoMain() { Eigen::Vector3d::Zero() /* base orientation */); drake::parsers::urdf::AddModelInstanceFromUrdfFile( - drake::GetDrakePath() + kModelPath, drake::multibody::joints::kFixed, + FindResourceOrThrow(kModelPath), drake::multibody::joints::kFixed, weld_to_frame, tree.get()); SimpleTreeVisualizer simple_tree_visualizer(*tree.get(), &lcm); diff --git a/drake/examples/kuka_iiwa_arm/iiwa_common.cc b/drake/examples/kuka_iiwa_arm/iiwa_common.cc index 4155c0b4add4..cc448885293a 100644 --- a/drake/examples/kuka_iiwa_arm/iiwa_common.cc +++ b/drake/examples/kuka_iiwa_arm/iiwa_common.cc @@ -7,8 +7,8 @@ #include #include "drake/common/drake_assert.h" -#include "drake/common/drake_path.h" #include "drake/common/eigen_types.h" +#include "drake/common/find_resource.h" #include "drake/common/text_logging.h" #include "drake/common/trajectories/piecewise_polynomial_trajectory.h" #include "drake/multibody/constraint/rigid_body_constraint.h" @@ -101,7 +101,7 @@ void CreateTreedFromFixedModelAtPose(const std::string& model_file_name, // TODO(naveenoid) : consider implementing SDF version of this method. drake::parsers::urdf::AddModelInstanceFromUrdfFile( - drake::GetDrakePath() + model_file_name, drake::multibody::joints::kFixed, + model_file_name, drake::multibody::joints::kFixed, weld_to_frame, tree); } diff --git a/drake/examples/kuka_iiwa_arm/iiwa_controller.cc b/drake/examples/kuka_iiwa_arm/iiwa_controller.cc index dd599f2f87d5..b3a40a4e458d 100644 --- a/drake/examples/kuka_iiwa_arm/iiwa_controller.cc +++ b/drake/examples/kuka_iiwa_arm/iiwa_controller.cc @@ -7,7 +7,7 @@ #include #include "robotlocomotion/robot_plan_t.hpp" -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/common/text_logging.h" #include "drake/common/text_logging_gflags.h" #include "drake/examples/kuka_iiwa_arm/iiwa_lcm.h" @@ -33,7 +33,7 @@ namespace examples { namespace kuka_iiwa_arm { namespace { -const char* const kIiwaUrdf = "/manipulation/models/iiwa_description/urdf/" +const char* const kIiwaUrdf = "drake/manipulation/models/iiwa_description/urdf/" "iiwa14_polytope_collision.urdf"; const char* const kLcmStatusChannel = "IIWA_STATUS"; const char* const kLcmCommandChannel = "IIWA_COMMAND"; @@ -51,7 +51,7 @@ int DoMain() { plan_sub->set_name("plan_sub"); const std::string urdf = (!FLAGS_urdf.empty() ? FLAGS_urdf : - GetDrakePath() + kIiwaUrdf); + FindResourceOrThrow(kIiwaUrdf)); auto plan_source = builder.AddSystem(urdf); plan_source->set_name("plan_source"); diff --git a/drake/examples/kuka_iiwa_arm/iiwa_world/BUILD b/drake/examples/kuka_iiwa_arm/iiwa_world/BUILD index e4ccaff17496..bc115bb05b6e 100644 --- a/drake/examples/kuka_iiwa_arm/iiwa_world/BUILD +++ b/drake/examples/kuka_iiwa_arm/iiwa_world/BUILD @@ -14,6 +14,7 @@ drake_cc_library( hdrs = ["world_sim_tree_builder.h"], visibility = ["//drake/examples/kuka_iiwa_arm:__subpackages__"], deps = [ + "//drake/common:find_resource", "//drake/common:unused", "//drake/multibody:rigid_body_tree", "//drake/multibody:rigid_body_tree_construction", diff --git a/drake/examples/kuka_iiwa_arm/iiwa_world/multi_arm_with_gripper_demo.cc b/drake/examples/kuka_iiwa_arm/iiwa_world/multi_arm_with_gripper_demo.cc index 38c4316072f2..887522de973c 100644 --- a/drake/examples/kuka_iiwa_arm/iiwa_world/multi_arm_with_gripper_demo.cc +++ b/drake/examples/kuka_iiwa_arm/iiwa_world/multi_arm_with_gripper_demo.cc @@ -23,11 +23,11 @@ std::unique_ptr> build_tree( // subsequently added to the world. tree_builder->StoreModel( "iiwa", - "/manipulation/models/iiwa_description/urdf/" + "drake/manipulation/models/iiwa_description/urdf/" "iiwa14_polytope_collision.urdf"); tree_builder->StoreModel( "wsg", - "/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf"); + "drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf"); iiwa->clear(); wsg->clear(); diff --git a/drake/examples/kuka_iiwa_arm/iiwa_world/world_sim_tree_builder.cc b/drake/examples/kuka_iiwa_arm/iiwa_world/world_sim_tree_builder.cc index d16631e153d8..46f114a067bc 100644 --- a/drake/examples/kuka_iiwa_arm/iiwa_world/world_sim_tree_builder.cc +++ b/drake/examples/kuka_iiwa_arm/iiwa_world/world_sim_tree_builder.cc @@ -6,7 +6,7 @@ #include "spruce.hh" -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/math/roll_pitch_yaw.h" #include "drake/multibody/parsers/model_instance_id_table.h" #include "drake/multibody/parsers/sdf_parser.h" @@ -88,18 +88,18 @@ int WorldSimTreeBuilder::AddModelInstanceToFrame( DRAKE_DEMAND(extension == ".urdf" || extension == ".sdf"); if (extension == ".urdf") { table = drake::parsers::urdf::AddModelInstanceFromUrdfFile( - drake::GetDrakePath() + model_map_[model_name], floating_base_type, + FindResourceOrThrow(model_map_[model_name]), floating_base_type, weld_to_frame, rigid_body_tree_.get()); } else if (extension == ".sdf") { table = drake::parsers::sdf::AddModelInstancesFromSdfFile( - drake::GetDrakePath() + model_map_[model_name], floating_base_type, + FindResourceOrThrow(model_map_[model_name]), floating_base_type, weld_to_frame, rigid_body_tree_.get()); } const int model_instance_id = table.begin()->second; ModelInstanceInfo info; - info.model_path = drake::GetDrakePath() + model_map_[model_name]; + info.model_path = FindResourceOrThrow(model_map_[model_name]); info.instance_id = model_instance_id; info.world_offset = weld_to_frame; instance_id_to_model_info_[model_instance_id] = info; diff --git a/drake/examples/kuka_iiwa_arm/iiwa_wsg_simulation.cc b/drake/examples/kuka_iiwa_arm/iiwa_wsg_simulation.cc index 46744ea53e02..c3cc6e3a56e2 100644 --- a/drake/examples/kuka_iiwa_arm/iiwa_wsg_simulation.cc +++ b/drake/examples/kuka_iiwa_arm/iiwa_wsg_simulation.cc @@ -12,7 +12,6 @@ #include -#include "drake/common/drake_path.h" #include "drake/examples/kuka_iiwa_arm/iiwa_common.h" #include "drake/examples/kuka_iiwa_arm/iiwa_lcm.h" #include "drake/examples/kuka_iiwa_arm/iiwa_world/iiwa_wsg_diagram_factory.h" @@ -58,7 +57,7 @@ using systems::RigidBodyPlant; using systems::Simulator; const char* const kIiwaUrdf = - "/manipulation/models/iiwa_description/urdf/" + "drake/manipulation/models/iiwa_description/urdf/" "iiwa14_polytope_collision.urdf"; // TODO(naveen): refactor this to reduce duplicate code. @@ -72,14 +71,14 @@ std::unique_ptr> BuildCombinedPlant( // subsequently added to the world. tree_builder->StoreModel("iiwa", kIiwaUrdf); tree_builder->StoreModel("table", - "/examples/kuka_iiwa_arm/models/table/" + "drake/examples/kuka_iiwa_arm/models/table/" "extra_heavy_duty_table_surface_only_collision.sdf"); - tree_builder->StoreModel( - "box", - "/examples/kuka_iiwa_arm/models/objects/block_for_pick_and_place.urdf"); + tree_builder->StoreModel("box", + "drake/examples/kuka_iiwa_arm/models/objects/" + "block_for_pick_and_place.urdf"); tree_builder->StoreModel( "wsg", - "/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf"); + "drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf"); // Build a world with two fixed tables. A box is placed one on // table, and the iiwa arm is fixed to the other. diff --git a/drake/examples/kuka_iiwa_arm/kuka_plan_runner.cc b/drake/examples/kuka_iiwa_arm/kuka_plan_runner.cc index 4118218b938b..ddb401285cf6 100644 --- a/drake/examples/kuka_iiwa_arm/kuka_plan_runner.cc +++ b/drake/examples/kuka_iiwa_arm/kuka_plan_runner.cc @@ -15,7 +15,7 @@ #include "robotlocomotion/robot_plan_t.hpp" #include "drake/common/drake_assert.h" -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/common/trajectories/piecewise_polynomial.h" #include "drake/common/trajectories/piecewise_polynomial_trajectory.h" #include "drake/examples/kuka_iiwa_arm/iiwa_common.h" @@ -166,8 +166,8 @@ class RobotPlanRunner { int do_main() { auto tree = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( - GetDrakePath() + "/manipulation/models/iiwa_description/urdf/" - "iiwa14_primitive_collision.urdf", + FindResourceOrThrow("drake/manipulation/models/iiwa_description/urdf/" + "iiwa14_primitive_collision.urdf"), multibody::joints::kFixed, tree.get()); RobotPlanRunner runner(*tree); diff --git a/drake/examples/kuka_iiwa_arm/kuka_simulation.cc b/drake/examples/kuka_iiwa_arm/kuka_simulation.cc index 6770465a27bc..17eaf9b88174 100644 --- a/drake/examples/kuka_iiwa_arm/kuka_simulation.cc +++ b/drake/examples/kuka_iiwa_arm/kuka_simulation.cc @@ -10,7 +10,7 @@ #include #include "drake/common/drake_assert.h" -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/examples/kuka_iiwa_arm/iiwa_common.h" #include "drake/examples/kuka_iiwa_arm/iiwa_lcm.h" #include "drake/examples/kuka_iiwa_arm/sim_diagram_builder.h" @@ -53,10 +53,10 @@ int DoMain() { // Adds a plant. RigidBodyPlant* plant = nullptr; - const std::string kModelPath = "/manipulation/models/iiwa_description/urdf/" - "iiwa14_polytope_collision.urdf"; + const char* kModelPath = "drake/manipulation/models/iiwa_description/" + "urdf/iiwa14_polytope_collision.urdf"; const std::string urdf = (!FLAGS_urdf.empty() ? FLAGS_urdf : - GetDrakePath() + kModelPath); + FindResourceOrThrow(kModelPath)); { auto tree = std::make_unique>(); parsers::urdf::AddModelInstanceFromUrdfFileToWorld( diff --git a/drake/examples/kuka_iiwa_arm/pick_and_place/BUILD b/drake/examples/kuka_iiwa_arm/pick_and_place/BUILD index be9afe581850..b8ac0ccbe04d 100644 --- a/drake/examples/kuka_iiwa_arm/pick_and_place/BUILD +++ b/drake/examples/kuka_iiwa_arm/pick_and_place/BUILD @@ -46,6 +46,7 @@ drake_cc_googletest( ], deps = [ ":pick_and_place", + "//drake/common:find_resource", ], ) @@ -57,6 +58,7 @@ drake_cc_googletest( deps = [ ":pick_and_place", "//drake/common:eigen_matrix_compare", + "//drake/common:find_resource", ], ) diff --git a/drake/examples/kuka_iiwa_arm/pick_and_place/test/pick_and_place_state_machine_test.cc b/drake/examples/kuka_iiwa_arm/pick_and_place/test/pick_and_place_state_machine_test.cc index ff71eb6cd76d..62d0876ef3dc 100644 --- a/drake/examples/kuka_iiwa_arm/pick_and_place/test/pick_and_place_state_machine_test.cc +++ b/drake/examples/kuka_iiwa_arm/pick_and_place/test/pick_and_place_state_machine_test.cc @@ -4,7 +4,7 @@ #include "bot_core/robot_state_t.hpp" #include "robotlocomotion/robot_plan_t.hpp" -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/examples/kuka_iiwa_arm/iiwa_common.h" #include "drake/lcmt_schunk_wsg_command.hpp" #include "drake/lcmt_schunk_wsg_status.hpp" @@ -16,7 +16,7 @@ namespace pick_and_place { namespace { const char* const kIiwaUrdf = - "/manipulation/models/iiwa_description/urdf/" + "drake/manipulation/models/iiwa_description/urdf/" "iiwa14_polytope_collision.urdf"; struct TestStep { @@ -40,7 +40,7 @@ GTEST_TEST(PickAndPlaceStateMachineTest, StateMachineTest) { PickAndPlaceStateMachine dut(place_locations, false); // Create world state and initialize with a trivial configuration. - WorldState world_state(GetDrakePath() + kIiwaUrdf, "iiwa_link_ee"); + WorldState world_state(FindResourceOrThrow(kIiwaUrdf), "iiwa_link_ee"); bot_core::robot_state_t iiwa_msg{}; iiwa_msg.utime = 1000; @@ -100,7 +100,7 @@ GTEST_TEST(PickAndPlaceStateMachineTest, StateMachineTest) { }; manipulation::planner::ConstraintRelaxingIk planner( - GetDrakePath() + kIiwaUrdf, "iiwa_link_ee", + FindResourceOrThrow(kIiwaUrdf), "iiwa_link_ee", Isometry3::Identity()); dut.Update(world_state, iiwa_callback, wsg_callback, &planner); diff --git a/drake/examples/kuka_iiwa_arm/pick_and_place/test/world_state_test.cc b/drake/examples/kuka_iiwa_arm/pick_and_place/test/world_state_test.cc index ea3c16c00cd3..fbb13aa87d3e 100644 --- a/drake/examples/kuka_iiwa_arm/pick_and_place/test/world_state_test.cc +++ b/drake/examples/kuka_iiwa_arm/pick_and_place/test/world_state_test.cc @@ -2,8 +2,8 @@ #include -#include "drake/common/drake_path.h" #include "drake/common/eigen_matrix_compare.h" +#include "drake/common/find_resource.h" #include "drake/examples/kuka_iiwa_arm/iiwa_common.h" namespace drake { @@ -13,11 +13,11 @@ namespace pick_and_place { namespace { const char* const kIiwaUrdf = - "/manipulation/models/iiwa_description/urdf/" + "drake/manipulation/models/iiwa_description/urdf/" "iiwa14_polytope_collision.urdf"; GTEST_TEST(PickAndPlaceWorldStateTest, EndEffectorTest) { - WorldState dut(GetDrakePath() + kIiwaUrdf, "iiwa_link_ee"); + WorldState dut(FindResourceOrThrow(kIiwaUrdf), "iiwa_link_ee"); bot_core::robot_state_t iiwa_msg{}; iiwa_msg.utime = 1000; @@ -64,7 +64,7 @@ GTEST_TEST(PickAndPlaceWorldStateTest, EndEffectorTest) { // Create another world state and move the base. We expect that the // end effector pose will move by a comparable amount. - WorldState dut2(GetDrakePath() + kIiwaUrdf, "iiwa_link_ee"); + WorldState dut2(FindResourceOrThrow(kIiwaUrdf), "iiwa_link_ee"); iiwa_msg.pose.translation.x += 1; expected_pos(0) += 1; diff --git a/drake/examples/kuka_iiwa_arm/test/robot_plan_interpolator_test.cc b/drake/examples/kuka_iiwa_arm/test/robot_plan_interpolator_test.cc index 338dee78f72d..083a9a72bab3 100644 --- a/drake/examples/kuka_iiwa_arm/test/robot_plan_interpolator_test.cc +++ b/drake/examples/kuka_iiwa_arm/test/robot_plan_interpolator_test.cc @@ -2,7 +2,7 @@ #include -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/examples/kuka_iiwa_arm/iiwa_common.h" namespace drake { @@ -12,16 +12,16 @@ namespace { static const int kNumJoints = 7; const char* const kIiwaUrdf = - "/manipulation/models/iiwa_description/urdf/" + "drake/manipulation/models/iiwa_description/urdf/" "iiwa14_polytope_collision.urdf"; const char* const kDualIiwaUrdf = - "/manipulation/models/iiwa_description/urdf/" + "drake/manipulation/models/iiwa_description/urdf/" "dual_iiwa14_polytope_collision.urdf"; GTEST_TEST(RobotPlanInterpolatorTest, InstanceTest) { // Test that the constructor works and that the expected ports are // present. - RobotPlanInterpolator dut(GetDrakePath() + kIiwaUrdf); + RobotPlanInterpolator dut(FindResourceOrThrow(kIiwaUrdf)); EXPECT_EQ(dut.get_plan_input_port().get_data_type(), systems::kAbstractValued); EXPECT_EQ(dut.get_state_input_port().get_data_type(), @@ -38,7 +38,7 @@ GTEST_TEST(RobotPlanInterpolatorTest, InstanceTest) { GTEST_TEST(RobotPlanInterpolatorTest, DualInstanceTest) { // Check that the port sizes come out appropriately for a dual armed // model. - RobotPlanInterpolator dut(GetDrakePath() + kDualIiwaUrdf); + RobotPlanInterpolator dut(FindResourceOrThrow(kDualIiwaUrdf)); EXPECT_EQ(dut.tree().get_num_positions(), kNumJoints * 2); EXPECT_EQ(dut.tree().get_num_velocities(), kNumJoints * 2); @@ -69,7 +69,7 @@ struct TrajectoryTestCase { GTEST_TEST(RobotPlanInterpolatorTest, TrajectoryTest) { - RobotPlanInterpolator dut(GetDrakePath() + kIiwaUrdf); + RobotPlanInterpolator dut(FindResourceOrThrow(kIiwaUrdf)); std::vector t{0, 1, 2, 3, 4}; Eigen::MatrixXd q = Eigen::MatrixXd::Zero(kNumJoints, t.size()); diff --git a/drake/examples/kuka_iiwa_arm/test/sim_diagram_builder_test.cc b/drake/examples/kuka_iiwa_arm/test/sim_diagram_builder_test.cc index 6d60eec48a93..a4fffd792550 100644 --- a/drake/examples/kuka_iiwa_arm/test/sim_diagram_builder_test.cc +++ b/drake/examples/kuka_iiwa_arm/test/sim_diagram_builder_test.cc @@ -2,7 +2,6 @@ #include -#include "drake/common/drake_path.h" #include "drake/common/eigen_matrix_compare.h" #include "drake/examples/kuka_iiwa_arm/iiwa_common.h" #include "drake/examples/kuka_iiwa_arm/iiwa_world/world_sim_tree_builder.h" @@ -28,11 +27,11 @@ std::unique_ptr> build_tree( // subsequently added to the world. tree_builder->StoreModel( "iiwa", - "/manipulation/models/iiwa_description/urdf/" - "iiwa14_polytope_collision.urdf"); + "drake/manipulation/models/iiwa_description/urdf/" + "iiwa14_polytope_collision.urdf"); tree_builder->StoreModel( "wsg", - "/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf"); + "drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf"); iiwa->clear(); wsg->clear(); diff --git a/drake/examples/particles/BUILD b/drake/examples/particles/BUILD index 29efb39a1085..baaa5819ed95 100644 --- a/drake/examples/particles/BUILD +++ b/drake/examples/particles/BUILD @@ -42,6 +42,7 @@ drake_cc_binary( ], deps = [ ":particles", + "//drake/common:find_resource", "//drake/common:text_logging_gflags", "//drake/lcm", "//drake/multibody/parsers", diff --git a/drake/examples/particles/uniformly_accelerated_particle.cc b/drake/examples/particles/uniformly_accelerated_particle.cc index 2d681f84ad88..2d338e452680 100644 --- a/drake/examples/particles/uniformly_accelerated_particle.cc +++ b/drake/examples/particles/uniformly_accelerated_particle.cc @@ -6,7 +6,7 @@ #include #include -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/common/text_logging_gflags.h" #include "drake/examples/particles/particle.h" #include "drake/examples/particles/utilities.h" @@ -36,7 +36,7 @@ namespace { /// Fixed path to particle SDF model (for visualization purposes only). static const char* const kParticleSdfPath = - "/examples/particles/models/particle.sdf"; + "drake/examples/particles/models/particle.sdf"; /// A sample diagram for visualizing a 1DOF particle to which a /// a constant acceleration is applied. @@ -78,7 +78,7 @@ UniformlyAcceleratedParticle::UniformlyAcceleratedParticle( const T& acceleration, lcm::DrakeLcmInterface* lcm) { // Parse particle sdf into rigid body tree. parsers::sdf::AddModelInstancesFromSdfFileToWorld( - GetDrakePath() + kParticleSdfPath, + FindResourceOrThrow(kParticleSdfPath), multibody::joints::kRollPitchYaw, tree_.get()); // Compile tree one more time just to be sure. diff --git a/drake/examples/schunk_wsg/BUILD b/drake/examples/schunk_wsg/BUILD index 8364868da4c8..c58b08503c1e 100644 --- a/drake/examples/schunk_wsg/BUILD +++ b/drake/examples/schunk_wsg/BUILD @@ -14,7 +14,7 @@ drake_cc_library( srcs = ["simulated_schunk_wsg_system.cc"], hdrs = ["simulated_schunk_wsg_system.h"], deps = [ - "//drake/common:drake_path", + "//drake/common:find_resource", "//drake/multibody/parsers", "//drake/multibody/rigid_body_plant", ], @@ -61,7 +61,7 @@ drake_cc_googletest( disable_in_compilation_mode_dbg = True, deps = [ "//drake/common", - "//drake/common:drake_path", + "//drake/common:find_resource", "//drake/common/trajectories:piecewise_polynomial_trajectory", "//drake/common/trajectories:trajectory", "//drake/lcm", diff --git a/drake/examples/schunk_wsg/simulated_schunk_wsg_system.cc b/drake/examples/schunk_wsg/simulated_schunk_wsg_system.cc index 036194539c6a..c22445a6da79 100644 --- a/drake/examples/schunk_wsg/simulated_schunk_wsg_system.cc +++ b/drake/examples/schunk_wsg/simulated_schunk_wsg_system.cc @@ -2,7 +2,7 @@ #include -#include "drake/common/drake_path.h" +#include "drake/common/find_resource.h" #include "drake/multibody/parsers/sdf_parser.h" namespace drake { @@ -17,8 +17,8 @@ std::unique_ptr> CreateSimulatedSchunkWsgSystem() { auto rigid_body_tree = std::make_unique>(); drake::parsers::sdf::AddModelInstancesFromSdfFile( - GetDrakePath() + - "/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf", + FindResourceOrThrow( + "drake/manipulation/models/wsg_50_description/sdf/schunk_wsg_50.sdf"), kFixed, nullptr /* weld to frame */, rigid_body_tree.get()); return std::make_unique>( std::move(rigid_body_tree)); diff --git a/drake/examples/schunk_wsg/test/schunk_wsg_lift_test.cc b/drake/examples/schunk_wsg/test/schunk_wsg_lift_test.cc index bfea26f2ba45..80888184da9c 100644 --- a/drake/examples/schunk_wsg/test/schunk_wsg_lift_test.cc +++ b/drake/examples/schunk_wsg/test/schunk_wsg_lift_test.cc @@ -17,8 +17,8 @@ #include -#include "drake/common/drake_path.h" #include "drake/common/eigen_types.h" +#include "drake/common/find_resource.h" #include "drake/common/trajectories/piecewise_polynomial_trajectory.h" #include "drake/lcm/drake_lcm.h" #include "drake/lcmt_contact_results_for_viz.hpp" @@ -61,7 +61,7 @@ std::unique_ptr BuildLiftTestTree( // Add a joint to the world which can lift the gripper. const auto lifter_id_table = parsers::sdf::AddModelInstancesFromSdfFile( - GetDrakePath() + "/examples/schunk_wsg/test/test_lifter.sdf", + FindResourceOrThrow("drake/examples/schunk_wsg/test/test_lifter.sdf"), multibody::joints::kFixed, nullptr, tree.get()); EXPECT_EQ(lifter_id_table.size(), 1); *lifter_instance_id = lifter_id_table.begin()->second; @@ -73,9 +73,9 @@ std::unique_ptr BuildLiftTestTree( tree->FindBody("lifted_link"), Eigen::Vector3d(0, -0.05, 0.05), Eigen::Vector3d::Zero()); const auto gripper_id_table = parsers::sdf::AddModelInstancesFromSdfFile( - GetDrakePath() + - "/manipulation/models/wsg_50_description/sdf/" - "schunk_wsg_50_ball_contact.sdf", + FindResourceOrThrow( + "drake/manipulation/models/wsg_50_description/sdf/" + "schunk_wsg_50_ball_contact.sdf"), multibody::joints::kFixed, gripper_frame, tree.get()); EXPECT_EQ(gripper_id_table.size(), 1); *gripper_instance_id = gripper_id_table.begin()->second; @@ -86,7 +86,7 @@ std::unique_ptr BuildLiftTestTree( nullptr, Eigen::Vector3d(0, 0, kBoxInitZ), Eigen::Vector3d::Zero()); parsers::urdf::AddModelInstanceFromUrdfFile( - GetDrakePath() + "/multibody/models/box_small.urdf", + FindResourceOrThrow("drake/multibody/models/box_small.urdf"), multibody::joints::kQuaternion, box_frame, tree.get()); tree->compile();