forked from RobotLocomotion/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Start work on inverse dynamics test.
- Loading branch information
Showing
2 changed files
with
51 additions
and
1 deletion.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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) |
46 changes: 46 additions & 0 deletions
46
drake/systems/plants/test/rigid_body_tree/rigid_body_tree_inverse_dynamics_test.cc
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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 |