Skip to content

Commit

Permalink
Port drake/examples to FindResource (RobotLocomotion#6446)
Browse files Browse the repository at this point in the history
  • Loading branch information
kunimatsu-tri authored Jun 30, 2017
1 parent dfdbb8e commit bafbec0
Show file tree
Hide file tree
Showing 78 changed files with 319 additions and 315 deletions.
8 changes: 4 additions & 4 deletions drake/examples/Acrobot/BUILD
Original file line number Diff line number Diff line change
Expand Up @@ -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",
Expand All @@ -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",
Expand All @@ -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",
Expand Down Expand Up @@ -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",
Expand Down
4 changes: 2 additions & 2 deletions drake/examples/Acrobot/acrobot_plant_w_lcm.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@

#include <gflags/gflags.h>

#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"
Expand Down Expand Up @@ -52,7 +52,7 @@ int DoMain() {
lcm::DrakeLcm lcm;
auto tree = std::make_unique<RigidBodyTree<double>>();
parsers::urdf::AddModelInstanceFromUrdfFileToWorld(
GetDrakePath() + "/examples/Acrobot/Acrobot.urdf",
FindResourceOrThrow("drake/examples/Acrobot/Acrobot.urdf"),
multibody::joints::kFixed, tree.get());
auto publisher = builder.AddSystem<systems::DrakeVisualizer>(*tree, &lcm);
auto acrobot = builder.AddSystem<AcrobotPlant>();
Expand Down
4 changes: 2 additions & 2 deletions drake/examples/Acrobot/acrobot_run_lqr.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

#include <gflags/gflags.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"
Expand Down Expand Up @@ -33,7 +33,7 @@ int do_main(int argc, char* argv[]) {
lcm::DrakeLcm lcm;
auto tree = std::make_unique<RigidBodyTree<double>>();
parsers::urdf::AddModelInstanceFromUrdfFileToWorld(
GetDrakePath() + "/examples/Acrobot/Acrobot.urdf",
FindResourceOrThrow("drake/examples/Acrobot/Acrobot.urdf"),
multibody::joints::kFixed, tree.get());

systems::DiagramBuilder<double> builder;
Expand Down
4 changes: 2 additions & 2 deletions drake/examples/Acrobot/acrobot_run_lqr_w_estimator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <gflags/gflags.h>

#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"
Expand Down Expand Up @@ -49,7 +49,7 @@ int do_main(int argc, char* argv[]) {
lcm::DrakeLcm lcm;
auto tree = std::make_unique<RigidBodyTree<double>>();
parsers::urdf::AddModelInstanceFromUrdfFileToWorld(
GetDrakePath() + "/examples/Acrobot/Acrobot.urdf",
FindResourceOrThrow("drake/examples/Acrobot/Acrobot.urdf"),
multibody::joints::kFixed, tree.get());
auto publisher = builder.AddSystem<systems::DrakeVisualizer>(*tree, &lcm);
publisher->set_name("publisher");
Expand Down
4 changes: 2 additions & 2 deletions drake/examples/Acrobot/acrobot_run_passive.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

#include <gflags/gflags.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"
Expand Down Expand Up @@ -32,7 +32,7 @@ int do_main(int argc, char* argv[]) {
lcm::DrakeLcm lcm;
auto tree = std::make_unique<RigidBodyTree<double>>();
parsers::urdf::AddModelInstanceFromUrdfFileToWorld(
GetDrakePath() + "/examples/Acrobot/Acrobot.urdf",
FindResourceOrThrow("drake/examples/Acrobot/Acrobot.urdf"),
multibody::joints::kFixed, tree.get());

systems::DiagramBuilder<double> builder;
Expand Down
4 changes: 2 additions & 2 deletions drake/examples/Acrobot/acrobot_run_swing_up.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

#include <gflags/gflags.h>

#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"
Expand Down Expand Up @@ -36,7 +36,7 @@ int do_main(int argc, char* argv[]) {
lcm::DrakeLcm lcm;
auto tree = std::make_unique<RigidBodyTree<double>>();
parsers::urdf::AddModelInstanceFromUrdfFileToWorld(
GetDrakePath() + "/examples/Acrobot/Acrobot.urdf",
FindResourceOrThrow("drake/examples/Acrobot/Acrobot.urdf"),
multibody::joints::kFixed, tree.get());

systems::DiagramBuilder<double> builder;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@

#include <gflags/gflags.h>

#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"
Expand Down Expand Up @@ -69,7 +69,7 @@ int do_main() {
lcm::DrakeLcm lcm;
auto tree = std::make_unique<RigidBodyTree<double>>();
parsers::urdf::AddModelInstanceFromUrdfFileToWorld(
GetDrakePath() + "/examples/Acrobot/Acrobot.urdf",
FindResourceOrThrow("drake/examples/Acrobot/Acrobot.urdf"),
multibody::joints::kFixed, tree.get());

auto publisher = builder.AddSystem<systems::DrakeVisualizer>(*tree, &lcm);
Expand Down
4 changes: 2 additions & 2 deletions drake/examples/Acrobot/test/acrobot_urdf_dynamics_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@

#include <gtest/gtest.h>

#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"
Expand All @@ -19,7 +19,7 @@ namespace {
GTEST_TEST(UrdfDynamicsTest, AllTests) {
auto tree = std::make_unique<RigidBodyTree<double>>();
parsers::urdf::AddModelInstanceFromUrdfFileToWorld(
GetDrakePath() + "/examples/Acrobot/Acrobot.urdf",
FindResourceOrThrow("drake/examples/Acrobot/Acrobot.urdf"),
multibody::joints::kFixed, tree.get());

systems::RigidBodyPlant<double> rbp(std::move(tree));
Expand Down
8 changes: 4 additions & 4 deletions drake/examples/Pendulum/BUILD
Original file line number Diff line number Diff line change
Expand Up @@ -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",
Expand All @@ -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",
Expand All @@ -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",
Expand All @@ -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",
Expand Down
4 changes: 2 additions & 2 deletions drake/examples/Pendulum/pendulum_run_dynamics.cc
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include <memory>

#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"
Expand All @@ -21,7 +21,7 @@ int do_main() {
lcm::DrakeLcm lcm;
auto tree = std::make_unique<RigidBodyTree<double>>();
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);
Expand Down
4 changes: 2 additions & 2 deletions drake/examples/Pendulum/pendulum_run_energy_shaping.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
#include <memory>

#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"
Expand Down Expand Up @@ -61,7 +61,7 @@ int do_main() {
lcm::DrakeLcm lcm;
auto tree = std::make_unique<RigidBodyTree<double>>();
parsers::urdf::AddModelInstanceFromUrdfFileToWorld(
GetDrakePath() + "/examples/Pendulum/Pendulum.urdf",
FindResourceOrThrow("drake/examples/Pendulum/Pendulum.urdf"),
multibody::joints::kFixed, tree.get());

systems::DiagramBuilder<double> builder;
Expand Down
4 changes: 2 additions & 2 deletions drake/examples/Pendulum/pendulum_run_lqr.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
#include <memory>

#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"
Expand All @@ -26,7 +26,7 @@ int do_main() {

auto tree = std::make_unique<RigidBodyTree<double>>();
drake::parsers::urdf::AddModelInstanceFromUrdfFileToWorld(
GetDrakePath() + "/examples/Pendulum/Pendulum.urdf",
FindResourceOrThrow("drake/examples/Pendulum/Pendulum.urdf"),
multibody::joints::kFixed, tree.get());

systems::DiagramBuilder<double> builder;
Expand Down
4 changes: 2 additions & 2 deletions drake/examples/Pendulum/pendulum_run_swing_up.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

#include <gflags/gflags.h>

#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"
Expand Down Expand Up @@ -90,7 +90,7 @@ int do_main() {
lcm::DrakeLcm lcm;
auto tree = std::make_unique<RigidBodyTree<double>>();
parsers::urdf::AddModelInstanceFromUrdfFileToWorld(
GetDrakePath() + "/examples/Pendulum/Pendulum.urdf",
FindResourceOrThrow("drake/examples/Pendulum/Pendulum.urdf"),
multibody::joints::kFixed, tree.get());

auto publisher = builder.AddSystem<systems::DrakeVisualizer>(*tree, &lcm);
Expand Down
4 changes: 2 additions & 2 deletions drake/examples/Pendulum/test/pendulum_urdf_dynamics_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@

#include <gtest/gtest.h>

#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"
Expand All @@ -17,7 +17,7 @@ namespace {
GTEST_TEST(UrdfDynamicsTest, AllTests) {
auto tree = std::make_unique<RigidBodyTree<double>>();
parsers::urdf::AddModelInstanceFromUrdfFileToWorld(
GetDrakePath() + "/examples/Pendulum/Pendulum.urdf",
FindResourceOrThrow("drake/examples/Pendulum/Pendulum.urdf"),
multibody::joints::kFixed, tree.get());

systems::RigidBodyPlant<double> rbp(std::move(tree));
Expand Down
3 changes: 3 additions & 0 deletions drake/examples/QPInverseDynamicsForHumanoids/BUILD
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,7 @@ drake_cc_googletest(
deps = [
":lcm_utils",
"//drake/common:eigen_matrix_compare",
"//drake/common:find_resource",
"//drake/multibody/parsers",
],
)
Expand All @@ -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",
Expand All @@ -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",
],
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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",
],
)
Expand All @@ -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",
],
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@

#include <gtest/gtest.h>

#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"

Expand All @@ -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<RigidBodyTree<double>>();
parsers::urdf::AddModelInstanceFromUrdfFileToWorld(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

#include <gtest/gtest.h>

#include "drake/common/drake_path.h"
#include "drake/common/find_resource.h"
#include "drake/multibody/parsers/urdf_parser.h"

namespace drake {
Expand All @@ -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:
//
Expand All @@ -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<RigidBodyTree<double>>();
parsers::urdf::AddModelInstanceFromUrdfFileToWorld(urdf, type, robot.get());
Expand Down
Loading

0 comments on commit bafbec0

Please sign in to comment.