Skip to content

Commit

Permalink
Start work on inverse dynamics test.
Browse files Browse the repository at this point in the history
  • Loading branch information
tkoolen committed Sep 13, 2016
1 parent 2940096 commit 2efe328
Show file tree
Hide file tree
Showing 2 changed files with 51 additions and 1 deletion.
6 changes: 5 additions & 1 deletion drake/systems/plants/test/rigid_body_tree/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,11 +1,15 @@
pods_find_pkg_config(bullet)

if(bullet_FOUND)
add_executable(rbt_collisions_test rbt_collisions_test.cc)
add_executable(rbt_collisions_test rbt_collisions_test.cc rigid_body_tree_inverse_dynamics_test.cc)
target_link_libraries(rbt_collisions_test drakeRBM ${GTEST_BOTH_LIBRARIES})
drake_add_test(NAME rbt_collisions_test COMMAND rbt_collisions_test)
endif()

add_executable(rigid_body_tree_test rigid_body_tree_test.cc)
target_link_libraries(rigid_body_tree_test drakeRBSystem ${GTEST_BOTH_LIBRARIES})
drake_add_test(NAME rigid_body_tree_test COMMAND rigid_body_tree_test)

add_executable(rigid_body_tree_inverse_dynamics_test rigid_body_tree_inverse_dynamics_test.cc)
target_link_libraries(rigid_body_tree_inverse_dynamics_test drakeRBSystem ${GTEST_BOTH_LIBRARIES})
drake_add_test(NAME rigid_body_tree_inverse_dynamics_test COMMAND rigid_body_tree_inverse_dynamics_test)
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
#include <iostream>

#include <gtest/gtest.h>

#include "drake/common/eigen_types.h"
#include "drake/math/autodiff.h"
#include "drake/math/roll_pitch_yaw.h"
#include "drake/common/drake_path.h"
#include "drake/systems/plants/parser_model_instance_id_table.h"
#include "drake/systems/plants/parser_urdf.h"
#include "drake/systems/plants/RigidBodyTree.h"

namespace drake {
namespace systems {
namespace plants {
namespace test {
namespace {

using drake::parsers::ModelInstanceIdTable;

class RigidBodyTreeInverseDynamicsTest : public ::testing::Test {
protected:
virtual void SetUp() {
tree.reset(new RigidBodyTree());
std::string kAtlasUrdf =
drake::GetDrakePath() + "/examples/Atlas/urdf/atlas_convex_hull.urdf";
drake::parsers::urdf::AddModelInstanceFromUrdfFile(
kAtlasUrdf, DrakeJoint::ROLLPITCHYAW,
nullptr /* weld_to_frame */, tree.get());
}

public:
// TODO(amcastro-tri): A stack object here (preferable to a pointer)
// generates build issues on Windows platforms. See git-hub issue #1854.
std::unique_ptr<RigidBodyTree> tree;
};

TEST_F(RigidBodyTreeInverseDynamicsTest, TestAccelerationJacobianIsMassMatrix) {
drake::math::initializeAutoDiff(q);
}

} // namespace
} // namespace test
} // namespace plants
} // namespace systems
} // namespace drake

0 comments on commit 2efe328

Please sign in to comment.